diff --git a/README.md b/README.md index 57fbf2a..c587800 100644 --- a/README.md +++ b/README.md @@ -8,6 +8,9 @@ Below is a list of all tutorials available in this repository: ### [Foxglove Visualization for 1X World Model Challenge](datasets/1x_eve/README.md) - 📝 Use Foxglove to visualize 1X World Model Challenge - 🎥 [Video](https://www.youtube.com/watch?v=A9wl491ltPA) +### [EuRoC MAV Dataset in Foxglove](datasets/EuRoC_MAV/README.md) +- 📝 Drone SLAM of the MH01 Environment from EuRoC MAV +- 🔗 [Related Blog Post](https://foxglove.dev/blog/converting-euroc-mav-dataset-to-mcap) ### [Convert .mat files to MCAP](datasets/NASA_mat_to_MCAP/README.md) - 📝 Visualize Matlab files for NASA Valkyrie box pickup task ### [Converting Argoverse 2 Dataset to MCAP](datasets/foxglove_av2_tutorial/README.md) diff --git a/datasets/EuRoC_MAV/.gitignore b/datasets/EuRoC_MAV/.gitignore new file mode 100644 index 0000000..999ef30 --- /dev/null +++ b/datasets/EuRoC_MAV/.gitignore @@ -0,0 +1,3 @@ +*.mcap +data/* +.env \ No newline at end of file diff --git a/datasets/EuRoC_MAV/README.md b/datasets/EuRoC_MAV/README.md new file mode 100644 index 0000000..cbdeec8 --- /dev/null +++ b/datasets/EuRoC_MAV/README.md @@ -0,0 +1,45 @@ +--- +title: "EuRoC MAV Dataset in Foxglove" +short_description: "Drone SLAM of the MH01 Environment from EuRoC MAV" +blog_post_url: "https://foxglove.dev/blog/converting-euroc-mav-dataset-to-mcap" +--- + +# EuRoC MAV Dataset in Foxglove + +This tutorial shows how to convert the EuRoC MAV dataset into an MCAP file for visualization in Foxglove. + +![SLAM_gif](media/MH01_Final_gif_cut.gif) + +## Run this tutorial locally: +1. Download one of the EuRoC environments from [ETH Zurich](https://projects.asl.ethz.ch/datasets/doku.php?id=kmavvisualinertialdatasets) in ASL format. The Machine Hall 01 set is visualized in the tutorial. +2. Make sure to have a working [ROS distribution](https://docs.ros.org/en/humble/Installation.html) and install dependancies: +```bash +sudo apt install \ + ros-$ROS_DISTRO-foxglove-bridge \ + ros-$ROS_DISTRO-imu-tools \ + ros-$ROS_DISTRO-rtabmap-ros \ + ros-$ROS_DISTRO-rosbag2-storage-mcap \ + ros-$ROS_DISTRO-image-proc +``` +In a new python environment, install: +```bash +pip install foxglove-sdk numpy opencv-python pyyaml +``` +3. Convert the dataset to MCAP +```bash +python3 convert-euroc-2-mcap.py --src --dst .mcap +``` +4. Build the ROS 2 package called euroc_slam +```bash +cd ~/tutorials/EuRoC_MAV/ros2_ws +colcon build --symlink-install +source install/setup.bash +``` +5. Run SLAM and visualize in Foxglove while the dataset plays back: +```bash +ros2 launch euroc_slam firefly.launch.py +``` +In a seperate terminal: +```bash +ros2 bag play --clock +``` diff --git a/datasets/EuRoC_MAV/convert-euroc-2-mcap.py b/datasets/EuRoC_MAV/convert-euroc-2-mcap.py new file mode 100644 index 0000000..64da38b --- /dev/null +++ b/datasets/EuRoC_MAV/convert-euroc-2-mcap.py @@ -0,0 +1,180 @@ +import foxglove +import argparse +import os +import csv +import cv2 +import yaml +import numpy as np +from foxglove import Schema, Channel +from sensor_msgs.msg import Image, Imu +from std_msgs.msg import Header +from geometry_msgs.msg import Quaternion, Vector3 +from rclpy.serialization import serialize_message +from pathlib import Path + + +def get_image_msg(img_path: str, timestamp: int, cam_num: int) -> Image: + # Stereo images should be loaded in as grayscale + img = cv2.imread(img_path, cv2.IMREAD_GRAYSCALE) + if img is None: + raise ValueError(f"Could not load image: {img_path}") + + height, width = img.shape + + sec = int(timestamp // 1e9) + nsec = int(timestamp % 1e9) + + # Populate the image message data + ros_image = Image() + ros_image.header = Header() + ros_image.header.stamp.sec = sec + ros_image.header.stamp.nanosec = nsec + ros_image.header.frame_id = f"cam{cam_num}" + ros_image.height = height + ros_image.width = width + ros_image.encoding = "mono8" # Stereo images + ros_image.step = width # For mono8, 1 byte per pixel + ros_image.data = img.tobytes() + + return ros_image + + +def read_images(cam_directory: str, channel: Channel, cam_num: int) -> None: + # Loop through the data.csv file and read in the image files + csv_path = os.path.join(cam_directory, "data.csv") + with open(csv_path, "r") as csv_file: + reader = csv.reader(csv_file) + next(reader) # Skip the first row with headers + for row in reader: + timestamp = int(row[0]) + image_name = row[1] + image_path = os.path.join(cam_directory, "data", image_name) + if not os.path.exists(image_path): + print(f"Image {image_path} does not exist") + continue + + # Convert image to ROS2 message and write to channel + image_msg = get_image_msg(image_path, timestamp, cam_num) + channel.log(serialize_message(image_msg), log_time=timestamp) + + +def read_imu(imu_data_path: str, imu_channel: Channel, imu_yaml_path: str) -> None: + """Read IMU data and write to MCAP channel. + + IMU data is in the format: + timestamp [ns],w_RS_S_x [rad s^-1],w_RS_S_y [rad s^-1],w_RS_S_z [rad s^-1],a_RS_S_x [m s^-2],a_RS_S_y [m s^-2],a_RS_S_z [m s^-2] + + We will convert this to a custom IMU message that interfaces with sensor_msgs/msgs/Imu. + This will be in the form: + - header (header) + - orientation (quaternion) + - orientation covariance (float32[9]) + - angular velocity (vector3) + - angular velocity covariance (float32[9]) + - linear acceleration (vector3) + - linear acceleration covariance (float32[9]) + + Args: + imu_data_path: Path to IMU data CSV file + imu_channel: MCAP channel to write IMU messages to + imu_yaml_path: Path to IMU configuration YAML file + """ + # Get the IMU config with covariance information + with open(imu_yaml_path, "r") as imu_yaml_file: + imu_yaml = yaml.load(imu_yaml_file, Loader=yaml.FullLoader) + + # Get the noise and bias parameters, see https://github.com/ethz-asl/kalibr/wiki/IMU-Noise-Model for more details + sample_sqr_dt = np.sqrt(1.0 / float(imu_yaml["rate_hz"])) + sigma_gd = imu_yaml["gyroscope_noise_density"] * sample_sqr_dt + sigma_ad = imu_yaml["accelerometer_noise_density"] * sample_sqr_dt + + # Calculate the covariance matrices + orientation_cov = np.zeros((3, 3), dtype=np.float64) + angular_velocity_cov = np.diag([sigma_gd**2, sigma_gd**2, sigma_gd**2]).astype(np.float64) + linear_acceleration_cov = np.diag([sigma_ad**2, sigma_ad**2, sigma_ad**2]).astype(np.float64) + + with open(imu_data_path, "r") as imu_file: + reader = csv.reader(imu_file) + next(reader) # Skip the first row with headers + for row in reader: + timestamp = int(row[0]) + angular_velocity = [float(row[1]), float(row[2]), float(row[3])] + linear_acceleration = [float(row[4]), float(row[5]), float(row[6])] + + imu_msg = Imu() + imu_msg.header = Header() + imu_msg.header.stamp.sec = timestamp // int(1e9) + imu_msg.header.stamp.nanosec = timestamp % int(1e9) + imu_msg.header.frame_id = "imu4" # Transformation reference frame + # Orientation + imu_msg.orientation = Quaternion() + imu_msg.orientation.x = 0.0 + imu_msg.orientation.y = 0.0 + imu_msg.orientation.z = 0.0 + imu_msg.orientation.w = 1.0 + imu_msg.orientation_covariance = list(orientation_cov.flatten(order="C").astype(float)) + # Angular velocity + imu_msg.angular_velocity = Vector3() + imu_msg.angular_velocity.x = angular_velocity[0] + imu_msg.angular_velocity.y = angular_velocity[1] + imu_msg.angular_velocity.z = angular_velocity[2] + imu_msg.angular_velocity_covariance = list(angular_velocity_cov.flatten(order="C").astype(float)) + # Linear acceleration + imu_msg.linear_acceleration = Vector3() + imu_msg.linear_acceleration.x = linear_acceleration[0] + imu_msg.linear_acceleration.y = linear_acceleration[1] + imu_msg.linear_acceleration.z = linear_acceleration[2] + imu_msg.linear_acceleration_covariance = list(linear_acceleration_cov.flatten(order="C").astype(float)) + + imu_channel.log(serialize_message(imu_msg), log_time=timestamp) + + +def main() -> None: + parser = argparse.ArgumentParser(description='Convert Euroc dataset to MCAP format') + parser.add_argument('--src', type=str, required=True, help='Path to the Euroc dataset directory') + parser.add_argument('--dst', type=str, required=True, help='Path to the output MCAP file') + args = parser.parse_args() + + out_mcap_path = args.dst + if os.path.exists(out_mcap_path): # Remove the previous file if it already exists + os.remove(out_mcap_path) + + writer = foxglove.open_mcap(out_mcap_path, allow_overwrite=True) # Open the mcap file for writing + + imu_msg_path = Path("msgs/imu_flat.msg") + img_msg_path = Path("msgs/image_flat.msg") + + img_schema = Schema( + name="sensor_msgs/msg/Image", + encoding="ros2msg", + data=img_msg_path.read_bytes(), + ) + imu_schema = Schema( + name="sensor_msgs/msg/Imu", + encoding="ros2msg", + data=imu_msg_path.read_bytes(), + ) + + # ros2msg channels require cdr encoding type + cam0_channel = Channel(topic="/cam0/image_raw", schema=img_schema, message_encoding="cdr") + cam1_channel = Channel(topic="/cam1/image_raw", schema=img_schema, message_encoding="cdr") + imu_channel = Channel(topic="/imu0", schema=imu_schema, message_encoding="cdr") + + # Read in the data.csv file + data_csv_path = os.path.join(args.src, "data.csv") + cam0_dir = os.path.join(args.src, "cam0") + cam1_dir = os.path.join(args.src, "cam1") + imu_dir = os.path.join(args.src, "imu0", "data.csv") + imu_yaml_path = os.path.join(args.src, "imu0", "sensor.yaml") + + read_images(cam0_dir, cam0_channel, 0) + print("Done writing cam0") + read_images(cam1_dir, cam1_channel, 1) + print("Done writing cam1") + read_imu(imu_dir, imu_channel, imu_yaml_path) + print("Done writing imu") + + +if __name__ == "__main__": + main() + \ No newline at end of file diff --git a/datasets/EuRoC_MAV/data/README.md b/datasets/EuRoC_MAV/data/README.md new file mode 100644 index 0000000..852e619 --- /dev/null +++ b/datasets/EuRoC_MAV/data/README.md @@ -0,0 +1,3 @@ +Save your Euroc format datasets here! + +See https://projects.asl.ethz.ch/datasets/doku.php?id=kmavvisualinertialdatasets for examples. \ No newline at end of file diff --git a/datasets/EuRoC_MAV/foxglove-layouts/EurocVizPanels.json b/datasets/EuRoC_MAV/foxglove-layouts/EurocVizPanels.json new file mode 100644 index 0000000..7ecd8f2 --- /dev/null +++ b/datasets/EuRoC_MAV/foxglove-layouts/EurocVizPanels.json @@ -0,0 +1,743 @@ +{ + "configById": { + "3D!1olov4a": { + "cameraState": { + "distance": 10.266841665529618, + "perspective": true, + "phi": 58.241932766782014, + "target": [ + 0, + 0, + 0 + ], + "targetOffset": [ + -2.629183925738109, + 3.3714109280618723, + -1.895344253070008e-16 + ], + "targetOrientation": [ + 0, + 0, + 0, + 1 + ], + "thetaOffset": -83.4596551528181, + "fovy": 45, + "near": 0.5, + "far": 5000 + }, + "followMode": "follow-pose", + "scene": { + "transforms": { + "showLabel": false, + "labelSize": 0.02, + "visible": true, + "axisScale": 0.632, + "editable": false + } + }, + "transforms": { + "frame:vicon/firefly_sbx/firefly_sbx": { + "visible": false + }, + "frame:base_link_gt": { + "visible": false + }, + "frame:firefly/base_link": { + "visible": false + }, + "frame:firefly/base_link_inertia": { + "visible": false + }, + "frame:cam0": { + "visible": false + }, + "frame:cam1": { + "visible": false + }, + "frame:imu4": { + "visible": false + }, + "frame:base_link": { + "visible": true + }, + "frame:odom": { + "visible": true + }, + "frame:map": { + "visible": true + }, + "frame:firefly/rotor_1": { + "rpyCoefficient": [ + 0, + 0, + -180 + ], + "visible": false + }, + "frame:firefly/rotor_0": { + "rpyCoefficient": [ + 0, + 0, + -180 + ], + "visible": false + }, + "frame:firefly/rotor_4": { + "rpyCoefficient": [ + 0, + 0, + 84.6 + ], + "visible": false + }, + "frame:rotor_1": { + "rpyCoefficient": [ + 0, + 0, + 22.399999999999995 + ], + "visible": false + }, + "frame:rotor_0": { + "rpyCoefficient": [ + 0, + 0, + 50.60000000000001 + ], + "visible": false + }, + "frame:rotor_3": { + "rpyCoefficient": [ + 0, + 0, + 148.6 + ], + "visible": false + }, + "frame:rotor_2": { + "visible": false + }, + "frame:rotor_4": { + "visible": false + }, + "frame:rotor_5": { + "visible": false + }, + "frame:base_link_inertia": { + "visible": false + }, + "frame:firefly/rotor_2": { + "visible": false + }, + "frame:firefly/rotor_3": { + "visible": false + }, + "frame:firefly/rotor_5": { + "visible": false + }, + "frame:world": { + "visible": true + } + }, + "topics": { + "/cloud_ground": { + "visible": true, + "colorField": "rgb", + "colorMode": "rgb", + "colorMap": "turbo", + "pointSize": 3, + "minValue": 0, + "maxValue": 30 + }, + "/cloud_map": { + "visible": true, + "colorField": "rgb", + "colorMode": "rgb", + "colorMap": "turbo", + "pointSize": 3, + "maxValue": 30.3851, + "minValue": 0 + }, + "/cloud_obstacles": { + "visible": true, + "colorField": "rgb", + "colorMode": "rgb", + "colorMap": "turbo", + "pointSize": 3, + "stixelsEnabled": false, + "minValue": 0, + "maxValue": 30 + }, + "/local_grid_empty": { + "visible": false + }, + "/local_grid_ground": { + "visible": false + }, + "/local_grid_obstacle": { + "visible": false + }, + "/odom_local_map": { + "visible": false, + "colorField": "rgb", + "colorMode": "rgb", + "colorMap": "turbo", + "pointSize": 1.5 + }, + "/odom_last_frame": { + "visible": false, + "colorField": "z", + "colorMode": "colormap", + "colorMap": "turbo" + }, + "/odom_local_scan_map": { + "visible": false, + "pointSize": 6.72 + }, + "/robot_description": { + "visible": false, + "showOutlines": true, + "displayMode": "collision", + "opacity": 1, + "links": { + "rotor_0": { + "visible": true + }, + "firefly/base_link": { + "visible": true + }, + "firefly/rotor_0": { + "visible": true + } + }, + "fallbackColor": "7c6bffff", + "showAxis": false, + "axisScale": 0.25 + }, + "/local_path": { + "visible": false, + "lineWidth": 4.0226 + }, + "/cam0/image_raw": { + "visible": false, + "distance": 0.076, + "cameraInfoTopic": "/stereo_camera/left/camera_info" + }, + "/stereo_camera/left/image_color": { + "visible": false, + "frameLocked": true, + "cameraInfoTopic": "/stereo_camera/left/camera_info", + "planarProjectionFactor": 0, + "color": "#ffffff40", + "distance": 0.3 + }, + "/stereo_camera/left/camera_info": { + "visible": false, + "distance": 0.3, + "width": 0.005, + "color": "#7c6bffff" + }, + "/stereo_camera/right/camera_info": { + "visible": false + }, + "/stereo_camera/right/image_color/compressed": { + "visible": false + }, + "/stereo_camera/right/image_color": { + "visible": false, + "frameLocked": true, + "cameraInfoTopic": "/stereo_camera/right/camera_info", + "distance": 1, + "planarProjectionFactor": 0, + "color": "#ffffff" + }, + "/global_path": { + "visible": false + }, + "/mapPath": { + "visible": true, + "lineWidth": 0.0298, + "gradient": [ + "#ffffff40", + "#82ff88ff" + ] + }, + "/localization_pose": { + "visible": false + }, + "/goal": { + "visible": false + }, + "/goal_out": { + "visible": false + }, + "/landmarks": { + "visible": false + } + }, + "layers": { + "grid": { + "visible": false, + "frameLocked": true, + "label": "Grid", + "instanceId": "45fc1d0b-01ee-4ba4-8d89-cd6a6ce5aaf5", + "layerId": "foxglove.Grid", + "frameId": "world", + "size": 10, + "divisions": 10, + "lineWidth": 1, + "color": "#248eff", + "position": [ + 0, + 0, + 0 + ], + "rotation": [ + 0, + 0, + 0 + ] + }, + "aa62192e-7ac7-4588-8016-908eda65a1fa": { + "displayMode": "visual", + "fallbackColor": "#ffffff", + "showAxis": false, + "axisScale": 1, + "showOutlines": true, + "opacity": 1, + "visible": true, + "frameLocked": true, + "instanceId": "aa62192e-7ac7-4588-8016-908eda65a1fa", + "label": "URDF", + "layerId": "foxglove.Urdf", + "sourceType": "url", + "url": "https://cdn.jsdelivr.net/gh/cKohl10/tutorials@main/datasets/EuRoC_MAV/ros2_ws/src/euroc_slam/urdf/firefly_url.urdf", + "filePath": "", + "parameter": "", + "topic": "", + "framePrefix": "", + "order": 1 + } + }, + "publish": { + "type": "point", + "poseTopic": "/move_base_simple/goal", + "pointTopic": "/clicked_point", + "poseEstimateTopic": "/initialpose", + "poseEstimateXDeviation": 0.5, + "poseEstimateYDeviation": 0.5, + "poseEstimateThetaDeviation": 0.26179939 + }, + "imageMode": {}, + "followTf": "world" + }, + "3D!2hjtaq6": { + "cameraState": { + "distance": 1.020937373671968, + "perspective": true, + "phi": 74.03298350824883, + "target": [ + 0, + 0, + 0 + ], + "targetOffset": [ + -0.00042604209219607224, + 0.0011943089130383906, + 1.407789781828545e-19 + ], + "targetOrientation": [ + 0, + 0, + 0, + 1 + ], + "thetaOffset": 90.3373313343349, + "fovy": 45, + "near": 0.5, + "far": 5000 + }, + "followMode": "follow-pose", + "followTf": "base_link", + "scene": { + "transforms": { + "visible": true, + "showLabel": false, + "axisScale": 0.245 + } + }, + "transforms": { + "frame:vicon/firefly_sbx/firefly_sbx": { + "visible": false + }, + "frame:base_link_gt": { + "visible": false + }, + "frame:world": { + "visible": false + }, + "frame:map": { + "visible": false + }, + "frame:odom": { + "visible": false + }, + "frame:firefly/base_link": { + "visible": true + }, + "frame:firefly/base_link_inertia": { + "visible": false + }, + "frame:firefly/rotor_0": { + "visible": true + }, + "frame:firefly/rotor_1": { + "visible": true + }, + "frame:firefly/rotor_2": { + "visible": true + }, + "frame:firefly/rotor_3": { + "visible": true + }, + "frame:base_link": { + "visible": false + }, + "frame:imu4": { + "visible": false + }, + "frame:cam0": { + "visible": false + }, + "frame:cam1": { + "visible": false + } + }, + "topics": { + "/robot_description": { + "visible": false, + "opacity": 1, + "displayMode": "collision", + "fallbackColor": "#7c6bff" + }, + "/cloud_obstacles": { + "visible": true, + "colorField": "rgb", + "colorMode": "rgb", + "colorMap": "turbo" + }, + "/cloud_map": { + "visible": true, + "colorField": "rgb", + "colorMode": "rgb", + "colorMap": "turbo" + }, + "/cloud_ground": { + "visible": true, + "colorField": "rgb", + "colorMode": "rgb", + "colorMap": "turbo" + }, + "/local_grid_empty": { + "visible": false + }, + "/local_grid_ground": { + "visible": false + }, + "/local_grid_obstacle": { + "visible": false + }, + "/octomap_ground": { + "visible": true, + "colorField": "rgb", + "colorMode": "rgb", + "colorMap": "turbo", + "pointSize": 4 + }, + "/octomap_obstacles": { + "visible": true, + "colorField": "rgb", + "colorMode": "rgb", + "colorMap": "turbo", + "pointSize": 4 + }, + "/octomap_occupied_space": { + "visible": true, + "colorField": "rgb", + "colorMode": "rgb", + "colorMap": "turbo", + "pointSize": 4 + }, + "/odom_last_frame": { + "visible": true, + "colorField": "z", + "colorMode": "colormap", + "colorMap": "turbo", + "pointSize": 4 + }, + "/odom_local_map": { + "visible": true, + "colorField": "rgb", + "colorMode": "rgb", + "colorMap": "turbo", + "pointSize": 4 + }, + "/odom_local_scan_map": { + "visible": true, + "pointSize": 4 + }, + "/stereo_camera/left/camera_info": { + "visible": true, + "distance": 0.25, + "color": "#33ff0066" + }, + "/stereo_camera/left/image_color": { + "visible": true, + "frameLocked": true, + "cameraInfoTopic": "/stereo_camera/left/camera_info", + "distance": 0.25, + "planarProjectionFactor": 0, + "color": "#ffffff91" + }, + "/cam1/image_raw": { + "visible": false + }, + "/cam0/image_raw": { + "visible": false, + "cameraInfoTopic": "/stereo_camera/left/camera_info", + "distance": 0.379, + "color": "#ff9999ff" + } + }, + "layers": { + "grid": { + "visible": false, + "frameLocked": true, + "label": "Grid", + "instanceId": "8822c6fc-a84d-4646-a09c-11abad4be96e", + "layerId": "foxglove.Grid", + "size": 10, + "divisions": 10, + "lineWidth": 1, + "color": "#248eff", + "position": [ + 0, + 0, + 0 + ], + "rotation": [ + 0, + 0, + 0 + ] + }, + "09b75daa-dca9-4285-9170-0a3abb65d0c3": { + "displayMode": "auto", + "fallbackColor": "#ffffff", + "showAxis": false, + "axisScale": 1, + "showOutlines": true, + "opacity": 1, + "visible": true, + "frameLocked": true, + "instanceId": "09b75daa-dca9-4285-9170-0a3abb65d0c3", + "label": "URDF", + "layerId": "foxglove.Urdf", + "sourceType": "url", + "url": "https://cdn.jsdelivr.net/gh/cKohl10/tutorials@main/datasets/EuRoC_MAV/ros2_ws/src/euroc_slam/urdf/firefly_url.urdfhttps://cdn.jsdelivr.net/gh/cKohl10/tutorials@main/datasets/EuRoC_MAV/ros2_ws/src/euroc_slam/urdf/firefly_url.urdf", + "filePath": "", + "parameter": "", + "topic": "", + "framePrefix": "", + "order": 1 + } + }, + "publish": { + "type": "point", + "poseTopic": "/move_base_simple/goal", + "pointTopic": "/clicked_point", + "poseEstimateTopic": "/initialpose", + "poseEstimateXDeviation": 0.5, + "poseEstimateYDeviation": 0.5, + "poseEstimateThetaDeviation": 0.26179939 + }, + "imageMode": {} + }, + "Image!2s8oxaz": { + "cameraState": { + "distance": 20, + "perspective": true, + "phi": 60, + "target": [ + 0, + 0, + 0 + ], + "targetOffset": [ + 0, + 0, + 0 + ], + "targetOrientation": [ + 0, + 0, + 0, + 1 + ], + "thetaOffset": 45, + "fovy": 45, + "near": 0.5, + "far": 5000 + }, + "followMode": "follow-pose", + "scene": {}, + "transforms": {}, + "topics": { + "/local_grid_obstacle": { + "visible": false + }, + "/local_grid_ground": { + "visible": false + }, + "/local_grid_empty": { + "visible": false + }, + "/cloud_obstacles": { + "visible": false + }, + "/cloud_map": { + "visible": false, + "colorField": "rgb", + "colorMode": "rgb", + "colorMap": "turbo" + }, + "/odom_local_scan_map": { + "visible": false + }, + "/odom_local_map": { + "visible": true, + "colorField": "rgb", + "colorMode": "rgb", + "colorMap": "turbo", + "pointSize": 3.74 + }, + "/local_path": { + "visible": false, + "lineWidth": 0.238, + "gradient": [ + "#ab005eff", + "#ff124180" + ], + "type": "line" + }, + "/mapPath": { + "visible": false, + "lineWidth": 0.2186 + }, + "/global_path": { + "visible": false + }, + "/map": { + "visible": false + }, + "/labels": { + "visible": false + } + }, + "layers": {}, + "publish": { + "type": "point", + "poseTopic": "/move_base_simple/goal", + "pointTopic": "/clicked_point", + "poseEstimateTopic": "/initialpose", + "poseEstimateXDeviation": 0.5, + "poseEstimateYDeviation": 0.5, + "poseEstimateThetaDeviation": 0.26179939 + }, + "imageMode": { + "imageTopic": "/cam0/image_raw", + "calibrationTopic": "/stereo_camera/left/camera_info" + } + }, + "Plot!40eigil": { + "paths": [ + { + "timestampMethod": "receiveTime", + "value": "/imu0.angular_velocity.x", + "enabled": true, + "color": "#4e98e2", + "label": "Angular Velocity X", + "lineSize": 2 + }, + { + "timestampMethod": "receiveTime", + "value": "/imu0.angular_velocity.y", + "enabled": true, + "color": "#f5774d", + "label": "Angular Velocity Y", + "lineSize": 2 + }, + { + "timestampMethod": "receiveTime", + "value": "/imu0.angular_velocity.z", + "enabled": true, + "color": "#f7df71", + "label": "Angular Velocity Z", + "lineSize": 2 + } + ], + "showXAxisLabels": true, + "showYAxisLabels": true, + "showLegend": true, + "legendDisplay": "floating", + "showPlotValuesInLegend": false, + "isSynced": true, + "xAxisVal": "timestamp", + "sidebarDimension": 240, + "timeWindowMode": "sliding", + "followingViewWidth": 20, + "xAxisLabel": "Time (s)", + "yAxisLabel": "Angular Velocity (rad/s)", + "foxglovePanelTitle": "IMU0 Data" + }, + "Gauge!1r58yff": { + "path": "/tf.transforms[:]{child_frame_id==\"base_link\"}.transform.translation.z", + "minValue": -3, + "maxValue": 2, + "colorMap": "red-yellow-green", + "colorMode": "colormap", + "gradient": [ + "#0000ff", + "#ff00ff" + ], + "reverse": false, + "foxglovePanelTitle": "Altitude" + } + }, + "globalVariables": {}, + "userNodes": {}, + "playbackConfig": { + "speed": 1 + }, + "layout": { + "first": { + "first": "3D!1olov4a", + "second": { + "first": "3D!2hjtaq6", + "second": "Image!2s8oxaz", + "direction": "column" + }, + "direction": "row", + "splitPercentage": 65.51012940354613 + }, + "second": { + "first": "Plot!40eigil", + "second": "Gauge!1r58yff", + "direction": "row", + "splitPercentage": 80.73251056185755 + }, + "direction": "column", + "splitPercentage": 68.81258941344778 + } +} \ No newline at end of file diff --git a/datasets/EuRoC_MAV/media/MH01_Final_gif_cut.gif b/datasets/EuRoC_MAV/media/MH01_Final_gif_cut.gif new file mode 100644 index 0000000..683feb7 Binary files /dev/null and b/datasets/EuRoC_MAV/media/MH01_Final_gif_cut.gif differ diff --git a/datasets/EuRoC_MAV/media/close.png b/datasets/EuRoC_MAV/media/close.png new file mode 100644 index 0000000..a42ba6d Binary files /dev/null and b/datasets/EuRoC_MAV/media/close.png differ diff --git a/datasets/EuRoC_MAV/media/far.png b/datasets/EuRoC_MAV/media/far.png new file mode 100644 index 0000000..a006657 Binary files /dev/null and b/datasets/EuRoC_MAV/media/far.png differ diff --git a/datasets/EuRoC_MAV/media/far_grey.png b/datasets/EuRoC_MAV/media/far_grey.png new file mode 100644 index 0000000..54957a4 Binary files /dev/null and b/datasets/EuRoC_MAV/media/far_grey.png differ diff --git a/datasets/EuRoC_MAV/media/final_viz.png b/datasets/EuRoC_MAV/media/final_viz.png new file mode 100644 index 0000000..4bfc7ec Binary files /dev/null and b/datasets/EuRoC_MAV/media/final_viz.png differ diff --git a/datasets/EuRoC_MAV/media/final_viz2.png b/datasets/EuRoC_MAV/media/final_viz2.png new file mode 100644 index 0000000..3c4f990 Binary files /dev/null and b/datasets/EuRoC_MAV/media/final_viz2.png differ diff --git a/datasets/EuRoC_MAV/media/full_header.png b/datasets/EuRoC_MAV/media/full_header.png new file mode 100644 index 0000000..759ff49 Binary files /dev/null and b/datasets/EuRoC_MAV/media/full_header.png differ diff --git a/datasets/EuRoC_MAV/media/model.png b/datasets/EuRoC_MAV/media/model.png new file mode 100644 index 0000000..84a272d Binary files /dev/null and b/datasets/EuRoC_MAV/media/model.png differ diff --git a/datasets/EuRoC_MAV/media/no_drone.png b/datasets/EuRoC_MAV/media/no_drone.png new file mode 100644 index 0000000..d5da4c5 Binary files /dev/null and b/datasets/EuRoC_MAV/media/no_drone.png differ diff --git a/datasets/EuRoC_MAV/media/no_drone_slam.png b/datasets/EuRoC_MAV/media/no_drone_slam.png new file mode 100644 index 0000000..4291e5c Binary files /dev/null and b/datasets/EuRoC_MAV/media/no_drone_slam.png differ diff --git a/datasets/EuRoC_MAV/media/slam_snapshot.png b/datasets/EuRoC_MAV/media/slam_snapshot.png new file mode 100644 index 0000000..edeefd6 Binary files /dev/null and b/datasets/EuRoC_MAV/media/slam_snapshot.png differ diff --git a/datasets/EuRoC_MAV/msgs/image_flat.msg b/datasets/EuRoC_MAV/msgs/image_flat.msg new file mode 100644 index 0000000..90b1f50 --- /dev/null +++ b/datasets/EuRoC_MAV/msgs/image_flat.msg @@ -0,0 +1,19 @@ +================================================================================ +MSG: builtin_interfaces/Time +int32 sec +uint32 nanosec + +================================================================================ +MSG: std_msgs/Header +builtin_interfaces/Time stamp +string frame_id + +================================================================================ +MSG: sensor_msgs/Image +std_msgs/Header header +uint32 height +uint32 width +string encoding +uint8 is_bigendian +uint32 step +uint8[] data \ No newline at end of file diff --git a/datasets/EuRoC_MAV/msgs/imu_flat.msg b/datasets/EuRoC_MAV/msgs/imu_flat.msg new file mode 100644 index 0000000..dd9a253 --- /dev/null +++ b/datasets/EuRoC_MAV/msgs/imu_flat.msg @@ -0,0 +1,32 @@ +================================================================================ +MSG: geometry_msgs/Vector3 +float64 x +float64 y +float64 z + +================================================================================ +MSG: geometry_msgs/Quaternion +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 + +================================================================================ +MSG: builtin_interfaces/Time +int32 sec +uint32 nanosec + +================================================================================ +MSG: std_msgs/Header +builtin_interfaces/Time stamp +string frame_id + +================================================================================ +MSG: sensor_msgs/Imu +std_msgs/Header header +geometry_msgs/Quaternion orientation +float64[9] orientation_covariance # Row major about x, y, z axes +geometry_msgs/Vector3 angular_velocity +float64[9] angular_velocity_covariance # Row major about x, y, z axes +geometry_msgs/Vector3 linear_acceleration +float64[9] linear_acceleration_covariance # Row major x, y z diff --git a/datasets/EuRoC_MAV/ros2_ws/.gitignore b/datasets/EuRoC_MAV/ros2_ws/.gitignore new file mode 100644 index 0000000..29cad58 --- /dev/null +++ b/datasets/EuRoC_MAV/ros2_ws/.gitignore @@ -0,0 +1,3 @@ +build/ +install/ +log/ \ No newline at end of file diff --git a/datasets/EuRoC_MAV/ros2_ws/src/euroc_slam/LICENSE b/datasets/EuRoC_MAV/ros2_ws/src/euroc_slam/LICENSE new file mode 100644 index 0000000..d645695 --- /dev/null +++ b/datasets/EuRoC_MAV/ros2_ws/src/euroc_slam/LICENSE @@ -0,0 +1,202 @@ + + Apache License + Version 2.0, January 2004 + http://www.apache.org/licenses/ + + TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION + + 1. Definitions. + + "License" shall mean the terms and conditions for use, reproduction, + and distribution as defined by Sections 1 through 9 of this document. + + "Licensor" shall mean the copyright owner or entity authorized by + the copyright owner that is granting the License. + + "Legal Entity" shall mean the union of the acting entity and all + other entities that control, are controlled by, or are under common + control with that entity. For the purposes of this definition, + "control" means (i) the power, direct or indirect, to cause the + direction or management of such entity, whether by contract or + otherwise, or (ii) ownership of fifty percent (50%) or more of the + outstanding shares, or (iii) beneficial ownership of such entity. + + "You" (or "Your") shall mean an individual or Legal Entity + exercising permissions granted by this License. + + "Source" form shall mean the preferred form for making modifications, + including but not limited to software source code, documentation + source, and configuration files. + + "Object" form shall mean any form resulting from mechanical + transformation or translation of a Source form, including but + not limited to compiled object code, generated documentation, + and conversions to other media types. + + "Work" shall mean the work of authorship, whether in Source or + Object form, made available under the License, as indicated by a + copyright notice that is included in or attached to the work + (an example is provided in the Appendix below). + + "Derivative Works" shall mean any work, whether in Source or Object + form, that is based on (or derived from) the Work and for which the + editorial revisions, annotations, elaborations, or other modifications + represent, as a whole, an original work of authorship. For the purposes + of this License, Derivative Works shall not include works that remain + separable from, or merely link (or bind by name) to the interfaces of, + the Work and Derivative Works thereof. + + "Contribution" shall mean any work of authorship, including + the original version of the Work and any modifications or additions + to that Work or Derivative Works thereof, that is intentionally + submitted to Licensor for inclusion in the Work by the copyright owner + or by an individual or Legal Entity authorized to submit on behalf of + the copyright owner. For the purposes of this definition, "submitted" + means any form of electronic, verbal, or written communication sent + to the Licensor or its representatives, including but not limited to + communication on electronic mailing lists, source code control systems, + and issue tracking systems that are managed by, or on behalf of, the + Licensor for the purpose of discussing and improving the Work, but + excluding communication that is conspicuously marked or otherwise + designated in writing by the copyright owner as "Not a Contribution." + + "Contributor" shall mean Licensor and any individual or Legal Entity + on behalf of whom a Contribution has been received by Licensor and + subsequently incorporated within the Work. + + 2. Grant of Copyright License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + copyright license to reproduce, prepare Derivative Works of, + publicly display, publicly perform, sublicense, and distribute the + Work and such Derivative Works in Source or Object form. + + 3. Grant of Patent License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + (except as stated in this section) patent license to make, have made, + use, offer to sell, sell, import, and otherwise transfer the Work, + where such license applies only to those patent claims licensable + by such Contributor that are necessarily infringed by their + Contribution(s) alone or by combination of their Contribution(s) + with the Work to which such Contribution(s) was submitted. If You + institute patent litigation against any entity (including a + cross-claim or counterclaim in a lawsuit) alleging that the Work + or a Contribution incorporated within the Work constitutes direct + or contributory patent infringement, then any patent licenses + granted to You under this License for that Work shall terminate + as of the date such litigation is filed. + + 4. Redistribution. You may reproduce and distribute copies of the + Work or Derivative Works thereof in any medium, with or without + modifications, and in Source or Object form, provided that You + meet the following conditions: + + (a) You must give any other recipients of the Work or + Derivative Works a copy of this License; and + + (b) You must cause any modified files to carry prominent notices + stating that You changed the files; and + + (c) You must retain, in the Source form of any Derivative Works + that You distribute, all copyright, patent, trademark, and + attribution notices from the Source form of the Work, + excluding those notices that do not pertain to any part of + the Derivative Works; and + + (d) If the Work includes a "NOTICE" text file as part of its + distribution, then any Derivative Works that You distribute must + include a readable copy of the attribution notices contained + within such NOTICE file, excluding those notices that do not + pertain to any part of the Derivative Works, in at least one + of the following places: within a NOTICE text file distributed + as part of the Derivative Works; within the Source form or + documentation, if provided along with the Derivative Works; or, + within a display generated by the Derivative Works, if and + wherever such third-party notices normally appear. The contents + of the NOTICE file are for informational purposes only and + do not modify the License. You may add Your own attribution + notices within Derivative Works that You distribute, alongside + or as an addendum to the NOTICE text from the Work, provided + that such additional attribution notices cannot be construed + as modifying the License. + + You may add Your own copyright statement to Your modifications and + may provide additional or different license terms and conditions + for use, reproduction, or distribution of Your modifications, or + for any such Derivative Works as a whole, provided Your use, + reproduction, and distribution of the Work otherwise complies with + the conditions stated in this License. + + 5. Submission of Contributions. Unless You explicitly state otherwise, + any Contribution intentionally submitted for inclusion in the Work + by You to the Licensor shall be under the terms and conditions of + this License, without any additional terms or conditions. + Notwithstanding the above, nothing herein shall supersede or modify + the terms of any separate license agreement you may have executed + with Licensor regarding such Contributions. + + 6. Trademarks. This License does not grant permission to use the trade + names, trademarks, service marks, or product names of the Licensor, + except as required for reasonable and customary use in describing the + origin of the Work and reproducing the content of the NOTICE file. + + 7. Disclaimer of Warranty. Unless required by applicable law or + agreed to in writing, Licensor provides the Work (and each + Contributor provides its Contributions) on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or + implied, including, without limitation, any warranties or conditions + of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A + PARTICULAR PURPOSE. You are solely responsible for determining the + appropriateness of using or redistributing the Work and assume any + risks associated with Your exercise of permissions under this License. + + 8. Limitation of Liability. In no event and under no legal theory, + whether in tort (including negligence), contract, or otherwise, + unless required by applicable law (such as deliberate and grossly + negligent acts) or agreed to in writing, shall any Contributor be + liable to You for damages, including any direct, indirect, special, + incidental, or consequential damages of any character arising as a + result of this License or out of the use or inability to use the + Work (including but not limited to damages for loss of goodwill, + work stoppage, computer failure or malfunction, or any and all + other commercial damages or losses), even if such Contributor + has been advised of the possibility of such damages. + + 9. Accepting Warranty or Additional Liability. While redistributing + the Work or Derivative Works thereof, You may choose to offer, + and charge a fee for, acceptance of support, warranty, indemnity, + or other liability obligations and/or rights consistent with this + License. However, in accepting such obligations, You may act only + on Your own behalf and on Your sole responsibility, not on behalf + of any other Contributor, and only if You agree to indemnify, + defend, and hold each Contributor harmless for any liability + incurred by, or claims asserted against, such Contributor by reason + of your accepting any such warranty or additional liability. + + END OF TERMS AND CONDITIONS + + APPENDIX: How to apply the Apache License to your work. + + To apply the Apache License to your work, attach the following + boilerplate notice, with the fields enclosed by brackets "[]" + replaced with your own identifying information. (Don't include + the brackets!) The text should be enclosed in the appropriate + comment syntax for the file format. We also recommend that a + file or class name and description of purpose be included on the + same "printed page" as the copyright notice for easier + identification within third-party archives. + + Copyright [yyyy] [name of copyright owner] + + 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. diff --git a/datasets/EuRoC_MAV/ros2_ws/src/euroc_slam/euroc_slam/__init__.py b/datasets/EuRoC_MAV/ros2_ws/src/euroc_slam/euroc_slam/__init__.py new file mode 100644 index 0000000..e69de29 diff --git a/datasets/EuRoC_MAV/ros2_ws/src/euroc_slam/euroc_slam/__pycache__/__init__.cpython-310.pyc b/datasets/EuRoC_MAV/ros2_ws/src/euroc_slam/euroc_slam/__pycache__/__init__.cpython-310.pyc new file mode 100644 index 0000000..b61377c Binary files /dev/null and b/datasets/EuRoC_MAV/ros2_ws/src/euroc_slam/euroc_slam/__pycache__/__init__.cpython-310.pyc differ diff --git a/datasets/EuRoC_MAV/ros2_ws/src/euroc_slam/euroc_slam/__pycache__/firefly_state_publisher.cpython-310.pyc b/datasets/EuRoC_MAV/ros2_ws/src/euroc_slam/euroc_slam/__pycache__/firefly_state_publisher.cpython-310.pyc new file mode 100644 index 0000000..df88dac Binary files /dev/null and b/datasets/EuRoC_MAV/ros2_ws/src/euroc_slam/euroc_slam/__pycache__/firefly_state_publisher.cpython-310.pyc differ diff --git a/datasets/EuRoC_MAV/ros2_ws/src/euroc_slam/euroc_slam/firefly_state_publisher.py b/datasets/EuRoC_MAV/ros2_ws/src/euroc_slam/euroc_slam/firefly_state_publisher.py new file mode 100644 index 0000000..97d265d --- /dev/null +++ b/datasets/EuRoC_MAV/ros2_ws/src/euroc_slam/euroc_slam/firefly_state_publisher.py @@ -0,0 +1,68 @@ +#!/usr/bin/env python3 +import rclpy +from rclpy.node import Node +from sensor_msgs.msg import JointState +import math + +class StatePublisher(Node): + def __init__(self): + super().__init__('firefly_state_publisher') + + # 1) spin_rate in revolutions per second + self.declare_parameter('spin_rate', 10.0) + self.spin_rate = self.get_parameter('spin_rate').get_parameter_value().double_value + + # 2) We’ll update at 30 Hz + self.update_hz = 30.0 + period = 1.0 / self.update_hz + + # 3) Precompute angular velocity (rad/s) and per‑tick increment + self.ang_vel = 2 * math.pi * self.spin_rate # rad/s + self.increment = self.ang_vel * period # rad per update + + # 4) JointState publisher + self.joint_pub = self.create_publisher(JointState, 'joint_states', 10) + self.joint_state = JointState() + self.joint_state.name = [ + 'firefly_rotor_0_joint', + 'firefly_rotor_1_joint', + 'firefly_rotor_2_joint', + 'firefly_rotor_3_joint', + 'firefly_rotor_4_joint', + 'firefly_rotor_5_joint', + ] + + self.angle = 0.0 # current angle in radians + + # 5) Timer instead of manual loop + self.create_timer(period, self.timer_callback) + self.get_logger().info(f'StatePublisher started: spin_rate={self.spin_rate} Hz, update={self.update_hz} Hz') + + def timer_callback(self): + # advance angle and wrap to [0, 2π) + self.angle = (self.angle + self.increment) % (2 * math.pi) + + # stamp and publish + now = self.get_clock().now().to_msg() + self.joint_state.header.stamp = now + + # alternate spin direction on adjacent rotors + positions = [] + for i in range(len(self.joint_state.name)): + sign = 1.0 if (i % 2 == 0) else -1.0 + positions.append(sign * self.angle) + self.joint_state.position = positions + + self.joint_pub.publish(self.joint_state) + +def main(args=None): + rclpy.init(args=args) + node = StatePublisher() + try: + rclpy.spin(node) + finally: + node.destroy_node() + rclpy.shutdown() + +if __name__ == '__main__': + main() diff --git a/datasets/EuRoC_MAV/ros2_ws/src/euroc_slam/launch/firefly.launch.py b/datasets/EuRoC_MAV/ros2_ws/src/euroc_slam/launch/firefly.launch.py new file mode 100644 index 0000000..20f7c4e --- /dev/null +++ b/datasets/EuRoC_MAV/ros2_ws/src/euroc_slam/launch/firefly.launch.py @@ -0,0 +1,68 @@ +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription, TimerAction +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import Command, LaunchConfiguration, PathJoinSubstitution +from launch_ros.actions import Node +from launch_ros.substitutions import FindPackageShare +from launch_ros.parameter_descriptions import ParameterValue + + +def generate_launch_description(): + use_sim_time = LaunchConfiguration('use_sim_time', default='false') + + # Load URDF file + urdf_file = PathJoinSubstitution([FindPackageShare('euroc_slam'), 'urdf', 'firefly.urdf']) + robot_description = ParameterValue(Command(['cat ', urdf_file]), value_type=str) + + # Create nodes + foxglove_bridge_node = Node( + package='foxglove_bridge', + executable='foxglove_bridge', + name='foxglove_bridge', + output='screen', + ) + + robot_state_publisher_node = Node( + package='robot_state_publisher', + executable='robot_state_publisher', + name='robot_state_publisher', + output='screen', + parameters=[{'use_sim_time': use_sim_time, 'robot_description': robot_description}] + ) + + static_transform_publisher_node = Node( + package='tf2_ros', + executable='static_transform_publisher', + name='static_transform_publisher', + output='screen', + arguments=['0', '0', '0', '0', '0', '0', 'base_link', 'firefly_base_link'] + ) + + firefly_state_publisher_node = Node( + package='euroc_slam', + executable='firefly_state_publisher', + name='firefly_state_publisher', + output='screen' + ) + + rtabmap_include = IncludeLaunchDescription( + PythonLaunchDescriptionSource([ + FindPackageShare('rtabmap_examples'), + '/launch/euroc_datasets.launch.py' + ]), + launch_arguments={ + 'gt': 'false' + }.items() + ) + + return LaunchDescription([ + DeclareLaunchArgument( + 'use_sim_time', + default_value='false', + description='Use simulation (Gazebo) clock if true'), + foxglove_bridge_node, + TimerAction(period=1.0, actions=[robot_state_publisher_node]), # 2 second delay + TimerAction(period=2.0, actions=[rtabmap_include]), + TimerAction(period=3.0, actions=[firefly_state_publisher_node]), + TimerAction(period=4.0, actions=[static_transform_publisher_node]) + ]) diff --git a/datasets/EuRoC_MAV/ros2_ws/src/euroc_slam/meshes/firefly_purple.dae b/datasets/EuRoC_MAV/ros2_ws/src/euroc_slam/meshes/firefly_purple.dae new file mode 100644 index 0000000..9c20216 --- /dev/null +++ b/datasets/EuRoC_MAV/ros2_ws/src/euroc_slam/meshes/firefly_purple.dae @@ -0,0 +1,90 @@ + + + + + Blender User + Blender 4.4.3 commit date:2025-04-29, commit time:14:09, hash:802179c51ccc + + 2025-06-29T16:22:36 + 2025-06-29T16:22:36 + + Z_UP + + + + + + + + 0 0 0 1 + + + 0.2015545 0.1470271 1 1 + + + 1.4 + + + + + + + + + + + + + + + + + -0.04449999 -0.07105237 0.01069998 -0.04349994 -0.0716297 0.01069998 -0.04449999 -0.07105237 0.01189994 -0.04349994 -0.0716297 0.01189994 -0.03710907 -0.07531946 0.01069998 -0.03375959 -0.07725328 0.01069998 -0.04449999 -0.06466007 0.01189994 -0.03637218 -0.06535255 0.01189994 -0.03637218 -0.06535255 0.01069998 -0.03428477 -0.06727057 0.01189994 -0.0343104 -0.06688129 0.01189994 -0.0343104 -0.06688129 0.01069998 -0.03448289 -0.0665313 0.01069998 -0.03448289 -0.0665313 0.01189994 -0.03477627 -0.0662741 0.01189994 -0.03477627 -0.0662741 0.01069998 -0.0157237 -0.07727408 0.01189994 -0.01499998 -0.08678519 0.01189994 -0.01499998 -0.08412688 0.01189994 -0.01499998 -0.07812488 0.01069998 -0.01499998 -0.07872378 0.01189994 -0.01510047 -0.08716017 0.01069998 -0.01537495 -0.0874347 0.01069998 -0.01574999 -0.0875352 0.01189994 -0.01612496 -0.0874347 0.01189994 -0.02801787 -0.08056825 0.01069998 -0.02185428 -0.08412688 0.01189994 -0.02064436 -0.08482539 0.01189994 -0.01671439 -0.08709436 0.01189994 -0.01671439 -0.08709436 0.01069998 -0.02695298 -0.07872378 0.01189994 -0.02695298 -0.07872378 0.01069998 -0.02549195 -0.07619327 0.01069998 -0.02064436 -0.078992 0.01189994 -0.01806378 -0.07932716 0.01069998 -0.01771539 -0.07872378 0.01189994 -0.01708966 -0.07764005 0.01189994 -0.04699999 -0.03875374 0.01069998 -0.04699999 -0.04373538 0.01189994 -0.04699999 -0.04899996 0.01069998 -0.04699999 -0.04899996 0.01189994 -0.05274999 -0.04899996 0.01189994 -0.05274999 -0.04899996 0.01069998 -0.05274999 -0.04373538 0.01189994 -0.05274999 -0.03875374 0.01069998 0.05274999 -0.03875374 0.01189994 0.05274999 -0.04373538 0.01189994 0.05274999 -0.03875374 0.01069998 0.05274999 -0.04373538 0.01069998 0.05037498 -0.03875374 0.01189994 0.05037498 -0.03875374 0.01069998 0.04699999 -0.04899996 0.01069998 0.04699999 -0.03875374 0.01189994 -0.007499992 -0.0625 0.01189994 -0.007499992 -0.06535255 0.01069998 -0.02437216 -0.06535255 0.01069998 -0.01671439 -0.06977385 0.01189994 -0.007874965 -0.07487726 0.01069998 -0.03049999 -0.05609047 0.01189994 -0.02974998 -0.05038297 0.01189994 -0.02974998 -0.05038297 0.01069998 -0.03029894 -0.05093199 0.01189994 -0.03029894 -0.05093199 0.01069998 -0.02824997 -0.05038297 0.01069998 -0.02824997 -0.05038297 0.01189994 -0.01199996 -0.0625 0.01189994 -0.01671439 -0.06053739 0.01069998 -0.01927858 -0.05609047 0.01069998 -0.01927858 -0.05609047 0.01189994 -0.0194869 -0.05544239 0.01069998 0.04299998 -0.04959785 0.01189994 0.04299998 -0.04959785 0.01069998 0.04299998 -0.04499995 0.01069998 0.03599995 -0.04499995 0.01189994 0.03524994 -0.045201 0.01189994 0.03470098 -0.04574996 0.01069998 0.0345 -0.04649996 0.01069998 0.0345 -0.04649996 0.01189994 0.0345 -0.0595054 0.01069998 0.003866016 -0.0715 0.01189994 0.003499984 -0.07113397 0.01069998 0.002999961 -0.07099997 0.01069998 0.002999961 -0.07099997 0.01189994 0.002499997 -0.07113397 0.01069998 0.002133965 -0.0715 0.01069998 0.002133965 -0.0715 0.01189994 0.003999948 -0.07199996 0.01189994 0.003999948 -0.074 0.01069998 0.001999974 -0.074 0.01069998 0.002133965 -0.07449996 0.01189994 0.002133965 -0.07449996 0.01069998 0.002499997 -0.07486599 0.01189994 0.002999961 -0.07499998 0.01189994 0.002499997 -0.07486599 0.01069998 0.003499984 -0.07486599 0.01069998 0.003499984 -0.07486599 0.01189994 0.003866016 -0.07449996 0.01189994 0.003866016 -0.07449996 0.01069998 0.001999974 -0.074 0.01189994 0.001999974 -0.07199996 0.01189994 -0.001999974 -0.07199996 0.01069998 -0.002999961 -0.07099997 0.01189994 -0.002499997 -0.07113397 0.01069998 -0.002999961 -0.07099997 0.01069998 -0.003499984 -0.07113397 0.01069998 -0.003499984 -0.07113397 0.01189994 -0.003749966 -0.07138395 0.01069998 -0.003866016 -0.0715 0.01189994 -0.003866016 -0.0715 0.01069998 -0.001999974 -0.074 0.01069998 -0.003999948 -0.074 0.01189994 -0.003866016 -0.07449996 0.01069998 -0.003749966 -0.07461595 0.01069998 -0.003499984 -0.07486599 0.01069998 -0.003499984 -0.07486599 0.01189994 -0.002999961 -0.07499998 0.01069998 -0.002499997 -0.07486599 0.01189994 -0.002499997 -0.07486599 0.01069998 -0.002133965 -0.07449996 0.01189994 -0.003999948 -0.074 0.01069998 0.04699999 -0.06099998 0.01189994 0.04749995 -0.06086599 0.01189994 0.04786598 -0.06049996 0.01189994 0.04799997 -0.06 0.01069998 0.04786598 -0.05949997 0.01189994 0.04786598 -0.05949997 0.01069998 0.04699999 -0.05899995 0.01189994 0.04699999 -0.05899995 0.01069998 0.04499995 -0.05899995 0.01069998 0.04413396 -0.05949997 0.01069998 0.04413396 -0.05949997 0.01189994 0.04399996 -0.06 0.01189994 0.04413396 -0.06049996 0.01069998 0.04449999 -0.06086599 0.01189994 0.04449999 -0.06086599 0.01069998 0.04699999 -0.055 0.01189994 0.04699999 -0.055 0.01069998 0.04749995 -0.05486595 0.01069998 0.04786598 -0.05449998 0.01189994 0.04786598 -0.05349999 0.01069998 0.04749995 -0.05313396 0.01189994 0.04699999 -0.05299997 0.01189994 0.04499995 -0.05299997 0.01189994 0.04499995 -0.05299997 0.01069998 0.04449999 -0.05313396 0.01189994 0.04413396 -0.05349999 0.01189994 0.04449999 -0.05313396 0.01069998 0.04413396 -0.05449998 0.01189994 0.04499995 -0.055 0.01189994 0.04449999 -0.05486595 0.01069998 0.04499995 -0.055 0.01069998 -0.04699999 -0.05899995 0.01189994 -0.04699999 -0.05899995 0.01069998 -0.04749995 -0.05913394 0.01069998 -0.04799997 -0.06 0.01189994 -0.04799997 -0.06 0.01069998 -0.04786598 -0.06049996 0.01069998 -0.04749995 -0.06086599 0.01189994 -0.04749995 -0.06086599 0.01069998 -0.04699999 -0.06099998 0.01069998 -0.04749995 -0.05313396 0.01069998 -0.04786598 -0.05349999 0.01069998 -0.04786598 -0.05449998 0.01069998 -0.04749995 -0.05486595 0.01069998 0.05799996 -0.04224997 0.01189994 0.05737495 -0.04208248 0.01189994 0.05691748 -0.04162496 0.01069998 0.05691748 -0.04162496 0.01189994 0.05674999 -0.04099994 0.01189994 0.05691748 -0.04037499 0.01189994 0.05737495 -0.03991746 0.01189994 0.05737495 -0.03991746 0.01069998 0.05799996 -0.03974997 0.01069998 0.05862498 -0.03991746 0.01069998 0.05908244 -0.04037499 0.01069998 0.05862498 -0.03991746 0.01189994 0.05924999 -0.04099994 0.01069998 0.05924999 -0.04099994 0.01189994 0.05862498 -0.04208248 0.01069998 0.05862498 -0.04208248 0.01189994 -0.05799996 -0.04224997 0.01069998 -0.05862498 -0.04208248 0.01069998 -0.05908244 -0.04162496 0.01069998 -0.05924999 -0.04099994 0.01069998 -0.05908244 -0.04037499 0.01069998 -0.05908244 -0.04037499 0.01189994 -0.05737495 -0.03991746 0.01069998 -0.05737495 -0.03991746 0.01189994 -0.05691748 -0.04037499 0.01069998 -0.05674999 -0.04099994 0.01189994 -0.05691748 -0.04162496 0.01189994 -0.05737495 -0.04208248 0.01189994 0.07385855 -0.0428732 0.01069998 0.07385855 -0.0428732 0.01189994 0.07405859 -0.04252678 0.01069998 0.07405859 -0.04252678 0.01189994 0.07505857 -0.04252678 0.01189994 0.08054035 -0.04569166 0.01189994 0.08054035 -0.04569166 0.01069998 0.08672219 -0.04926079 0.01069998 0.07435858 -0.04373919 0.01189994 0.08054035 -0.04730826 0.01069998 0.08054035 -0.04730826 0.01189994 0.08431857 -0.04948955 0.01069998 0.08602219 -0.05047315 0.01069998 0.08431857 -0.04948955 0.01189994 7e-4 -0.099734 0.01189994 7e-4 -0.09784388 0.01069998 7e-4 -0.08925718 0.01069998 7e-4 -0.08626598 0.01069998 7e-4 -0.08626598 0.01189994 -7e-4 -0.09784388 0.01189994 -7e-4 -0.08925718 0.01189994 -7e-4 -0.08925718 0.01069998 -7e-4 -0.08626598 0.01069998 -0.08602219 -0.05047315 0.01069998 -0.08602219 -0.05047315 0.01189994 -0.07435858 -0.04373919 0.01189994 -0.08672219 -0.04926079 0.01189994 -0.07715189 -0.04373538 0.01189994 -0.07505857 -0.04252678 0.01189994 -0.07412558 -0.04227679 0.01189994 -0.07455855 -0.04202675 0.01189994 -0.07480859 -0.04209375 0.01069998 -0.07499158 -0.04227679 0.01189994 -0.02799999 -0.04373538 0.01189994 -0.02799999 -0.04373538 0.01069998 -0.02799999 -0.02999997 0.01189994 -0.0309596 -0.02999997 0.01189994 -0.03375959 -0.02999997 0.01189994 -0.04299998 -0.02999997 0.01069998 -0.04349994 -0.03275376 0.01069998 -0.04299998 -0.03275376 0.01069998 -0.05524998 -0.0345453 0.01069998 -0.05524998 -0.03350377 0.01189994 -0.05549997 -0.03547829 0.01189994 -0.05524998 -0.03541129 0.01069998 -0.05524998 -0.03541129 0.01189994 -0.055067 -0.03522825 0.01069998 -0.055 -0.03497827 0.01069998 -0.055067 -0.03472828 0.01189994 -0.05649995 -0.03541129 0.01069998 -0.06074994 -0.0345453 0.01189994 -0.06074994 -0.0345453 0.01069998 -0.0687313 -0.03275376 0.01069998 -0.07369947 -0.02988547 0.01069998 -0.07673126 -0.028135 0.01069998 -0.09342759 -0.04373538 0.01069998 -0.09546309 -0.04752308 0.01189994 -0.0943278 -0.04948955 0.01189994 -0.0943278 -0.04948955 0.01069998 -0.08863955 -0.05934184 0.01189994 -0.0747832 -0.05934184 0.01069998 -0.07270997 -0.06053876 0.01069998 -0.07061219 -0.06174999 0.01069998 -0.0663284 -0.06414836 0.01189994 -0.06601816 -0.06411576 0.01189994 -0.06601816 -0.06411576 0.01069998 -0.06556481 -0.06370747 0.01189994 -0.06556481 -0.06370747 0.01069998 -0.06074994 -0.06073075 0.01189994 -0.0640307 -0.06073075 0.01189994 -0.06049996 -0.05616378 0.01069998 -0.06074994 -0.05623078 0.01069998 -0.06074994 -0.05623078 0.01189994 -0.06099998 -0.05666375 0.01189994 -0.06093299 -0.05691379 0.01069998 -0.06074994 -0.05709677 0.01189994 -0.05649995 -0.05623078 0.01069998 -0.05524998 -0.05709677 0.01189994 -0.05049997 -0.06535255 0.01069998 -0.05049997 -0.06174999 0.01189994 -0.02064436 -0.09059888 0.01189994 -0.0309596 -0.08464336 0.01069998 -0.02296829 -0.08925718 0.01189994 -0.03185427 -0.08412688 0.01069998 -0.03375959 -0.08302676 0.01189994 -0.04349994 -0.07740318 0.01069998 -0.04574996 -0.07610416 0.01189994 -0.04710906 -0.07531946 0.01189994 -0.04710906 -0.07531946 0.01069998 -0.050125 -0.07357829 0.01069998 -0.01399999 -0.09443509 0.01069998 -0.01203185 -0.09784388 0.01189994 -0.007071793 -0.106435 0.01189994 0.001874983 -0.106435 0.01189994 -0.001874983 -0.106435 0.01069998 -0.003749966 -0.106435 0.01069998 -0.007071793 -0.106435 0.01069998 0.006575286 -0.106435 0.01189994 0.01189088 -0.09784388 0.01069998 0.01189088 -0.09784388 0.01189994 0.01337498 -0.09544515 0.01189994 0.02064436 -0.09059888 0.01069998 0.02296829 -0.08925718 0.01069998 0.02848696 -0.08607095 0.01189994 0.0309596 -0.08464336 0.01189994 0.03185427 -0.08412688 0.01189994 0.0309596 -0.08464336 0.01069998 0.03185427 -0.08412688 0.01069998 0.03375959 -0.08302676 0.01069998 0.03375959 -0.08302676 0.01189994 0.04121267 -0.07872378 0.01189994 0.04349994 -0.07740318 0.01189994 0.04121267 -0.07872378 0.01069998 0.04349994 -0.07740318 0.01069998 0.050125 -0.07357829 0.01189994 0.05049997 -0.07292878 0.01189994 0.05049997 -0.06535255 0.01189994 0.05049997 -0.06174999 0.01069998 0.05049997 -0.06073075 0.01189994 0.05049997 -0.06073075 0.01069998 0.05524998 -0.05709677 0.01189994 0.05524998 -0.06073075 0.01189994 0.06024998 -0.05623078 0.01069998 0.05949997 -0.05623078 0.01069998 0.06074994 -0.05709677 0.01069998 0.06556481 -0.06370747 0.01069998 0.06556481 -0.06370747 0.01189994 0.06601816 -0.06411576 0.01189994 0.0663284 -0.06414836 0.01069998 0.0663284 -0.06414836 0.01189994 0.06662499 -0.06405198 0.01069998 0.07270997 -0.06053876 0.01069998 0.07270997 -0.06053876 0.01189994 0.07061219 -0.06174999 0.01069998 0.07061219 -0.06174999 0.01189994 0.08054035 -0.05916637 0.01189994 0.08888781 -0.05891185 0.01189994 0.0873813 -0.05895787 0.01069998 0.09571141 -0.04709315 0.01189994 0.09571141 -0.04709315 0.01069998 0.0937727 -0.04373538 0.01069998 0.0887832 -0.03509318 0.01069998 0.0873813 -0.03428375 0.01069998 0.07270997 -0.03045678 0.01189994 0.0687313 -0.03275376 0.01189994 0.06149995 -0.03275376 0.01189994 0.0608505 -0.03312879 0.01069998 0.06112498 -0.03285425 0.01189994 0.0608505 -0.03312879 0.01189994 0.06049996 -0.03547829 0.01189994 0.06074994 -0.03541129 0.01069998 0.06099998 -0.03497827 0.01069998 0.06074994 -0.0345453 0.01189994 0.06074994 -0.0345453 0.01069998 0.06024998 -0.03541129 0.01189994 0.05949997 -0.03541129 0.01189994 0.05574995 -0.03541129 0.01189994 0.05524998 -0.0345453 0.01189994 0.055067 -0.03472828 0.01189994 0.055067 -0.03472828 0.01069998 0.055 -0.03497827 0.01189994 0.055067 -0.03522825 0.01069998 0.05524998 -0.03541129 0.01069998 0.05524998 -0.03541129 0.01189994 0.05549997 -0.03547829 0.01069998 0.05037498 -0.03275376 0.01189994 0.04349994 -0.03275376 0.01189994 0.04299998 -0.03275376 0.01189994 0.0309596 -0.02999997 0.01069998 0.02848696 -0.02999997 0.01069998 0.02799999 -0.02999997 0.01189994 0.02799999 -0.04475378 0.01189994 -0.02107179 -0.04875379 0.01069998 -0.01475 -0.04875379 0.01069998 -0.01475 -0.04875379 0.01189994 -0.01577627 -0.05368095 0.01069998 -0.01596045 -0.05556076 0.01189994 -0.01574945 -0.05609047 0.01189994 -0.01337498 -0.05866587 0.01189994 -0.01199996 -0.05899995 0.01069998 -0.008738398 -0.05731558 0.01189994 -0.01016455 -0.05855399 0.01069998 -0.008738398 -0.05731558 0.01069998 -0.008250415 -0.05609047 0.01069998 -0.008039474 -0.05556076 0.01069998 -0.009249985 -0.04948955 0.01189994 -0.009249985 -0.05209529 0.01069998 -0.009249985 -0.04875379 0.01189994 -0.003749966 -0.04875379 0.01069998 -0.002749979 -0.04948955 0.01189994 -0.002749979 -0.04948955 0.01069998 0 -0.05899995 0.01069998 -0.00396049 -0.05556076 0.01069998 -0.002749979 -0.05209529 0.01069998 -0.002749979 -0.05209529 0.01189994 -0.003776252 -0.05368095 0.01189994 -0.003749489 -0.05609047 0.01069998 -0.003749966 -0.05608928 0.01189994 -0.003749489 -0.05609047 0.01189994 -0.003261566 -0.05731558 0.01069998 -0.003261566 -0.05731558 0.01189994 -0.001874983 -0.05851966 0.01189994 -0.001835405 -0.05855399 0.01069998 -0.001835405 -0.05855399 0.01189994 0 -0.05899995 0.01189994 0.001349985 -0.05867195 0.01069998 0.001835405 -0.05855399 0.01069998 0.001835405 -0.05855399 0.01189994 0.001874983 -0.05851966 0.01189994 0.003749489 -0.05609047 0.01069998 0.003749489 -0.05609047 0.01189994 0.00396049 -0.05556076 0.01189994 0.00396049 -0.05556076 0.01069998 0.002749979 -0.05209529 0.01189994 0.002749979 -0.04875379 0.01069998 0.02107179 -0.04875379 0.01069998 0.01475 -0.04875379 0.01189994 0.01475 -0.04875379 0.01069998 0.01526159 -0.05731558 0.01069998 0.01383537 -0.05855399 0.01069998 0.008223712 -0.05368095 0.01189994 0.008039474 -0.05556076 0.01069998 0.008738398 -0.05731558 0.01189994 0.01199996 -0.05899995 0.01189994 0.01337498 -0.05866587 0.01189994 0.01596045 -0.05556076 0.01189994 0.01577627 -0.05368095 0.01189994 0.009249985 -0.05209529 0.01189994 0.009249985 -0.04875379 0.01189994 0.002749979 -0.04875379 0.01189994 0.03049999 -0.05609047 0.01189994 0.03049999 -0.06174999 0.01189994 0.03049999 -0.05609047 0.01069998 0.03049999 -0.06181478 0.01189994 0.03049999 -0.06174999 0.01069998 0.01337498 -0.07170188 0.01189994 0.02064436 -0.06750488 0.01189994 0.02437216 -0.06535255 0.01069998 0.02848696 -0.06297689 0.01069998 0.02848696 -0.06297689 0.01189994 0.007499992 -0.0625 0.01189994 0.02064436 -0.0547741 0.01189994 0.01834267 -0.05900257 0.01189994 0.01199996 -0.0625 0.01189994 0.01337498 -0.06214594 0.01189994 0.01337498 -0.06214594 0.01069998 0.01491338 -0.06174999 0.01189994 0.01491338 -0.06174999 0.01069998 0.01562148 -0.06156766 0.01069998 -0.0345 -0.0595054 0.01189994 -0.03866988 -0.05709785 0.01069998 -0.0345 -0.04948955 0.01189994 -0.0345 -0.05609047 0.01069998 -0.0345 -0.04649996 0.01189994 -0.03470098 -0.04574996 0.01189994 -0.0345 -0.04649996 0.01069998 -0.03470098 -0.04574996 0.01069998 -0.03599995 -0.04499995 0.01189994 -0.03599995 -0.04499995 0.01069998 0.001874983 -0.06949996 0.01069998 0.001349985 -0.06949996 0.01189994 0.001349985 -0.06949996 0.01069998 -0.001874983 -0.06949996 0.01189994 -0.003499984 -0.06949996 0.01069998 -0.003499984 -0.0625 0.01189994 -0.003499984 -0.0625 0.01069998 -0.001874983 -0.0625 0.01189994 0.001874983 -0.0625 0.01069998 0.003499984 -0.0625 0.01189994 0.003499984 -0.0625 0.01069998 0.003499984 -0.06535255 0.01069998 0.01499998 -0.07812488 0.01069998 0.01499998 -0.07872378 0.01189994 0.01612496 -0.0874347 0.01189994 0.01574999 -0.0875352 0.01189994 0.01510047 -0.08716017 0.01069998 0.01510047 -0.08716017 0.01189994 0.02801787 -0.08056825 0.01189994 0.02801787 -0.08056825 0.01069998 0.02185428 -0.08412688 0.01069998 0.02064436 -0.08482539 0.01189994 0.02549195 -0.07619327 0.01069998 0.02695298 -0.07872378 0.01189994 0.01622366 -0.07714009 0.01189994 0.01806378 -0.07932716 0.01069998 0.01771539 -0.07872378 0.01069998 0.01771539 -0.07872378 0.01189994 0.01708966 -0.07764005 0.01189994 0.01842987 -0.07969325 0.01069998 0.01842987 -0.07969325 0.01189994 0.01892989 -0.07982718 0.01189994 0.01942986 -0.07969325 0.01189994 0.0211091 -0.07872378 0.01069998 0.0211091 -0.07872378 0.01189994 0.0343104 -0.06688129 0.01189994 0.03448289 -0.0665313 0.01189994 0.03477627 -0.0662741 0.01069998 0.03477627 -0.0662741 0.01189994 0.04103589 -0.06266009 0.01069998 0.04349994 -0.06408268 0.01189994 0.04349994 -0.06408268 0.01069998 0.04449999 -0.06466007 0.01189994 0.03375959 -0.07725328 0.01069998 0.04349994 -0.0716297 0.01189994 0.03501826 -0.07069325 0.01189994 0.03538429 -0.07032728 0.01189994 0.03551828 -0.06982725 0.01189994 0.03551828 -0.06982725 0.01069998 0.01922887 -0.07714515 0.01189994 0.01882886 -0.07703799 0.01189994 0.01853609 -0.07674515 0.01069998 0.01842886 -0.0763452 0.01069998 0.01842886 -0.0763452 0.01189994 0.01882886 -0.07565236 0.01069998 0.01853609 -0.07594519 0.01189994 0.01882886 -0.07565236 0.01189994 0.01962888 -0.07565236 0.01069998 0.02002888 -0.0763452 0.01069998 0.01962888 -0.07703799 0.01069998 0.0301882 -0.07232719 0.01069998 0.02848696 -0.07330936 0.01189994 0.02848696 -0.07330936 0.01069998 0.0250054 -0.07531946 0.01069998 0.02818816 -0.06886309 0.01189994 0.02818816 -0.06886309 0.01069998 0.02325999 -0.0763272 0.01069998 0.02125996 -0.0728631 0.01189994 0.01337498 -0.08925718 0.01069998 0.04499995 -0.06099998 0.01069998 0.04349994 -0.07531946 0.01069998 0.01337498 -0.07872378 0.01069998 0.02799999 -0.04373538 0.01069998 -0.07270997 -0.05609047 0.01069998 -0.008223712 -0.05368095 0.01069998 0.0874052 -0.04944378 0.01069998 0.0873813 -0.04941987 0.01069998 -0.05624997 -0.05098956 0.01069998 -0.01337498 -0.06174999 0.01069998 -0.01337498 -0.06214594 0.01069998 -0.02064436 -0.0547741 0.01069998 -0.007499992 -0.0625 0.01069998 -0.05274999 -0.04373538 0.01069998 -0.05449998 -0.04373538 0.01069998 -0.02818816 -0.06886309 0.01069998 -0.03375959 -0.08302676 0.01069998 -0.04121267 -0.07872378 0.01069998 -0.04449999 -0.06535255 0.01069998 -0.03375959 -0.06535255 0.01069998 -0.04103589 -0.06266009 0.01069998 -0.04349994 -0.06174999 0.01069998 -0.04349994 -0.06408268 0.01069998 -0.03428477 -0.06727057 0.01069998 -0.03538429 -0.07032728 0.01069998 -0.03551828 -0.06982725 0.01069998 -0.03501826 -0.07069325 0.01069998 -0.03538429 -0.06932729 0.01069998 -0.03375959 -0.07141995 0.01069998 -0.03441029 -0.06764006 0.01069998 -0.03221929 -0.06964516 0.01069998 -0.03261929 -0.06953799 0.01069998 -0.03181928 -0.06953799 0.01069998 -0.0315265 -0.06924515 0.01069998 -0.0315265 -0.0684452 0.01069998 -0.0309596 -0.06535255 0.01069998 -0.03261929 -0.06815236 0.01069998 -0.03291207 -0.0684452 0.01069998 -0.0330193 -0.06884515 0.01069998 -0.03291207 -0.06924515 0.01069998 -0.01882886 -0.07565236 0.01069998 -0.01922887 -0.07554519 0.01069998 -0.01882886 -0.07703799 0.01069998 -0.01708966 -0.07764005 0.01069998 -0.01853609 -0.07674515 0.01069998 -0.01842886 -0.0763452 0.01069998 -0.01853609 -0.07594519 0.01069998 -0.01962888 -0.07565236 0.01069998 -0.01992166 -0.07594519 0.01069998 -0.02002888 -0.0763452 0.01069998 -0.01992166 -0.07674515 0.01069998 -0.01962888 -0.07703799 0.01069998 -0.01622366 -0.07714009 0.01069998 -0.01671439 -0.07727158 0.01069998 -0.01672369 -0.07727408 0.01069998 -0.01337498 -0.07531946 0.01069998 -0.01337498 -0.07872378 0.01069998 -0.01499998 -0.07872378 0.01069998 -0.01504516 -0.0778684 0.01069998 -0.01517546 -0.07764279 0.01069998 -0.01337498 -0.08925718 0.01069998 -0.01499998 -0.08678519 0.01069998 -0.01499998 -0.08412688 0.01069998 -0.01337498 -0.08412688 0.01069998 -0.02185428 -0.08412688 0.01069998 -0.02064436 -0.08482539 0.01069998 -0.01612496 -0.0874347 0.01069998 -0.01574999 -0.0875352 0.01069998 -0.01771539 -0.07872378 0.01069998 -0.01922887 -0.07714515 0.01069998 -0.01842987 -0.07969325 0.01069998 -0.01892989 -0.07982718 0.01069998 -0.01942986 -0.07969325 0.01069998 -0.02064436 -0.07872378 0.01069998 -0.02064436 -0.078992 0.01069998 -0.04699999 -0.04373538 0.01069998 0.04349994 -0.03275376 0.01069998 0.05274999 -0.04899996 0.01069998 0.05037498 -0.03275376 0.01069998 0.05037498 -0.04948955 0.01069998 0.05037498 -0.04899996 0.01069998 0.04349994 -0.04373538 0.01069998 0.04699999 -0.04373538 0.01069998 0.04699999 -0.03875374 0.01069998 -0.003999948 -0.07199996 0.01069998 -0.01537495 -0.07747536 0.01069998 -0.0157237 -0.07727408 0.01069998 -0.01337498 -0.07170188 0.01069998 -0.01671439 -0.07531946 0.01069998 -0.01671439 -0.06977385 0.01069998 -0.02064436 -0.07531946 0.01069998 -0.02325999 -0.0763272 0.01069998 -0.0211091 -0.07872378 0.01069998 -0.02267819 -0.07531946 0.01069998 -0.02125996 -0.0728631 0.01069998 -0.02064436 -0.06750488 0.01069998 -0.03049999 -0.06181478 0.01069998 -0.0309596 -0.06174999 0.01069998 -0.03049999 -0.06174999 0.01069998 -0.0309596 -0.05609047 0.01069998 -0.02899998 -0.0501821 0.01069998 -0.0309596 -0.04948955 0.01069998 -0.03049999 -0.05168205 0.01069998 -0.03049999 -0.05609047 0.01069998 -0.007874965 -0.0625 0.01069998 -0.01199996 -0.0625 0.01069998 0.03599995 -0.04499995 0.01069998 0.03524994 -0.045201 0.01069998 0.0345 -0.05609047 0.01069998 0.04349994 -0.06174999 0.01069998 0.03925144 -0.05609047 0.01069998 0.04299998 -0.04948955 0.01069998 0.03375959 -0.05609047 0.01069998 0.0345 -0.04948955 0.01069998 -0.003499984 -0.06535255 0.01069998 -0.002133965 -0.0715 0.01069998 -0.002133965 -0.07449996 0.01069998 -0.04574996 -0.05609047 0.01069998 -0.05049997 -0.06073075 0.01069998 -0.04574996 -0.06174999 0.01069998 -0.05049997 -0.06174999 0.01069998 -0.04786598 -0.05949997 0.01069998 -0.04499995 -0.06099998 0.01069998 -0.04574996 -0.06099998 0.01069998 -0.04574996 -0.05899995 0.01069998 -0.04499995 -0.05899995 0.01069998 -0.04449999 -0.06086599 0.01069998 -0.04413396 -0.06049996 0.01069998 -0.04399996 -0.06 0.01069998 -0.04413396 -0.05949997 0.01069998 -0.04449999 -0.05913394 0.01069998 -0.04574996 -0.05299997 0.01069998 -0.04699999 -0.05299997 0.01069998 -0.05449998 -0.04948955 0.01069998 -0.04574996 -0.04948955 0.01069998 -0.04799997 -0.05399996 0.01069998 -0.04699999 -0.055 0.01069998 -0.04499995 -0.055 0.01069998 -0.04574996 -0.055 0.01069998 -0.04499995 -0.05299997 0.01069998 -0.04449999 -0.05313396 0.01069998 -0.04449999 -0.05486595 0.01069998 -0.04413396 -0.05449998 0.01069998 -0.04399996 -0.05399996 0.01069998 -0.04349994 -0.04948955 0.01069998 -0.04413396 -0.05349999 0.01069998 -0.05974996 -0.05098956 0.01069998 -0.05974996 -0.0530104 0.01069998 -0.05799996 -0.0540207 0.01069998 -0.05649995 -0.05315464 0.01069998 -0.05449998 -0.05609047 0.01069998 -0.05624997 -0.0530104 0.01069998 0.05649995 -0.05084526 0.01069998 0.05649995 -0.04948955 0.01069998 0.05799996 -0.0540207 0.01069998 0.05949997 -0.05609047 0.01069998 0.05949997 -0.05315464 0.01069998 0.05974996 -0.0530104 0.01069998 0.05949997 -0.04948955 0.01069998 0.05974996 -0.05098956 0.01069998 0.05949997 -0.05084526 0.01069998 0.05799996 -0.04997926 0.01069998 0.07729035 -0.05414986 0.01069998 0.07554036 -0.05313944 0.01069998 0.07379037 -0.05414986 0.01069998 0.07379037 -0.05609047 0.01069998 0.07435858 -0.04373919 0.01069998 0.0741086 -0.04380619 0.01069998 0.07385855 -0.04373919 0.01069998 0.07505857 -0.04252678 0.01069998 0.07715189 -0.04373538 0.01069998 0.07499158 -0.04227679 0.01069998 0.07480859 -0.04209375 0.01069998 0.07673126 -0.028135 0.01069998 0.07455855 -0.04202675 0.01069998 0.07270997 -0.03045678 0.01069998 0.07430857 -0.04209375 0.01069998 0.07412558 -0.04227679 0.01069998 0.07385468 -0.04373538 0.01069998 0.07367557 -0.04355615 0.01069998 0.07360857 -0.04330617 0.01069998 0.08722215 -0.04926079 0.01069998 0.0873813 -0.04373538 0.01069998 0.08697217 -0.04919379 0.01069998 0.0943278 -0.04948955 0.01069998 0.0873813 -0.04996764 0.01069998 0.0905168 -0.05609047 0.01069998 0.0874052 -0.0499438 0.01069998 0.08608907 -0.05072319 0.01069998 0.0867722 -0.05090618 0.01069998 0.08054035 -0.04948955 0.01069998 0.07729035 -0.05609047 0.01069998 0.08695518 -0.05072319 0.01069998 0.08702218 -0.05047315 0.01069998 0.08722215 -0.05012679 0.01069998 0.08054035 -0.05609047 0.01069998 0.08627218 -0.05090618 0.01069998 0.0873813 -0.05609047 0.01069998 0.08652216 -0.05097317 0.01069998 0 -0.07887929 0.01069998 -0.001749992 -0.07988959 0.01069998 -0.001749992 -0.08191037 0.01069998 0.001349985 -0.08412688 0.01069998 0 -0.08292067 0.01069998 0.001349985 -0.08214128 0.01069998 0.001749992 -0.07988959 0.01069998 0.001349985 -0.07872378 0.01069998 0.001349985 -0.07965868 0.01069998 8.83013e-4 -0.08558297 0.01069998 7e-4 -0.08539998 0.01069998 4.5e-4 -0.08533298 0.01069998 2e-4 -0.08539998 0.01069998 -0.001874983 -0.08412688 0.01069998 -2e-4 -0.08539998 0.01069998 -4.5e-4 -0.08533298 0.01069998 -7e-4 -0.08539998 0.01069998 -9.5e-4 -0.08583295 0.01069998 -8.83013e-4 -0.08558297 0.01069998 2e-4 -0.1006 0.01069998 4.12635e-4 -0.100666 0.01069998 7e-4 -0.099734 0.01069998 8.63119e-4 -0.09988528 0.01069998 9.44415e-4 -0.100092 0.01069998 -8.83013e-4 -0.100417 0.01069998 -0.001874983 -0.09784388 0.01069998 -9.5e-4 -0.100167 0.01069998 -8.83013e-4 -0.09991699 0.01069998 -7e-4 -0.1006 0.01069998 -4.5e-4 -0.1006669 0.01069998 -2e-4 -0.1006 0.01069998 6.32671e-4 -0.100632 0.01069998 8.16526e-4 -0.100507 0.01069998 -8.83013e-4 -0.08608299 0.01069998 -0.001874983 -0.08925718 0.01069998 -7e-4 -0.09784388 0.01069998 -7e-4 -0.099734 0.01069998 -0.08554035 -0.03581899 0.01069998 -0.0887832 -0.03509318 0.01069998 -0.0872904 -0.03682935 0.01069998 -0.0872904 -0.03885006 0.01069998 -0.08554035 -0.03986048 0.01069998 -0.07405859 -0.04252678 0.01069998 -0.07385855 -0.0428732 0.01069998 -0.07505857 -0.04252678 0.01069998 -0.08379036 -0.03885006 0.01069998 -0.08379036 -0.03682935 0.01069998 -0.07412558 -0.04227679 0.01069998 -0.07430857 -0.04209375 0.01069998 -0.07455855 -0.04202675 0.01069998 -0.07499158 -0.04227679 0.01069998 -0.07367557 -0.04355615 0.01069998 -0.07360857 -0.04330617 0.01069998 -0.07270997 -0.03045678 0.01069998 -0.07367557 -0.04305619 0.01069998 -0.07369947 -0.04303228 0.01069998 -0.07385855 -0.04373919 0.01069998 -0.0741086 -0.04380619 0.01069998 -0.07435858 -0.04373919 0.01069998 -0.08652216 -0.05097317 0.01069998 -0.08627218 -0.05090618 0.01069998 -0.0874722 -0.04969376 0.01069998 -0.0874052 -0.0499438 0.01069998 -0.0905168 -0.05609047 0.01069998 -0.08722215 -0.05012679 0.01069998 -0.08702218 -0.05047315 0.01069998 -0.08695518 -0.05072319 0.01069998 -0.07379037 -0.05414986 0.01069998 -0.07554036 -0.05313944 0.01069998 -0.07729035 -0.05414986 0.01069998 -0.08431857 -0.04948955 0.01069998 -0.08608907 -0.05072319 0.01069998 -0.08722215 -0.04926079 0.01069998 -0.0874052 -0.04944378 0.01069998 -0.07715189 -0.04373538 0.01069998 -0.08672219 -0.04926079 0.01069998 -0.08697217 -0.04919379 0.01069998 -0.08741748 -0.04948955 0.01069998 -0.09546309 -0.04752308 0.01069998 -0.0867722 -0.05090618 0.01069998 -0.07729035 -0.05609047 0.01069998 -0.08863955 -0.05934184 0.01069998 -0.07729035 -0.05617058 0.01069998 -0.07554036 -0.057181 0.01069998 -0.07369947 -0.05996757 0.01069998 -0.07379037 -0.05617058 0.01069998 -0.07379037 -0.05609047 0.01069998 0.002749979 -0.05209529 0.01069998 0.003776252 -0.05368095 0.01069998 0.007874965 -0.05609047 0.01069998 0.007874965 -0.06174999 0.01069998 -0.001874983 -0.05851966 0.01069998 0 -0.05899995 0.01069998 -0.003749966 -0.05609047 0.01069998 -0.003749966 -0.05608928 0.01069998 -0.003749966 -0.05364036 0.01069998 -0.007874965 -0.04948955 0.01069998 -0.003749966 -0.04948955 0.01069998 -0.002749979 -0.04875379 0.01069998 -0.007874965 -0.04875379 0.01069998 -0.009249985 -0.04875379 0.01069998 -0.009249985 -0.04948955 0.01069998 -0.007874965 -0.06174999 0.01069998 -0.01596045 -0.05556076 0.01069998 -0.01671439 -0.05609047 0.01069998 -0.01574945 -0.05609047 0.01069998 -0.01526159 -0.05731558 0.01069998 -0.01562148 -0.06156766 0.01069998 -0.01383537 -0.05855399 0.01069998 -0.01337498 -0.05866587 0.01069998 -0.01491338 -0.06174999 0.01069998 -0.01834267 -0.05900257 0.01069998 -0.01475 -0.05209529 0.01069998 -0.01475 -0.04948955 0.01069998 -0.01671439 -0.04948955 0.01069998 -0.02064436 -0.04948955 0.01069998 -0.01671439 -0.04875379 0.01069998 -0.02064436 -0.04875379 0.01069998 -0.02799999 -0.04475378 0.01069998 -0.0309596 -0.04373538 0.01069998 -0.0309596 -0.02999997 0.01069998 -0.02799999 -0.02999997 0.01069998 -0.04574996 -0.03275376 0.01069998 -0.05574995 -0.03541129 0.01069998 -0.05549997 -0.03547829 0.01069998 -0.05449998 -0.03275376 0.01069998 -0.05514949 -0.03312879 0.01069998 -0.05487495 -0.03285425 0.01069998 -0.05524998 -0.03350377 0.01069998 -0.055067 -0.03472828 0.01069998 -0.06149995 -0.03275376 0.01069998 -0.0640307 -0.03275376 0.01069998 -0.06099998 -0.03497827 0.01069998 -0.06093299 -0.03522825 0.01069998 -0.06121295 -0.03281086 0.01069998 -0.05674999 -0.04099994 0.01069998 -0.05691748 -0.04162496 0.01069998 -0.05737495 -0.04208248 0.01069998 -0.05799996 -0.03974997 0.01069998 -0.05862498 -0.03991746 0.01069998 -0.06024998 -0.03541129 0.01069998 -0.06074994 -0.03350377 0.01069998 -0.06093299 -0.03472828 0.01069998 -0.06080704 -0.03321677 0.01069998 -0.06096965 -0.03297346 0.01069998 -0.06049996 -0.03547829 0.01069998 -0.06074994 -0.03541129 0.01069998 -0.07181149 -0.04146039 0.01069998 -0.07181149 -0.03943955 0.01069998 -0.0700615 -0.03842926 0.01069998 -0.06831145 -0.03943955 0.01069998 -0.06831145 -0.04146039 0.01069998 -0.0700615 -0.04247069 0.01069998 -0.06549996 -0.06073075 0.01069998 -0.06549996 -0.06174999 0.01069998 -0.06549996 -0.06340247 0.01069998 -0.06574815 -0.06395977 0.01069998 -0.06662499 -0.06405198 0.01069998 -0.0663284 -0.06414836 0.01069998 -0.05649995 -0.05609047 0.01069998 -0.06024998 -0.05623078 0.01069998 -0.06093299 -0.05641376 0.01069998 -0.06074994 -0.05709677 0.01069998 -0.06074994 -0.06073075 0.01069998 -0.05524998 -0.06073075 0.01069998 -0.05524998 -0.05709677 0.01069998 -0.05449998 -0.06073075 0.01069998 -0.055067 -0.05691379 0.01069998 -0.055 -0.05666375 0.01069998 -0.055067 -0.05641376 0.01069998 -0.05524998 -0.05623078 0.01069998 -0.05549997 -0.05616378 0.01069998 -0.05574995 -0.05623078 0.01069998 -0.04449999 -0.06466007 0.01069998 -0.04574996 -0.06535255 0.01069998 -0.05049997 -0.07292878 0.01069998 -0.04349994 -0.07531946 0.01069998 -0.04574996 -0.07531946 0.01069998 -0.04574996 -0.07610416 0.01069998 -0.05039948 -0.07330375 0.01069998 -0.0309596 -0.08412688 0.01069998 -0.03375959 -0.07872378 0.01069998 -0.0314821 -0.07856827 0.01069998 -0.03141927 -0.06884515 0.01069998 -0.0309596 -0.07303661 0.01069998 -0.02895605 -0.07419329 0.01069998 -0.0250054 -0.07531946 0.01069998 -0.0296064 -0.07531946 0.01069998 -0.0309596 -0.07766336 0.01069998 -0.0309596 -0.07872378 0.01069998 -0.02296829 -0.08925718 0.01069998 -0.02064436 -0.08925718 0.01069998 -0.02064436 -0.09059888 0.01069998 -0.01671439 -0.09286791 0.01069998 -0.01671439 -0.08925718 0.01069998 -0.008249998 -0.09198957 0.01069998 -0.008249998 -0.09401035 0.01069998 -0.007874965 -0.09784388 0.01069998 -0.00999999 -0.09502071 0.01069998 -0.01174998 -0.09401035 0.01069998 -0.01203185 -0.09784388 0.01069998 -0.01337498 -0.09551757 0.01069998 -0.01174998 -0.09198957 0.01069998 -0.00999999 -0.09097927 0.01069998 0.01174998 -0.09401035 0.01069998 0.01174998 -0.09198957 0.01069998 0.00999999 -0.09097927 0.01069998 0.007874965 -0.08925718 0.01069998 0.007874965 -0.09784388 0.01069998 0.008249998 -0.09401035 0.01069998 0.006575286 -0.106435 0.01069998 0.001874983 -0.106435 0.01069998 0.007874965 -0.104335 0.01069998 0.001874983 -0.09784388 0.01069998 0.008249998 -0.09198957 0.01069998 0.00999999 -0.09502071 0.01069998 0.01337498 -0.09544515 0.01069998 0.01399999 -0.09443509 0.01069998 0.0309596 -0.08412688 0.01069998 0.0309596 -0.07872378 0.01069998 0.05039948 -0.07330375 0.01069998 0.05037498 -0.07332825 0.01069998 0.05049997 -0.07292878 0.01069998 0.05524998 -0.05709677 0.01069998 0.05524998 -0.06073075 0.01069998 0.055067 -0.05691379 0.01069998 0.055 -0.05666375 0.01069998 0.055067 -0.05641376 0.01069998 0.05449998 -0.06073075 0.01069998 0.05037498 -0.06174999 0.01069998 0.05649995 -0.05623078 0.01069998 0.05574995 -0.05623078 0.01069998 0.05549997 -0.05616378 0.01069998 0.05524998 -0.05623078 0.01069998 0.05624997 -0.0530104 0.01069998 0.05649995 -0.05609047 0.01069998 0.05649995 -0.05315464 0.01069998 0.07729035 -0.05617058 0.01069998 0.07554036 -0.057181 0.01069998 0.0747832 -0.05934184 0.01069998 0.07379037 -0.05617058 0.01069998 0.06093299 -0.05641376 0.01069998 0.07270997 -0.05609047 0.01069998 0.06074994 -0.05623078 0.01069998 0.06049996 -0.05616378 0.01069998 0.06074994 -0.06073075 0.01069998 0.06549996 -0.06073075 0.01069998 0.06093299 -0.05691379 0.01069998 0.06099998 -0.05666375 0.01069998 0.06549996 -0.06340247 0.01069998 0.06601816 -0.06411576 0.01069998 0.06574815 -0.06395977 0.01069998 0.06549996 -0.06174999 0.01069998 0.08054035 -0.05916637 0.01069998 0.08888781 -0.05891185 0.01069998 0.08554035 -0.03986048 0.01069998 0.0874722 -0.04969376 0.01069998 0.08741748 -0.04948955 0.01069998 0.0872904 -0.03885006 0.01069998 0.0872904 -0.03682935 0.01069998 0.08554035 -0.03581899 0.01069998 0.08379036 -0.03682935 0.01069998 0.08054035 -0.03033417 0.01069998 0.08054035 -0.04373538 0.01069998 0.08379036 -0.03885006 0.01069998 0.0700615 -0.04247069 0.01069998 0.07270997 -0.04373538 0.01069998 0.07181149 -0.04146039 0.01069998 0.06093299 -0.03472828 0.01069998 0.05949997 -0.04373538 0.01069998 0.06024998 -0.03541129 0.01069998 0.06049996 -0.03547829 0.01069998 0.06831145 -0.04146039 0.01069998 0.06074994 -0.03350377 0.01069998 0.06831145 -0.03943955 0.01069998 0.06093299 -0.03522825 0.01069998 0.0700615 -0.03842926 0.01069998 0.0687313 -0.03275376 0.01069998 0.07181149 -0.03943955 0.01069998 0.07367557 -0.04305619 0.01069998 0.06149995 -0.03275376 0.01069998 0.06112498 -0.03285425 0.01069998 0.05674999 -0.04099994 0.01069998 0.05737495 -0.04208248 0.01069998 0.05649995 -0.04373538 0.01069998 0.05799996 -0.04224997 0.01069998 0.05908244 -0.04162496 0.01069998 0.05691748 -0.04037499 0.01069998 0.05949997 -0.03541129 0.01069998 0.05649995 -0.03541129 0.01069998 0.05574995 -0.03541129 0.01069998 0.05487495 -0.03285425 0.01069998 0.05514949 -0.03312879 0.01069998 0.05524998 -0.03350377 0.01069998 0.05449998 -0.04373538 0.01069998 0.055 -0.03497827 0.01069998 0.05449998 -0.03275376 0.01069998 0.05524998 -0.0345453 0.01069998 0.04299998 -0.03275376 0.01069998 0.03375959 -0.04373538 0.01069998 0.04299998 -0.02999997 0.01069998 0.0309596 -0.04373538 0.01069998 0.03375959 -0.02999997 0.01069998 0.02848696 -0.04373538 0.01069998 0.02799999 -0.02999997 0.01069998 0.02799999 -0.04475378 0.01069998 0.01927858 -0.05609047 0.01069998 0.01596045 -0.05556076 0.01069998 0.02064436 -0.04875379 0.01069998 0.01475 -0.04948955 0.01069998 0.0194869 -0.05544239 0.01069998 0.01475 -0.05209529 0.01069998 0.01577627 -0.05368095 0.01069998 0.01574945 -0.05609047 0.01069998 0.01337498 -0.05866587 0.01069998 0.01834267 -0.05900257 0.01069998 0.003261566 -0.05731558 0.01069998 0.008738398 -0.05731558 0.01069998 0.01016455 -0.05855399 0.01069998 0.01337498 -0.06174999 0.01069998 0.01199996 -0.05899995 0.01069998 0.009249985 -0.04948955 0.01069998 0.009249985 -0.05209529 0.01069998 0.008223712 -0.05368095 0.01069998 0.008250415 -0.05609047 0.01069998 0.002749979 -0.04948955 0.01069998 0.007874965 -0.04948955 0.01069998 0.007874965 -0.04875379 0.01069998 0.009249985 -0.04875379 0.01069998 0.02848696 -0.04948955 0.01069998 0.02848696 -0.05031949 0.01069998 0.02824997 -0.05038297 0.01069998 0.02064436 -0.04948955 0.01069998 0.02064436 -0.0547741 0.01069998 0.02899998 -0.0501821 0.01069998 0.02974998 -0.05038297 0.01069998 0.03029894 -0.05093199 0.01069998 0.03049999 -0.05168205 0.01069998 0.0309596 -0.04948955 0.01069998 0.0309596 -0.05609047 0.01069998 0.03049999 -0.06181478 0.01069998 0.01337498 -0.07170188 0.01069998 0.007874965 -0.07531946 0.01069998 0.007874965 -0.07487726 0.01069998 0.002999961 -0.07499998 0.01069998 0.007499992 -0.0750938 0.01069998 0.003999948 -0.07199996 0.01069998 0.003866016 -0.0715 0.01069998 0.003499984 -0.06949996 0.01069998 0.007499992 -0.06535255 0.01069998 0.007499992 -0.0625 0.01069998 0.001874983 -0.05851966 0.01069998 0.001874983 -0.06174999 0.01069998 0.01199996 -0.0625 0.01069998 -0.0345 -0.04948955 0.01069998 -0.03524994 -0.045201 0.01069998 -0.04349994 -0.04373538 0.01069998 -0.04299998 -0.04499995 0.01069998 -0.04299998 -0.04948955 0.01069998 -0.04299998 -0.04959785 0.01069998 -0.04349994 -0.05609047 0.01069998 -0.03925144 -0.05609047 0.01069998 -0.0345 -0.0595054 0.01069998 -0.001874983 -0.06949996 0.01069998 0.001349985 -0.07531946 0.01069998 0.001999974 -0.07199996 0.01069998 0.001874983 -0.07531946 0.01069998 -0.003749966 -0.06535255 0.01069998 0.001349985 -0.06174999 0.01069998 0.001349985 -0.0625 0.01069998 -0.001874983 -0.0625 0.01069998 -0.001874983 -0.06174999 0.01069998 0.02695298 -0.07872378 0.01069998 0.02848696 -0.07872378 0.01069998 0.01537495 -0.0874347 0.01069998 0.01337498 -0.08412688 0.01069998 0.01499998 -0.08412688 0.01069998 0.01499998 -0.08678519 0.01069998 0.02848696 -0.08412688 0.01069998 0.02848696 -0.08607095 0.01069998 0.02064436 -0.08482539 0.01069998 0.02064436 -0.08925718 0.01069998 0.01612496 -0.0874347 0.01069998 0.01574999 -0.0875352 0.01069998 0.01922887 -0.07714515 0.01069998 0.01882886 -0.07703799 0.01069998 0.01708966 -0.07764005 0.01069998 0.01672369 -0.07727408 0.01069998 0.01992166 -0.07674515 0.01069998 0.01992166 -0.07594519 0.01069998 0.02848696 -0.06938076 0.01069998 0.02848696 -0.06535255 0.01069998 0.02125996 -0.0728631 0.01069998 0.02064436 -0.06750488 0.01069998 0.01922887 -0.07554519 0.01069998 0.01517546 -0.07764279 0.01069998 0.01504516 -0.0778684 0.01069998 0.01853609 -0.07594519 0.01069998 0.01622366 -0.07714009 0.01069998 0.0157237 -0.07727408 0.01069998 0.01537495 -0.07747536 0.01069998 0.01892989 -0.07982718 0.01069998 0.01942986 -0.07969325 0.01069998 0.02064436 -0.078992 0.01069998 0.02064436 -0.07872378 0.01069998 0.02064436 -0.07531946 0.01069998 0.02267819 -0.07531946 0.01069998 0.03637218 -0.06535255 0.01069998 0.03448289 -0.0665313 0.01069998 0.0343104 -0.06688129 0.01069998 0.03428477 -0.06727057 0.01069998 0.03375959 -0.07141995 0.01069998 0.03441029 -0.06764006 0.01069998 0.03538429 -0.06932729 0.01069998 0.03501826 -0.07069325 0.01069998 0.03538429 -0.07032728 0.01069998 0.03375959 -0.06174999 0.01069998 0.03866988 -0.05709785 0.01069998 0.05049997 -0.06535255 0.01069998 0.05037498 -0.06535255 0.01069998 0.04449999 -0.06535255 0.01069998 0.04449999 -0.07105237 0.01069998 0.050125 -0.07357829 0.01069998 0.04349994 -0.0716297 0.01069998 0.04710906 -0.07531946 0.01069998 0.03710907 -0.07531946 0.01069998 0.03375959 -0.07872378 0.01069998 0.0314821 -0.07856827 0.01069998 0.02895605 -0.07419329 0.01069998 0.02848696 -0.07531946 0.01069998 0.0296064 -0.07531946 0.01069998 0.03261929 -0.06953799 0.01069998 0.03221929 -0.06964516 0.01069998 0.03181928 -0.06953799 0.01069998 0.03221929 -0.06804519 0.01069998 0.03291207 -0.0684452 0.01069998 0.0330193 -0.06884515 0.01069998 0.03291207 -0.06924515 0.01069998 0.03181928 -0.06815236 0.01069998 0.0315265 -0.0684452 0.01069998 0.0309596 -0.06535255 0.01069998 0.03141927 -0.06884515 0.01069998 0.0309596 -0.07303661 0.01069998 0.0315265 -0.06924515 0.01069998 0.07270997 -0.04948955 0.01069998 0.04413396 -0.05349999 0.01069998 0.04399996 -0.05399996 0.01069998 0.04349994 -0.05609047 0.01069998 0.04413396 -0.05449998 0.01069998 0.04786598 -0.05449998 0.01069998 0.05624997 -0.05098956 0.01069998 0.05449998 -0.05609047 0.01069998 0.05449998 -0.04948955 0.01069998 0.05037498 -0.05609047 0.01069998 0.04799997 -0.05399996 0.01069998 0.04749995 -0.05313396 0.01069998 0.04699999 -0.05299997 0.01069998 0.04349994 -0.04948955 0.01069998 0.04699999 -0.06099998 0.01069998 0.04449999 -0.05913394 0.01069998 0.04399996 -0.06 0.01069998 0.04449999 -0.06466007 0.01069998 0.04749995 -0.06086599 0.01069998 0.04786598 -0.06049996 0.01069998 0.04749995 -0.05913394 0.01069998 0.03375959 -0.06535255 0.01069998 0.03261929 -0.06815236 0.01069998 0.0309596 -0.06174999 0.01069998 0.03375959 -0.04948955 0.01069998 0.0309596 -0.07766336 0.01069998 0.007874965 -0.07872378 0.01069998 0.001874983 -0.07872378 0.01069998 8.83013e-4 -0.08608299 0.01069998 9.5e-4 -0.08583295 0.01069998 0.001874983 -0.08412688 0.01069998 0.001749992 -0.08191037 0.01069998 0.001349985 -0.09784388 0.01069998 0.001874983 -0.08925718 0.01069998 0.001349985 -0.08925718 0.01069998 0.01499998 -0.07872378 0.01069998 0.007874965 -0.08412688 0.01069998 0.001349985 -0.106435 0.01069998 9.27786e-4 -0.100314 0.01069998 0.01337498 -0.07531946 0.01069998 -0.001874983 -0.07531946 0.01069998 -0.003749966 -0.09784388 0.01069998 -0.001874983 -0.07872378 0.01069998 -0.003749966 -0.07872378 0.01069998 -0.003749966 -0.06174999 0.01069998 -0.007874965 -0.05609047 0.01069998 -0.003776252 -0.05368095 0.01069998 -0.007499992 -0.0750938 0.01069998 -0.007874965 -0.07531946 0.01069998 -0.003749966 -0.07531946 0.01069998 -0.007874965 -0.07872378 0.01069998 -0.007874965 -0.08412688 0.01069998 -0.007874965 -0.08925718 0.01069998 -0.003749966 -0.08412688 0.01069998 -0.003749966 -0.08925718 0.01069998 -0.007874965 -0.105044 0.01069998 -0.03181928 -0.06815236 0.01069998 -0.03221929 -0.06804519 0.01069998 -0.03375959 -0.06174999 0.01069998 -0.03375959 -0.05609047 0.01069998 -0.03375959 -0.04948955 0.01069998 -0.03375959 -0.02999997 0.01069998 -0.03375959 -0.04373538 0.01069998 -0.04574996 -0.04373538 0.01069998 -0.05649995 -0.05084526 0.01069998 -0.05799996 -0.04997926 0.01069998 -0.0640307 -0.04948955 0.01069998 -0.05649995 -0.04948955 0.01069998 -0.05649995 -0.04373538 0.01069998 -0.07270997 -0.04373538 0.01069998 -0.07270997 -0.04948955 0.01069998 -0.0640307 -0.04373538 0.01069998 -0.0640307 -0.05609047 0.01069998 -0.06099998 -0.05666375 0.01069998 -0.0640307 -0.06073075 0.01069998 -0.07369947 -0.05609047 0.01069998 -0.07369947 -0.04948955 0.01069998 -0.07369947 -0.04358005 0.01069998 -0.07369947 -0.04373538 0.01069998 -0.07385468 -0.04373538 0.01069998 -0.0301882 -0.07232719 0.01069998 -0.01337498 -0.08412688 0.01189994 0.01672369 -0.07727408 0.01189994 0.007874965 -0.09784388 0.01189994 0.02064436 -0.09059888 0.01189994 0.0874052 -0.0499438 0.01189994 0.0873813 -0.05609047 0.01189994 0.08379036 -0.03682935 0.01189994 0.08554035 -0.03581899 0.01189994 -0.01806378 -0.07932716 0.01189994 -0.01337498 -0.07872378 0.01189994 -0.04574996 -0.06535255 0.01189994 -0.03375959 -0.06535255 0.01189994 -0.03538429 -0.06932729 0.01189994 -0.03551828 -0.06982725 0.01189994 -0.03375959 -0.07141995 0.01189994 -0.03441029 -0.06764006 0.01189994 -0.03501826 -0.07069325 0.01189994 -0.03538429 -0.07032728 0.01189994 -0.04449999 -0.06535255 0.01189994 -0.04574996 -0.06174999 0.01189994 -0.04349994 -0.07531946 0.01189994 -0.03375959 -0.07725328 0.01189994 -0.0314821 -0.07856827 0.01189994 -0.0309596 -0.07766336 0.01189994 -0.02325999 -0.0763272 0.01189994 -0.0211091 -0.07872378 0.01189994 -0.0301882 -0.07232719 0.01189994 -0.03221929 -0.06804519 0.01189994 -0.03181928 -0.06815236 0.01189994 -0.0315265 -0.0684452 0.01189994 -0.0315265 -0.06924515 0.01189994 -0.03181928 -0.06953799 0.01189994 -0.03221929 -0.06964516 0.01189994 -0.03261929 -0.06953799 0.01189994 -0.03291207 -0.06924515 0.01189994 -0.0330193 -0.06884515 0.01189994 -0.03291207 -0.0684452 0.01189994 -0.04349994 -0.06408268 0.01189994 -0.04103589 -0.06266009 0.01189994 -0.03261929 -0.06815236 0.01189994 -0.03141927 -0.06884515 0.01189994 -0.0309596 -0.07303661 0.01189994 -0.02895605 -0.07419329 0.01189994 -0.0250054 -0.07531946 0.01189994 -0.0296064 -0.07531946 0.01189994 -0.02549195 -0.07619327 0.01189994 -0.02801787 -0.08056825 0.01189994 -0.01537495 -0.0874347 0.01189994 -0.01671439 -0.08925718 0.01189994 -0.01337498 -0.08925718 0.01189994 -0.01510047 -0.08716017 0.01189994 -0.01537495 -0.07747536 0.01189994 -0.01517546 -0.07764279 0.01189994 -0.01499998 -0.07812488 0.01189994 -0.01882886 -0.07565236 0.01189994 -0.01671439 -0.07531946 0.01189994 -0.01922887 -0.07554519 0.01189994 -0.01962888 -0.07565236 0.01189994 -0.01622366 -0.07714009 0.01189994 -0.01671439 -0.07727158 0.01189994 -0.01672369 -0.07727408 0.01189994 -0.01853609 -0.07594519 0.01189994 -0.01842886 -0.0763452 0.01189994 -0.01853609 -0.07674515 0.01189994 -0.01882886 -0.07703799 0.01189994 -0.01922887 -0.07714515 0.01189994 -0.01962888 -0.07703799 0.01189994 -0.01992166 -0.07674515 0.01189994 -0.02002888 -0.0763452 0.01189994 -0.01992166 -0.07594519 0.01189994 -0.01892989 -0.07982718 0.01189994 -0.01842987 -0.07969325 0.01189994 -0.01942986 -0.07969325 0.01189994 -0.02064436 -0.07872378 0.01189994 -0.02064436 -0.07531946 0.01189994 -0.04574996 -0.04948955 0.01189994 -0.04574996 -0.04373538 0.01189994 -0.04699999 -0.03875374 0.01189994 -0.04574996 -0.03275376 0.01189994 -0.05449998 -0.03275376 0.01189994 -0.05274999 -0.03875374 0.01189994 0.05274999 -0.04899996 0.01189994 0.05037498 -0.04899996 0.01189994 -0.02899998 -0.0501821 0.01189994 -0.0309596 -0.04948955 0.01189994 -0.03049999 -0.05168205 0.01189994 -0.03049999 -0.06181478 0.01189994 -0.0309596 -0.06174999 0.01189994 -0.03049999 -0.06174999 0.01189994 -0.007874965 -0.07487726 0.01189994 -0.01337498 -0.07170188 0.01189994 -0.02064436 -0.06750488 0.01189994 -0.003749966 -0.07138395 0.01189994 -0.007874965 -0.07531946 0.01189994 -0.007499992 -0.0750938 0.01189994 -0.003866016 -0.07449996 0.01189994 -0.007499992 -0.06535255 0.01189994 -0.003999948 -0.07199996 0.01189994 -0.007874965 -0.0625 0.01189994 -0.01337498 -0.06214594 0.01189994 -0.01337498 -0.06174999 0.01189994 -0.01491338 -0.06174999 0.01189994 -0.01383537 -0.05855399 0.01189994 -0.01562148 -0.06156766 0.01189994 -0.02064436 -0.0547741 0.01189994 -0.0194869 -0.05544239 0.01189994 -0.01671439 -0.06053739 0.01189994 -0.01834267 -0.05900257 0.01189994 0.0345 -0.04948955 0.01189994 0.03375959 -0.04948955 0.01189994 0.03470098 -0.04574996 0.01189994 0.03375959 -0.04373538 0.01189994 0.04349994 -0.04373538 0.01189994 0.04299998 -0.04499995 0.01189994 0.04299998 -0.04948955 0.01189994 0.04349994 -0.05609047 0.01189994 0.03925144 -0.05609047 0.01189994 0.03375959 -0.06174999 0.01189994 0.03866988 -0.05709785 0.01189994 0.0345 -0.0595054 0.01189994 0.0345 -0.05609047 0.01189994 0.008250415 -0.05609047 0.01189994 0.01574945 -0.05609047 0.01189994 0.01562148 -0.06156766 0.01189994 0.01526159 -0.05731558 0.01189994 0.01383537 -0.05855399 0.01189994 0.01016455 -0.05855399 0.01189994 0.01475 -0.05209529 0.01189994 0.0194869 -0.05544239 0.01189994 0.01927858 -0.05609047 0.01189994 0.02064436 -0.04875379 0.01189994 0.02107179 -0.04875379 0.01189994 0.02064436 -0.04948955 0.01189994 0.02848696 -0.04373538 0.01189994 0.02799999 -0.04373538 0.01189994 0.02848696 -0.02999997 0.01189994 0.04299998 -0.02999997 0.01189994 0.055067 -0.03522825 0.01189994 0.05514949 -0.03312879 0.01189994 0.05487495 -0.03285425 0.01189994 0.05524998 -0.03350377 0.01189994 0.05649995 -0.03541129 0.01189994 0.05799996 -0.03974997 0.01189994 0.05908244 -0.04037499 0.01189994 0.05908244 -0.04162496 0.01189994 0.05949997 -0.04373538 0.01189994 0.05549997 -0.03547829 0.01189994 0.06093299 -0.03472828 0.01189994 0.0700615 -0.04247069 0.01189994 0.07181149 -0.04146039 0.01189994 0.06074994 -0.03350377 0.01189994 0.06099998 -0.03497827 0.01189994 0.06093299 -0.03522825 0.01189994 0.06831145 -0.03943955 0.01189994 0.06074994 -0.03541129 0.01189994 0.06831145 -0.04146039 0.01189994 0.07385468 -0.04373538 0.01189994 0.07367557 -0.04355615 0.01189994 0.07360857 -0.04330617 0.01189994 0.07181149 -0.03943955 0.01189994 0.0700615 -0.03842926 0.01189994 0.07367557 -0.04305619 0.01189994 0.07412558 -0.04227679 0.01189994 0.07430857 -0.04209375 0.01189994 0.07455855 -0.04202675 0.01189994 0.07480859 -0.04209375 0.01189994 0.08054035 -0.03033417 0.01189994 0.0872904 -0.03682935 0.01189994 0.08054035 -0.04373538 0.01189994 0.08379036 -0.03885006 0.01189994 0.08554035 -0.03986048 0.01189994 0.0872904 -0.03885006 0.01189994 0.0873813 -0.04373538 0.01189994 0.0873813 -0.03428375 0.01189994 0.0937727 -0.04373538 0.01189994 0.0943278 -0.04948955 0.01189994 0.0874722 -0.04969376 0.01189994 0.0905168 -0.05609047 0.01189994 0.0873813 -0.05895787 0.01189994 0.06549996 -0.06073075 0.01189994 0.06074994 -0.05623078 0.01189994 0.06049996 -0.05616378 0.01189994 0.06074994 -0.05709677 0.01189994 0.06074994 -0.06073075 0.01189994 0.06093299 -0.05691379 0.01189994 0.06099998 -0.05666375 0.01189994 0.06093299 -0.05641376 0.01189994 0.06549996 -0.06174999 0.01189994 0.06574815 -0.06395977 0.01189994 0.06662499 -0.06405198 0.01189994 0.06549996 -0.06340247 0.01189994 0.06024998 -0.05623078 0.01189994 0.05949997 -0.05623078 0.01189994 0.05949997 -0.05609047 0.01189994 0.05449998 -0.06073075 0.01189994 0.055067 -0.05691379 0.01189994 0.055 -0.05666375 0.01189994 0.055067 -0.05641376 0.01189994 0.05524998 -0.05623078 0.01189994 0.05449998 -0.05609047 0.01189994 0.05549997 -0.05616378 0.01189994 0.05649995 -0.05609047 0.01189994 0.05574995 -0.05623078 0.01189994 0.05649995 -0.05623078 0.01189994 0.05039948 -0.07330375 0.01189994 0.04710906 -0.07531946 0.01189994 0.04449999 -0.07105237 0.01189994 0.04349994 -0.07531946 0.01189994 0.03710907 -0.07531946 0.01189994 0.02296829 -0.08925718 0.01189994 0.02848696 -0.08412688 0.01189994 0.02185428 -0.08412688 0.01189994 0.008249998 -0.09401035 0.01189994 0.00999999 -0.09502071 0.01189994 0.01174998 -0.09401035 0.01189994 0.01174998 -0.09198957 0.01189994 -0.007874965 -0.105044 0.01189994 -0.003749966 -0.106435 0.01189994 -0.00999999 -0.09097927 0.01189994 -0.008249998 -0.09198957 0.01189994 -0.008249998 -0.09401035 0.01189994 -0.007874965 -0.09784388 0.01189994 -0.00999999 -0.09502071 0.01189994 -0.01174998 -0.09401035 0.01189994 -0.01174998 -0.09198957 0.01189994 -0.04121267 -0.07872378 0.01189994 -0.03375959 -0.07872378 0.01189994 -0.0309596 -0.07872378 0.01189994 -0.03185427 -0.08412688 0.01189994 -0.0309596 -0.08412688 0.01189994 -0.0309596 -0.08464336 0.01189994 -0.02064436 -0.08925718 0.01189994 -0.01671439 -0.09286791 0.01189994 -0.01337498 -0.09551757 0.01189994 -0.04349994 -0.07740318 0.01189994 -0.03710907 -0.07531946 0.01189994 -0.05049997 -0.07292878 0.01189994 -0.04574996 -0.07531946 0.01189994 -0.050125 -0.07357829 0.01189994 -0.05039948 -0.07330375 0.01189994 -0.04574996 -0.06099998 0.01189994 -0.04699999 -0.06099998 0.01189994 -0.05049997 -0.06535255 0.01189994 -0.04786598 -0.05949997 0.01189994 -0.04749995 -0.05913394 0.01189994 -0.05049997 -0.06073075 0.01189994 -0.05449998 -0.06073075 0.01189994 -0.04786598 -0.06049996 0.01189994 -0.055067 -0.05641376 0.01189994 -0.05574995 -0.05623078 0.01189994 -0.05524998 -0.06073075 0.01189994 -0.05549997 -0.05616378 0.01189994 -0.05524998 -0.05623078 0.01189994 -0.06093299 -0.05641376 0.01189994 -0.06049996 -0.05616378 0.01189994 -0.05649995 -0.05609047 0.01189994 -0.06024998 -0.05623078 0.01189994 -0.05649995 -0.05623078 0.01189994 -0.06093299 -0.05691379 0.01189994 -0.07270997 -0.06053876 0.01189994 -0.06549996 -0.06340247 0.01189994 -0.07729035 -0.05617058 0.01189994 -0.07554036 -0.057181 0.01189994 -0.07379037 -0.05617058 0.01189994 -0.07369947 -0.05996757 0.01189994 -0.07729035 -0.05414986 0.01189994 -0.07369947 -0.04948955 0.01189994 -0.07554036 -0.05313944 0.01189994 -0.07379037 -0.05414986 0.01189994 -0.07379037 -0.05609047 0.01189994 -0.0867722 -0.05090618 0.01189994 -0.08695518 -0.05072319 0.01189994 -0.0905168 -0.05609047 0.01189994 -0.08702218 -0.05047315 0.01189994 -0.08722215 -0.05012679 0.01189994 -0.08627218 -0.05090618 0.01189994 -0.08652216 -0.05097317 0.01189994 -0.07729035 -0.05609047 0.01189994 -0.08608907 -0.05072319 0.01189994 -0.08697217 -0.04919379 0.01189994 -0.0874052 -0.0499438 0.01189994 -0.0874722 -0.04969376 0.01189994 -0.08741748 -0.04948955 0.01189994 -0.0874052 -0.04944378 0.01189994 -0.08722215 -0.04926079 0.01189994 -0.09342759 -0.04373538 0.01189994 -0.08554035 -0.03581899 0.01189994 -0.0872904 -0.03885006 0.01189994 -0.0872904 -0.03682935 0.01189994 -0.08379036 -0.03885006 0.01189994 -0.08554035 -0.03986048 0.01189994 -0.07430857 -0.04209375 0.01189994 -0.07405859 -0.04252678 0.01189994 -0.08379036 -0.03682935 0.01189994 -0.07480859 -0.04209375 0.01189994 -0.07385855 -0.0428732 0.01189994 -0.07369947 -0.02988547 0.01189994 -0.07369947 -0.04303228 0.01189994 -0.07270997 -0.03045678 0.01189994 -0.07369947 -0.04358005 0.01189994 -0.07369947 -0.04373538 0.01189994 -0.07367557 -0.04355615 0.01189994 -0.06831145 -0.03943955 0.01189994 -0.0700615 -0.03842926 0.01189994 -0.07181149 -0.03943955 0.01189994 -0.07367557 -0.04305619 0.01189994 -0.07360857 -0.04330617 0.01189994 -0.06831145 -0.04146039 0.01189994 -0.0640307 -0.04373538 0.01189994 -0.0700615 -0.04247069 0.01189994 -0.07181149 -0.04146039 0.01189994 -0.07270997 -0.04373538 0.01189994 -0.06024998 -0.03541129 0.01189994 -0.05862498 -0.03991746 0.01189994 -0.06093299 -0.03472828 0.01189994 -0.0640307 -0.03275376 0.01189994 -0.05649995 -0.04373538 0.01189994 -0.05799996 -0.04224997 0.01189994 -0.05649995 -0.03541129 0.01189994 -0.05799996 -0.03974997 0.01189994 -0.05862498 -0.04208248 0.01189994 -0.05908244 -0.04162496 0.01189994 -0.06096965 -0.03297346 0.01189994 -0.06121295 -0.03281086 0.01189994 -0.06080704 -0.03321677 0.01189994 -0.06149995 -0.03275376 0.01189994 -0.06074994 -0.03350377 0.01189994 -0.06099998 -0.03497827 0.01189994 -0.06093299 -0.03522825 0.01189994 -0.05924999 -0.04099994 0.01189994 -0.06074994 -0.03541129 0.01189994 -0.06049996 -0.03547829 0.01189994 -0.055067 -0.03522825 0.01189994 -0.05691748 -0.04037499 0.01189994 -0.05574995 -0.03541129 0.01189994 -0.05449998 -0.04373538 0.01189994 -0.05487495 -0.03285425 0.01189994 -0.05514949 -0.03312879 0.01189994 -0.055 -0.03497827 0.01189994 -0.05524998 -0.0345453 0.01189994 -0.04349994 -0.03275376 0.01189994 -0.04299998 -0.03275376 0.01189994 -0.04349994 -0.04373538 0.01189994 -0.04299998 -0.02999997 0.01189994 -0.02799999 -0.04475378 0.01189994 -0.02107179 -0.04875379 0.01189994 -0.02064436 -0.04875379 0.01189994 -0.02064436 -0.04948955 0.01189994 -0.01671439 -0.04948955 0.01189994 -0.01475 -0.04948955 0.01189994 -0.01671439 -0.04875379 0.01189994 -0.01475 -0.05209529 0.01189994 -0.01577627 -0.05368095 0.01189994 -0.01671439 -0.05609047 0.01189994 -0.01526159 -0.05731558 0.01189994 -0.007874965 -0.06174999 0.01189994 -0.01016455 -0.05855399 0.01189994 -0.01199996 -0.05899995 0.01189994 -0.009249985 -0.05209529 0.01189994 -0.008223712 -0.05368095 0.01189994 -0.008039474 -0.05556076 0.01189994 -0.008250415 -0.05609047 0.01189994 -0.007874965 -0.04875379 0.01189994 -0.003749966 -0.04948955 0.01189994 -0.003749966 -0.04875379 0.01189994 -0.002749979 -0.04875379 0.01189994 -0.003749966 -0.05364036 0.01189994 -0.007874965 -0.04948955 0.01189994 -0.00396049 -0.05556076 0.01189994 -0.007874965 -0.05609047 0.01189994 -0.003749966 -0.06174999 0.01189994 -0.001874983 -0.06174999 0.01189994 0.001349985 -0.05867195 0.01189994 0 -0.05899995 0.01189994 0.003776252 -0.05368095 0.01189994 0.007874965 -0.05609047 0.01189994 0.007874965 -0.06174999 0.01189994 0.003261566 -0.05731558 0.01189994 0.001874983 -0.06174999 0.01189994 0.002749979 -0.04948955 0.01189994 0.007874965 -0.04875379 0.01189994 0.008039474 -0.05556076 0.01189994 0.007874965 -0.04948955 0.01189994 0.009249985 -0.04948955 0.01189994 -0.003499984 -0.06949996 0.01189994 -0.002999961 -0.07499998 0.01189994 -0.003749966 -0.07461595 0.01189994 -0.002499997 -0.07113397 0.01189994 -0.002133965 -0.0715 0.01189994 -0.001999974 -0.07199996 0.01189994 -0.04574996 -0.05609047 0.01189994 -0.04574996 -0.05899995 0.01189994 -0.04499995 -0.05899995 0.01189994 -0.04449999 -0.05913394 0.01189994 -0.04413396 -0.05949997 0.01189994 -0.04399996 -0.06 0.01189994 -0.04413396 -0.06049996 0.01189994 -0.04449999 -0.06086599 0.01189994 -0.04499995 -0.06099998 0.01189994 -0.04449999 -0.05313396 0.01189994 -0.04499995 -0.05299997 0.01189994 -0.04413396 -0.05349999 0.01189994 -0.04399996 -0.05399996 0.01189994 -0.04349994 -0.04948955 0.01189994 -0.04413396 -0.05449998 0.01189994 -0.04349994 -0.05609047 0.01189994 -0.04449999 -0.05486595 0.01189994 -0.04499995 -0.055 0.01189994 -0.04574996 -0.055 0.01189994 -0.04699999 -0.055 0.01189994 -0.05449998 -0.05609047 0.01189994 -0.055 -0.05666375 0.01189994 -0.055067 -0.05691379 0.01189994 -0.04749995 -0.05486595 0.01189994 -0.04786598 -0.05449998 0.01189994 -0.04799997 -0.05399996 0.01189994 -0.04786598 -0.05349999 0.01189994 -0.05449998 -0.04948955 0.01189994 -0.04749995 -0.05313396 0.01189994 0.0873813 -0.04996764 0.01189994 0.08722215 -0.05012679 0.01189994 0.08702218 -0.05047315 0.01189994 0.08695518 -0.05072319 0.01189994 0.0867722 -0.05090618 0.01189994 0.08652216 -0.05097317 0.01189994 0.08627218 -0.05090618 0.01189994 0.08608907 -0.05072319 0.01189994 0.08722215 -0.04926079 0.01189994 0.0873813 -0.04941987 0.01189994 0.0874052 -0.04944378 0.01189994 0.08741748 -0.04948955 0.01189994 0.07499158 -0.04227679 0.01189994 0.07715189 -0.04373538 0.01189994 0.08672219 -0.04926079 0.01189994 0.08697217 -0.04919379 0.01189994 0.07385855 -0.04373919 0.01189994 0.08602219 -0.05047315 0.01189994 0.08054035 -0.04948955 0.01189994 0.0741086 -0.04380619 0.01189994 -7e-4 -0.099734 0.01189994 -8.83013e-4 -0.09991699 0.01189994 -0.001874983 -0.106435 0.01189994 -8.83013e-4 -0.100417 0.01189994 6.32671e-4 -0.100632 0.01189994 4.12635e-4 -0.100666 0.01189994 2e-4 -0.1006 0.01189994 0.001349985 -0.106435 0.01189994 -2e-4 -0.1006 0.01189994 -4.5e-4 -0.1006669 0.01189994 -7e-4 -0.1006 0.01189994 8.63119e-4 -0.09988528 0.01189994 0.001349985 -0.09784388 0.01189994 9.44415e-4 -0.100092 0.01189994 9.27786e-4 -0.100314 0.01189994 8.16526e-4 -0.100507 0.01189994 7e-4 -0.09784388 0.01189994 0.001349985 -0.08925718 0.01189994 -7e-4 -0.08626598 0.01189994 0.001349985 -0.08412688 0.01189994 4.5e-4 -0.08533298 0.01189994 7e-4 -0.08925718 0.01189994 8.83013e-4 -0.08608299 0.01189994 9.5e-4 -0.08583295 0.01189994 8.83013e-4 -0.08558297 0.01189994 7e-4 -0.08539998 0.01189994 -8.83013e-4 -0.08558297 0.01189994 -7e-4 -0.08539998 0.01189994 -0.001874983 -0.08412688 0.01189994 -4.5e-4 -0.08533298 0.01189994 -2e-4 -0.08539998 0.01189994 2e-4 -0.08539998 0.01189994 -0.0741086 -0.04380619 0.01189994 -0.08431857 -0.04948955 0.01189994 -0.05799996 -0.0540207 0.01189994 -0.05974996 -0.0530104 0.01189994 -0.05974996 -0.05098956 0.01189994 -0.05799996 -0.04997926 0.01189994 -0.0640307 -0.04948955 0.01189994 -0.05649995 -0.04948955 0.01189994 -0.05649995 -0.05084526 0.01189994 -0.05624997 -0.05098956 0.01189994 -0.05624997 -0.0530104 0.01189994 -0.05649995 -0.05315464 0.01189994 0.05949997 -0.04948955 0.01189994 0.05949997 -0.05084526 0.01189994 0.05974996 -0.05098956 0.01189994 0.05974996 -0.0530104 0.01189994 0.05949997 -0.05315464 0.01189994 0.05799996 -0.0540207 0.01189994 0.05649995 -0.05315464 0.01189994 0.05624997 -0.0530104 0.01189994 0.05449998 -0.04948955 0.01189994 0.05649995 -0.04948955 0.01189994 0.05624997 -0.05098956 0.01189994 0.05649995 -0.05084526 0.01189994 0.05799996 -0.04997926 0.01189994 0.07379037 -0.05609047 0.01189994 0.07379037 -0.05414986 0.01189994 0.07554036 -0.05313944 0.01189994 0.07729035 -0.05414986 0.01189994 0.08054035 -0.05609047 0.01189994 0.07729035 -0.05609047 0.01189994 0.07729035 -0.05617058 0.01189994 0.07554036 -0.057181 0.01189994 0.07379037 -0.05617058 0.01189994 0.07270997 -0.05609047 0.01189994 -0.001749992 -0.08191037 0.01189994 0 -0.08292067 0.01189994 0.001349985 -0.08214128 0.01189994 0 -0.07887929 0.01189994 0.001349985 -0.07965868 0.01189994 0.003499984 -0.06535255 0.01189994 0.007499992 -0.0750938 0.01189994 0.001874983 -0.06949996 0.01189994 0.002499997 -0.07113397 0.01189994 0.003499984 -0.06949996 0.01189994 0.007499992 -0.06535255 0.01189994 0.003499984 -0.07113397 0.01189994 0.003999948 -0.074 0.01189994 0.001874983 -0.07531946 0.01189994 0.0309596 -0.06535255 0.01189994 0.02899998 -0.0501821 0.01189994 0.02974998 -0.05038297 0.01189994 0.03029894 -0.05093199 0.01189994 0.03049999 -0.05168205 0.01189994 0.01475 -0.04948955 0.01189994 0.02848696 -0.04948955 0.01189994 0.02824997 -0.05038297 0.01189994 0.007874965 -0.0625 0.01189994 0.01337498 -0.06174999 0.01189994 -0.04299998 -0.04499995 0.01189994 -0.03524994 -0.045201 0.01189994 -0.03375959 -0.06174999 0.01189994 -0.04349994 -0.06174999 0.01189994 -0.03866988 -0.05709785 0.01189994 -0.03925144 -0.05609047 0.01189994 -0.04299998 -0.04959785 0.01189994 -0.04299998 -0.04948955 0.01189994 -0.003749966 -0.06535255 0.01189994 -0.003499984 -0.06535255 0.01189994 0.001349985 -0.07531946 0.01189994 -0.001874983 -0.07531946 0.01189994 -0.001999974 -0.074 0.01189994 0.001349985 -0.0625 0.01189994 0.001349985 -0.06174999 0.01189994 0.001874983 -0.0625 0.01189994 0.01537495 -0.07747536 0.01189994 0.0157237 -0.07727408 0.01189994 0.01922887 -0.07554519 0.01189994 0.01962888 -0.07565236 0.01189994 0.01992166 -0.07594519 0.01189994 0.01337498 -0.07872378 0.01189994 0.01337498 -0.07531946 0.01189994 0.01499998 -0.07812488 0.01189994 0.01504516 -0.0778684 0.01189994 0.01517546 -0.07764279 0.01189994 0.01992166 -0.07674515 0.01189994 0.01962888 -0.07703799 0.01189994 0.01853609 -0.07674515 0.01189994 0.02064436 -0.08925718 0.01189994 0.01337498 -0.08925718 0.01189994 0.01537495 -0.0874347 0.01189994 0.01499998 -0.08678519 0.01189994 0.01337498 -0.08412688 0.01189994 0.01499998 -0.08412688 0.01189994 0.02002888 -0.0763452 0.01189994 0.01806378 -0.07932716 0.01189994 0.02064436 -0.07872378 0.01189994 0.02064436 -0.078992 0.01189994 0.02848696 -0.06938076 0.01189994 0.02848696 -0.06535255 0.01189994 0.02437216 -0.06535255 0.01189994 0.02064436 -0.07531946 0.01189994 0.0296064 -0.07531946 0.01189994 0.0250054 -0.07531946 0.01189994 0.02848696 -0.07531946 0.01189994 0.02895605 -0.07419329 0.01189994 0.0301882 -0.07232719 0.01189994 0.03375959 -0.07725328 0.01189994 0.0314821 -0.07856827 0.01189994 0.0309596 -0.07766336 0.01189994 0.02549195 -0.07619327 0.01189994 0.02325999 -0.0763272 0.01189994 0.02267819 -0.07531946 0.01189994 0.03375959 -0.06535255 0.01189994 0.05037498 -0.07332825 0.01189994 0.04449999 -0.06535255 0.01189994 0.04103589 -0.06266009 0.01189994 0.04349994 -0.06174999 0.01189994 0.03637218 -0.06535255 0.01189994 0.03375959 -0.07141995 0.01189994 0.03538429 -0.06932729 0.01189994 0.03261929 -0.06815236 0.01189994 0.03291207 -0.0684452 0.01189994 0.03441029 -0.06764006 0.01189994 0.03428477 -0.06727057 0.01189994 0.0330193 -0.06884515 0.01189994 0.03291207 -0.06924515 0.01189994 0.03261929 -0.06953799 0.01189994 0.03221929 -0.06964516 0.01189994 0.03181928 -0.06953799 0.01189994 0.0315265 -0.06924515 0.01189994 0.0309596 -0.07303661 0.01189994 0.03141927 -0.06884515 0.01189994 0.0315265 -0.0684452 0.01189994 0.03181928 -0.06815236 0.01189994 -0.07369947 -0.05609047 0.01189994 -0.07270997 -0.04948955 0.01189994 -0.06574815 -0.06395977 0.01189994 -0.06662499 -0.06405198 0.01189994 -0.06549996 -0.06174999 0.01189994 -0.07061219 -0.06174999 0.01189994 -0.07270997 -0.05609047 0.01189994 -0.06549996 -0.06073075 0.01189994 -0.0640307 -0.05609047 0.01189994 -0.07385468 -0.04373538 0.01189994 -0.07385855 -0.04373919 0.01189994 -0.04699999 -0.05299997 0.01189994 -0.04574996 -0.05299997 0.01189994 -0.0309596 -0.04373538 0.01189994 -0.03375959 -0.04373538 0.01189994 -0.0309596 -0.05609047 0.01189994 -0.03375959 -0.04948955 0.01189994 -0.03375959 -0.05609047 0.01189994 -0.0345 -0.05609047 0.01189994 -0.0309596 -0.06535255 0.01189994 -0.02818816 -0.06886309 0.01189994 -0.02437216 -0.06535255 0.01189994 -0.02125996 -0.0728631 0.01189994 -0.02267819 -0.07531946 0.01189994 -0.003749966 -0.05609047 0.01189994 -0.001749992 -0.07988959 0.01189994 -8.83013e-4 -0.08608299 0.01189994 -9.5e-4 -0.08583295 0.01189994 -0.001874983 -0.08925718 0.01189994 -0.007874965 -0.07872378 0.01189994 -0.001874983 -0.09784388 0.01189994 -0.003749966 -0.08412688 0.01189994 -0.007874965 -0.08412688 0.01189994 -0.003749966 -0.08925718 0.01189994 -0.007874965 -0.08925718 0.01189994 -0.003749966 -0.09784388 0.01189994 -9.5e-4 -0.100167 0.01189994 -0.01504516 -0.0778684 0.01189994 -0.01337498 -0.07531946 0.01189994 -0.003749966 -0.07531946 0.01189994 -0.003749966 -0.07872378 0.01189994 -0.001874983 -0.07872378 0.01189994 0.001349985 -0.07872378 0.01189994 0.001874983 -0.07872378 0.01189994 0.001874983 -0.08925718 0.01189994 0.001874983 -0.08412688 0.01189994 0.001749992 -0.08191037 0.01189994 0.001749992 -0.07988959 0.01189994 0.007874965 -0.104335 0.01189994 0.001874983 -0.09784388 0.01189994 0.007874965 -0.08925718 0.01189994 0.007874965 -0.07872378 0.01189994 0.007874965 -0.07487726 0.01189994 0.008249998 -0.09198957 0.01189994 0.00999999 -0.09097927 0.01189994 0.007874965 -0.08412688 0.01189994 0.007874965 -0.07531946 0.01189994 0.02848696 -0.05031949 0.01189994 0.0309596 -0.04948955 0.01189994 0.03375959 -0.07872378 0.01189994 0.0309596 -0.07872378 0.01189994 0.0309596 -0.08412688 0.01189994 0.02848696 -0.07872378 0.01189994 0.03221929 -0.06804519 0.01189994 0.0309596 -0.06174999 0.01189994 0.0309596 -0.05609047 0.01189994 0.03375959 -0.05609047 0.01189994 0.0309596 -0.04373538 0.01189994 0.0309596 -0.02999997 0.01189994 0.03375959 -0.02999997 0.01189994 0.05449998 -0.04373538 0.01189994 0.05449998 -0.03275376 0.01189994 0.04699999 -0.04373538 0.01189994 0.04699999 -0.04899996 0.01189994 0.05037498 -0.04948955 0.01189994 0.04399996 -0.05399996 0.01189994 0.04349994 -0.04948955 0.01189994 0.04749995 -0.05486595 0.01189994 0.04786598 -0.05349999 0.01189994 0.04799997 -0.05399996 0.01189994 0.04449999 -0.05486595 0.01189994 0.05037498 -0.05609047 0.01189994 0.04499995 -0.05899995 0.01189994 0.04413396 -0.06049996 0.01189994 0.04449999 -0.05913394 0.01189994 0.04749995 -0.05913394 0.01189994 0.04799997 -0.06 0.01189994 0.04499995 -0.06099998 0.01189994 0.05037498 -0.06535255 0.01189994 0.05049997 -0.06174999 0.01189994 0.05037498 -0.06174999 0.01189994 0.07270997 -0.04948955 0.01189994 0.07270997 -0.04373538 0.01189994 0.05649995 -0.04373538 0.01189994 0.007874965 -0.0625 0.01069998 0.01115 -0.20599 0.01739996 0.0116201 -0.2064149 0.01739996 0.01243984 -0.207805 0.01189994 0.01383775 -0.210175 0.01739996 0.01383775 -0.210175 0.01189994 0.01392388 -0.210321 0.01189994 0.007396399 -0.203398 0.01739996 0.008253931 -0.203375 0.01189994 0.007194161 -0.203622 0.01189994 0.005724966 -0.20613 0.01189994 0.005724966 -0.20613 0.01739996 0.007554113 -0.211008 0.01739996 0.007554113 -0.211008 0.01189994 0.005724966 -0.209118 0.01739996 0.008183658 -0.21135 0.01189994 0.01115 -0.21135 0.01189994 0.01115 -0.21135 0.01739996 0.01243984 -0.21135 0.01739996 0.0132277 -0.21135 0.01189994 0.0132277 -0.21135 0.01739996 0.01027494 -0.214558 0.01739996 0.01084226 -0.215125 0.01189994 0.01084226 -0.215125 0.01739996 0.01104998 -0.2159 0.01739996 0.01104998 -0.2159 0.01189994 0.01084226 -0.216675 0.01739996 0.01027494 -0.217242 0.01189994 0.009499967 -0.21745 0.01189994 0.007999956 -0.21745 0.01189994 0.007224977 -0.217242 0.01189994 0.00665766 -0.216675 0.01189994 0.006449997 -0.2159 0.01189994 0.00665766 -0.215125 0.01189994 0.007224977 -0.214558 0.01189994 0.007999956 -0.21435 0.01189994 0.01341015 -0.221765 0.01739996 0.01341015 -0.221765 0.01189994 0.01243984 -0.222736 0.01189994 0.008183658 -0.22045 0.01189994 0.01115 -0.22045 0.01189994 0.01243984 -0.22045 0.01189994 0.01287978 -0.22045 0.01189994 0.005724966 -0.222781 0.01739996 0.004892289 -0.2234539 0.01189994 0.006363928 -0.222264 0.01739996 0.0068807 -0.221625 0.01189994 0.007554113 -0.2207919 0.01739996 0.00454998 -0.22824 0.01189994 0.00454998 -0.22824 0.01739996 0.00454998 -0.22878 0.01189994 0.00454998 -0.22878 0.01739996 -0.009499967 -0.21745 0.01189994 -0.009499967 -0.21745 0.01739996 -0.01027494 -0.217242 0.01189994 -0.01084226 -0.216675 0.01189994 -0.01084226 -0.216675 0.01739996 -0.01104998 -0.2159 0.01739996 -0.01104998 -0.2159 0.01189994 -0.01084226 -0.215125 0.01739996 -0.01027494 -0.214558 0.01189994 -0.01027494 -0.214558 0.01739996 -0.007999956 -0.21745 0.01739996 -0.007224977 -0.214558 0.01189994 -0.00665766 -0.215125 0.01189994 -0.006449997 -0.2159 0.01739996 -0.007224977 -0.217242 0.01189994 -0.00665766 -0.216675 0.01739996 -0.007999956 -0.21745 0.01189994 -0.007999956 -0.21435 0.01739996 -0.009499967 -0.21435 0.01739996 -0.0132277 -0.21135 0.01739996 -0.008183658 -0.21135 0.01739996 -0.0132277 -0.21135 0.01189994 -0.006747901 -0.210175 0.01739996 -0.005724966 -0.209118 0.01189994 -0.006747901 -0.210175 0.01189994 -0.008253931 -0.203375 0.01189994 -0.0116201 -0.2064149 0.01739996 -0.01383775 -0.210175 0.01739996 -0.01383775 -0.210175 0.01189994 -0.007973194 -0.203263 0.01739996 -0.007396399 -0.203398 0.01189994 -0.007396399 -0.203398 0.01739996 -0.007194161 -0.203622 0.01739996 -0.00454998 -0.224084 0.01739996 -0.007554113 -0.2207919 0.01739996 -0.006363928 -0.222264 0.01739996 -0.006363928 -0.222264 0.01189994 -0.005724966 -0.222781 0.01189994 -0.008183658 -0.22045 0.01189994 -0.001437485 -0.220515 0.01189994 -0.002374947 -0.220264 0.01189994 -0.002499997 -0.22023 0.01739996 -0.003780126 -0.21895 0.01739996 -0.004330098 -0.2184 0.01189994 -0.004999995 -0.2159 0.01739996 -0.004805803 -0.215175 0.01739996 -0.004805803 -0.215175 0.01189994 -0.004330098 -0.2134 0.01189994 -0.003874957 -0.212945 0.01739996 -0.003874957 -0.212945 0.01189994 -0.003780126 -0.21285 0.01739996 -0.002374947 -0.211536 0.01739996 -0.002374947 -0.211536 0.01189994 -0.001437485 -0.2112849 0.01739996 0 -0.2109 0.01739996 0.001437485 -0.2112849 0.01739996 0 -0.2109 0.01189994 0.001437485 -0.2112849 0.01189994 0.002499997 -0.21157 0.01739996 0.004805803 -0.215175 0.01739996 0.004999995 -0.2159 0.01189994 0.004805803 -0.216625 0.01739996 0.004330098 -0.2184 0.01739996 0.004805803 -0.216625 0.01189994 0.003780126 -0.21895 0.01189994 0.001437485 -0.220515 0.01739996 0.01575118 -0.223667 0.01189994 0.01640146 -0.222694 0.01739996 0.007766962 -0.231651 0.01189994 0.01115 -0.228268 0.01739996 0.01117819 -0.22824 0.01189994 0.01243984 -0.226978 0.01739996 0.01530379 -0.224114 0.01739996 0.007766962 -0.231651 0.01739996 0.005645632 -0.2325299 0.01739996 0.005645632 -0.2325299 0.01189994 -0.005645632 -0.2325299 0.01189994 -0.004805803 -0.2325299 0.01739996 -0.004805803 -0.2325299 0.01189994 -0.002374947 -0.2325299 0.01739996 -0.002374947 -0.2325299 0.01189994 -0.005724966 -0.232514 0.01189994 -0.006793677 -0.2323009 0.01189994 -0.007766962 -0.231651 0.01739996 -0.01117819 -0.22824 0.01189994 -0.01575118 -0.223667 0.01189994 -0.01661396 -0.221625 0.01739996 -0.01640146 -0.222694 0.01739996 -0.01662975 -0.209637 0.01189994 -0.01662975 -0.21895 0.01739996 -0.01662975 -0.2215459 0.01739996 -0.01662975 -0.209637 0.01739996 -0.01635575 -0.208384 0.01739996 -0.007226347 -0.198457 0.01739996 -0.007771193 -0.199407 0.01189994 -0.008620977 -0.200099 0.01189994 -0.007771193 -0.199407 0.01739996 -0.008620977 -0.200099 0.01739996 -0.007059216 -0.197374 0.01739996 -0.00847584 -0.1509 0.01189994 -0.009734332 -0.109614 0.01189994 -0.009734332 -0.109614 0.01739996 -0.009975492 -0.101703 0.01189994 -0.01399999 -0.09443509 0.01189994 -0.0121417 -0.09743857 0.01189994 -0.01042288 -0.100216 0.01739996 -0.01399999 -0.09443509 0.01739996 -0.01399999 -0.08856135 0.01189994 -0.01399999 -0.08856135 0.01739996 -0.01399999 -0.08051878 0.01739996 -0.005999982 -0.07589995 0.01189994 -0.002374947 -0.07589995 0.01189994 -0.002374947 -0.07589995 0.01739996 -0.001437485 -0.07589995 0.01739996 0.001437485 -0.07589995 0.01189994 0.004805803 -0.07589995 0.01189994 0.005999982 -0.07589995 0.01189994 0.01115 -0.07887339 0.01189994 0.01399999 -0.08856135 0.01189994 0.01399999 -0.08051878 0.01739996 0.01399999 -0.08856135 0.01739996 0.01399999 -0.09443509 0.01739996 0.01399999 -0.09443509 0.01189994 0.0121417 -0.09743857 0.01739996 0.01115 -0.09904128 0.01189994 0.01115 -0.09904128 0.01739996 0.01042288 -0.100216 0.01739996 0.01042288 -0.100216 0.01189994 0.007185637 -0.193226 0.01739996 0.007185637 -0.193226 0.01189994 0.00847584 -0.1509 0.01189994 0.009734332 -0.109614 0.01189994 0.008620977 -0.200099 0.01189994 0.007771193 -0.199407 0.01739996 0.007226347 -0.198457 0.01189994 0.007226347 -0.198457 0.01739996 0.007059216 -0.197374 0.01189994 0.01530379 -0.206619 0.01739996 0.01530379 -0.206619 0.01189994 0.0143916 -0.205089 0.01739996 0.01243984 -0.202998 0.01189994 0.01177364 -0.202285 0.01739996 0.01115 -0.201852 0.01189994 0.01635575 -0.208384 0.01739996 0.01635575 -0.208384 0.01189994 0.01662975 -0.21285 0.01189994 0.01662975 -0.21895 0.01189994 0.01662975 -0.21895 0.01739996 7.75e-4 -0.09915429 0.01189994 7.75e-4 -0.09743857 0.01189994 7.75e-4 -0.09743857 0.01739996 7.75e-4 -0.08856135 0.01189994 7.75e-4 -0.08684569 0.01189994 7.75e-4 -0.08684569 0.01739996 -7.75e-4 -0.09915429 0.01739996 -7.75e-4 -0.09743857 0.01189994 -7.75e-4 -0.09743857 0.01739996 -7.75e-4 -0.08856135 0.01189994 -7.75e-4 -0.08684569 0.01739996 0.003999948 -0.1832 0.01189994 0.003999948 -0.1832 0.01739996 0.003599941 -0.183093 0.01189994 0.003307163 -0.1827999 0.01189994 0.003307163 -0.1827999 0.01739996 0.003307163 -0.182 0.01739996 0.004399955 -0.181707 0.01189994 0.004399955 -0.181707 0.01739996 0.004692792 -0.1827999 0.01189994 0.004692792 -0.1827999 0.01739996 0.007224977 -0.214558 0.01739996 0.007999956 -0.21435 0.01739996 -0.003874957 -0.109614 0.01739996 0.005724966 -0.07589995 0.01739996 -0.00999999 -0.09174996 0.01739996 0.001342296 -0.223125 0.01739996 -0.001342296 -0.208675 0.01739996 -0.001437485 -0.20832 0.01739996 -0.005724966 -0.209118 0.01739996 -0.01392388 -0.210321 0.01739996 0.01357269 -0.221522 0.01739996 0.006935536 -0.22824 0.01739996 0.01243984 -0.21285 0.01739996 0.01397335 -0.21068 0.01739996 0.01392388 -0.210321 0.01739996 0.01243984 -0.207805 0.01739996 0.007194161 -0.203622 0.01739996 0.007670938 -0.203271 0.01739996 0.01243984 -0.202998 0.01739996 0.01115 -0.201852 0.01739996 0.008253931 -0.203375 0.01739996 0.008620977 -0.200099 0.01739996 0.007973194 -0.203263 0.01739996 0.004812002 -0.207868 0.01739996 0.004914522 -0.207513 0.01739996 0.004805803 -0.210175 0.01739996 0.005724966 -0.210175 0.01739996 0.007825374 -0.211259 0.01739996 0.008183658 -0.21135 0.01739996 0.001437485 -0.2325299 0.01739996 0.004805803 -0.22931 0.01739996 0.004650473 -0.229155 0.01739996 0.01117819 -0.22824 0.01739996 0.01115 -0.22824 0.01739996 0.005865275 -0.22931 0.01739996 0.006793677 -0.2323009 0.01739996 0.005724966 -0.229404 0.01739996 0.005724966 -0.232514 0.01739996 0.005621969 -0.2294729 0.01739996 0.004805803 -0.2325299 0.01739996 0.005334973 -0.22953 0.01739996 0.005299985 -0.22953 0.01739996 0.004924952 -0.229429 0.01739996 0.01243984 -0.222736 0.01739996 0.01115 -0.224025 0.01739996 0.01287978 -0.22045 0.01739996 0.01325476 -0.22055 0.01739996 0.01352936 -0.220825 0.01739996 0.01530379 -0.221625 0.01739996 0.01362979 -0.2211999 0.01739996 0.01362979 -0.221235 0.01739996 0.008183658 -0.22045 0.01739996 0.005724966 -0.221625 0.01739996 0.0068807 -0.221625 0.01739996 0.007825374 -0.220541 0.01739996 0.004641056 -0.223725 0.01739996 0.001437485 -0.22348 0.01739996 0.001549959 -0.2239 0.01739996 0.00454998 -0.224084 0.01739996 0.001549959 -0.2254 0.01739996 0.001437485 -0.22582 0.01739996 0.01115 -0.09743857 0.01739996 0.01115 -0.08856135 0.01739996 0.01115 -0.09262681 0.01739996 0.01243984 -0.08856135 0.01739996 0.01115 -0.09337317 0.01739996 -0.007670938 -0.203271 0.01739996 -0.008253931 -0.203375 0.01739996 -0.01177364 -0.202285 0.01739996 -0.0143916 -0.205089 0.01739996 -0.007825374 -0.211259 0.01739996 -0.01662975 -0.21285 0.01739996 -0.01357924 -0.211262 0.01739996 -0.0138489 -0.2110199 0.01739996 -0.01397335 -0.21068 0.01739996 -0.01662975 -0.210175 0.01739996 -0.004812002 -0.207868 0.01739996 -0.004914522 -0.207513 0.01739996 -0.005724966 -0.20613 0.01739996 -0.005724966 -0.210175 0.01739996 -0.005133807 -0.208508 0.01739996 -0.004891514 -0.208229 0.01739996 -0.01352936 -0.220825 0.01739996 -0.01362979 -0.2211999 0.01739996 -0.008183658 -0.22045 0.01739996 -0.007825374 -0.220541 0.01739996 -0.006793677 -0.2323009 0.01739996 -0.005724966 -0.229404 0.01739996 -0.005724966 -0.232514 0.01739996 -0.005621969 -0.2294729 0.01739996 -0.01362979 -0.221235 0.01739996 -0.01357269 -0.221522 0.01739996 -0.01350384 -0.221625 0.01739996 -0.01341015 -0.221765 0.01739996 -0.01575118 -0.223667 0.01739996 -0.006935536 -0.22824 0.01739996 -0.01117819 -0.22824 0.01739996 -0.005865275 -0.22931 0.01739996 -0.005334973 -0.22953 0.01739996 -0.005645632 -0.2325299 0.01739996 -0.005299985 -0.22953 0.01739996 -0.004924952 -0.229429 0.01739996 -0.003874957 -0.2325299 0.01739996 -0.004650473 -0.229155 0.01739996 -0.004805803 -0.22931 0.01739996 -0.004641056 -0.223725 0.01739996 -0.00454998 -0.22824 0.01739996 -0.00454998 -0.22878 0.01739996 -0.005724966 -0.221625 0.01739996 -0.005724966 -0.222781 0.01739996 -0.004892289 -0.2234539 0.01739996 -0.004805803 -0.221625 0.01739996 -0.004805803 -0.2235479 0.01739996 0.001437485 -0.20598 0.01739996 0.001342296 -0.2056249 0.01739996 7.75e-4 -0.205058 0.01739996 0 -0.20485 0.01739996 -7.75e-4 -0.205058 0.01739996 -0.001342296 -0.2056249 0.01739996 -0.002374947 -0.210175 0.01739996 -0.001549959 -0.2078999 0.01739996 0.001549959 -0.2064 0.01739996 0.001549959 -0.2078999 0.01739996 0.001437485 -0.20832 0.01739996 0.001342296 -0.208675 0.01739996 7.75e-4 -0.209242 0.01739996 0.001437485 -0.210175 0.01739996 0 -0.20945 0.01739996 -7.75e-4 -0.209242 0.01739996 -0.002499997 -0.21157 0.01739996 -0.003874957 -0.210175 0.01739996 -0.003874957 -0.21285 0.01739996 -0.004330098 -0.2134 0.01739996 -0.003874957 -0.21895 0.01739996 -0.003874957 -0.218855 0.01739996 -0.004805803 -0.21895 0.01739996 -0.004330098 -0.2184 0.01739996 -0.004805803 -0.216625 0.01739996 -0.002374947 -0.220264 0.01739996 0.001437485 -0.221625 0.01739996 0.004805803 -0.21895 0.01739996 0.003780126 -0.21895 0.01739996 0.004805803 -0.221625 0.01739996 0.002499997 -0.22023 0.01739996 0.004999995 -0.2159 0.01739996 0.005724966 -0.21895 0.01739996 -0.001437485 -0.210175 0.01739996 0 -0.2109 0.01739996 0.004805803 -0.21285 0.01739996 0.003780126 -0.21285 0.01739996 0.004330098 -0.2134 0.01739996 -0.001342296 -0.223125 0.01739996 -7.75e-4 -0.222558 0.01739996 -0.001437485 -0.221625 0.01739996 0 -0.22235 0.01739996 7.75e-4 -0.222558 0.01739996 -0.001342296 -0.226175 0.01739996 -0.001437485 -0.22582 0.01739996 -0.001549959 -0.2254 0.01739996 -0.001549959 -0.2239 0.01739996 -0.001437485 -0.22348 0.01739996 0.001342296 -0.226175 0.01739996 7.75e-4 -0.226742 0.01739996 0 -0.2269499 0.01739996 -7.75e-4 -0.226742 0.01739996 0.01350384 -0.221625 0.01739996 -0.005724966 -0.1509 0.01739996 -0.00847584 -0.1509 0.01739996 -0.007185637 -0.193226 0.01739996 -0.009975492 -0.101703 0.01739996 -0.005724966 -0.109614 0.01739996 -0.009374976 -0.09408247 0.01739996 -0.005724966 -0.09743857 0.01739996 -0.0121417 -0.09743857 0.01739996 -0.00999999 -0.09424996 0.01739996 -0.010625 -0.09408247 0.01739996 -0.00891745 -0.09237498 0.01739996 -0.008749961 -0.09299999 0.01739996 -0.01108247 -0.093625 0.01739996 -0.010625 -0.09191745 0.01739996 -0.005724966 -0.07589995 0.01739996 -0.005999982 -0.07589995 0.01739996 0.005999982 -0.07589995 0.01739996 0.005724966 -0.08856135 0.01739996 0.01115 -0.07887339 0.01739996 0.01243984 -0.07961809 0.01739996 0.01243984 -0.09695649 0.01739996 0.009734332 -0.109614 0.01739996 0.009975492 -0.101703 0.01739996 0.005724966 -0.09743857 0.01739996 0.007059216 -0.197374 0.01739996 0.005724966 -0.193226 0.01739996 0.00847584 -0.1509 0.01739996 0.005724966 -0.1509 0.01739996 0.005724966 -0.109614 0.01739996 0.01530379 -0.210175 0.01739996 0.01662975 -0.209637 0.01739996 -0.001100957 -0.100412 0.01739996 0.001100957 -0.100412 0.01739996 0.0011096 -0.09935116 0.01739996 -0.0011096 -0.09935116 0.01739996 -0.00130099 -0.09968888 0.01739996 -0.001297831 -0.100077 0.01739996 7.63216e-4 -0.100603 0.01739996 3.75e-4 -0.1006 0.01739996 -3.75e-4 -0.1006 0.01739996 7.75e-4 -0.09915429 0.01739996 7.75e-4 -0.08856135 0.01739996 0.0011096 -0.08664876 0.01739996 0.001437485 -0.08856135 0.01739996 0.00130099 -0.0863111 0.01739996 0.001297831 -0.08592277 0.01739996 -0.001082479 -0.08027499 0.01739996 -6.25e-4 -0.07981747 0.01739996 0 -0.07964998 0.01739996 6.25e-4 -0.08198249 0.01739996 -7.75e-4 -0.08856135 0.01739996 -0.001235187 -0.08576697 0.01739996 7.63216e-4 -0.08539676 0.01739996 0.001100957 -0.08558815 0.01739996 0.001082479 -0.08152496 0.01739996 0.001249969 -0.08089995 0.01739996 0.001082479 -0.08027499 0.01739996 0.001437485 -0.07589995 0.01739996 6.25e-4 -0.07981747 0.01739996 -0.001015424 -0.08551579 0.01739996 0 -0.08214998 0.01739996 -7.08435e-4 -0.08538478 0.01739996 -3.75e-4 -0.08539998 0.01739996 3.75e-4 -0.08539998 0.01739996 -0.00106877 -0.08668726 0.01739996 -0.00126481 -0.08641719 0.01739996 -0.003999948 -0.1832 0.01739996 -0.003874957 -0.193226 0.01739996 -0.004399955 -0.181707 0.01739996 -0.004399955 -0.183093 0.01739996 -0.004692792 -0.1827999 0.01739996 -0.004799962 -0.1823999 0.01739996 -0.004692792 -0.182 0.01739996 -0.003999948 -0.1816 0.01739996 -0.003874957 -0.1816329 0.01739996 -0.003599941 -0.181707 0.01739996 -0.003307163 -0.1827999 0.01739996 -0.003599941 -0.183093 0.01739996 -0.003874957 -0.183167 0.01739996 -0.003307163 -0.182 0.01739996 -0.003199994 -0.1823999 0.01739996 -0.002374947 -0.1509 0.01739996 -0.001437485 -0.20598 0.01739996 -0.004399955 -0.120093 0.01739996 -0.004799962 -0.1194 0.01739996 -0.004805803 -0.1509 0.01739996 -0.002374947 -0.109614 0.01739996 -0.003874957 -0.1509 0.01739996 -0.003599941 -0.120093 0.01739996 -0.003874957 -0.120167 0.01739996 -0.005724966 -0.21285 0.01739996 -0.007224977 -0.214558 0.01739996 -0.00665766 -0.215125 0.01739996 -0.005724966 -0.21895 0.01739996 -0.007224977 -0.217242 0.01739996 -0.01325476 -0.22055 0.01739996 -0.01287978 -0.22045 0.01739996 -0.01027494 -0.217242 0.01739996 -0.005724966 -0.193226 0.01739996 -0.004805803 -0.193226 0.01739996 -0.004805803 -0.109614 0.01739996 -0.005724966 -0.08856135 0.01739996 -0.004805803 -0.09743857 0.01739996 -0.004805803 -0.08856135 0.01739996 -0.003874957 -0.09743857 0.01739996 -0.003874957 -0.118633 0.01739996 -0.004805803 -0.21285 0.01739996 -0.007554113 -0.211008 0.01739996 -0.0068807 -0.221625 0.01739996 -0.001549959 -0.2064 0.01739996 -0.002374947 -0.193226 0.01739996 -0.004805803 -0.210175 0.01739996 -0.003874957 -0.22824 0.01739996 -0.003874957 -0.221625 0.01739996 -0.002374947 -0.221625 0.01739996 -0.001437485 -0.220515 0.01739996 0 -0.2208999 0.01739996 -6.25e-4 -0.08198249 0.01739996 -0.001082479 -0.08152496 0.01739996 -0.001324176 -0.08608865 0.01739996 -0.001249969 -0.08089995 0.01739996 -0.001437485 -0.08856135 0.01739996 -0.002374947 -0.08856135 0.01739996 -0.003874957 -0.07589995 0.01739996 -0.001437485 -0.09743857 0.01739996 -0.003307163 -0.119 0.01739996 -0.003199994 -0.1194 0.01739996 -0.001437485 -0.193226 0.01739996 0.001437485 -0.22824 0.01739996 -0.001437485 -0.22824 0.01739996 -0.001437485 -0.2325299 0.01739996 -0.002374947 -0.22824 0.01739996 0.004805803 -0.07589995 0.01739996 0.004805803 -0.09743857 0.01739996 0.003199994 -0.1194 0.01739996 0.003307163 -0.119 0.01739996 0.003599941 -0.118707 0.01739996 0.003999948 -0.1186 0.01739996 0.00130099 -0.09968888 0.01739996 0.001297831 -0.100077 0.01739996 0.001437485 -0.09743857 0.01739996 0.001437485 -0.109614 0.01739996 0.004799962 -0.1194 0.01739996 0.004692792 -0.119 0.01739996 0.004399955 -0.118707 0.01739996 0.004692792 -0.1198 0.01739996 0.004399955 -0.120093 0.01739996 0.003999948 -0.1202 0.01739996 0.003599941 -0.120093 0.01739996 0.003307163 -0.1198 0.01739996 -7.63216e-4 -0.100603 0.01739996 0.004799962 -0.1823999 0.01739996 0.004692792 -0.182 0.01739996 0.004399955 -0.183093 0.01739996 0.001437485 -0.193226 0.01739996 0.003599941 -0.183093 0.01739996 0.003599941 -0.181707 0.01739996 0.003999948 -0.1816 0.01739996 0.003199994 -0.1823999 0.01739996 0.001437485 -0.1509 0.01739996 -0.001437485 -0.1509 0.01739996 -0.001437485 -0.109614 0.01739996 -0.002374947 -0.09743857 0.01739996 -0.003874957 -0.08856135 0.01739996 -0.004805803 -0.07589995 0.01739996 0.005133807 -0.208508 0.01739996 0.004891514 -0.208229 0.01739996 0.004805803 -0.193226 0.01739996 0.004805803 -0.1509 0.01739996 0.004805803 -0.109614 0.01739996 0.004805803 -0.08856135 0.01739996 0.006747901 -0.210175 0.01739996 0.004805803 -0.2235479 0.01739996 0.004892289 -0.2234539 0.01739996 0.009499967 -0.21435 0.01739996 0.01115 -0.21285 0.01739996 0.01027494 -0.217242 0.01739996 0.009499967 -0.21745 0.01739996 0.007999956 -0.21745 0.01739996 0.007224977 -0.217242 0.01739996 0.00665766 -0.216675 0.01739996 0.006449997 -0.2159 0.01739996 0.005724966 -0.21285 0.01739996 0.00665766 -0.215125 0.01739996 0.01115 -0.22045 0.01739996 0.01243984 -0.22045 0.01739996 0.01115 -0.21895 0.01739996 0.01243984 -0.21895 0.01739996 0.01357924 -0.211262 0.01739996 0.0138489 -0.2110199 0.01739996 0.01575118 -0.223667 0.01739996 0.01661396 -0.221625 0.01739996 0.01662975 -0.2215459 0.01739996 0.01530379 -0.21895 0.01739996 0.01662975 -0.21285 0.01739996 0.01530379 -0.21285 0.01739996 0.01662975 -0.210175 0.01739996 -0.003999948 -0.1202 0.01739996 -0.004692792 -0.1198 0.01739996 -0.004692792 -0.119 0.01739996 -0.004399955 -0.118707 0.01189994 -0.004399955 -0.118707 0.01739996 -0.003999948 -0.1186 0.01739996 -0.003874957 -0.118633 0.01189994 -0.003599941 -0.118707 0.01739996 -0.003307163 -0.119 0.01189994 -0.003599941 -0.120093 0.01189994 -0.003307163 -0.1198 0.01739996 -0.004399955 -0.120093 0.01189994 0.005724966 -0.109614 0.01189994 -0.001235187 -0.08576697 0.01189994 -0.001324176 -0.08608865 0.01189994 0.01115 -0.22824 0.01189994 -0.003780126 -0.21285 0.01189994 0.007396399 -0.203398 0.01189994 0.007973194 -0.203263 0.01189994 0.007771193 -0.199407 0.01189994 0.007670938 -0.203271 0.01189994 0.005724966 -0.193226 0.01189994 0.01115 -0.20599 0.01189994 0.0116201 -0.2064149 0.01189994 0.01177364 -0.202285 0.01189994 0.0143916 -0.205089 0.01189994 0.01357924 -0.211262 0.01189994 0.0138489 -0.2110199 0.01189994 0.01397335 -0.21068 0.01189994 0.005133807 -0.208508 0.01189994 0.005724966 -0.209118 0.01189994 0.006747901 -0.210175 0.01189994 0.005724966 -0.21285 0.01189994 0.007825374 -0.211259 0.01189994 0.004812002 -0.207868 0.01189994 0.004914522 -0.207513 0.01189994 0.01362979 -0.2211999 0.01189994 0.01325476 -0.22055 0.01189994 0.01350384 -0.221625 0.01189994 0.01357269 -0.221522 0.01189994 0.01362979 -0.221235 0.01189994 0.005724966 -0.232514 0.01189994 0.005724966 -0.229404 0.01189994 0.005865275 -0.22931 0.01189994 0.006793677 -0.2323009 0.01189994 0.01115 -0.228268 0.01189994 0.006935536 -0.22824 0.01189994 0.01115 -0.224025 0.01189994 0.01243984 -0.226978 0.01189994 0.01530379 -0.224114 0.01189994 0.005621969 -0.2294729 0.01189994 0.005334973 -0.22953 0.01189994 0.005299985 -0.22953 0.01189994 0.004805803 -0.2325299 0.01189994 0.004924952 -0.229429 0.01189994 0.001437485 -0.2325299 0.01189994 0.004650473 -0.229155 0.01189994 0.004805803 -0.22931 0.01189994 0.001437485 -0.22582 0.01189994 0.00454998 -0.224084 0.01189994 0.001549959 -0.2254 0.01189994 0.004805803 -0.2235479 0.01189994 0.007825374 -0.220541 0.01189994 0.005724966 -0.21895 0.01189994 0.007554113 -0.2207919 0.01189994 0.010625 -0.09191745 0.01189994 0.009374976 -0.09191745 0.01189994 0.00891745 -0.09237498 0.01189994 0.008749961 -0.09299999 0.01189994 0.00891745 -0.093625 0.01189994 0.009374976 -0.09408247 0.01189994 0.00999999 -0.09424996 0.01189994 0.010625 -0.09408247 0.01189994 0.01115 -0.09743857 0.01189994 0.01108247 -0.093625 0.01189994 0.01115 -0.09337317 0.01189994 0.01243984 -0.08856135 0.01189994 0.01124995 -0.09299999 0.01189994 0.01115 -0.08856135 0.01189994 0.01115 -0.09262681 0.01189994 0.01108247 -0.09237498 0.01189994 -0.008183658 -0.21135 0.01189994 -0.007825374 -0.211259 0.01189994 -0.01392388 -0.210321 0.01189994 -0.01662975 -0.210175 0.01189994 -0.01397335 -0.21068 0.01189994 -0.0138489 -0.2110199 0.01189994 -0.01357924 -0.211262 0.01189994 -0.007194161 -0.203622 0.01189994 -0.01177364 -0.202285 0.01189994 -0.007973194 -0.203263 0.01189994 -0.007670938 -0.203271 0.01189994 -0.007059216 -0.197374 0.01189994 -0.007226347 -0.198457 0.01189994 -0.0116201 -0.2064149 0.01189994 -0.01635575 -0.208384 0.01189994 -0.0143916 -0.205089 0.01189994 -0.004914522 -0.207513 0.01189994 -0.005724966 -0.20613 0.01189994 -0.005724966 -0.193226 0.01189994 -0.007554113 -0.211008 0.01189994 -0.005133807 -0.208508 0.01189994 -0.004805803 -0.22931 0.01189994 -0.004924952 -0.229429 0.01189994 -0.01640146 -0.222694 0.01189994 -0.01350384 -0.221625 0.01189994 -0.005299985 -0.22953 0.01189994 -0.005334973 -0.22953 0.01189994 -0.005621969 -0.2294729 0.01189994 -0.005724966 -0.229404 0.01189994 -0.005865275 -0.22931 0.01189994 -0.007766962 -0.231651 0.01189994 -0.006935536 -0.22824 0.01189994 -0.01341015 -0.221765 0.01189994 -0.0068807 -0.221625 0.01189994 -0.01662975 -0.21895 0.01189994 -0.007554113 -0.2207919 0.01189994 -0.007825374 -0.220541 0.01189994 -0.01287978 -0.22045 0.01189994 -0.01325476 -0.22055 0.01189994 -0.01352936 -0.220825 0.01189994 -0.01362979 -0.2211999 0.01189994 -0.01662975 -0.2215459 0.01189994 -0.01661396 -0.221625 0.01189994 -0.01362979 -0.221235 0.01189994 -0.01357269 -0.221522 0.01189994 -0.004892289 -0.2234539 0.01189994 -0.004805803 -0.221625 0.01189994 -0.004805803 -0.2235479 0.01189994 -0.004641056 -0.223725 0.01189994 -0.004650473 -0.229155 0.01189994 -0.00454998 -0.22878 0.01189994 -0.00454998 -0.22824 0.01189994 -0.00454998 -0.224084 0.01189994 -0.001437485 -0.20598 0.01189994 -0.001549959 -0.2064 0.01189994 -0.001549959 -0.2078999 0.01189994 0.001437485 -0.20598 0.01189994 0 -0.20485 0.01189994 -7.75e-4 -0.205058 0.01189994 0.001437485 -0.20832 0.01189994 0.001437485 -0.210175 0.01189994 -0.001437485 -0.210175 0.01189994 -7.75e-4 -0.209242 0.01189994 0 -0.20945 0.01189994 7.75e-4 -0.209242 0.01189994 0.001342296 -0.208675 0.01189994 0.004330098 -0.2134 0.01189994 0.004805803 -0.21285 0.01189994 0.003780126 -0.21285 0.01189994 0.002499997 -0.21157 0.01189994 0 -0.2208999 0.01189994 0.001437485 -0.220515 0.01189994 0.002499997 -0.22023 0.01189994 -0.002499997 -0.22023 0.01189994 -0.004805803 -0.21285 0.01189994 -0.004999995 -0.2159 0.01189994 -0.004805803 -0.216625 0.01189994 -0.003874957 -0.21895 0.01189994 -0.003874957 -0.218855 0.01189994 -0.003780126 -0.21895 0.01189994 -0.001437485 -0.20832 0.01189994 -0.001342296 -0.208675 0.01189994 0 -0.2109 0.01189994 -0.001437485 -0.2112849 0.01189994 -0.001437485 -0.221625 0.01189994 -0.001437485 -0.22348 0.01189994 -0.002374947 -0.221625 0.01189994 -0.001549959 -0.2239 0.01189994 0.001549959 -0.2239 0.01189994 0.004641056 -0.223725 0.01189994 0.001437485 -0.22348 0.01189994 0.001342296 -0.223125 0.01189994 7.75e-4 -0.222558 0.01189994 0.001437485 -0.221625 0.01189994 0 -0.22235 0.01189994 -7.75e-4 -0.222558 0.01189994 -0.001342296 -0.223125 0.01189994 0.001342296 -0.226175 0.01189994 -0.001437485 -0.22582 0.01189994 -0.001342296 -0.226175 0.01189994 -7.75e-4 -0.226742 0.01189994 0 -0.2269499 0.01189994 7.75e-4 -0.226742 0.01189994 0.009975492 -0.101703 0.01189994 0.005724966 -0.1509 0.01189994 0.0121417 -0.09743857 0.01189994 0.005724966 -0.09743857 0.01189994 0.01243984 -0.07961809 0.01189994 0.01399999 -0.08051878 0.01189994 0.01243984 -0.09695649 0.01189994 0.00999999 -0.09174996 0.01189994 0.005724966 -0.08856135 0.01189994 -0.01399999 -0.08051878 0.01189994 -0.009374976 -0.09191745 0.01189994 -0.00999999 -0.09174996 0.01189994 -0.00999999 -0.09424996 0.01189994 -0.009374976 -0.09408247 0.01189994 -0.005724966 -0.08856135 0.01189994 -0.00891745 -0.093625 0.01189994 -0.008749961 -0.09299999 0.01189994 -0.00891745 -0.09237498 0.01189994 -0.010625 -0.09191745 0.01189994 -0.01108247 -0.09237498 0.01189994 -0.01124995 -0.09299999 0.01189994 -0.01108247 -0.093625 0.01189994 -0.010625 -0.09408247 0.01189994 -0.01042288 -0.100216 0.01189994 -0.007185637 -0.193226 0.01189994 -0.005724966 -0.109614 0.01189994 0.01530379 -0.221625 0.01189994 0.01640146 -0.222694 0.01189994 0.01662975 -0.2215459 0.01189994 0.01661396 -0.221625 0.01189994 0.001100957 -0.100412 0.01189994 -0.0011096 -0.09935116 0.01189994 7.63216e-4 -0.100603 0.01189994 0.001437485 -0.109614 0.01189994 0.0011096 -0.09935116 0.01189994 0.00130099 -0.09968888 0.01189994 -0.00130099 -0.09968888 0.01189994 -0.001297831 -0.100077 0.01189994 -0.001100957 -0.100412 0.01189994 -7.63216e-4 -0.100603 0.01189994 0 -0.07964998 0.01189994 6.25e-4 -0.07981747 0.01189994 0.001082479 -0.08027499 0.01189994 -0.00126481 -0.08641719 0.01189994 6.25e-4 -0.08198249 0.01189994 3.75e-4 -0.08539998 0.01189994 0 -0.08214998 0.01189994 -3.75e-4 -0.08539998 0.01189994 -7.08435e-4 -0.08538478 0.01189994 -6.25e-4 -0.08198249 0.01189994 -0.001015424 -0.08551579 0.01189994 -0.001437485 -0.08856135 0.01189994 -7.75e-4 -0.09915429 0.01189994 -0.001437485 -0.09743857 0.01189994 -0.00106877 -0.08668726 0.01189994 -7.75e-4 -0.08684569 0.01189994 0.0011096 -0.08664876 0.01189994 0.001437485 -0.08856135 0.01189994 0.00130099 -0.0863111 0.01189994 0.001297831 -0.08592277 0.01189994 -6.25e-4 -0.07981747 0.01189994 -0.001082479 -0.08027499 0.01189994 -0.001437485 -0.07589995 0.01189994 -0.001249969 -0.08089995 0.01189994 0.001249969 -0.08089995 0.01189994 0.001082479 -0.08152496 0.01189994 0.001100957 -0.08558815 0.01189994 7.63216e-4 -0.08539676 0.01189994 -0.001082479 -0.08152496 0.01189994 -0.004805803 -0.193226 0.01189994 -0.003999948 -0.1816 0.01189994 -0.004399955 -0.181707 0.01189994 -0.004805803 -0.1509 0.01189994 -0.004692792 -0.182 0.01189994 -0.004799962 -0.1823999 0.01189994 -0.004692792 -0.1827999 0.01189994 -0.004399955 -0.183093 0.01189994 -0.003874957 -0.193226 0.01189994 -0.003999948 -0.1832 0.01189994 -0.003874957 -0.183167 0.01189994 -0.003599941 -0.183093 0.01189994 -0.003307163 -0.1827999 0.01189994 -0.003199994 -0.1823999 0.01189994 -0.003307163 -0.182 0.01189994 -0.003599941 -0.181707 0.01189994 -0.003999948 -0.1186 0.01189994 -0.004692792 -0.1198 0.01189994 -0.003874957 -0.1816329 0.01189994 -0.003874957 -0.1509 0.01189994 -0.004799962 -0.1194 0.01189994 -0.004805803 -0.109614 0.01189994 -0.004692792 -0.119 0.01189994 -0.003999948 -0.1202 0.01189994 -0.003874957 -0.120167 0.01189994 -0.003307163 -0.1198 0.01189994 -0.002374947 -0.1509 0.01189994 -0.003199994 -0.1194 0.01189994 -0.002374947 -0.109614 0.01189994 0.01662975 -0.209637 0.01189994 0.01530379 -0.210175 0.01189994 0.01530379 -0.21285 0.01189994 0.01662975 -0.210175 0.01189994 0.01530379 -0.21895 0.01189994 0.01352936 -0.220825 0.01189994 0.01243984 -0.21895 0.01189994 0.01243984 -0.21285 0.01189994 0.01115 -0.21895 0.01189994 0.01084226 -0.216675 0.01189994 0.01243984 -0.21135 0.01189994 0.01027494 -0.214558 0.01189994 0.01115 -0.21285 0.01189994 0.009499967 -0.21435 0.01189994 0.004805803 -0.215175 0.01189994 0.004805803 -0.210175 0.01189994 0.005724966 -0.210175 0.01189994 0.004891514 -0.208229 0.01189994 0.006363928 -0.222264 0.01189994 0.005724966 -0.221625 0.01189994 0.005724966 -0.222781 0.01189994 0.004805803 -0.221625 0.01189994 0.004805803 -0.21895 0.01189994 0.004330098 -0.2184 0.01189994 0.004805803 -0.08856135 0.01189994 0.001297831 -0.100077 0.01189994 0.001437485 -0.09743857 0.01189994 0.004805803 -0.09743857 0.01189994 0.005724966 -0.07589995 0.01189994 0.004692792 -0.1198 0.01189994 0.004692792 -0.119 0.01189994 0.004399955 -0.118707 0.01189994 0.004805803 -0.109614 0.01189994 0.003999948 -0.1186 0.01189994 0.003599941 -0.118707 0.01189994 0.004799962 -0.1194 0.01189994 0.003307163 -0.119 0.01189994 0.003199994 -0.1194 0.01189994 0.003307163 -0.1198 0.01189994 0.003599941 -0.120093 0.01189994 0.003999948 -0.1202 0.01189994 0.004399955 -0.120093 0.01189994 0.001549959 -0.2078999 0.01189994 0.001549959 -0.2064 0.01189994 0.004399955 -0.183093 0.01189994 0.003599941 -0.181707 0.01189994 0.001437485 -0.1509 0.01189994 0.003999948 -0.1816 0.01189994 0.004805803 -0.1509 0.01189994 0.004692792 -0.182 0.01189994 0.004805803 -0.193226 0.01189994 0.004799962 -0.1823999 0.01189994 0.003307163 -0.182 0.01189994 0.003199994 -0.1823999 0.01189994 0.001437485 -0.193226 0.01189994 0.001342296 -0.2056249 0.01189994 7.75e-4 -0.205058 0.01189994 -0.001437485 -0.193226 0.01189994 -0.001437485 -0.1509 0.01189994 -0.001437485 -0.109614 0.01189994 3.75e-4 -0.1006 0.01189994 -3.75e-4 -0.1006 0.01189994 -0.001342296 -0.2056249 0.01189994 -0.002374947 -0.09743857 0.01189994 -0.003599941 -0.118707 0.01189994 -0.003874957 -0.09743857 0.01189994 -0.002374947 -0.08856135 0.01189994 -0.003874957 -0.08856135 0.01189994 -0.003874957 -0.22824 0.01189994 -0.001549959 -0.2254 0.01189994 -0.003874957 -0.2325299 0.01189994 -0.002374947 -0.22824 0.01189994 -0.001437485 -0.22824 0.01189994 0.001437485 -0.22824 0.01189994 -0.001437485 -0.2325299 0.01189994 -0.003874957 -0.109614 0.01189994 -0.004805803 -0.09743857 0.01189994 -0.003874957 -0.07589995 0.01189994 -0.002374947 -0.193226 0.01189994 -0.002374947 -0.210175 0.01189994 -0.003874957 -0.210175 0.01189994 -0.004891514 -0.208229 0.01189994 -0.004812002 -0.207868 0.01189994 -0.005724966 -0.1509 0.01189994 -0.005724966 -0.09743857 0.01189994 -0.004805803 -0.08856135 0.01189994 -0.004805803 -0.07589995 0.01189994 -0.005724966 -0.07589995 0.01189994 -0.005724966 -0.21285 0.01189994 -0.005724966 -0.210175 0.01189994 -0.004805803 -0.210175 0.01189994 -0.003874957 -0.21285 0.01189994 -0.002499997 -0.21157 0.01189994 -0.005724966 -0.21895 0.01189994 -0.004805803 -0.21895 0.01189994 -0.005724966 -0.221625 0.01189994 -0.003874957 -0.221625 0.01189994 -0.007999956 -0.21435 0.01189994 -0.00665766 -0.216675 0.01189994 -0.006449997 -0.2159 0.01189994 -0.009499967 -0.21435 0.01189994 -0.01662975 -0.21285 0.01189994 -0.01084226 -0.215125 0.01189994 2e-4 -0.1006 0.01859998 4.12635e-4 -0.100666 0.01739996 6.32671e-4 -0.100632 0.01859998 6.32671e-4 -0.100632 0.01739996 8.16526e-4 -0.100507 0.01739996 9.44415e-4 -0.100092 0.01859998 9.27786e-4 -0.100314 0.01739996 9.44415e-4 -0.100092 0.01739996 8.63119e-4 -0.09988528 0.01739996 7e-4 -0.099734 0.01859998 7e-4 -0.099734 0.01739996 -7e-4 -0.099734 0.01739996 -7e-4 -0.099734 0.01859998 -8.83013e-4 -0.09991699 0.01739996 -8.83013e-4 -0.09991699 0.01859998 -9.5e-4 -0.100167 0.01859998 -9.5e-4 -0.100167 0.01739996 -8.83013e-4 -0.100417 0.01859998 -7e-4 -0.1006 0.01859998 0.08888781 -0.05891185 0.01739996 0.09281396 -0.05211156 0.01859998 0.09281396 -0.05211156 0.01739996 0.09546309 -0.04752308 0.01859998 0.09172016 -0.04055827 0.01859998 0.09172016 -0.04055827 0.01739996 0.0887832 -0.03509318 0.01859998 0.08054035 -0.03033417 0.01739996 0.07673126 -0.028135 0.01859998 0.07394945 -0.02974116 0.01859998 0.07394945 -0.02974116 0.01739996 0.07308501 -0.03024017 0.01859998 0.0687313 -0.03275376 0.01859998 0.06340569 -0.04197806 0.01859998 0.01236647 -0.07222425 0.01859998 0.03189635 -0.06094866 0.01859998 0.03812855 -0.05735045 0.01859998 0.04412007 -0.0538913 0.01859998 0.04720264 -0.05211156 0.01739996 0.04720264 -0.05211156 0.01859998 0.05444729 -0.04792886 0.01739996 -0.005999982 -0.07589995 0.01859998 -0.001724958 -0.07589995 0.01859998 0.001724958 -0.07589995 0.01859998 -0.01189398 -0.07249706 0.01739996 -0.04412007 -0.0538913 0.01739996 -0.05444729 -0.04792886 0.01859998 -0.05444729 -0.04792886 0.01739996 -0.06273126 -0.04314619 0.01859998 -0.06340569 -0.04197806 0.01859998 -0.06273126 -0.04314619 0.01739996 -0.06422537 -0.04055827 0.01739996 -0.0687313 -0.03275376 0.01859998 -0.07673126 -0.028135 0.01859998 -0.08054035 -0.03033417 0.01859998 -0.08054035 -0.03033417 0.01739996 -0.09178638 -0.0538913 0.01739996 -0.08888781 -0.05891185 0.01859998 -0.08054035 -0.05916637 0.01859998 -0.07394945 -0.05936729 0.01859998 -0.07308501 -0.05939358 0.01859998 -0.06844866 -0.05953496 0.01739996 -0.06599998 -0.06094866 0.01739996 -0.06340569 -0.06244647 0.01859998 -0.05639737 -0.06649279 0.01859998 -0.05639737 -0.06649279 0.01739996 -0.04599756 -0.07249706 0.01859998 -0.04505658 -0.07304036 0.01859998 -0.04505658 -0.07304036 0.01739996 -0.04072648 -0.07554036 0.01739996 -0.04072648 -0.07554036 0.01859998 -0.01236647 -0.09707516 0.01739996 0.006575286 -0.106435 0.01859998 -0.001724958 -0.106435 0.01859998 -0.005624949 -0.106435 0.01859998 0.006575286 -0.106435 0.01739996 0.01236647 -0.09707516 0.01739996 -0.03399759 -0.07249706 0.01739996 -0.019894 -0.07249706 0.01739996 -0.03203547 -0.0654872 0.01739996 0.03592747 -0.07022815 0.01859998 0.01384896 -0.07598716 0.01859998 0.019894 -0.07249706 0.01859998 0.01384896 -0.07598716 0.01739996 0.03203547 -0.0654872 0.01739996 0.06340569 -0.06244647 0.01739996 0.04599756 -0.07249706 0.01739996 0.04505658 -0.07304036 0.01739996 0.0173344 -0.08904576 0.01739996 0.01236647 -0.0843665 0.01739996 -0.01236647 -0.07249706 0.01739996 -0.04364305 -0.07249706 0.01739996 0.06340569 -0.04197806 0.01739996 -0.08608907 -0.05072319 0.01739996 -0.08602219 -0.05047315 0.01739996 -7e-4 -0.08626598 0.01739996 0.08722215 -0.04926079 0.01739996 0.08713126 -0.04923635 0.01739996 0.08672219 -0.04926079 0.01739996 0.05674999 -0.05199998 0.01739996 -0.05924999 -0.05199998 0.01739996 -0.05908244 -0.052625 0.01739996 -0.05677986 -0.05211156 0.01739996 -0.05691748 -0.052625 0.01739996 -0.05737495 -0.05308246 0.01739996 -0.05908244 -0.05137497 0.01739996 -0.06059998 -0.04706287 0.01739996 -0.06340569 -0.04684996 0.01739996 -0.06078296 -0.04724586 0.01739996 -0.05691748 -0.05137497 0.01739996 -0.05737495 -0.05091744 0.01739996 -0.05799996 -0.05074995 0.01739996 -0.05862498 -0.05091744 0.01739996 -0.06009995 -0.04792886 0.01739996 -0.06035 -0.04799586 0.01739996 -0.06059998 -0.04792886 0.01739996 0.05862498 -0.05308246 0.01739996 0.06340569 -0.0538913 0.01739996 0.05908244 -0.052625 0.01739996 0.05737495 -0.05308246 0.01739996 0.05691748 -0.052625 0.01739996 0.05677986 -0.05211156 0.01739996 0.06076306 -0.04721426 0.01739996 0.06059998 -0.04706287 0.01739996 0.06059998 -0.04684996 0.01739996 0.05799996 -0.05074995 0.01739996 0.05924999 -0.05199998 0.01739996 0.05908244 -0.05137497 0.01739996 0.05691748 -0.05137497 0.01739996 0.06031256 -0.04799449 0.01739996 0.06053268 -0.04796135 0.01739996 0.06071645 -0.04783594 0.01739996 0.06082779 -0.0476433 0.01739996 0.06340569 -0.04684996 0.01739996 0.06084436 -0.04742139 0.01739996 0.05639737 -0.04792886 0.01739996 0.06009995 -0.04792886 0.01739996 0.05862498 -0.05091744 0.01739996 -0.001724958 -0.0843665 0.01739996 0 -0.08339995 0.01739996 -0.001249969 -0.08306509 0.01739996 -0.002165019 -0.08214998 0.01739996 -0.001724958 -0.0825901 0.01739996 0 -0.07839995 0.01739996 -0.001724958 -0.07589995 0.01739996 -0.001249969 -0.07873487 0.01739996 -0.001724958 -0.07920986 0.01739996 -0.005624949 -0.07589995 0.01739996 -0.002165019 -0.07964998 0.01739996 -0.002499997 -0.08089995 0.01739996 0.001724958 -0.0825901 0.01739996 0.002165019 -0.08214998 0.01739996 0.002499997 -0.08089995 0.01739996 0.002165019 -0.07964998 0.01739996 0.001724958 -0.07589995 0.01739996 0.001724958 -0.07920986 0.01739996 0.001249969 -0.07873487 0.01739996 -0.07222646 -0.04169994 0.01739996 -0.07131147 -0.04261505 0.01739996 -0.0700615 -0.04294997 0.01739996 -0.06881147 -0.04261505 0.01739996 -0.0725615 -0.04044997 0.01739996 -0.07308501 -0.04055827 0.01739996 -0.06789636 -0.03919994 0.01739996 -0.06881147 -0.03828489 0.01739996 -0.0700615 -0.03794997 0.01739996 -0.07131147 -0.03828489 0.01739996 -0.07308501 -0.03024017 0.01739996 -0.07222646 -0.03919994 0.01739996 0.07131147 -0.04261505 0.01739996 0.07222646 -0.04169994 0.01739996 0.07253235 -0.04055827 0.01739996 0.06422537 -0.04055827 0.01739996 0.06881147 -0.03828489 0.01739996 0.06789636 -0.03919994 0.01739996 0.0675615 -0.04044997 0.01739996 0.06759047 -0.04055827 0.01739996 0.06789636 -0.04169994 0.01739996 0.06881147 -0.04261505 0.01739996 0.0700615 -0.04294997 0.01739996 0.07308501 -0.04684996 0.01739996 0.07308501 -0.03024017 0.01739996 0.07222646 -0.03919994 0.01739996 0.0687313 -0.03275376 0.01739996 0.07131147 -0.03828489 0.01739996 0.0700615 -0.03794997 0.01739996 0.07430857 -0.04209375 0.01739996 0.07412558 -0.04227679 0.01739996 0.08254659 -0.04684996 0.01739996 0.08054035 -0.04569166 0.01739996 0.07505857 -0.04252678 0.01739996 0.07499158 -0.04227679 0.01739996 0.07394945 -0.04055827 0.01739996 0.07480859 -0.04209375 0.01739996 0.07455855 -0.04202675 0.01739996 0.0874052 -0.04944378 0.01739996 0.09546309 -0.04752308 0.01739996 0.0874722 -0.04969376 0.01739996 0.0874052 -0.0499438 0.01739996 0.08722215 -0.05012679 0.01739996 0.0867722 -0.05090618 0.01739996 0.08695518 -0.05072319 0.01739996 0.08702218 -0.05047315 0.01739996 0.08602219 -0.05047315 0.01739996 0.08608907 -0.05072319 0.01739996 0.08627218 -0.05090618 0.01739996 0.08054035 -0.05211156 0.01739996 0.08652216 -0.05097317 0.01739996 0.07435858 -0.04373919 0.01739996 0.0741086 -0.04380619 0.01739996 0.07385855 -0.04373919 0.01739996 0.07394945 -0.04376357 0.01739996 0.07405859 -0.04252678 0.01739996 0.07394945 -0.04271578 0.01739996 0.07385855 -0.0428732 0.01739996 0.07308501 -0.04055827 0.01739996 0.07367557 -0.04305619 0.01739996 0.07360857 -0.04330617 0.01739996 0.07367557 -0.04355615 0.01739996 -4.5e-4 -0.08533298 0.01739996 -7e-4 -0.08539998 0.01739996 -8.83013e-4 -0.08558297 0.01739996 7e-4 -0.08626598 0.01739996 8.83013e-4 -0.08608299 0.01739996 9.5e-4 -0.08583295 0.01739996 8.83013e-4 -0.08558297 0.01739996 0.001724958 -0.0843665 0.01739996 7e-4 -0.08539998 0.01739996 4.5e-4 -0.08533298 0.01739996 2e-4 -0.08539998 0.01739996 -2e-4 -0.08539998 0.01739996 -7e-4 -0.09745848 0.01739996 -0.001724958 -0.09745848 0.01739996 -8.83013e-4 -0.100417 0.01739996 -7e-4 -0.1006 0.01739996 -4.5e-4 -0.1006669 0.01739996 -2e-4 -0.1006 0.01739996 7e-4 -0.09745848 0.01739996 2e-4 -0.1006 0.01739996 -0.001724958 -0.106435 0.01739996 0.001724958 -0.106435 0.01739996 -0.08672219 -0.04926079 0.01739996 -0.08254659 -0.04684996 0.01739996 -0.08627218 -0.05090618 0.01739996 -0.08054035 -0.05211156 0.01739996 -0.08722215 -0.05012679 0.01739996 -0.08702218 -0.05047315 0.01739996 -0.08695518 -0.05072319 0.01739996 -0.0867722 -0.05090618 0.01739996 -0.08697217 -0.04919379 0.01739996 -0.08722215 -0.04926079 0.01739996 -0.09510135 -0.04684996 0.01739996 -0.09546309 -0.04752308 0.01739996 -0.0874052 -0.04944378 0.01739996 -0.0874722 -0.04969376 0.01739996 -0.0874052 -0.0499438 0.01739996 -0.07430857 -0.04209375 0.01739996 -0.07412558 -0.04227679 0.01739996 -0.07480859 -0.04209375 0.01739996 -0.07499158 -0.04227679 0.01739996 -0.09172016 -0.04055827 0.01739996 -0.08054035 -0.04569166 0.01739996 -0.07505857 -0.04252678 0.01739996 -0.07253235 -0.04055827 0.01739996 -0.07308501 -0.04684996 0.01739996 -0.07360857 -0.04330617 0.01739996 -0.07367557 -0.04355615 0.01739996 -0.07367557 -0.04305619 0.01739996 -0.07385855 -0.0428732 0.01739996 -0.07394945 -0.04271578 0.01739996 -0.07394945 -0.04055827 0.01739996 -0.07405859 -0.04252678 0.01739996 -0.0797466 -0.04684996 0.01739996 -0.07435858 -0.04373919 0.01739996 -0.0741086 -0.04380619 0.01739996 -0.07394945 -0.04376357 0.01739996 -0.07385855 -0.04373919 0.01739996 -0.08054035 -0.04730826 0.01739996 0.06599998 -0.06094866 0.01739996 0.07308501 -0.0538913 0.01739996 0.08054035 -0.05916637 0.01739996 0.07616537 -0.05624276 0.01739996 0.07679039 -0.05516028 0.01739996 0.07554036 -0.05391025 0.01739996 0.07394945 -0.0538913 0.01739996 0.07445776 -0.05453526 0.01739996 0.07429039 -0.05516028 0.01739996 0.07445776 -0.05578529 0.01739996 0.08713126 -0.05028414 0.01739996 0.09510135 -0.04684996 0.01739996 0.08713126 -0.04684996 0.01739996 0.08554035 -0.03908967 0.01739996 0.08616536 -0.03892225 0.01739996 0.08554035 -0.03658968 0.01739996 0.08491539 -0.03892225 0.01739996 0.08713126 -0.04055827 0.01739996 0.08697217 -0.04919379 0.01739996 0.08491539 -0.03675717 0.01739996 0.08054035 -0.04055827 0.01739996 0.08445775 -0.03721469 0.01739996 0.08445775 -0.03846466 0.01739996 0.08713126 -0.03413939 0.01739996 0.0725615 -0.04044997 0.01739996 0.06059998 -0.04437667 0.01739996 0.05215275 -0.05387234 0.01739996 0.05737495 -0.05091744 0.01739996 0.05639737 -0.05211156 0.01739996 0.04412007 -0.0538913 0.01739996 0.03812855 -0.05735045 0.01739996 0.05212008 -0.0538913 0.01739996 0.01236647 -0.07249706 0.01739996 0.01189398 -0.07249706 0.01739996 0.01236647 -0.07222425 0.01739996 0.03189635 -0.06094866 0.01739996 -0.05399996 -0.06094866 0.01739996 -0.05639737 -0.06094866 0.01739996 -0.044743 -0.07249706 0.01739996 -0.04599756 -0.07249706 0.01739996 -0.04455655 -0.07217437 0.01739996 -0.04437357 -0.07199138 0.01739996 -0.01236647 -0.07222425 0.01739996 -0.03340154 -0.06585317 0.01739996 -0.04032975 -0.06185317 0.01739996 -0.04285567 -0.06622821 0.01739996 -0.03592747 -0.07022815 0.01739996 -0.0355615 -0.07159417 0.01739996 -0.04362356 -0.07242441 0.01739996 -0.04369056 -0.07217437 0.01739996 -0.04387354 -0.07199138 0.01739996 -0.04422169 -0.06659418 0.01739996 -0.04412358 -0.07192438 0.01739996 -0.04057204 -0.06094866 0.01739996 -0.03189635 -0.06094866 0.01739996 -0.04069578 -0.06048715 0.01739996 -0.05212008 -0.0538913 0.01739996 -0.05215275 -0.05387234 0.01739996 -0.05222338 -0.0538913 0.01739996 -0.05674999 -0.05199998 0.01739996 -0.05639737 -0.05211156 0.01739996 -0.04720264 -0.05211156 0.01739996 -0.05639737 -0.04792886 0.01739996 -0.06059998 -0.04437667 0.01739996 -0.06059998 -0.04684996 0.01739996 -0.06340569 -0.04197806 0.01739996 -0.06789636 -0.04169994 0.01739996 -0.06759047 -0.04055827 0.01739996 -0.0675615 -0.04044997 0.01739996 -0.07394945 -0.02974116 0.01739996 -0.08445775 -0.03846466 0.01739996 -0.07455855 -0.04202675 0.01739996 -0.08429038 -0.03783965 0.01739996 -0.08554035 -0.03658968 0.01739996 -0.08054035 -0.04055827 0.01739996 -0.0749154 -0.05624276 0.01739996 -0.07445776 -0.05578529 0.01739996 -0.07394945 -0.05936729 0.01739996 -0.07445776 -0.05453526 0.01739996 -0.0749154 -0.05407768 0.01739996 -0.08054035 -0.0538913 0.01739996 -0.07679039 -0.05516028 0.01739996 -0.08054035 -0.05916637 0.01739996 -0.08888781 -0.05891185 0.01739996 -0.07554036 -0.05641025 0.01739996 -0.07429039 -0.05516028 0.01739996 -0.07394945 -0.0538913 0.01739996 -0.07308501 -0.05939358 0.01739996 -0.06340569 -0.0538913 0.01739996 -0.01236647 -0.0843665 0.01739996 -0.01600885 -0.08172816 0.01739996 -0.01348298 -0.07735317 0.01739996 -0.01384896 -0.07598716 0.01739996 -0.04022645 -0.07467436 0.01739996 -0.04015946 -0.07442438 0.01739996 -0.04022645 -0.0741744 0.01739996 -0.0404095 -0.07399135 0.01739996 -0.04065948 -0.07392436 0.01739996 -0.04090946 -0.07399135 0.01739996 -0.04369056 -0.07267439 0.01739996 -0.04109245 -0.0741744 0.01739996 -0.0173344 -0.08904576 0.01739996 -0.0254392 -0.0843665 0.01739996 -0.01737487 -0.08209419 0.01739996 -0.00891745 -0.093625 0.01739996 -0.009374976 -0.09191745 0.01739996 -0.01108247 -0.09237498 0.01739996 -0.01124995 -0.09299999 0.01739996 -0.005624949 -0.106435 0.01739996 -0.006575286 -0.106435 0.01739996 -0.01212924 -0.09745848 0.01739996 0.001724958 -0.09745848 0.01739996 0.00999999 -0.09424996 0.01739996 0.01212924 -0.09745848 0.01739996 0.009374976 -0.09408247 0.01739996 0.00891745 -0.093625 0.01739996 0.010625 -0.09408247 0.01739996 0.01108247 -0.093625 0.01739996 0.01124995 -0.09299999 0.01739996 0.01108247 -0.09237498 0.01739996 0.010625 -0.09191745 0.01739996 0.00999999 -0.09174996 0.01739996 0.001249969 -0.08306509 0.01739996 0.009374976 -0.09191745 0.01739996 0.00891745 -0.09237498 0.01739996 0.008749961 -0.09299999 0.01739996 0.0254392 -0.0843665 0.01739996 0.01737487 -0.08209419 0.01739996 0.03399759 -0.07249706 0.01739996 0.0355615 -0.07159417 0.01739996 0.03592747 -0.07022815 0.01739996 0.019894 -0.07249706 0.01739996 0.01348298 -0.07735317 0.01739996 0.01600885 -0.08172816 0.01739996 0.04369056 -0.07267439 0.01739996 0.04109245 -0.0741744 0.01739996 0.0404095 -0.07399135 0.01739996 0.04022645 -0.0741744 0.01739996 0.04015946 -0.07442438 0.01739996 0.03812855 -0.07704025 0.01739996 0.04022645 -0.07467436 0.01739996 0.04072648 -0.07554036 0.01739996 0.04090946 -0.07399135 0.01739996 0.04065948 -0.07392436 0.01739996 0.04364305 -0.07249706 0.01739996 0.04362356 -0.07242441 0.01739996 0.04069578 -0.06048715 0.01739996 0.03812855 -0.06094866 0.01739996 0.04057204 -0.06094866 0.01739996 0.04032975 -0.06185317 0.01739996 0.03812855 -0.07249706 0.01739996 0.05399996 -0.06094866 0.01739996 0.044743 -0.07249706 0.01739996 0.04455655 -0.07217437 0.01739996 0.04422169 -0.06659418 0.01739996 0.04437357 -0.07199138 0.01739996 0.04285567 -0.06622821 0.01739996 0.04412358 -0.07192438 0.01739996 0.04387354 -0.07199138 0.01739996 0.04369056 -0.07217437 0.01739996 -0.05351889 -0.05423849 0.01739996 -0.05604475 -0.05861347 0.01739996 -0.05567878 -0.05997949 0.01739996 0.05567878 -0.05997949 0.01739996 0.05604475 -0.05861347 0.01739996 0.05639737 -0.0538913 0.01739996 0.05351889 -0.05423849 0.01739996 0.05222338 -0.0538913 0.01739996 0.07308501 -0.05211156 0.01739996 0.07394945 -0.04684996 0.01739996 0.0797466 -0.04684996 0.01739996 0.08054035 -0.04730826 0.01739996 0.09178638 -0.0538913 0.01739996 0.08713126 -0.0538913 0.01739996 0.08054035 -0.0538913 0.01739996 0.08713126 -0.05211156 0.01739996 0.07394945 -0.05211156 0.01739996 0.06340569 -0.05211156 0.01739996 0.05922007 -0.05211156 0.01739996 0.06340569 -0.06094866 0.01739996 0.05639737 -0.06649279 0.01739996 0.05639737 -0.06094866 0.01739996 0.05799996 -0.05324995 0.01739996 -0.005624949 -0.0843665 0.01739996 -9.5e-4 -0.08583295 0.01739996 -8.83013e-4 -0.08608299 0.01739996 -0.005624949 -0.09745848 0.01739996 -0.06340569 -0.06244647 0.01739996 -0.06340569 -0.06094866 0.01739996 -0.05639737 -0.0538913 0.01739996 -0.05799996 -0.05324995 0.01739996 -0.05862498 -0.05308246 0.01739996 -0.07394945 -0.04684996 0.01739996 -0.06340569 -0.05211156 0.01739996 -0.06084996 -0.0474959 0.01739996 -0.06078296 -0.04774588 0.01739996 -0.09281396 -0.05211156 0.01739996 -0.08652216 -0.05097317 0.01739996 -0.07394945 -0.05211156 0.01739996 -0.07308501 -0.05211156 0.01739996 -0.07308501 -0.0538913 0.01739996 -0.05922007 -0.05211156 0.01739996 0.06844866 -0.05953496 0.01859998 0.06844866 -0.05953496 0.01739996 0.07308501 -0.05939358 0.01859998 0.07308501 -0.05939358 0.01739996 0.07394945 -0.05936729 0.01739996 0.08713126 -0.0589655 0.01739996 -0.010625 -0.09191745 0.01859998 -0.08672219 -0.04926079 0.01859998 -0.08054035 -0.04569166 0.01859998 0.07505857 -0.04252678 0.01859998 -0.0675615 -0.04044997 0.01859998 0.001724958 -0.07920986 0.01859998 0.05922007 -0.05211156 0.01859998 -0.06078296 -0.04724586 0.01859998 -0.06059998 -0.04706287 0.01859998 -0.05862498 -0.05308246 0.01859998 -0.05908244 -0.052625 0.01859998 -0.05737495 -0.05308246 0.01859998 -0.06084996 -0.0474959 0.01859998 -0.05922007 -0.05211156 0.01859998 -0.05924999 -0.05199998 0.01859998 -0.05799996 -0.05074995 0.01859998 -0.05737495 -0.05091744 0.01859998 -0.05639737 -0.04792886 0.01859998 -0.05691748 -0.05137497 0.01859998 -0.05674999 -0.05199998 0.01859998 -0.05677986 -0.05211156 0.01859998 -0.06009995 -0.04792886 0.01859998 -0.05862498 -0.05091744 0.01859998 -0.06035 -0.04799586 0.01859998 -0.05908244 -0.05137497 0.01859998 -0.06059998 -0.04792886 0.01859998 -0.06078296 -0.04774588 0.01859998 0.05908244 -0.052625 0.01859998 0.05862498 -0.05308246 0.01859998 0.05677986 -0.05211156 0.01859998 0.05691748 -0.052625 0.01859998 0.05737495 -0.05308246 0.01859998 0.05799996 -0.05324995 0.01859998 0.05674999 -0.05199998 0.01859998 0.05691748 -0.05137497 0.01859998 0.05639737 -0.04792886 0.01859998 0.05737495 -0.05091744 0.01859998 0.05799996 -0.05074995 0.01859998 0.06009995 -0.04792886 0.01859998 0.06031256 -0.04799449 0.01859998 0.05862498 -0.05091744 0.01859998 0.06053268 -0.04796135 0.01859998 0.06059998 -0.04706287 0.01859998 0.06076306 -0.04721426 0.01859998 0.06071645 -0.04783594 0.01859998 0.05908244 -0.05137497 0.01859998 0.06082779 -0.0476433 0.01859998 0.06084436 -0.04742139 0.01859998 0 -0.08339995 0.01859998 0.001249969 -0.08306509 0.01859998 0.001724958 -0.0825901 0.01859998 0.002499997 -0.08089995 0.01859998 0.005999982 -0.07589995 0.01859998 -0.001249969 -0.07873487 0.01859998 0 -0.07839995 0.01859998 0.001249969 -0.07873487 0.01859998 -0.002165019 -0.08214998 0.01859998 -0.002165019 -0.07964998 0.01859998 -0.001724958 -0.07920986 0.01859998 -0.06881147 -0.04261505 0.01859998 -0.0700615 -0.04294997 0.01859998 -0.06422537 -0.04055827 0.01859998 -0.06759047 -0.04055827 0.01859998 -0.06789636 -0.04169994 0.01859998 -0.07253235 -0.04055827 0.01859998 -0.0725615 -0.04044997 0.01859998 -0.07222646 -0.03919994 0.01859998 -0.07131147 -0.03828489 0.01859998 -0.0700615 -0.03794997 0.01859998 -0.06881147 -0.03828489 0.01859998 -0.06789636 -0.03919994 0.01859998 0.07253235 -0.04055827 0.01859998 0.07222646 -0.04169994 0.01859998 0.07131147 -0.04261505 0.01859998 0.06340569 -0.04684996 0.01859998 0.0700615 -0.04294997 0.01859998 0.06881147 -0.04261505 0.01859998 0.0675615 -0.04044997 0.01859998 0.07222646 -0.03919994 0.01859998 0.0725615 -0.04044997 0.01859998 0.06789636 -0.03919994 0.01859998 0.06881147 -0.03828489 0.01859998 0.0700615 -0.03794997 0.01859998 0.07131147 -0.03828489 0.01859998 0.07394945 -0.04684996 0.01859998 0.07435858 -0.04373919 0.01859998 0.0797466 -0.04684996 0.01859998 0.08713126 -0.05028414 0.01859998 0.08702218 -0.05047315 0.01859998 0.08695518 -0.05072319 0.01859998 0.0867722 -0.05090618 0.01859998 0.08652216 -0.05097317 0.01859998 0.08602219 -0.05047315 0.01859998 0.08054035 -0.04730826 0.01859998 0.08608907 -0.05072319 0.01859998 0.08627218 -0.05090618 0.01859998 0.08054035 -0.05211156 0.01859998 0.08697217 -0.04919379 0.01859998 0.08713126 -0.04923635 0.01859998 0.09510135 -0.04684996 0.01859998 0.0874052 -0.04944378 0.01859998 0.0874722 -0.04969376 0.01859998 0.07405859 -0.04252678 0.01859998 0.07412558 -0.04227679 0.01859998 0.07430857 -0.04209375 0.01859998 0.07499158 -0.04227679 0.01859998 0.08054035 -0.04569166 0.01859998 0.08254659 -0.04684996 0.01859998 0.08672219 -0.04926079 0.01859998 0.0741086 -0.04380619 0.01859998 0.07394945 -0.04376357 0.01859998 0.07385855 -0.04373919 0.01859998 0.07308501 -0.04684996 0.01859998 0.07360857 -0.04330617 0.01859998 0.07367557 -0.04355615 0.01859998 0.07308501 -0.04055827 0.01859998 0.07367557 -0.04305619 0.01859998 0.07385855 -0.0428732 0.01859998 0.07394945 -0.04271578 0.01859998 -7e-4 -0.09745848 0.01859998 -7e-4 -0.08626598 0.01859998 -8.83013e-4 -0.08608299 0.01859998 -9.5e-4 -0.08583295 0.01859998 -8.83013e-4 -0.08558297 0.01859998 -7e-4 -0.08539998 0.01859998 7e-4 -0.08626598 0.01859998 7e-4 -0.09745848 0.01859998 8.83013e-4 -0.08608299 0.01859998 9.5e-4 -0.08583295 0.01859998 0.001724958 -0.09745848 0.01859998 0.001724958 -0.0843665 0.01859998 8.83013e-4 -0.08558297 0.01859998 7e-4 -0.08539998 0.01859998 -4.5e-4 -0.08533298 0.01859998 -2e-4 -0.08539998 0.01859998 -0.001724958 -0.0843665 0.01859998 2e-4 -0.08539998 0.01859998 4.5e-4 -0.08533298 0.01859998 -2e-4 -0.1006 0.01859998 -4.5e-4 -0.1006669 0.01859998 8.63119e-4 -0.09988528 0.01859998 9.27786e-4 -0.100314 0.01859998 8.16526e-4 -0.100507 0.01859998 4.12635e-4 -0.100666 0.01859998 -0.07360857 -0.04330617 0.01859998 -0.07222646 -0.04169994 0.01859998 -0.07131147 -0.04261505 0.01859998 -0.07367557 -0.04355615 0.01859998 -0.07455855 -0.04202675 0.01859998 -0.07430857 -0.04209375 0.01859998 -0.07412558 -0.04227679 0.01859998 -0.07405859 -0.04252678 0.01859998 -0.07394945 -0.04055827 0.01859998 -0.07394945 -0.04271578 0.01859998 -0.07308501 -0.04055827 0.01859998 -0.07385855 -0.0428732 0.01859998 -0.07367557 -0.04305619 0.01859998 -0.07505857 -0.04252678 0.01859998 -0.07499158 -0.04227679 0.01859998 -0.08054035 -0.04730826 0.01859998 -0.08602219 -0.05047315 0.01859998 -0.08608907 -0.05072319 0.01859998 -0.08627218 -0.05090618 0.01859998 -0.08695518 -0.05072319 0.01859998 -0.09281396 -0.05211156 0.01859998 -0.08702218 -0.05047315 0.01859998 -0.08722215 -0.05012679 0.01859998 -0.09546309 -0.04752308 0.01859998 -0.0874052 -0.0499438 0.01859998 -0.0874722 -0.04969376 0.01859998 -0.09510135 -0.04684996 0.01859998 -0.0874052 -0.04944378 0.01859998 -0.07435858 -0.04373919 0.01859998 -0.0797466 -0.04684996 0.01859998 -0.07394945 -0.04684996 0.01859998 -0.0741086 -0.04380619 0.01859998 -0.07394945 -0.04376357 0.01859998 -0.07385855 -0.04373919 0.01859998 -0.03203547 -0.0654872 0.01859998 -0.04364305 -0.07249706 0.01859998 -0.04057204 -0.06094866 0.01859998 -0.044743 -0.07249706 0.01859998 -0.0355615 -0.07159417 0.01859998 -0.03592747 -0.07022815 0.01859998 -0.04455655 -0.07217437 0.01859998 -0.04437357 -0.07199138 0.01859998 -0.04422169 -0.06659418 0.01859998 -0.04412358 -0.07192438 0.01859998 -0.04387354 -0.07199138 0.01859998 -0.04285567 -0.06622821 0.01859998 -0.04369056 -0.07217437 0.01859998 -0.04362356 -0.07242441 0.01859998 -0.04412007 -0.0538913 0.01859998 -0.05212008 -0.0538913 0.01859998 -0.03189635 -0.06094866 0.01859998 -0.04069578 -0.06048715 0.01859998 -0.05639737 -0.05211156 0.01859998 -0.05691748 -0.052625 0.01859998 -0.05399996 -0.06094866 0.01859998 -0.05567878 -0.05997949 0.01859998 -0.05639737 -0.06094866 0.01859998 -0.05604475 -0.05861347 0.01859998 -0.05351889 -0.05423849 0.01859998 -0.019894 -0.07249706 0.01859998 -0.01384896 -0.07598716 0.01859998 -0.01348298 -0.07735317 0.01859998 -0.01600885 -0.08172816 0.01859998 -0.01737487 -0.08209419 0.01859998 -0.04369056 -0.07267439 0.01859998 -0.04109245 -0.0741744 0.01859998 -0.04015946 -0.07442438 0.01859998 -0.04090946 -0.07399135 0.01859998 -0.04065948 -0.07392436 0.01859998 -0.03399759 -0.07249706 0.01859998 -0.0404095 -0.07399135 0.01859998 -0.04022645 -0.0741744 0.01859998 0.002165019 -0.07964998 0.01859998 0.01189398 -0.07249706 0.01859998 0.01236647 -0.07249706 0.01859998 0.03203547 -0.0654872 0.01859998 0.03340154 -0.06585317 0.01859998 0.03812855 -0.07704025 0.01859998 0.0355615 -0.07159417 0.01859998 0.01737487 -0.08209419 0.01859998 0.01600885 -0.08172816 0.01859998 0.01348298 -0.07735317 0.01859998 0.05399996 -0.06094866 0.01859998 0.05639737 -0.06649279 0.01859998 0.04285567 -0.06622821 0.01859998 0.03812855 -0.06094866 0.01859998 0.04505658 -0.07304036 0.01859998 0.044743 -0.07249706 0.01859998 0.04599756 -0.07249706 0.01859998 0.04455655 -0.07217437 0.01859998 0.04422169 -0.06659418 0.01859998 0.04364305 -0.07249706 0.01859998 0.04362356 -0.07242441 0.01859998 0.04369056 -0.07217437 0.01859998 0.04387354 -0.07199138 0.01859998 0.04412358 -0.07192438 0.01859998 0.04437357 -0.07199138 0.01859998 0.05604475 -0.05861347 0.01859998 0.05567878 -0.05997949 0.01859998 0.04032975 -0.06185317 0.01859998 0.04057204 -0.06094866 0.01859998 0.04069578 -0.06048715 0.01859998 0.05212008 -0.0538913 0.01859998 0.05639737 -0.05211156 0.01859998 0.05215275 -0.05387234 0.01859998 0.05222338 -0.0538913 0.01859998 0.05351889 -0.05423849 0.01859998 0.05639737 -0.0538913 0.01859998 0.04015946 -0.07442438 0.01859998 0.04022645 -0.07467436 0.01859998 0.04072648 -0.07554036 0.01859998 0.04109245 -0.0741744 0.01859998 0.04369056 -0.07267439 0.01859998 0.04090946 -0.07399135 0.01859998 0.04065948 -0.07392436 0.01859998 0.03812855 -0.07249706 0.01859998 0.0404095 -0.07399135 0.01859998 0.04022645 -0.0741744 0.01859998 0.03399759 -0.07249706 0.01859998 0.0254392 -0.0843665 0.01859998 0.0173344 -0.08904576 0.01859998 0.01236647 -0.0843665 0.01859998 0.010625 -0.09191745 0.01859998 0.00999999 -0.09424996 0.01859998 0.01212924 -0.09745848 0.01859998 0.01236647 -0.09707516 0.01859998 0.002165019 -0.08214998 0.01859998 0.00999999 -0.09174996 0.01859998 0.01108247 -0.09237498 0.01859998 0.01124995 -0.09299999 0.01859998 0.01108247 -0.093625 0.01859998 0.010625 -0.09408247 0.01859998 0.009374976 -0.09408247 0.01859998 0.00891745 -0.093625 0.01859998 0.008749961 -0.09299999 0.01859998 0.00891745 -0.09237498 0.01859998 0.009374976 -0.09191745 0.01859998 0.001724958 -0.106435 0.01859998 -0.006575286 -0.106435 0.01859998 -0.010625 -0.09408247 0.01859998 -0.01108247 -0.093625 0.01859998 -0.01124995 -0.09299999 0.01859998 -0.01108247 -0.09237498 0.01859998 -0.01236647 -0.09707516 0.01859998 -0.00999999 -0.09424996 0.01859998 -0.01212924 -0.09745848 0.01859998 -0.009374976 -0.09408247 0.01859998 -0.00891745 -0.093625 0.01859998 -0.00999999 -0.09174996 0.01859998 -0.009374976 -0.09191745 0.01859998 -0.00891745 -0.09237498 0.01859998 -0.008749961 -0.09299999 0.01859998 -0.04022645 -0.07467436 0.01859998 -0.01236647 -0.0843665 0.01859998 -0.0254392 -0.0843665 0.01859998 -0.0173344 -0.08904576 0.01859998 -0.06599998 -0.06094866 0.01859998 -0.06340569 -0.06094866 0.01859998 -0.06844866 -0.05953496 0.01859998 -0.06340569 -0.0538913 0.01859998 -0.0749154 -0.05624276 0.01859998 -0.07554036 -0.05641025 0.01859998 -0.07616537 -0.05624276 0.01859998 -0.0766229 -0.05578529 0.01859998 -0.07679039 -0.05516028 0.01859998 -0.0766229 -0.05453526 0.01859998 -0.07616537 -0.05407768 0.01859998 -0.08054035 -0.0538913 0.01859998 -0.07554036 -0.05391025 0.01859998 -0.0749154 -0.05407768 0.01859998 -0.07445776 -0.05453526 0.01859998 -0.08652216 -0.05097317 0.01859998 -0.0867722 -0.05090618 0.01859998 -0.08429038 -0.03783965 0.01859998 -0.08445775 -0.03846466 0.01859998 -0.08491539 -0.03892225 0.01859998 -0.08491539 -0.03675717 0.01859998 -0.08445775 -0.03721469 0.01859998 -0.08054035 -0.04055827 0.01859998 -0.07480859 -0.04209375 0.01859998 -0.08554035 -0.03908967 0.01859998 -0.09172016 -0.04055827 0.01859998 -0.08254659 -0.04684996 0.01859998 -0.08697217 -0.04919379 0.01859998 -0.08722215 -0.04926079 0.01859998 -0.08616536 -0.03892225 0.01859998 -0.08662289 -0.03846466 0.01859998 -0.0887832 -0.03509318 0.01859998 -0.08679038 -0.03783965 0.01859998 -0.08662289 -0.03721469 0.01859998 -0.08616536 -0.03675717 0.01859998 -0.08554035 -0.03658968 0.01859998 -0.07308501 -0.03024017 0.01859998 -0.07394945 -0.02974116 0.01859998 -0.06059998 -0.04684996 0.01859998 -0.06340569 -0.04684996 0.01859998 -0.06059998 -0.04437667 0.01859998 -0.05222338 -0.0538913 0.01859998 -0.05215275 -0.05387234 0.01859998 -0.04720264 -0.05211156 0.01859998 -0.04032975 -0.06185317 0.01859998 -0.03340154 -0.06585317 0.01859998 -0.01236647 -0.07222425 0.01859998 -0.01236647 -0.07249706 0.01859998 -0.01189398 -0.07249706 0.01859998 -0.005624949 -0.07589995 0.01859998 -0.002499997 -0.08089995 0.01859998 0.05444729 -0.04792886 0.01859998 0.06059998 -0.04437667 0.01859998 0.06059998 -0.04684996 0.01859998 0.06273126 -0.04314619 0.01859998 0.06422537 -0.04055827 0.01859998 0.06789636 -0.04169994 0.01859998 0.06759047 -0.04055827 0.01859998 0.07455855 -0.04202675 0.01859998 0.07480859 -0.04209375 0.01859998 0.07394945 -0.04055827 0.01859998 0.08679038 -0.03783965 0.01859998 0.08054035 -0.03033417 0.01859998 0.08491539 -0.03675717 0.01859998 0.08713126 -0.03413939 0.01859998 0.08554035 -0.03658968 0.01859998 0.08616536 -0.03675717 0.01859998 0.08662289 -0.03846466 0.01859998 0.08616536 -0.03892225 0.01859998 0.08554035 -0.03908967 0.01859998 0.08491539 -0.03892225 0.01859998 0.08445775 -0.03846466 0.01859998 0.08429038 -0.03783965 0.01859998 0.08054035 -0.04055827 0.01859998 0.08445775 -0.03721469 0.01859998 0.08662289 -0.03721469 0.01859998 0.08713126 -0.04055827 0.01859998 0.08713126 -0.04684996 0.01859998 0.08722215 -0.04926079 0.01859998 0.08888781 -0.05891185 0.01859998 0.09178638 -0.0538913 0.01859998 0.08713126 -0.0589655 0.01859998 0.08713126 -0.0538913 0.01859998 0.07445776 -0.05453526 0.01859998 0.0749154 -0.05407768 0.01859998 0.07554036 -0.05391025 0.01859998 0.08054035 -0.0538913 0.01859998 0.07616537 -0.05407768 0.01859998 0.0766229 -0.05453526 0.01859998 0.07616537 -0.05624276 0.01859998 0.0766229 -0.05578529 0.01859998 0.08054035 -0.05916637 0.01859998 0.07679039 -0.05516028 0.01859998 0.07554036 -0.05641025 0.01859998 0.0749154 -0.05624276 0.01859998 0.07445776 -0.05578529 0.01859998 0.07429039 -0.05516028 0.01859998 0.07394945 -0.05936729 0.01859998 0.06599998 -0.06094866 0.01859998 0.06340569 -0.06094866 0.01859998 -0.07394945 -0.05211156 0.01859998 -0.07308501 -0.05211156 0.01859998 -0.09178638 -0.0538913 0.01859998 -0.08054035 -0.05211156 0.01859998 -0.07308501 -0.0538913 0.01859998 -0.07308501 -0.04684996 0.01859998 -0.06340569 -0.05211156 0.01859998 -0.07394945 -0.0538913 0.01859998 -0.07429039 -0.05516028 0.01859998 -0.07445776 -0.05578529 0.01859998 -0.05639737 -0.0538913 0.01859998 -0.05799996 -0.05324995 0.01859998 -0.005624949 -0.09745848 0.01859998 -0.001724958 -0.09745848 0.01859998 -0.005624949 -0.0843665 0.01859998 -0.001724958 -0.0825901 0.01859998 -0.001249969 -0.08306509 0.01859998 0.05639737 -0.06094866 0.01859998 0.06340569 -0.06244647 0.01859998 0.06340569 -0.0538913 0.01859998 0.07394945 -0.05211156 0.01859998 0.07308501 -0.05211156 0.01859998 0.05924999 -0.05199998 0.01859998 0.0874052 -0.0499438 0.01859998 0.08722215 -0.05012679 0.01859998 0.08713126 -0.05211156 0.01859998 0.07394945 -0.0538913 0.01859998 0.07308501 -0.0538913 0.01859998 0.06340569 -0.05211156 0.01859998 0.03340154 -0.06585317 0.01739996 0.181376 -0.0981068 0.01189994 0.182169 -0.09950017 0.01189994 0.182169 -0.09950017 0.01739996 0.185391 -0.09924358 0.01739996 0.183964 -0.0996012 0.01739996 0.185391 -0.09924358 0.01189994 0.183964 -0.0996012 0.01189994 0.18314 -0.09980785 0.01189994 0.183968 -0.0933389 0.01189994 0.18457 -0.09314399 0.01739996 0.189105 -0.09310209 0.01739996 0.189441 -0.09323871 0.01739996 0.189441 -0.09323871 0.01189994 0.189673 -0.0935167 0.01739996 0.189673 -0.0935167 0.01189994 0.189748 -0.09387117 0.01189994 0.189748 -0.09387117 0.01739996 0.189648 -0.0942195 0.01739996 0.187126 -0.09858769 0.01739996 0.189254 -0.09490168 0.01189994 0.189254 -0.09490168 0.01739996 0.190383 -0.09894776 0.01739996 0.189633 -0.100247 0.01189994 0.192317 -0.101797 0.01739996 0.192317 -0.101797 0.01189994 0.191848 -0.102302 0.01189994 0.191206 -0.102554 0.01189994 0.190518 -0.102503 0.01189994 0.191206 -0.102554 0.01739996 0.190518 -0.102503 0.01739996 0.189921 -0.102158 0.01189994 0.189532 -0.101588 0.01189994 0.189633 -0.100247 0.01739996 0.198759 -0.09926909 0.01739996 0.199115 -0.1005949 0.01739996 0.199115 -0.1005949 0.01189994 0.199587 -0.102357 0.01189994 0.201129 -0.108114 0.01189994 0.201521 -0.109576 0.01739996 0.201521 -0.109576 0.01189994 0.1964899 -0.100569 0.01739996 0.197135 -0.09945166 0.01739996 0.197355 -0.09907066 0.01739996 0.197355 -0.09907066 0.01189994 0.195963 -0.10749 0.01739996 0.195658 -0.106353 0.01189994 0.195658 -0.106353 0.01739996 0.195294 -0.104992 0.01189994 0.194989 -0.103854 0.01189994 0.195963 -0.10749 0.01189994 0.1960009 -0.107612 0.01189994 0.1960009 -0.107612 0.01739996 0.196072 -0.107843 0.01189994 0.200404 -0.11045 0.01739996 0.175181 -0.117219 0.01189994 0.175098 -0.117071 0.01739996 0.17295 -0.1132709 0.01739996 0.175098 -0.117071 0.01189994 0.176421 -0.117131 0.01189994 0.178943 -0.112762 0.01189994 0.1790429 -0.112406 0.01739996 0.1780059 -0.1087 0.01189994 0.177254 -0.108012 0.01739996 0.177886 -0.108351 0.01739996 0.175651 -0.108023 0.01189994 0.175651 -0.108023 0.01739996 0.185349 -0.122496 0.01739996 0.194194 -0.120126 0.01739996 0.195918 -0.119605 0.01189994 0.195807 -0.11966 0.01189994 0.195807 -0.11966 0.01739996 0.195918 -0.119605 0.01739996 0.196129 -0.119355 0.01189994 0.196223 -0.119078 0.01739996 0.196204 -0.118786 0.01739996 0.196074 -0.118523 0.01739996 0.195854 -0.11833 0.01739996 0.195854 -0.11833 0.01189994 0.195387 -0.11806 0.01739996 0.187435 -0.116938 0.01189994 0.188572 -0.1166329 0.01739996 0.188572 -0.1166329 0.01189994 0.191071 -0.115964 0.01189994 0.184475 -0.121379 0.01739996 0.18453 -0.122211 0.01189994 0.18453 -0.122211 0.01739996 0.191305 -0.11045 0.01739996 0.189566 -0.112189 0.01189994 0.1894749 -0.11228 0.01189994 0.1894749 -0.11228 0.01739996 0.187726 -0.112749 0.01189994 0.186975 -0.11295 0.01739996 0.184475 -0.11228 0.01739996 0.183944 -0.11175 0.01739996 0.182645 -0.11045 0.01189994 0.182478 -0.109828 0.01189994 0.182443 -0.109699 0.01189994 0.182008 -0.107825 0.01739996 0.182008 -0.107825 0.01189994 0.182645 -0.10545 0.01739996 0.183697 -0.104398 0.01739996 0.183697 -0.104398 0.01189994 0.186975 -0.10295 0.01739996 0.186975 -0.10295 0.01189994 0.18875 -0.103426 0.01739996 0.18875 -0.103426 0.01189994 0.190005 -0.1041499 0.01189994 0.191305 -0.10545 0.01189994 0.191506 -0.106201 0.01189994 0.06286877 -0.04290795 0.01189994 0.06332838 -0.04211199 0.01739996 0.06332838 -0.04211199 0.01189994 0.06454378 -0.04000675 0.01189994 0.06454378 -0.04000675 0.01739996 0.06645005 -0.03670507 0.01189994 0.06813418 -0.03378796 0.01739996 0.07517117 -0.0290358 0.01739996 0.07388126 -0.02978044 0.01739996 0.07673126 -0.028135 0.01739996 0.08369636 -0.03215634 0.01189994 0.0887832 -0.03509318 0.01189994 0.0887832 -0.03509318 0.01739996 0.09018677 -0.037705 0.01739996 0.09045505 -0.03820425 0.01189994 0.09200137 -0.04108166 0.01189994 0.09200137 -0.04108166 0.01739996 0.09245896 -0.04171717 0.01739996 0.0930655 -0.04221266 0.01739996 0.09245896 -0.04171717 0.01189994 0.0930655 -0.04221266 0.01189994 0.134921 -0.06810969 0.01189994 0.09979528 -0.04637658 0.01189994 0.176577 -0.09297358 0.01189994 0.1744599 -0.0925734 0.01189994 0.175482 -0.09297007 0.01739996 0.188644 -0.09002751 0.01189994 0.186589 -0.09005606 0.01189994 0.18107 -0.09094595 0.01189994 0.180384 -0.09126991 0.01739996 0.177601 -0.09258335 0.01739996 0.177601 -0.09258335 0.01189994 0.06969636 -0.05640506 0.01189994 0.06969636 -0.05640506 0.01739996 0.06273126 -0.05238378 0.01739996 0.0747832 -0.05934184 0.01189994 0.07831346 -0.05923426 0.01189994 0.09006088 -0.06323695 0.01739996 0.09006088 -0.06323695 0.01189994 0.1264449 -0.08279025 0.01739996 0.1264449 -0.08279025 0.01189994 0.1637459 -0.102836 0.01739996 0.1637459 -0.102836 0.01189994 0.167401 -0.1048 0.01739996 0.167401 -0.1048 0.01189994 0.168255 -0.105487 0.01739996 0.168806 -0.106434 0.01739996 0.168806 -0.106434 0.01189994 0.16898 -0.107515 0.01189994 0.169297 -0.111339 0.01189994 0.169297 -0.111339 0.01739996 0.1704159 -0.1150079 0.01189994 0.172288 -0.118357 0.01739996 0.173236 -0.11922 0.01189994 0.172288 -0.118357 0.01189994 0.173702 -0.119489 0.01739996 0.1813009 -0.123877 0.01739996 0.185826 -0.125474 0.01739996 0.184658 -0.125551 0.01739996 0.1836259 -0.125201 0.01739996 0.183549 -0.1251749 0.01189994 0.1836259 -0.125201 0.01189994 0.184658 -0.125551 0.01189994 0.196732 -0.122552 0.01739996 0.198501 -0.121215 0.01189994 0.198554 -0.121154 0.01739996 0.198501 -0.121215 0.01739996 0.197782 -0.122034 0.01739996 0.198974 -0.120427 0.01739996 0.198554 -0.121154 0.01189994 0.199439 -0.119621 0.01189994 0.2001889 -0.118322 0.01189994 0.200658 -0.11751 0.01739996 0.2042 -0.111376 0.01739996 0.2037799 -0.112103 0.01189994 0.204499 -0.109099 0.01189994 0.204226 -0.111299 0.01189994 0.204576 -0.110267 0.01189994 0.204499 -0.109099 0.01739996 0.203261 -0.104478 0.01189994 0.203251 -0.104439 0.01189994 0.202789 -0.102716 0.01189994 0.201741 -0.09880369 0.01739996 0.201059 -0.09714275 0.01189994 0.201059 -0.09714275 0.01739996 0.189866 -0.09041649 0.01189994 0.189866 -0.09041649 0.01739996 0.1903319 -0.0906856 0.01189994 0.1926479 -0.09202307 0.01189994 0.200179 -0.09637099 0.01739996 0.08625769 -0.04890596 0.01189994 0.08477181 -0.04804807 0.01189994 0.08477181 -0.04804807 0.01739996 0.07559806 -0.04275166 0.01189994 0.08399677 -0.04939049 0.01739996 0.0763089 -0.04495185 0.01739996 0.08730965 -0.04997515 0.01189994 0.08693468 -0.05062478 0.01189994 0.156363 -0.09535688 0.01739996 0.155963 -0.09546411 0.01739996 0.15527 -0.0950641 0.01189994 0.15527 -0.0950641 0.01739996 0.155963 -0.09386408 0.01189994 0.155963 -0.09386408 0.01739996 0.156656 -0.09426409 0.01189994 0.156656 -0.09426409 0.01739996 0.156763 -0.09466409 0.01189994 0.156689 -0.09493905 0.01739996 0.156689 -0.09493905 0.01189994 0.156363 -0.09535688 0.01189994 0.106096 -0.05663585 0.01739996 0.105403 -0.05703586 0.01189994 0.105803 -0.05692869 0.01739996 0.1050029 -0.05692869 0.01189994 0.104603 -0.05623584 0.01189994 0.1047109 -0.05663585 0.01739996 0.104603 -0.05623584 0.01739996 0.1047109 -0.0558359 0.01739996 0.1050029 -0.05554306 0.01189994 0.105403 -0.05543589 0.01189994 0.105803 -0.05554306 0.01189994 0.105403 -0.05543589 0.01739996 0.105803 -0.05554306 0.01739996 0.106096 -0.0558359 0.01739996 0.0685938 -0.032992 0.01739996 0.203261 -0.104478 0.01739996 0.201577 -0.09819257 0.01739996 0.198685 -0.09911775 0.01739996 0.191985 -0.09317147 0.01739996 0.1889359 -0.09310358 0.01739996 0.186184 -0.09312909 0.01739996 0.184808 -0.09008085 0.01739996 0.179939 -0.09558075 0.01739996 0.179846 -0.09529328 0.01739996 0.182022 -0.09072577 0.01739996 0.183968 -0.0933389 0.01739996 0.18107 -0.09094595 0.01739996 0.1802549 -0.0945394 0.01739996 0.180018 -0.0947265 0.01739996 0.179873 -0.09499216 0.01739996 0.176577 -0.09297358 0.01739996 0.170201 -0.09165489 0.01739996 0.181376 -0.0981068 0.01739996 0.187196 -0.101467 0.01739996 0.186515 -0.09896177 0.01739996 0.184879 -0.10013 0.01739996 0.186868 -0.09885245 0.01739996 0.2037799 -0.112103 0.01739996 0.201012 -0.110505 0.01739996 0.200973 -0.1105239 0.01739996 0.200681 -0.110544 0.01739996 0.204576 -0.110267 0.01739996 0.204226 -0.111299 0.01739996 0.201532 -0.109744 0.01739996 0.2015399 -0.109868 0.01739996 0.2014459 -0.110145 0.01739996 0.201429 -0.110175 0.01739996 0.201236 -0.110395 0.01739996 0.201129 -0.108114 0.01739996 0.2032369 -0.104464 0.01739996 0.199587 -0.102357 0.01739996 0.203251 -0.104439 0.01739996 0.202789 -0.102716 0.01739996 0.19863 -0.09900665 0.01739996 0.199585 -0.09755897 0.01739996 0.19841 -0.09881365 0.01739996 0.197548 -0.09885066 0.01739996 0.197811 -0.09872126 0.01739996 0.198103 -0.09870219 0.01739996 0.1983799 -0.09879618 0.01739996 0.195294 -0.104992 0.01739996 0.195191 -0.09981876 0.01739996 0.195007 -0.103138 0.01739996 0.194907 -0.103494 0.01739996 0.194989 -0.103854 0.01739996 0.1943359 -0.106651 0.01739996 0.08662289 -0.03721469 0.01739996 0.08679038 -0.03783965 0.01739996 0.08662289 -0.03846466 0.01739996 0.08291637 -0.03350734 0.01739996 0.08643859 -0.03703039 0.01739996 0.164476 -0.101571 0.01739996 0.1724489 -0.108104 0.01739996 0.172202 -0.108279 0.01739996 0.172044 -0.108537 0.01739996 0.172001 -0.108836 0.01739996 0.16898 -0.107515 0.01739996 0.1704159 -0.1150079 0.01739996 0.175468 -0.1174409 0.01739996 0.175824 -0.117504 0.01739996 0.173236 -0.11922 0.01739996 0.175181 -0.117219 0.01739996 0.178961 -0.112046 0.01739996 0.178943 -0.112762 0.01739996 0.176421 -0.117131 0.01739996 0.176169 -0.117391 0.01739996 0.177613 -0.108101 0.01739996 0.178239 -0.109517 0.01739996 0.1780059 -0.1087 0.01739996 0.179154 -0.110045 0.01739996 0.179614 -0.109249 0.01739996 0.1844 -0.121948 0.01739996 0.184381 -0.121656 0.01739996 0.186823 -0.117312 0.01739996 0.1870819 -0.117048 0.01739996 0.187435 -0.116938 0.01739996 0.18475 -0.122404 0.01739996 0.18478 -0.122421 0.01739996 0.195656 -0.119735 0.01739996 0.185057 -0.122515 0.01739996 0.183549 -0.1251749 0.01739996 0.185181 -0.122507 0.01739996 0.192072 -0.123801 0.01739996 0.196129 -0.119355 0.01739996 0.196111 -0.119385 0.01739996 0.196206 -0.118829 0.01739996 0.195724 -0.117476 0.01739996 0.18907 -0.11577 0.01739996 0.189933 -0.116269 0.01739996 0.191071 -0.115964 0.01739996 0.18953 -0.114974 0.01739996 0.191195 -0.115936 0.01739996 0.191431 -0.115882 0.01739996 0.191787 -0.1159819 0.01739996 0.179523 -0.101858 0.01739996 0.179103 -0.101745 0.01739996 0.178748 -0.1016499 0.01739996 0.177973 -0.101858 0.01739996 0.1771979 -0.1032 0.01739996 0.16662 -0.09785777 0.01739996 0.1776649 -0.104235 0.01739996 0.180822 -0.102608 0.01739996 0.181129 -0.102915 0.01739996 0.182736 -0.103843 0.01739996 0.181389 -0.103175 0.01739996 0.1815969 -0.10395 0.01739996 0.181389 -0.104725 0.01739996 0.181298 -0.106332 0.01739996 0.180822 -0.105292 0.01739996 0.180047 -0.1055 0.01739996 0.179692 -0.105405 0.01739996 0.180829 -0.1071439 0.01739996 0.1792719 -0.105292 0.01739996 0.180079 -0.108443 0.01739996 0.181975 -0.10795 0.01739996 0.187726 -0.112749 0.01739996 0.1876789 -0.1128309 0.01739996 0.187597 -0.112783 0.01739996 0.187213 -0.113637 0.01739996 0.1852 -0.112474 0.01739996 0.181471 -0.111383 0.01739996 0.181931 -0.110587 0.01739996 0.182645 -0.11045 0.01739996 0.182478 -0.109828 0.01739996 0.182443 -0.109699 0.01739996 0.192019 -0.105313 0.01739996 0.191305 -0.10545 0.01739996 0.191506 -0.106201 0.01739996 0.1919749 -0.10795 0.01739996 0.19169 -0.109012 0.01739996 0.1894749 -0.10362 0.01739996 0.18226 -0.106887 0.01739996 0.184475 -0.10362 0.01739996 0.186224 -0.103151 0.01739996 0.192821 -0.112985 0.01739996 0.192561 -0.112725 0.01739996 0.192561 -0.111175 0.01739996 0.191214 -0.112057 0.01739996 0.192353 -0.11195 0.01739996 0.195977 -0.114042 0.01739996 0.196943 -0.115365 0.01739996 0.1952019 -0.11425 0.01739996 0.194847 -0.114155 0.01739996 0.194427 -0.114042 0.01739996 0.193128 -0.113292 0.01739996 0.1907449 -0.112869 0.01739996 0.196544 -0.113475 0.01739996 0.193128 -0.110608 0.01739996 0.192652 -0.1095679 0.01739996 0.193903 -0.1104 0.01739996 0.194258 -0.110495 0.01739996 0.196072 -0.107843 0.01739996 0.194678 -0.110608 0.01739996 0.195977 -0.111358 0.01739996 0.196337 -0.108101 0.01739996 0.199937 -0.11018 0.01739996 0.1962839 -0.111665 0.01739996 0.196544 -0.111925 0.01739996 0.196752 -0.1127 0.01739996 0.08309 -0.05949079 0.01739996 0.08157849 -0.05913466 0.01739996 0.0749154 -0.05407768 0.01739996 0.07831346 -0.05923426 0.01739996 0.0766229 -0.05578529 0.01739996 0.0747832 -0.05934184 0.01739996 0.07554036 -0.05641025 0.01739996 0.0749154 -0.05624276 0.01739996 0.07616537 -0.05407768 0.01739996 0.0815218 -0.05367726 0.01739996 0.0766229 -0.05453526 0.01739996 0.06286877 -0.04290795 0.01739996 0.07383388 -0.04923868 0.01739996 0.06273126 -0.04314619 0.01739996 0.08429038 -0.03783965 0.01739996 0.08227139 -0.03462445 0.01739996 0.08369636 -0.03215634 0.01739996 0.08579218 -0.03665715 0.01739996 0.08616536 -0.03675717 0.01739996 0.08995926 -0.03906309 0.01739996 0.09134727 -0.03986448 0.01739996 0.09045505 -0.03820425 0.01739996 0.1744599 -0.0925734 0.01739996 0.170931 -0.0903899 0.01739996 0.134921 -0.06810969 0.01739996 0.1335459 -0.07049196 0.01739996 0.09979528 -0.04637658 0.01739996 0.09779059 -0.04984879 0.01739996 0.08724677 -0.04376125 0.01739996 0.186589 -0.09005606 0.01739996 0.188644 -0.09002751 0.01739996 0.08625769 -0.04890596 0.01739996 0.08659535 -0.04871457 0.01739996 0.08698368 -0.04871779 0.01739996 0.0873183 -0.04891455 0.01739996 0.08674329 -0.05096244 0.01739996 0.08640867 -0.05115938 0.01739996 0.08693468 -0.05062478 0.01739996 0.08548265 -0.05024826 0.01739996 0.08548575 -0.05063647 0.01739996 0.08568269 -0.05097115 0.01739996 0.08750969 -0.04925239 0.01739996 0.08750647 -0.04964059 0.01739996 0.09564685 -0.05356186 0.01739996 0.07539808 -0.04202878 0.01739996 0.07741516 -0.0430358 0.01739996 0.08510297 -0.04747438 0.01739996 0.0755949 -0.04236346 0.01739996 0.07708388 -0.04360949 0.01739996 0.07559806 -0.04275166 0.01739996 0.06943649 -0.04153245 0.01739996 0.07482308 -0.04409396 0.01739996 0.0750603 -0.04183745 0.01739996 0.07114398 -0.03982496 0.01739996 0.07068645 -0.03936749 0.01739996 0.07114398 -0.04107499 0.01739996 0.07414609 -0.04237514 0.01739996 0.07131147 -0.04044997 0.01739996 0.07433736 -0.04203748 0.01739996 0.0746721 -0.04184055 0.01739996 0.0689789 -0.04107499 0.01739996 0.06881147 -0.04044997 0.01739996 0.06501257 -0.03919488 0.01739996 0.0689789 -0.03982496 0.01739996 0.06943649 -0.03936749 0.01739996 0.0700615 -0.03919994 0.01739996 0.07365876 -0.04395318 0.01739996 0.07355105 -0.04363727 0.01739996 0.07359117 -0.04330587 0.01739996 0.07068645 -0.04153245 0.01739996 0.07377105 -0.04302477 0.01739996 0.074539 -0.04426926 0.01739996 0.074207 -0.04430395 0.01739996 0.1555629 -0.09535688 0.01739996 0.155163 -0.09466409 0.01739996 0.156763 -0.09466409 0.01739996 0.166151 -0.0986697 0.01739996 0.156656 -0.0950641 0.01739996 0.15527 -0.09426409 0.01739996 0.155362 -0.09417259 0.01739996 0.128746 -0.0788058 0.01739996 0.129496 -0.07750678 0.01739996 0.1555629 -0.09397131 0.01739996 0.156363 -0.09397131 0.01739996 0.1774049 -0.1039749 0.01739996 0.09299057 -0.05816256 0.01739996 0.100711 -0.0627641 0.01739996 0.101803 -0.06385689 0.01739996 0.1014029 -0.06396406 0.01739996 0.12828 -0.07961195 0.01739996 0.100711 -0.06356406 0.01739996 0.102096 -0.0627641 0.01739996 0.1021299 -0.06343907 0.01739996 0.183 -0.11752 0.01739996 0.184521 -0.114994 0.01739996 0.186754 -0.114433 0.01739996 0.183567 -0.116952 0.01739996 0.1843169 -0.115653 0.01739996 0.176019 -0.120827 0.01739996 0.18145 -0.11752 0.01739996 0.182225 -0.117727 0.01739996 0.182744 -0.113346 0.01739996 0.183432 -0.113397 0.01739996 0.184029 -0.113742 0.01739996 0.184418 -0.114312 0.01739996 0.180883 -0.116952 0.01739996 0.180675 -0.116177 0.01739996 0.180883 -0.115402 0.01739996 0.1816329 -0.114103 0.01739996 0.182102 -0.113598 0.01739996 0.172745 -0.108041 0.01739996 0.127821 -0.08040797 0.01739996 0.1649349 -0.100775 0.01739996 0.09206557 -0.0597648 0.01739996 0.09252518 -0.05896878 0.01739996 0.08198136 -0.0528813 0.01739996 0.07429349 -0.04844266 0.01739996 0.08244675 -0.05207508 0.01739996 0.09374058 -0.0568636 0.01739996 0.100802 -0.06267255 0.01739996 0.1823959 -0.109781 0.01739996 0.178643 -0.110931 0.01739996 0.189995 -0.114168 0.01739996 0.177973 -0.104542 0.01739996 0.165401 -0.09996867 0.01739996 0.189566 -0.112189 0.01739996 0.190253 -0.111502 0.01739996 0.07389289 -0.04419118 0.01739996 0.0700615 -0.04169994 0.01739996 0.07597768 -0.04552555 0.01739996 0.08366549 -0.04996418 0.01739996 0.07550889 -0.04633748 0.01739996 0.06379377 -0.04130578 0.01739996 0.09420937 -0.05605167 0.01739996 0.08602041 -0.05116248 0.01739996 0.07475888 -0.04763656 0.01739996 0.1774049 -0.102425 0.01739996 0.1983799 -0.112875 0.01739996 0.202095 -0.11502 0.01739996 0.196474 -0.116177 0.01739996 0.2001889 -0.118322 0.01739996 0.199439 -0.119621 0.01739996 0.07909935 -0.04011869 0.01739996 0.06645005 -0.03670507 0.01739996 0.106203 -0.05623584 0.01739996 0.105403 -0.05703586 0.01739996 0.1050029 -0.05692869 0.01739996 0.08730965 -0.04997515 0.01739996 0.0973311 -0.05064475 0.01739996 0.1050029 -0.05554306 0.01739996 0.160656 -0.08813589 0.01739996 0.168057 -0.0953679 0.01739996 0.160363 -0.08842867 0.01739996 0.159963 -0.0885359 0.01739996 0.159963 -0.08693587 0.01739996 0.160363 -0.0870431 0.01739996 0.160656 -0.08733588 0.01739996 0.160763 -0.08773589 0.01739996 0.159563 -0.08842867 0.01739996 0.1299639 -0.0766949 0.01739996 0.131402 -0.0742051 0.01739996 0.08319675 -0.05077606 0.01739996 0.1592699 -0.08813589 0.01739996 0.1591629 -0.08773589 0.01739996 0.133086 -0.07128798 0.01739996 0.1592699 -0.08733588 0.01739996 0.159563 -0.0870431 0.01739996 0.18314 -0.09980785 0.01739996 0.182777 -0.09987807 0.01739996 0.182425 -0.09976649 0.01739996 0.169741 -0.09245085 0.01739996 0.08678716 -0.04455727 0.01739996 0.0795589 -0.03932267 0.01739996 0.186736 -0.102263 0.01739996 0.1844199 -0.100926 0.01739996 0.194795 -0.105855 0.01739996 0.192479 -0.104517 0.01739996 0.190005 -0.1041499 0.01739996 0.193067 -0.09894776 0.01739996 0.1924999 -0.09838038 0.01739996 0.191725 -0.09817278 0.01739996 0.189921 -0.102158 0.01739996 0.189532 -0.101588 0.01739996 0.189429 -0.100906 0.01739996 0.19095 -0.09838038 0.01739996 0.193275 -0.0997228 0.01739996 0.193067 -0.100498 0.01739996 0.191848 -0.102302 0.01739996 0.189909 -0.09676879 0.01739996 0.188609 -0.09601879 0.01739996 0.195836 -0.09870165 0.01739996 0.190553 -0.09565168 0.01739996 0.20024 -0.09642428 0.01739996 0.197268 -0.0962215 0.01739996 0.197931 -0.0950731 0.01739996 0.1926479 -0.09202307 0.01739996 0.189669 -0.091834 0.01739996 0.1903319 -0.0906856 0.01739996 0.100711 -0.06356406 0.01189994 0.101003 -0.06385689 0.01739996 0.100603 -0.06316405 0.01739996 0.100711 -0.0627641 0.01189994 0.101003 -0.06247127 0.01739996 0.100802 -0.06267255 0.01189994 0.1014029 -0.0623641 0.01189994 0.1014029 -0.0623641 0.01739996 0.101803 -0.06247127 0.01739996 0.102203 -0.06316405 0.01739996 0.102203 -0.06316405 0.01189994 0.102096 -0.06356406 0.01739996 0.102096 -0.06356406 0.01189994 0.190553 -0.09565168 0.01189994 0.101003 -0.06247127 0.01189994 0.08659535 -0.04871457 0.01189994 0.06273126 -0.04314619 0.01189994 0.196943 -0.115365 0.01189994 0.198759 -0.09926909 0.01189994 0.189105 -0.09310209 0.01189994 0.179846 -0.09529328 0.01189994 0.175482 -0.09297007 0.01189994 0.179873 -0.09499216 0.01189994 0.180018 -0.0947265 0.01189994 0.1802549 -0.0945394 0.01189994 0.180384 -0.09126991 0.01189994 0.18457 -0.09314399 0.01189994 0.182022 -0.09072577 0.01189994 0.184808 -0.09008085 0.01189994 0.191985 -0.09317147 0.01189994 0.186515 -0.09896177 0.01189994 0.186868 -0.09885245 0.01189994 0.187126 -0.09858769 0.01189994 0.188609 -0.09601879 0.01189994 0.179939 -0.09558075 0.01189994 0.170201 -0.09165489 0.01189994 0.182777 -0.09987807 0.01189994 0.182425 -0.09976649 0.01189994 0.1983799 -0.09879618 0.01189994 0.198103 -0.09870219 0.01189994 0.198685 -0.09911775 0.01189994 0.19863 -0.09900665 0.01189994 0.19841 -0.09881365 0.01189994 0.197548 -0.09885066 0.01189994 0.201532 -0.109744 0.01189994 0.2032369 -0.104464 0.01189994 0.201236 -0.110395 0.01189994 0.201429 -0.110175 0.01189994 0.2042 -0.111376 0.01189994 0.2014459 -0.110145 0.01189994 0.2015399 -0.109868 0.01189994 0.1983799 -0.112875 0.01189994 0.199937 -0.11018 0.01189994 0.200404 -0.11045 0.01189994 0.201012 -0.110505 0.01189994 0.200973 -0.1105239 0.01189994 0.202095 -0.11502 0.01189994 0.196337 -0.108101 0.01189994 0.195977 -0.111358 0.01189994 0.195007 -0.103138 0.01189994 0.194795 -0.105855 0.01189994 0.194907 -0.103494 0.01189994 0.192479 -0.104517 0.01189994 0.08429038 -0.03783965 0.01189994 0.08445775 -0.03846466 0.01189994 0.0795589 -0.03932267 0.01189994 0.08445775 -0.03721469 0.01189994 0.08491539 -0.03675717 0.01189994 0.08491539 -0.03892225 0.01189994 0.08554035 -0.03908967 0.01189994 0.08616536 -0.03892225 0.01189994 0.08662289 -0.03846466 0.01189994 0.08679038 -0.03783965 0.01189994 0.08995926 -0.03906309 0.01189994 0.08662289 -0.03721469 0.01189994 0.08643859 -0.03703039 0.01189994 0.08616536 -0.03675717 0.01189994 0.08579218 -0.03665715 0.01189994 0.08291637 -0.03350734 0.01189994 0.08554035 -0.03658968 0.01189994 0.08227139 -0.03462445 0.01189994 0.176019 -0.120827 0.01189994 0.175468 -0.1174409 0.01189994 0.175824 -0.117504 0.01189994 0.176169 -0.117391 0.01189994 0.1790429 -0.112406 0.01189994 0.1724489 -0.108104 0.01189994 0.168255 -0.105487 0.01189994 0.172202 -0.108279 0.01189994 0.172044 -0.108537 0.01189994 0.172001 -0.108836 0.01189994 0.173702 -0.119489 0.01189994 0.17295 -0.1132709 0.01189994 0.178961 -0.112046 0.01189994 0.178643 -0.110931 0.01189994 0.178239 -0.109517 0.01189994 0.177254 -0.108012 0.01189994 0.172745 -0.108041 0.01189994 0.196223 -0.119078 0.01189994 0.198974 -0.120427 0.01189994 0.196206 -0.118829 0.01189994 0.196204 -0.118786 0.01189994 0.185181 -0.122507 0.01189994 0.196111 -0.119385 0.01189994 0.195656 -0.119735 0.01189994 0.197782 -0.122034 0.01189994 0.194194 -0.120126 0.01189994 0.196732 -0.122552 0.01189994 0.192072 -0.123801 0.01189994 0.185349 -0.122496 0.01189994 0.185826 -0.125474 0.01189994 0.1870819 -0.117048 0.01189994 0.186823 -0.117312 0.01189994 0.184475 -0.121379 0.01189994 0.184381 -0.121656 0.01189994 0.18478 -0.122421 0.01189994 0.185057 -0.122515 0.01189994 0.1844 -0.121948 0.01189994 0.18475 -0.122404 0.01189994 0.189933 -0.116269 0.01189994 0.18953 -0.114974 0.01189994 0.191195 -0.115936 0.01189994 0.191431 -0.115882 0.01189994 0.191787 -0.1159819 0.01189994 0.195387 -0.11806 0.01189994 0.177973 -0.104542 0.01189994 0.1792719 -0.105292 0.01189994 0.177973 -0.101858 0.01189994 0.1774049 -0.102425 0.01189994 0.1771979 -0.1032 0.01189994 0.16662 -0.09785777 0.01189994 0.180822 -0.102608 0.01189994 0.181129 -0.102915 0.01189994 0.181389 -0.103175 0.01189994 0.180822 -0.105292 0.01189994 0.181389 -0.104725 0.01189994 0.1815969 -0.10395 0.01189994 0.186736 -0.102263 0.01189994 0.186224 -0.103151 0.01189994 0.184475 -0.10362 0.01189994 0.1919749 -0.10795 0.01189994 0.1943359 -0.106651 0.01189994 0.19169 -0.109012 0.01189994 0.190253 -0.111502 0.01189994 0.1823959 -0.109781 0.01189994 0.183944 -0.11175 0.01189994 0.184475 -0.11228 0.01189994 0.186754 -0.114433 0.01189994 0.1852 -0.112474 0.01189994 0.186975 -0.11295 0.01189994 0.187597 -0.112783 0.01189994 0.181975 -0.10795 0.01189994 0.180079 -0.108443 0.01189994 0.181298 -0.106332 0.01189994 0.180829 -0.1071439 0.01189994 0.179692 -0.105405 0.01189994 0.180047 -0.1055 0.01189994 0.182736 -0.103843 0.01189994 0.182645 -0.10545 0.01189994 0.18226 -0.106887 0.01189994 0.192561 -0.111175 0.01189994 0.192353 -0.11195 0.01189994 0.194678 -0.110608 0.01189994 0.192652 -0.1095679 0.01189994 0.194258 -0.110495 0.01189994 0.193903 -0.1104 0.01189994 0.191305 -0.11045 0.01189994 0.193128 -0.110608 0.01189994 0.192561 -0.112725 0.01189994 0.192821 -0.112985 0.01189994 0.191214 -0.112057 0.01189994 0.193128 -0.113292 0.01189994 0.1952019 -0.11425 0.01189994 0.195977 -0.114042 0.01189994 0.196544 -0.113475 0.01189994 0.1962839 -0.111665 0.01189994 0.196544 -0.111925 0.01189994 0.196752 -0.1127 0.01189994 0.170931 -0.0903899 0.01189994 0.09018677 -0.037705 0.01189994 0.09134727 -0.03986448 0.01189994 0.07517117 -0.0290358 0.01189994 0.07673126 -0.028135 0.01189994 0.07388126 -0.02978044 0.01189994 0.0685938 -0.032992 0.01189994 0.06273126 -0.05238378 0.01189994 0.07383388 -0.04923868 0.01189994 0.0749154 -0.05407768 0.01189994 0.07445776 -0.05453526 0.01189994 0.07429039 -0.05516028 0.01189994 0.07445776 -0.05578529 0.01189994 0.07679039 -0.05516028 0.01189994 0.0766229 -0.05453526 0.01189994 0.07616537 -0.05407768 0.01189994 0.07554036 -0.05391025 0.01189994 0.0749154 -0.05624276 0.01189994 0.07554036 -0.05641025 0.01189994 0.07616537 -0.05624276 0.01189994 0.0766229 -0.05578529 0.01189994 0.08309 -0.05949079 0.01189994 0.0815218 -0.05367726 0.01189994 0.08157849 -0.05913466 0.01189994 0.164476 -0.101571 0.01189994 0.127821 -0.08040797 0.01189994 0.09206557 -0.0597648 0.01189994 0.199585 -0.09755897 0.01189994 0.20024 -0.09642428 0.01189994 0.201741 -0.09880369 0.01189994 0.201577 -0.09819257 0.01189994 0.1889359 -0.09310358 0.01189994 0.186184 -0.09312909 0.01189994 0.08548575 -0.05063647 0.01189994 0.08750647 -0.04964059 0.01189994 0.08750969 -0.04925239 0.01189994 0.0873183 -0.04891455 0.01189994 0.08698368 -0.04871779 0.01189994 0.09420937 -0.05605167 0.01189994 0.08568269 -0.05097115 0.01189994 0.08366549 -0.04996418 0.01189994 0.08602041 -0.05116248 0.01189994 0.08640867 -0.05115938 0.01189994 0.08674329 -0.05096244 0.01189994 0.0700615 -0.03919994 0.01189994 0.06943649 -0.03936749 0.01189994 0.0689789 -0.03982496 0.01189994 0.07365876 -0.04395318 0.01189994 0.074207 -0.04430395 0.01189994 0.08548265 -0.05024826 0.01189994 0.08399677 -0.04939049 0.01189994 0.0763089 -0.04495185 0.01189994 0.074539 -0.04426926 0.01189994 0.07482308 -0.04409396 0.01189994 0.0755949 -0.04236346 0.01189994 0.07539808 -0.04202878 0.01189994 0.0750603 -0.04183745 0.01189994 0.0746721 -0.04184055 0.01189994 0.07433736 -0.04203748 0.01189994 0.07068645 -0.03936749 0.01189994 0.07114398 -0.03982496 0.01189994 0.07114398 -0.04107499 0.01189994 0.07414609 -0.04237514 0.01189994 0.07068645 -0.04153245 0.01189994 0.07355105 -0.04363727 0.01189994 0.06881147 -0.04044997 0.01189994 0.0689789 -0.04107499 0.01189994 0.06501257 -0.03919488 0.01189994 0.06943649 -0.04153245 0.01189994 0.07597768 -0.04552555 0.01189994 0.07377105 -0.04302477 0.01189994 0.07359117 -0.04330587 0.01189994 0.07131147 -0.04044997 0.01189994 0.07389289 -0.04419118 0.01189994 0.0700615 -0.04169994 0.01189994 0.07708388 -0.04360949 0.01189994 0.07741516 -0.0430358 0.01189994 0.15527 -0.09426409 0.01189994 0.155163 -0.09466409 0.01189994 0.12828 -0.07961195 0.01189994 0.1555629 -0.09535688 0.01189994 0.155963 -0.09546411 0.01189994 0.156656 -0.0950641 0.01189994 0.156363 -0.09397131 0.01189994 0.1014029 -0.06396406 0.01189994 0.101803 -0.06385689 0.01189994 0.1555629 -0.09397131 0.01189994 0.155362 -0.09417259 0.01189994 0.128746 -0.0788058 0.01189994 0.101003 -0.06385689 0.01189994 0.09252518 -0.05896878 0.01189994 0.100603 -0.06316405 0.01189994 0.1021299 -0.06343907 0.01189994 0.129496 -0.07750678 0.01189994 0.102096 -0.0627641 0.01189994 0.09374058 -0.0568636 0.01189994 0.101803 -0.06247127 0.01189994 0.189669 -0.091834 0.01189994 0.197931 -0.0950731 0.01189994 0.200179 -0.09637099 0.01189994 0.197811 -0.09872126 0.01189994 0.197268 -0.0962215 0.01189994 0.189648 -0.0942195 0.01189994 0.189429 -0.100906 0.01189994 0.1924999 -0.09838038 0.01189994 0.191725 -0.09817278 0.01189994 0.189909 -0.09676879 0.01189994 0.19095 -0.09838038 0.01189994 0.190383 -0.09894776 0.01189994 0.193067 -0.100498 0.01189994 0.193275 -0.0997228 0.01189994 0.193067 -0.09894776 0.01189994 0.187196 -0.101467 0.01189994 0.195191 -0.09981876 0.01189994 0.1964899 -0.100569 0.01189994 0.197135 -0.09945166 0.01189994 0.195836 -0.09870165 0.01189994 0.08724677 -0.04376125 0.01189994 0.1894749 -0.10362 0.01189994 0.184879 -0.10013 0.01189994 0.192019 -0.105313 0.01189994 0.06813418 -0.03378796 0.01189994 0.07909935 -0.04011869 0.01189994 0.08678716 -0.04455727 0.01189994 0.08510297 -0.04747438 0.01189994 0.0973311 -0.05064475 0.01189994 0.106203 -0.05623584 0.01189994 0.106096 -0.0558359 0.01189994 0.1047109 -0.0558359 0.01189994 0.1047109 -0.05663585 0.01189994 0.09564685 -0.05356186 0.01189994 0.133086 -0.07128798 0.01189994 0.105803 -0.05692869 0.01189994 0.106096 -0.05663585 0.01189994 0.09779059 -0.04984879 0.01189994 0.160363 -0.08842867 0.01189994 0.159563 -0.08842867 0.01189994 0.1592699 -0.08813589 0.01189994 0.159963 -0.0885359 0.01189994 0.168057 -0.0953679 0.01189994 0.179103 -0.101745 0.01189994 0.1844199 -0.100926 0.01189994 0.179523 -0.101858 0.01189994 0.160656 -0.08813589 0.01189994 0.160763 -0.08773589 0.01189994 0.160656 -0.08733588 0.01189994 0.1592699 -0.08733588 0.01189994 0.1591629 -0.08773589 0.01189994 0.1335459 -0.07049196 0.01189994 0.169741 -0.09245085 0.01189994 0.160363 -0.0870431 0.01189994 0.159963 -0.08693587 0.01189994 0.159563 -0.0870431 0.01189994 0.178748 -0.1016499 0.01189994 0.131402 -0.0742051 0.01189994 0.1299639 -0.0766949 0.01189994 0.1774049 -0.1039749 0.01189994 0.1776649 -0.104235 0.01189994 0.166151 -0.0986697 0.01189994 0.08319675 -0.05077606 0.01189994 0.07550889 -0.04633748 0.01189994 0.07475888 -0.04763656 0.01189994 0.06379377 -0.04130578 0.01189994 0.1907449 -0.112869 0.01189994 0.194427 -0.114042 0.01189994 0.194847 -0.114155 0.01189994 0.196074 -0.118523 0.01189994 0.195724 -0.117476 0.01189994 0.196474 -0.116177 0.01189994 0.200658 -0.11751 0.01189994 0.200681 -0.110544 0.01189994 0.09299057 -0.05816256 0.01189994 0.08244675 -0.05207508 0.01189994 0.165401 -0.09996867 0.01189994 0.177886 -0.108351 0.01189994 0.177613 -0.108101 0.01189994 0.179614 -0.109249 0.01189994 0.1649349 -0.100775 0.01189994 0.08198136 -0.0528813 0.01189994 0.07429349 -0.04844266 0.01189994 0.179154 -0.110045 0.01189994 0.181931 -0.110587 0.01189994 0.18907 -0.11577 0.01189994 0.187213 -0.113637 0.01189994 0.189995 -0.114168 0.01189994 0.1876789 -0.1128309 0.01189994 0.180883 -0.116952 0.01189994 0.18145 -0.11752 0.01189994 0.184521 -0.114994 0.01189994 0.182225 -0.117727 0.01189994 0.183 -0.11752 0.01189994 0.1813009 -0.123877 0.01189994 0.183567 -0.116952 0.01189994 0.1843169 -0.115653 0.01189994 0.184418 -0.114312 0.01189994 0.184029 -0.113742 0.01189994 0.183432 -0.113397 0.01189994 0.182744 -0.113346 0.01189994 0.182102 -0.113598 0.01189994 0.181471 -0.111383 0.01189994 0.1816329 -0.114103 0.01189994 0.180883 -0.115402 0.01189994 0.180675 -0.116177 0.01189994 0.178643 0.110931 0.01739996 0.178239 0.109517 0.01189994 0.1780059 0.1087 0.01739996 0.1790429 0.112406 0.01189994 0.178943 0.112762 0.01189994 0.178943 0.112762 0.01739996 0.177459 0.115331 0.01739996 0.176815 0.116448 0.01189994 0.175181 0.117219 0.01739996 0.175468 0.1174409 0.01739996 0.175824 0.117504 0.01739996 0.176421 0.117131 0.01189994 0.172818 0.112651 0.01739996 0.17295 0.1132709 0.01739996 0.17295 0.1132709 0.01189994 0.175098 0.117071 0.01739996 0.175098 0.117071 0.01189994 0.172745 0.108041 0.01739996 0.1724489 0.108104 0.01189994 0.1724489 0.108104 0.01739996 0.172202 0.108279 0.01189994 0.172001 0.108836 0.01189994 0.175651 0.108023 0.01189994 0.177254 0.108012 0.01189994 0.175651 0.108023 0.01739996 0.177254 0.108012 0.01739996 0.1843169 0.115653 0.01739996 0.184525 0.1148779 0.01739996 0.1843169 0.114103 0.01739996 0.1829749 0.113328 0.01189994 0.1822 0.113536 0.01189994 0.1822 0.113536 0.01739996 0.1816329 0.114103 0.01189994 0.186675 0.122141 0.01739996 0.185349 0.122496 0.01189994 0.186675 0.122141 0.01189994 0.188437 0.121669 0.01739996 0.188437 0.121669 0.01189994 0.196129 0.118605 0.01189994 0.196129 0.118605 0.01739996 0.191787 0.1159819 0.01739996 0.191071 0.115964 0.01739996 0.189933 0.116269 0.01739996 0.188572 0.1166329 0.01739996 0.189933 0.116269 0.01189994 0.187435 0.116938 0.01739996 0.188572 0.1166329 0.01189994 0.186823 0.117312 0.01739996 0.186823 0.117312 0.01189994 0.18534 0.119881 0.01189994 0.184475 0.121379 0.01189994 0.183964 0.0996012 0.01739996 0.183964 0.0996012 0.01189994 0.182425 0.09976649 0.01739996 0.182169 0.09950017 0.01189994 0.182169 0.09950017 0.01739996 0.179939 0.09558075 0.01189994 0.180018 0.0947265 0.01189994 0.179873 0.09499216 0.01189994 0.179846 0.09529328 0.01189994 0.179846 0.09529328 0.01739996 0.1802549 0.0945394 0.01189994 0.1889359 0.09310358 0.01739996 0.18457 0.09314399 0.01189994 0.189673 0.0935167 0.01189994 0.189673 0.0935167 0.01739996 0.189441 0.09323871 0.01739996 0.187126 0.09858769 0.01189994 0.201521 0.109576 0.01189994 0.201129 0.108114 0.01739996 0.195007 0.103138 0.01189994 0.195007 0.103138 0.01739996 0.194907 0.103494 0.01739996 0.195658 0.106353 0.01189994 0.195963 0.10749 0.01739996 0.195963 0.10749 0.01189994 0.196337 0.108101 0.01739996 0.1960009 0.107612 0.01189994 0.201236 0.110395 0.01739996 0.201429 0.110175 0.01189994 0.201012 0.110505 0.01189994 0.200973 0.1105239 0.01739996 0.200404 0.11045 0.01739996 0.199937 0.11018 0.01739996 0.190253 0.111502 0.01189994 0.191305 0.11045 0.01189994 0.19169 0.109012 0.01189994 0.191941 0.108075 0.01739996 0.191941 0.108075 0.01189994 0.1919749 0.10795 0.01189994 0.1914719 0.106072 0.01739996 0.191305 0.10545 0.01739996 0.191305 0.10545 0.01189994 0.190005 0.1041499 0.01739996 0.190005 0.1041499 0.01189994 0.1894749 0.10362 0.01739996 0.1894749 0.10362 0.01189994 0.186975 0.10295 0.01739996 0.186975 0.10295 0.01189994 0.186353 0.103117 0.01739996 0.186353 0.103117 0.01189994 0.184475 0.10362 0.01739996 0.186224 0.103151 0.01189994 0.184475 0.10362 0.01189994 0.184383 0.103711 0.01189994 0.183697 0.104398 0.01189994 0.183697 0.104398 0.01739996 0.182645 0.10545 0.01189994 0.182443 0.109699 0.01739996 0.182645 0.11045 0.01739996 0.183944 0.11175 0.01739996 0.182645 0.11045 0.01189994 0.186975 0.11295 0.01739996 0.187726 0.112749 0.01739996 0.1894749 0.11228 0.01739996 0.190253 0.111502 0.01739996 0.0687313 0.03275376 0.01739996 0.0685938 0.032992 0.01189994 0.06813418 0.03378796 0.01189994 0.06766879 0.03459417 0.01189994 0.06286877 0.04290795 0.01189994 0.06286877 0.04290795 0.01739996 0.08369636 0.03215634 0.01189994 0.08369636 0.03215634 0.01739996 0.09200137 0.04108166 0.01189994 0.09200137 0.04108166 0.01739996 0.1744599 0.0925734 0.01739996 0.170931 0.0903899 0.01189994 0.170931 0.0903899 0.01739996 0.134921 0.06810969 0.01189994 0.134921 0.06810969 0.01739996 0.09979528 0.04637658 0.01189994 0.0930655 0.04221266 0.01189994 0.175482 0.09297007 0.01739996 0.175482 0.09297007 0.01189994 0.176577 0.09297358 0.01739996 0.177601 0.09258335 0.01739996 0.184808 0.09008085 0.01739996 0.188644 0.09002751 0.01739996 0.189866 0.09041649 0.01189994 0.1903319 0.0906856 0.01739996 0.1926479 0.09202307 0.01189994 0.201577 0.09819257 0.01189994 0.200179 0.09637099 0.01739996 0.200179 0.09637099 0.01189994 0.20024 0.09642428 0.01739996 0.201059 0.09714275 0.01189994 0.201059 0.09714275 0.01739996 0.204499 0.109099 0.01739996 0.203251 0.104439 0.01189994 0.203251 0.104439 0.01739996 0.204499 0.109099 0.01189994 0.2042 0.111376 0.01189994 0.2042 0.111376 0.01739996 0.204226 0.111299 0.01739996 0.204226 0.111299 0.01189994 0.204576 0.110267 0.01189994 0.203314 0.112909 0.01739996 0.202564 0.114208 0.01739996 0.202095 0.11502 0.01739996 0.202564 0.114208 0.01189994 0.198554 0.121154 0.01739996 0.198501 0.121215 0.01189994 0.197782 0.122034 0.01739996 0.186437 0.125311 0.01189994 0.190349 0.124262 0.01739996 0.190349 0.124262 0.01189994 0.192111 0.12379 0.01739996 0.196732 0.122552 0.01739996 0.185826 0.125474 0.01739996 0.184658 0.125551 0.01189994 0.1836259 0.125201 0.01739996 0.184658 0.125551 0.01739996 0.173236 0.11922 0.01739996 0.173702 0.119489 0.01739996 0.176019 0.120827 0.01739996 0.176019 0.120827 0.01189994 0.1813009 0.123877 0.01739996 0.1813009 0.123877 0.01189994 0.06273126 0.05238378 0.01739996 0.08019727 0.0591768 0.01739996 0.07831346 0.05923426 0.01189994 0.0747832 0.05934184 0.01739996 0.08157849 0.05913466 0.01189994 0.08309 0.05949079 0.01739996 0.1264449 0.08279025 0.01189994 0.168806 0.106434 0.01189994 0.167401 0.1048 0.01189994 0.172288 0.118357 0.01739996 0.171286 0.116563 0.01189994 0.169582 0.112272 0.01739996 0.1704159 0.1150079 0.01189994 0.169297 0.111339 0.01739996 0.169582 0.112272 0.01189994 0.169297 0.111339 0.01189994 0.169234 0.110582 0.01189994 0.08625769 0.04890596 0.01739996 0.08477181 0.04804807 0.01739996 0.08477181 0.04804807 0.01189994 0.07559806 0.04275166 0.01189994 0.07414609 0.04237514 0.01189994 0.0745666 0.04187846 0.01189994 0.0745666 0.04187846 0.01739996 0.07489395 0.04181379 0.01739996 0.07521706 0.04189747 0.01189994 0.07547187 0.04211318 0.01189994 0.08399677 0.04939049 0.01739996 0.07482308 0.04409396 0.01189994 0.0763089 0.04495185 0.01739996 0.07482308 0.04409396 0.01739996 0.08730965 0.04997515 0.01189994 0.08730965 0.04997515 0.01739996 0.160656 0.08733588 0.01189994 0.160363 0.0870431 0.01189994 0.160656 0.08733588 0.01739996 0.159963 0.08693587 0.01739996 0.159963 0.08693587 0.01189994 0.159563 0.0870431 0.01189994 0.159563 0.0870431 0.01739996 0.1592699 0.08733588 0.01189994 0.159237 0.08746087 0.01739996 0.1591629 0.08773589 0.01739996 0.1592699 0.08813589 0.01739996 0.159563 0.08842867 0.01739996 0.159563 0.08842867 0.01189994 0.160363 0.08842867 0.01739996 0.160363 0.08842867 0.01189994 0.160564 0.08822739 0.01739996 0.160656 0.08813589 0.01739996 0.160656 0.08813589 0.01189994 0.156656 0.0950641 0.01739996 0.156763 0.09466409 0.01739996 0.156363 0.09397131 0.01739996 0.155963 0.09386408 0.01189994 0.155963 0.09386408 0.01739996 0.1555629 0.09397131 0.01189994 0.15527 0.09426409 0.01739996 0.155163 0.09466409 0.01189994 0.155963 0.09546411 0.01739996 0.156363 0.09535688 0.01739996 0.156363 0.09535688 0.01189994 0.102096 0.06356406 0.01739996 0.102203 0.06316405 0.01739996 0.102096 0.0627641 0.01189994 0.102096 0.0627641 0.01739996 0.1014029 0.0623641 0.01739996 0.101003 0.06247127 0.01189994 0.101003 0.06247127 0.01739996 0.100603 0.06316405 0.01739996 0.100711 0.06356406 0.01189994 0.100711 0.06356406 0.01739996 0.101003 0.06385689 0.01189994 0.101803 0.06385689 0.01189994 0.1014029 0.06396406 0.01739996 0.101803 0.06385689 0.01739996 0.183396 0.120248 0.01189994 0.08445775 0.03846466 0.01189994 0.08429038 0.03783965 0.01189994 0.194847 0.114155 0.01189994 0.164476 0.101571 0.01189994 0.16898 0.107515 0.01189994 0.172044 0.108537 0.01189994 0.168255 0.105487 0.01189994 0.172818 0.112651 0.01189994 0.173744 0.1146759 0.01189994 0.176169 0.117391 0.01189994 0.175824 0.117504 0.01189994 0.175468 0.1174409 0.01189994 0.175181 0.117219 0.01189994 0.178643 0.110931 0.01189994 0.178961 0.112046 0.01189994 0.181471 0.111383 0.01189994 0.177459 0.115331 0.01189994 0.172745 0.108041 0.01189994 0.177613 0.108101 0.01189994 0.184475 0.122129 0.01189994 0.185181 0.122507 0.01189994 0.185057 0.122515 0.01189994 0.184281 0.124066 0.01189994 0.18478 0.122421 0.01189994 0.18475 0.122404 0.01189994 0.194194 0.120126 0.01189994 0.192072 0.123801 0.01189994 0.1920869 0.123776 0.01189994 0.192111 0.12379 0.01189994 0.195656 0.119735 0.01189994 0.196732 0.122552 0.01189994 0.197782 0.122034 0.01189994 0.195807 0.11966 0.01189994 0.195918 0.119605 0.01189994 0.196111 0.119385 0.01189994 0.196129 0.119355 0.01189994 0.198554 0.121154 0.01189994 0.198974 0.120427 0.01189994 0.196229 0.11898 0.01189994 0.196186 0.118817 0.01189994 0.195387 0.11806 0.01189994 0.194427 0.114042 0.01189994 0.191787 0.1159819 0.01189994 0.191195 0.115936 0.01189994 0.191071 0.115964 0.01189994 0.187435 0.116938 0.01189994 0.1870819 0.117048 0.01189994 0.184695 0.120998 0.01189994 0.0749154 0.05407768 0.01189994 0.07554036 0.05391025 0.01189994 0.07383388 0.04923868 0.01189994 0.0766229 0.05453526 0.01189994 0.07679039 0.05516028 0.01189994 0.0766229 0.05578529 0.01189994 0.07616537 0.05624276 0.01189994 0.07554036 0.05641025 0.01189994 0.07528859 0.05634278 0.01189994 0.0749154 0.05624276 0.01189994 0.07464218 0.05596959 0.01189994 0.07445776 0.05578529 0.01189994 0.07429039 0.05516028 0.01189994 0.186868 0.09885245 0.01189994 0.186515 0.09896177 0.01189994 0.189441 0.09323871 0.01189994 0.1903319 0.0906856 0.01189994 0.189105 0.09310209 0.01189994 0.189748 0.09387117 0.01189994 0.189648 0.0942195 0.01189994 0.187196 0.101467 0.01189994 0.177601 0.09258335 0.01189994 0.18107 0.09094595 0.01189994 0.1744599 0.0925734 0.01189994 0.176577 0.09297358 0.01189994 0.1889359 0.09310358 0.01189994 0.188644 0.09002751 0.01189994 0.184808 0.09008085 0.01189994 0.182425 0.09976649 0.01189994 0.181376 0.0981068 0.01189994 0.184879 0.10013 0.01189994 0.185391 0.09924358 0.01189994 0.1844199 0.100926 0.01189994 0.18314 0.09980785 0.01189994 0.201236 0.110395 0.01189994 0.200973 0.1105239 0.01189994 0.203314 0.112909 0.01189994 0.198759 0.09926909 0.01189994 0.2014459 0.110145 0.01189994 0.2037799 0.112103 0.01189994 0.2015399 0.109868 0.01189994 0.201532 0.109744 0.01189994 0.201129 0.108114 0.01189994 0.1976299 0.09879618 0.01189994 0.195294 0.104992 0.01189994 0.198005 0.09869569 0.01189994 0.194989 0.103854 0.01189994 0.194907 0.103494 0.01189994 0.197355 0.09907066 0.01189994 0.1983799 0.09879618 0.01189994 0.19841 0.09881365 0.01189994 0.20024 0.09642428 0.01189994 0.19863 0.09900665 0.01189994 0.198685 0.09911775 0.01189994 0.1943359 0.106651 0.01189994 0.196072 0.107843 0.01189994 0.196337 0.108101 0.01189994 0.200404 0.11045 0.01189994 0.199937 0.11018 0.01189994 0.199599 0.110764 0.01189994 0.179103 0.101745 0.01189994 0.179523 0.101858 0.01189994 0.180822 0.102608 0.01189994 0.1774049 0.102425 0.01189994 0.177973 0.101858 0.01189994 0.178748 0.1016499 0.01189994 0.1771979 0.1032 0.01189994 0.1774049 0.1039749 0.01189994 0.179692 0.105405 0.01189994 0.180047 0.1055 0.01189994 0.1815969 0.10395 0.01189994 0.182736 0.103843 0.01189994 0.181389 0.104725 0.01189994 0.180822 0.105292 0.01189994 0.183944 0.11175 0.01189994 0.182443 0.109699 0.01189994 0.179614 0.109249 0.01189994 0.181975 0.10795 0.01189994 0.181298 0.106332 0.01189994 0.1852 0.112474 0.01189994 0.184475 0.11228 0.01189994 0.192652 0.1095679 0.01189994 0.1894749 0.11228 0.01189994 0.18953 0.114974 0.01189994 0.187213 0.113637 0.01189994 0.187726 0.112749 0.01189994 0.19387 0.107457 0.01189994 0.18875 0.103426 0.01189994 0.192019 0.105313 0.01189994 0.1914719 0.106072 0.01189994 0.191554 0.106119 0.01189994 0.191506 0.106201 0.01189994 0.1832039 0.103031 0.01189994 0.181129 0.102915 0.01189994 0.181389 0.103175 0.01189994 0.18226 0.106887 0.01189994 0.193128 0.113292 0.01189994 0.191431 0.115882 0.01189994 0.192821 0.112985 0.01189994 0.191214 0.112057 0.01189994 0.193128 0.110608 0.01189994 0.192561 0.111175 0.01189994 0.192353 0.11195 0.01189994 0.192561 0.112725 0.01189994 0.193903 0.1104 0.01189994 0.194258 0.110495 0.01189994 0.194678 0.110608 0.01189994 0.198849 0.112063 0.01189994 0.196544 0.111925 0.01189994 0.1983799 0.112875 0.01189994 0.196752 0.1127 0.01189994 0.196544 0.113475 0.01189994 0.195977 0.114042 0.01189994 0.1952019 0.11425 0.01189994 0.09006088 0.06323695 0.01189994 0.1637459 0.102836 0.01189994 0.08019727 0.0591768 0.01189994 0.07880926 0.05837547 0.01189994 0.06273126 0.05238378 0.01189994 0.06969636 0.05640506 0.01189994 0.07774686 0.05925148 0.01189994 0.07047647 0.05505394 0.01189994 0.06273126 0.05058228 0.01189994 0.07445776 0.05453526 0.01189994 0.07112139 0.05393689 0.01189994 0.06273126 0.04314619 0.01189994 0.06273126 0.04909288 0.01189994 0.08554035 0.03908967 0.01189994 0.08491539 0.03892225 0.01189994 0.08679038 0.03783965 0.01189994 0.09045505 0.03820425 0.01189994 0.08662289 0.03846466 0.01189994 0.08616536 0.03892225 0.01189994 0.08445775 0.03721469 0.01189994 0.08491539 0.03675717 0.01189994 0.08554035 0.03658968 0.01189994 0.08616536 0.03675717 0.01189994 0.08662289 0.03721469 0.01189994 0.08724677 0.04376125 0.01189994 0.09245896 0.04171717 0.01189994 0.170201 0.09165489 0.01189994 0.1335459 0.07049196 0.01189994 0.09779059 0.04984879 0.01189994 0.1836259 0.125201 0.01189994 0.185826 0.125474 0.01189994 0.183549 0.1251749 0.01189994 0.08693468 0.05062478 0.01189994 0.09420937 0.05605167 0.01189994 0.08674329 0.05096244 0.01189994 0.08659535 0.04871457 0.01189994 0.08698368 0.04871779 0.01189994 0.08510297 0.04747438 0.01189994 0.0873183 0.04891455 0.01189994 0.09564685 0.05356186 0.01189994 0.08750969 0.04925239 0.01189994 0.08750647 0.04964059 0.01189994 0.08548265 0.05024826 0.01189994 0.08399677 0.04939049 0.01189994 0.08548575 0.05063647 0.01189994 0.08568269 0.05097115 0.01189994 0.08602041 0.05116248 0.01189994 0.0763089 0.04495185 0.01189994 0.06943649 0.03936749 0.01189994 0.0689789 0.03982496 0.01189994 0.06881147 0.04044997 0.01189994 0.0689789 0.04107499 0.01189994 0.0744853 0.04428535 0.01189994 0.07409709 0.04428219 0.01189994 0.07560777 0.042418 0.01189994 0.07429957 0.04207885 0.01189994 0.07131147 0.04044997 0.01189994 0.07489395 0.04181379 0.01189994 0.07114398 0.04107499 0.01189994 0.07068645 0.04153245 0.01189994 0.07377105 0.04302477 0.01189994 0.0700615 0.04169994 0.01189994 0.07357418 0.04335939 0.01189994 0.06943649 0.04153245 0.01189994 0.0700615 0.03919994 0.01189994 0.08625769 0.04890596 0.01189994 0.07708388 0.04360949 0.01189994 0.07741516 0.0430358 0.01189994 0.07068645 0.03936749 0.01189994 0.07114398 0.03982496 0.01189994 0.169741 0.09245085 0.01189994 0.159237 0.08746087 0.01189994 0.1591629 0.08773589 0.01189994 0.160763 0.08773589 0.01189994 0.160564 0.08822739 0.01189994 0.1685259 0.09455597 0.01189994 0.159963 0.0885359 0.01189994 0.1592699 0.08813589 0.01189994 0.131871 0.07339316 0.01189994 0.132621 0.07209408 0.01189994 0.105803 0.05554306 0.01189994 0.106096 0.0558359 0.01189994 0.106005 0.05672734 0.01189994 0.1050029 0.05692869 0.01189994 0.09611558 0.05274999 0.01189994 0.172288 0.118357 0.01189994 0.174365 0.118341 0.01189994 0.173236 0.11922 0.01189994 0.173702 0.119489 0.01189994 0.181964 0.122728 0.01189994 0.1781139 0.117198 0.01189994 0.1766819 0.119678 0.01189994 0.186754 0.114433 0.01189994 0.18375 0.113536 0.01189994 0.178759 0.1160809 0.01189994 0.181171 0.117313 0.01189994 0.180782 0.116744 0.01189994 0.180679 0.116061 0.01189994 0.180883 0.115402 0.01189994 0.183098 0.117458 0.01189994 0.182456 0.1177099 0.01189994 0.181768 0.117658 0.01189994 0.1843169 0.114103 0.01189994 0.184525 0.1148779 0.01189994 0.1843169 0.115653 0.01189994 0.184041 0.119131 0.01189994 0.183567 0.116952 0.01189994 0.179154 0.110045 0.01189994 0.181931 0.110587 0.01189994 0.1780059 0.1087 0.01189994 0.177886 0.108351 0.01189994 0.18907 0.11577 0.01189994 0.186975 0.11295 0.01189994 0.06501257 0.03919488 0.01189994 0.07376235 0.04408538 0.01189994 0.07357108 0.0437476 0.01189994 0.07597768 0.04552555 0.01189994 0.07429349 0.04844266 0.01189994 0.06332838 0.04211199 0.01189994 0.08640867 0.05115938 0.01189994 0.08366549 0.04996418 0.01189994 0.1014029 0.06396406 0.01189994 0.1014029 0.0623641 0.01189994 0.101803 0.06247127 0.01189994 0.09252518 0.05896878 0.01189994 0.100603 0.06316405 0.01189994 0.08309 0.05949079 0.01189994 0.09206557 0.0597648 0.01189994 0.07616537 0.05407768 0.01189994 0.08198136 0.0528813 0.01189994 0.0815218 0.05367726 0.01189994 0.100711 0.0627641 0.01189994 0.102203 0.06316405 0.01189994 0.1299639 0.0766949 0.01189994 0.102096 0.06356406 0.01189994 0.12828 0.07961195 0.01189994 0.156763 0.09466409 0.01189994 0.156363 0.09397131 0.01189994 0.156656 0.09426409 0.01189994 0.16662 0.09785777 0.01189994 0.1776649 0.104235 0.01189994 0.177973 0.104542 0.01189994 0.1792719 0.105292 0.01189994 0.156656 0.0950641 0.01189994 0.1649349 0.100775 0.01189994 0.155963 0.09546411 0.01189994 0.15527 0.0950641 0.01189994 0.15527 0.09426409 0.01189994 0.127821 0.08040797 0.01189994 0.1555629 0.09535688 0.01189994 0.131402 0.0742051 0.01189994 0.168057 0.0953679 0.01189994 0.08557176 0.04666244 0.01189994 0.06645005 0.03670507 0.01189994 0.06691879 0.0358932 0.01189994 0.104603 0.05623584 0.01189994 0.08632177 0.04536336 0.01189994 0.07788389 0.04222387 0.01189994 0.0786339 0.04092484 0.01189994 0.19312 0.108756 0.01189994 0.195977 0.111358 0.01189994 0.1962839 0.111665 0.01189994 0.200681 0.110544 0.01189994 0.202095 0.11502 0.01189994 0.196943 0.115365 0.01189994 0.200658 0.11751 0.01189994 0.195854 0.11833 0.01189994 0.09686559 0.05145084 0.01189994 0.0973311 0.05064475 0.01189994 0.1692759 0.093257 0.01189994 0.182777 0.09987807 0.01189994 0.133086 0.07128798 0.01189994 0.08678716 0.04455727 0.01189994 0.0795589 0.03932267 0.01189994 0.07909935 0.04011869 0.01189994 0.186736 0.102263 0.01189994 0.186271 0.103069 0.01189994 0.183954 0.101732 0.01189994 0.192479 0.104517 0.01189994 0.194795 0.105855 0.01189994 0.190975 0.102572 0.01189994 0.1902 0.102364 0.01189994 0.189633 0.101797 0.01189994 0.192779 0.09858649 0.01189994 0.193168 0.09915649 0.01189994 0.192182 0.09824156 0.01189994 0.191494 0.09819006 0.01189994 0.193271 0.09983855 0.01189994 0.197931 0.0950731 0.01189994 0.193067 0.100498 0.01189994 0.192317 0.101797 0.01189994 0.1917499 0.102364 0.01189994 0.189425 0.101022 0.01189994 0.189633 0.100247 0.01189994 0.190383 0.09894776 0.01189994 0.190852 0.09844207 0.01189994 0.106203 0.05623584 0.01739996 0.106203 0.05623584 0.01189994 0.105403 0.05543589 0.01189994 0.105803 0.05554306 0.01739996 0.105403 0.05543589 0.01739996 0.1050029 0.05554306 0.01189994 0.1047109 0.0558359 0.01189994 0.1047109 0.0558359 0.01739996 0.104677 0.05596089 0.01189994 0.1047109 0.05663585 0.01189994 0.105403 0.05703586 0.01189994 0.105803 0.05692869 0.01189994 0.106005 0.05672734 0.01739996 0.106096 0.05663585 0.01189994 0.193271 0.09983855 0.01739996 0.197931 0.0950731 0.01739996 0.195294 0.104992 0.01739996 0.185057 0.122515 0.01739996 0.195387 0.11806 0.01739996 0.176421 0.117131 0.01739996 0.176815 0.116448 0.01739996 0.176169 0.117391 0.01739996 0.174365 0.118341 0.01739996 0.1704159 0.1150079 0.01739996 0.172202 0.108279 0.01739996 0.172001 0.108836 0.01739996 0.169234 0.110582 0.01739996 0.16898 0.107515 0.01739996 0.172044 0.108537 0.01739996 0.167401 0.1048 0.01739996 0.168255 0.105487 0.01739996 0.168806 0.106434 0.01739996 0.179154 0.110045 0.01739996 0.178961 0.112046 0.01739996 0.181471 0.111383 0.01739996 0.1790429 0.112406 0.01739996 0.196186 0.118817 0.01739996 0.200658 0.11751 0.01739996 0.196229 0.11898 0.01739996 0.195854 0.11833 0.01739996 0.192072 0.123801 0.01739996 0.1920869 0.123776 0.01739996 0.194194 0.120126 0.01739996 0.195656 0.119735 0.01739996 0.195807 0.11966 0.01739996 0.198501 0.121215 0.01739996 0.195918 0.119605 0.01739996 0.196111 0.119385 0.01739996 0.196129 0.119355 0.01739996 0.198974 0.120427 0.01739996 0.185349 0.122496 0.01739996 0.184475 0.122129 0.01739996 0.18475 0.122404 0.01739996 0.18478 0.122421 0.01739996 0.184041 0.119131 0.01739996 0.1870819 0.117048 0.01739996 0.191214 0.112057 0.01739996 0.192821 0.112985 0.01739996 0.193128 0.113292 0.01739996 0.191431 0.115882 0.01739996 0.194427 0.114042 0.01739996 0.196943 0.115365 0.01739996 0.07616537 0.05407768 0.01739996 0.07554036 0.05391025 0.01739996 0.07554036 0.05641025 0.01739996 0.07880926 0.05837547 0.01739996 0.0815218 0.05367726 0.01739996 0.0766229 0.05578529 0.01739996 0.07679039 0.05516028 0.01739996 0.0766229 0.05453526 0.01739996 0.07112139 0.05393689 0.01739996 0.07528859 0.05634278 0.01739996 0.179939 0.09558075 0.01739996 0.179873 0.09499216 0.01739996 0.180018 0.0947265 0.01739996 0.1802549 0.0945394 0.01739996 0.18107 0.09094595 0.01739996 0.18457 0.09314399 0.01739996 0.189748 0.09387117 0.01739996 0.189866 0.09041649 0.01739996 0.189105 0.09310209 0.01739996 0.186868 0.09885245 0.01739996 0.187126 0.09858769 0.01739996 0.189648 0.0942195 0.01739996 0.18314 0.09980785 0.01739996 0.182777 0.09987807 0.01739996 0.198005 0.09869569 0.01739996 0.1983799 0.09879618 0.01739996 0.19841 0.09881365 0.01739996 0.204576 0.110267 0.01739996 0.19863 0.09900665 0.01739996 0.198685 0.09911775 0.01739996 0.198759 0.09926909 0.01739996 0.201577 0.09819257 0.01739996 0.201521 0.109576 0.01739996 0.2037799 0.112103 0.01739996 0.201429 0.110175 0.01739996 0.2014459 0.110145 0.01739996 0.2015399 0.109868 0.01739996 0.201532 0.109744 0.01739996 0.201012 0.110505 0.01739996 0.200681 0.110544 0.01739996 0.199599 0.110764 0.01739996 0.194795 0.105855 0.01739996 0.195658 0.106353 0.01739996 0.1943359 0.106651 0.01739996 0.1960009 0.107612 0.01739996 0.196072 0.107843 0.01739996 0.177973 0.101858 0.01739996 0.1771979 0.1032 0.01739996 0.1774049 0.1039749 0.01739996 0.181129 0.102915 0.01739996 0.1832039 0.103031 0.01739996 0.180822 0.102608 0.01739996 0.179523 0.101858 0.01739996 0.179103 0.101745 0.01739996 0.177973 0.104542 0.01739996 0.1792719 0.105292 0.01739996 0.179692 0.105405 0.01739996 0.180047 0.1055 0.01739996 0.180822 0.105292 0.01739996 0.181389 0.104725 0.01739996 0.182736 0.103843 0.01739996 0.1815969 0.10395 0.01739996 0.181389 0.103175 0.01739996 0.191506 0.106201 0.01739996 0.192019 0.105313 0.01739996 0.18875 0.103426 0.01739996 0.191305 0.11045 0.01739996 0.18953 0.114974 0.01739996 0.184475 0.11228 0.01739996 0.184383 0.103711 0.01739996 0.182645 0.10545 0.01739996 0.181298 0.106332 0.01739996 0.18226 0.106887 0.01739996 0.181975 0.10795 0.01739996 0.179614 0.109249 0.01739996 0.181931 0.110587 0.01739996 0.194258 0.110495 0.01739996 0.193903 0.1104 0.01739996 0.193128 0.110608 0.01739996 0.192652 0.1095679 0.01739996 0.192561 0.111175 0.01739996 0.192353 0.11195 0.01739996 0.192561 0.112725 0.01739996 0.196752 0.1127 0.01739996 0.196544 0.111925 0.01739996 0.198849 0.112063 0.01739996 0.1962839 0.111665 0.01739996 0.195977 0.111358 0.01739996 0.194678 0.110608 0.01739996 0.19312 0.108756 0.01739996 0.194847 0.114155 0.01739996 0.1952019 0.11425 0.01739996 0.195977 0.114042 0.01739996 0.1983799 0.112875 0.01739996 0.196544 0.113475 0.01739996 0.186437 0.125311 0.01739996 0.185181 0.122507 0.01739996 0.1335459 0.07049196 0.01739996 0.170201 0.09165489 0.01739996 0.09245896 0.04171717 0.01739996 0.09779059 0.04984879 0.01739996 0.0930655 0.04221266 0.01739996 0.09979528 0.04637658 0.01739996 0.08445775 0.03721469 0.01739996 0.09045505 0.03820425 0.01739996 0.08662289 0.03721469 0.01739996 0.08616536 0.03675717 0.01739996 0.08554035 0.03658968 0.01739996 0.08429038 0.03783965 0.01739996 0.08491539 0.03892225 0.01739996 0.08554035 0.03908967 0.01739996 0.07383388 0.04923868 0.01739996 0.0749154 0.05407768 0.01739996 0.06273126 0.04909288 0.01739996 0.07047647 0.05505394 0.01739996 0.06273126 0.05058228 0.01739996 0.07464218 0.05596959 0.01739996 0.0749154 0.05624276 0.01739996 0.07774686 0.05925148 0.01739996 0.06969636 0.05640506 0.01739996 0.09006088 0.06323695 0.01739996 0.08157849 0.05913466 0.01739996 0.07831346 0.05923426 0.01739996 0.1637459 0.102836 0.01739996 0.1264449 0.08279025 0.01739996 0.127821 0.08040797 0.01739996 0.173744 0.1146759 0.01739996 0.171286 0.116563 0.01739996 0.08602041 0.05116248 0.01739996 0.08640867 0.05115938 0.01739996 0.08674329 0.05096244 0.01739996 0.08659535 0.04871457 0.01739996 0.08698368 0.04871779 0.01739996 0.08366549 0.04996418 0.01739996 0.08548575 0.05063647 0.01739996 0.08568269 0.05097115 0.01739996 0.08750647 0.04964059 0.01739996 0.08750969 0.04925239 0.01739996 0.08548265 0.05024826 0.01739996 0.0700615 0.03919994 0.01739996 0.06943649 0.03936749 0.01739996 0.0689789 0.03982496 0.01739996 0.0744853 0.04428535 0.01739996 0.07597768 0.04552555 0.01739996 0.07409709 0.04428219 0.01739996 0.07708388 0.04360949 0.01739996 0.07559806 0.04275166 0.01739996 0.06881147 0.04044997 0.01739996 0.0689789 0.04107499 0.01739996 0.06501257 0.03919488 0.01739996 0.06943649 0.04153245 0.01739996 0.0700615 0.04169994 0.01739996 0.07376235 0.04408538 0.01739996 0.07357108 0.0437476 0.01739996 0.07521706 0.04189747 0.01739996 0.07131147 0.04044997 0.01739996 0.07560777 0.042418 0.01739996 0.07547187 0.04211318 0.01739996 0.07429957 0.04207885 0.01739996 0.07114398 0.04107499 0.01739996 0.07414609 0.04237514 0.01739996 0.07377105 0.04302477 0.01739996 0.07068645 0.04153245 0.01739996 0.07357418 0.04335939 0.01739996 0.160763 0.08773589 0.01739996 0.169741 0.09245085 0.01739996 0.160363 0.0870431 0.01739996 0.1592699 0.08733588 0.01739996 0.132621 0.07209408 0.01739996 0.1685259 0.09455597 0.01739996 0.178748 0.1016499 0.01739996 0.159963 0.0885359 0.01739996 0.1692759 0.093257 0.01739996 0.1050029 0.05554306 0.01739996 0.09686559 0.05145084 0.01739996 0.133086 0.07128798 0.01739996 0.106096 0.0558359 0.01739996 0.0973311 0.05064475 0.01739996 0.1047109 0.05663585 0.01739996 0.105403 0.05703586 0.01739996 0.131871 0.07339316 0.01739996 0.105803 0.05692869 0.01739996 0.106096 0.05663585 0.01739996 0.192317 0.101797 0.01739996 0.189633 0.101797 0.01739996 0.1902 0.102364 0.01739996 0.190975 0.102572 0.01739996 0.192479 0.104517 0.01739996 0.1917499 0.102364 0.01739996 0.1976299 0.09879618 0.01739996 0.197355 0.09907066 0.01739996 0.193067 0.100498 0.01739996 0.193168 0.09915649 0.01739996 0.192779 0.09858649 0.01739996 0.192182 0.09824156 0.01739996 0.1926479 0.09202307 0.01739996 0.191494 0.09819006 0.01739996 0.190852 0.09844207 0.01739996 0.190383 0.09894776 0.01739996 0.189633 0.100247 0.01739996 0.189425 0.101022 0.01739996 0.181376 0.0981068 0.01739996 0.08724677 0.04376125 0.01739996 0.08678716 0.04455727 0.01739996 0.0795589 0.03932267 0.01739996 0.07909935 0.04011869 0.01739996 0.08632177 0.04536336 0.01739996 0.09611558 0.05274999 0.01739996 0.104677 0.05596089 0.01739996 0.104603 0.05623584 0.01739996 0.186224 0.103151 0.01739996 0.186271 0.103069 0.01739996 0.186736 0.102263 0.01739996 0.184879 0.10013 0.01739996 0.187196 0.101467 0.01739996 0.185391 0.09924358 0.01739996 0.186515 0.09896177 0.01739996 0.1919749 0.10795 0.01739996 0.19387 0.107457 0.01739996 0.191554 0.106119 0.01739996 0.194989 0.103854 0.01739996 0.183954 0.101732 0.01739996 0.1844199 0.100926 0.01739996 0.19169 0.109012 0.01739996 0.07114398 0.03982496 0.01739996 0.07068645 0.03936749 0.01739996 0.06645005 0.03670507 0.01739996 0.06691879 0.0358932 0.01739996 0.08510297 0.04747438 0.01739996 0.07741516 0.0430358 0.01739996 0.07788389 0.04222387 0.01739996 0.06766879 0.03459417 0.01739996 0.0873183 0.04891455 0.01739996 0.0786339 0.04092484 0.01739996 0.06813418 0.03378796 0.01739996 0.1050029 0.05692869 0.01739996 0.168057 0.0953679 0.01739996 0.1774049 0.102425 0.01739996 0.08693468 0.05062478 0.01739996 0.09420937 0.05605167 0.01739996 0.101803 0.06247127 0.01739996 0.100711 0.0627641 0.01739996 0.101003 0.06385689 0.01739996 0.08198136 0.0528813 0.01739996 0.16662 0.09785777 0.01739996 0.1776649 0.104235 0.01739996 0.156656 0.09426409 0.01739996 0.1299639 0.0766949 0.01739996 0.131402 0.0742051 0.01739996 0.09564685 0.05356186 0.01739996 0.08557176 0.04666244 0.01739996 0.0685938 0.032992 0.01739996 0.15527 0.0950641 0.01739996 0.1555629 0.09535688 0.01739996 0.1649349 0.100775 0.01739996 0.1555629 0.09397131 0.01739996 0.12828 0.07961195 0.01739996 0.155163 0.09466409 0.01739996 0.177886 0.108351 0.01739996 0.177613 0.108101 0.01739996 0.164476 0.101571 0.01739996 0.09252518 0.05896878 0.01739996 0.09206557 0.0597648 0.01739996 0.07429349 0.04844266 0.01739996 0.06332838 0.04211199 0.01739996 0.178239 0.109517 0.01739996 0.191195 0.115936 0.01739996 0.18907 0.11577 0.01739996 0.187213 0.113637 0.01739996 0.1852 0.112474 0.01739996 0.18375 0.113536 0.01739996 0.1829749 0.113328 0.01739996 0.178759 0.1160809 0.01739996 0.180782 0.116744 0.01739996 0.181171 0.117313 0.01739996 0.181768 0.117658 0.01739996 0.1816329 0.114103 0.01739996 0.180883 0.115402 0.01739996 0.180679 0.116061 0.01739996 0.182456 0.1177099 0.01739996 0.183098 0.117458 0.01739996 0.186754 0.114433 0.01739996 0.183567 0.116952 0.01739996 0.18534 0.119881 0.01739996 0.184695 0.120998 0.01739996 0.183396 0.120248 0.01739996 0.1781139 0.117198 0.01739996 0.184281 0.124066 0.01739996 0.183549 0.1251749 0.01739996 0.181964 0.122728 0.01739996 0.1766819 0.119678 0.01739996 0.184375 0.121754 0.01739996 0.184475 0.121379 0.01739996 0.184375 0.121754 0.01189994 -0.007194161 0.203622 0.01189994 -0.007194161 0.203622 0.01739996 -0.007396399 0.203398 0.01739996 -0.007973194 0.203263 0.01739996 -0.008253931 0.203375 0.01189994 -0.008253931 0.203375 0.01739996 -0.01383775 0.210175 0.01189994 -0.01383775 0.210175 0.01739996 -0.01243984 0.207805 0.01189994 -0.01115 0.20599 0.01189994 -0.01397335 0.21068 0.01189994 -0.01392388 0.210321 0.01739996 -0.01397335 0.21068 0.01739996 -0.007554113 0.211008 0.01739996 -0.006747901 0.210175 0.01739996 -0.006747901 0.210175 0.01189994 -0.005724966 0.209118 0.01739996 -0.005724966 0.209118 0.01189994 -0.008183658 0.21135 0.01739996 -0.007825374 0.211259 0.01189994 -0.007554113 0.211008 0.01189994 -0.01115 0.21135 0.01189994 -0.01115 0.21135 0.01739996 -0.0132277 0.21135 0.01739996 -0.01341015 0.221765 0.01189994 -0.01243984 0.222736 0.01739996 -0.006935536 0.22824 0.01189994 -0.006935536 0.22824 0.01739996 -0.005865275 0.22931 0.01739996 -0.005865275 0.22931 0.01189994 -0.008183658 0.22045 0.01739996 -0.008183658 0.22045 0.01189994 -0.01115 0.22045 0.01739996 -0.01287978 0.22045 0.01189994 -0.004650473 0.229155 0.01189994 -0.004924952 0.229429 0.01189994 -0.006363928 0.222264 0.01189994 -0.005724966 0.222781 0.01189994 -0.006363928 0.222264 0.01739996 -0.004892289 0.2234539 0.01739996 -0.00454998 0.224084 0.01189994 -0.00454998 0.22824 0.01189994 -0.00454998 0.22878 0.01189994 0.005724966 0.209118 0.01739996 0.005133807 0.208508 0.01189994 0.006747901 0.210175 0.01739996 0.007825374 0.211259 0.01189994 0.0132277 0.21135 0.01189994 0.01357924 0.211262 0.01189994 0.01392388 0.210321 0.01739996 0.008253931 0.203375 0.01189994 0.0116201 0.2064149 0.01739996 0.01383775 0.210175 0.01189994 0.007973194 0.203263 0.01189994 0.007973194 0.203263 0.01739996 0.007396399 0.203398 0.01189994 0.007396399 0.203398 0.01739996 0.007194161 0.203622 0.01739996 0.004914522 0.207513 0.01189994 0.005724966 0.20613 0.01189994 0.01341015 0.221765 0.01189994 0.01362979 0.221235 0.01189994 0.006935536 0.22824 0.01189994 0.005724966 0.229404 0.01189994 0.005621969 0.2294729 0.01189994 0.00454998 0.22878 0.01189994 0.00454998 0.224084 0.01739996 0.004805803 0.2235479 0.01189994 0.004641056 0.223725 0.01189994 0.004641056 0.223725 0.01739996 0.004892289 0.2234539 0.01739996 0.005724966 0.222781 0.01189994 0.008183658 0.22045 0.01739996 0 0.2208999 0.01739996 0.001437485 0.220515 0.01189994 0.002374947 0.220264 0.01189994 0.003780126 0.21895 0.01739996 0.004805803 0.216625 0.01739996 0.004805803 0.216625 0.01189994 0.004805803 0.215175 0.01189994 0.004330098 0.2134 0.01189994 0.003874957 0.212945 0.01739996 0.003780126 0.21285 0.01739996 0.002374947 0.211536 0.01739996 0.002374947 0.211536 0.01189994 0.001437485 0.2112849 0.01189994 0 0.2109 0.01739996 0 0.2109 0.01189994 -0.001437485 0.2112849 0.01739996 -0.002499997 0.21157 0.01739996 -0.001437485 0.2112849 0.01189994 -0.004330098 0.2134 0.01739996 -0.004330098 0.2134 0.01189994 -0.004999995 0.2159 0.01739996 -0.004999995 0.2159 0.01189994 -0.004805803 0.216625 0.01189994 -0.002499997 0.22023 0.01189994 -0.001437485 0.220515 0.01739996 -0.001437485 0.220515 0.01189994 -0.01662975 0.2215459 0.01739996 -0.01661396 0.221625 0.01189994 -0.01661396 0.221625 0.01739996 -0.01640146 0.222694 0.01189994 -0.01640146 0.222694 0.01739996 -0.01115 0.228268 0.01739996 -0.01117819 0.22824 0.01739996 -0.01243984 0.226978 0.01189994 -0.01575118 0.223667 0.01739996 -0.01530379 0.224114 0.01189994 -0.007766962 0.231651 0.01189994 -0.005724966 0.232514 0.01739996 -0.005645632 0.2325299 0.01189994 -0.005724966 0.232514 0.01189994 -0.006793677 0.2323009 0.01739996 0.004805803 0.2325299 0.01739996 0.003874957 0.2325299 0.01739996 0.002374947 0.2325299 0.01739996 0.001437485 0.2325299 0.01189994 -0.001437485 0.2325299 0.01739996 -0.001437485 0.2325299 0.01189994 -0.004805803 0.2325299 0.01189994 -0.005645632 0.2325299 0.01739996 0.006793677 0.2323009 0.01189994 0.005645632 0.2325299 0.01189994 0.005724966 0.232514 0.01739996 0.006793677 0.2323009 0.01739996 0.01117819 0.22824 0.01189994 0.01575118 0.223667 0.01189994 0.01661396 0.221625 0.01739996 0.01661396 0.221625 0.01189994 0.01662975 0.2215459 0.01739996 0.01662975 0.209637 0.01739996 0.01177364 0.202285 0.01189994 0.01177364 0.202285 0.01739996 0.0143916 0.205089 0.01189994 0.0143916 0.205089 0.01739996 0.007226347 0.198457 0.01189994 0.007771193 0.199407 0.01189994 0.007771193 0.199407 0.01739996 0.009975492 0.101703 0.01739996 0.009734332 0.109614 0.01739996 0.009734332 0.109614 0.01189994 0.00847584 0.1509 0.01739996 0.00847584 0.1509 0.01189994 0.01042288 0.100216 0.01739996 0.009975492 0.101703 0.01189994 0.01399999 0.09443509 0.01739996 0.0121417 0.09743857 0.01739996 0.01399999 0.09443509 0.01189994 0.0121417 0.09743857 0.01189994 0.01399999 0.08856135 0.01189994 0.01399999 0.08051878 0.01739996 0.005724966 0.07589995 0.01189994 0.005724966 0.07589995 0.01739996 0.002374947 0.07589995 0.01189994 0.003874957 0.07589995 0.01739996 0.002374947 0.07589995 0.01739996 0.001437485 0.07589995 0.01739996 -0.001437485 0.07589995 0.01739996 -0.001437485 0.07589995 0.01189994 -0.005724966 0.07589995 0.01739996 -0.01399999 0.08051878 0.01739996 -0.01243984 0.07961809 0.01189994 -0.01115 0.07887339 0.01189994 -0.005999982 0.07589995 0.01189994 -0.01399999 0.08051878 0.01189994 -0.01399999 0.09443509 0.01189994 -0.01399999 0.09443509 0.01739996 -0.01243984 0.09695649 0.01739996 -0.01115 0.09904128 0.01189994 -0.01042288 0.100216 0.01189994 -0.01115 0.09904128 0.01739996 -0.009975492 0.101703 0.01739996 -0.007059216 0.197374 0.01739996 -0.00847584 0.1509 0.01739996 -0.00847584 0.1509 0.01189994 -0.009734332 0.109614 0.01189994 -0.008620977 0.200099 0.01739996 -0.007771193 0.199407 0.01189994 -0.007771193 0.199407 0.01739996 -0.007226347 0.198457 0.01189994 -0.007059216 0.197374 0.01189994 -0.01115 0.201852 0.01189994 -0.01243984 0.202998 0.01189994 -0.01243984 0.202998 0.01739996 -0.01530379 0.206619 0.01189994 -0.0143916 0.205089 0.01739996 -0.01635575 0.208384 0.01739996 -0.01662975 0.209637 0.01739996 -0.01635575 0.208384 0.01189994 -0.01662975 0.209637 0.01189994 -0.01662975 0.210175 0.01189994 -0.01662975 0.210175 0.01739996 -0.01662975 0.21285 0.01189994 -0.01662975 0.21895 0.01189994 -0.01662975 0.21895 0.01739996 -7.75e-4 0.09915429 0.01189994 -7.75e-4 0.09915429 0.01739996 -7.75e-4 0.08684569 0.01189994 -7.75e-4 0.08684569 0.01739996 7.75e-4 0.09915429 0.01739996 7.75e-4 0.09915429 0.01189994 7.75e-4 0.09743857 0.01739996 -0.003199994 0.1823999 0.01189994 -0.003307163 0.1827999 0.01739996 -0.003199994 0.1823999 0.01739996 -0.003307163 0.182 0.01189994 -0.003307163 0.182 0.01739996 -0.003599941 0.181707 0.01739996 -0.003999948 0.1816 0.01739996 -0.004399955 0.181707 0.01189994 -0.004692792 0.1827999 0.01189994 -0.004799962 0.1823999 0.01739996 -0.004692792 0.1827999 0.01739996 -0.004399955 0.183093 0.01739996 -0.003999948 0.1202 0.01739996 -0.003599941 0.120093 0.01739996 -0.003307163 0.1198 0.01189994 -0.003199994 0.1194 0.01189994 -0.003199994 0.1194 0.01739996 -0.003999948 0.1186 0.01739996 -0.004399955 0.118707 0.01739996 -0.004799962 0.1194 0.01189994 -0.004692792 0.1198 0.01189994 -0.004692792 0.1198 0.01739996 -0.004399955 0.120093 0.01739996 -0.003999948 0.1202 0.01189994 0.004805803 0.09743857 0.01739996 0.001437485 0.20832 0.01739996 0.005724966 0.210175 0.01739996 -0.01350384 0.221625 0.01739996 -0.01243984 0.21285 0.01739996 -0.01530379 0.210175 0.01739996 -0.01243984 0.207805 0.01739996 -0.0116201 0.2064149 0.01739996 -0.01115 0.20599 0.01739996 -0.007670938 0.203271 0.01739996 -0.01177364 0.202285 0.01739996 -0.01115 0.201852 0.01739996 -0.005724966 0.193226 0.01739996 -0.007226347 0.198457 0.01739996 -0.004812002 0.207868 0.01739996 -0.004914522 0.207513 0.01739996 -0.005724966 0.20613 0.01739996 -0.005724966 0.210175 0.01739996 -0.007825374 0.211259 0.01739996 -0.00454998 0.22878 0.01739996 -0.004805803 0.22931 0.01739996 -0.004924952 0.229429 0.01739996 -0.004805803 0.2325299 0.01739996 -0.005299985 0.22953 0.01739996 -0.005334973 0.22953 0.01739996 -0.005621969 0.2294729 0.01739996 -0.005724966 0.229404 0.01739996 -0.007766962 0.231651 0.01739996 -0.01115 0.22824 0.01739996 -0.01115 0.224025 0.01739996 -0.01243984 0.226978 0.01739996 -0.01357269 0.221522 0.01739996 -0.01362979 0.221235 0.01739996 -0.01325476 0.22055 0.01739996 -0.01352936 0.220825 0.01739996 -0.01530379 0.221625 0.01739996 -0.01362979 0.2211999 0.01739996 -0.007825374 0.220541 0.01739996 -0.005724966 0.222781 0.01739996 -0.005724966 0.221625 0.01739996 -0.0068807 0.221625 0.01739996 -0.007554113 0.2207919 0.01739996 -0.004805803 0.2235479 0.01739996 -0.001437485 0.221625 0.01739996 -0.00999999 0.09174996 0.01739996 -0.01115 0.09743857 0.01739996 -0.00891745 0.093625 0.01739996 -0.005724966 0.08856135 0.01739996 -0.008749961 0.09299999 0.01739996 -0.01115 0.09262681 0.01739996 -0.01108247 0.093625 0.01739996 -0.01115 0.09337317 0.01739996 -0.0121417 0.09743857 0.01739996 0.007670938 0.203271 0.01739996 0.01383775 0.210175 0.01739996 0.008620977 0.200099 0.01739996 0.008253931 0.203375 0.01739996 0.01635575 0.208384 0.01739996 0.01397335 0.21068 0.01739996 0.01662975 0.210175 0.01739996 0.0138489 0.2110199 0.01739996 0.01357924 0.211262 0.01739996 0.007554113 0.211008 0.01739996 0.007825374 0.211259 0.01739996 0.008183658 0.21135 0.01739996 0.0132277 0.21135 0.01739996 0.004812002 0.207868 0.01739996 0.004914522 0.207513 0.01739996 0.005133807 0.208508 0.01739996 0.004891514 0.208229 0.01739996 0.007554113 0.2207919 0.01739996 0.01357269 0.2209129 0.01739996 0.01362979 0.2211999 0.01739996 0.01362979 0.221235 0.01739996 0.01341015 0.22067 0.01739996 0.01316678 0.220507 0.01739996 0.01287978 0.22045 0.01739996 0.007825374 0.220541 0.01739996 0.005724966 0.229404 0.01739996 0.01357269 0.221522 0.01739996 0.01350384 0.221625 0.01739996 0.01640146 0.222694 0.01739996 0.01341015 0.221765 0.01739996 0.01575118 0.223667 0.01739996 0.006935536 0.22824 0.01739996 0.01117819 0.22824 0.01739996 0.005865275 0.22931 0.01739996 0.007766962 0.231651 0.01739996 0.004805803 0.2293339 0.01739996 0.005012989 0.2294729 0.01739996 0.005645632 0.2325299 0.01739996 0.005299985 0.22953 0.01739996 0.005334973 0.22953 0.01739996 0.005621969 0.2294729 0.01739996 0.004769623 0.22931 0.01739996 0.004607081 0.229067 0.01739996 0.003874957 0.221625 0.01739996 0.00454998 0.22824 0.01739996 0.0068807 0.221625 0.01739996 0.006363928 0.222264 0.01739996 0.005724966 0.221625 0.01739996 0.005724966 0.222781 0.01739996 0.004805803 0.221625 0.01739996 0.004805803 0.2235479 0.01739996 -0.004805803 0.210175 0.01739996 -0.001549959 0.2064 0.01739996 0.001396477 0.205727 0.01739996 9.66409e-4 0.205188 0.01739996 3.44907e-4 0.2048889 0.01739996 -9.66409e-4 0.205188 0.01739996 -0.001396477 0.205727 0.01739996 -0.001437485 0.205907 0.01739996 0.002374947 0.210175 0.01739996 0.001549959 0.2078999 0.01739996 -0.001549959 0.2078999 0.01739996 -0.001437485 0.20832 0.01739996 -0.001342296 0.208675 0.01739996 -7.75e-4 0.209242 0.01739996 0 0.20945 0.01739996 0.001437485 0.210175 0.01739996 7.75e-4 0.209242 0.01739996 0.001342296 0.208675 0.01739996 0.002499997 0.21157 0.01739996 0.002499997 0.22023 0.01739996 0.003874957 0.218855 0.01739996 0.004330098 0.2184 0.01739996 0.004805803 0.21895 0.01739996 0.004999995 0.2159 0.01739996 0.004805803 0.215175 0.01739996 0.004805803 0.21285 0.01739996 0.004330098 0.2134 0.01739996 0.002374947 0.220264 0.01739996 -0.004805803 0.216625 0.01739996 -0.004330098 0.2184 0.01739996 -0.003780126 0.21895 0.01739996 -0.002499997 0.22023 0.01739996 0.001437485 0.2112849 0.01739996 -0.001437485 0.210175 0.01739996 -0.004805803 0.21285 0.01739996 -0.003780126 0.21285 0.01739996 0.001342296 0.223125 0.01739996 7.75e-4 0.222558 0.01739996 0 0.22235 0.01739996 -7.75e-4 0.222558 0.01739996 0.001396477 0.226073 0.01739996 0.001437485 0.225893 0.01739996 0.001549959 0.2254 0.01739996 0.001549959 0.2239 0.01739996 0.001437485 0.22348 0.01739996 -0.001342296 0.223125 0.01739996 -0.001437485 0.22348 0.01739996 -0.004641056 0.223725 0.01739996 -0.001549959 0.2239 0.01739996 -0.001549959 0.2254 0.01739996 -0.00454998 0.224084 0.01739996 -0.00454998 0.22824 0.01739996 -0.001437485 0.22824 0.01739996 -0.001437485 0.225893 0.01739996 -0.001396477 0.226073 0.01739996 -9.66409e-4 0.226612 0.01739996 -3.44907e-4 0.226911 0.01739996 0.001437485 0.22824 0.01739996 3.44907e-4 0.226911 0.01739996 9.66409e-4 0.226612 0.01739996 -0.01530379 0.224114 0.01739996 -0.01341015 0.221765 0.01739996 0.005724966 0.1509 0.01739996 0.005724966 0.193226 0.01739996 0.007185637 0.193226 0.01739996 0.007059216 0.197374 0.01739996 0.007226347 0.198457 0.01739996 0.005724966 0.109614 0.01739996 0.010625 0.09191745 0.01739996 0.009374976 0.09408247 0.01739996 0.005724966 0.09743857 0.01739996 0.01399999 0.08856135 0.01739996 0.01108247 0.09237498 0.01739996 0.009374976 0.09191745 0.01739996 0.010625 0.09408247 0.01739996 0.01108247 0.093625 0.01739996 0.01124995 0.09299999 0.01739996 0.005724966 0.08856135 0.01739996 0.00891745 0.093625 0.01739996 -0.009374976 0.09191745 0.01739996 -0.01115 0.08856135 0.01739996 -0.01115 0.07887339 0.01739996 -0.01243984 0.07961809 0.01739996 -0.01243984 0.08856135 0.01739996 -0.01124995 0.09299999 0.01739996 -0.01399999 0.08856135 0.01739996 -0.009734332 0.109614 0.01739996 -0.005724966 0.09743857 0.01739996 -0.01042288 0.100216 0.01739996 -0.007185637 0.193226 0.01739996 -0.01530379 0.206619 0.01739996 0.0011096 0.09935116 0.01739996 0.00130099 0.09968888 0.01739996 3.75e-4 0.1006 0.01739996 7.63216e-4 0.100603 0.01739996 -0.0011096 0.09935116 0.01739996 -0.001437485 0.09743857 0.01739996 -0.00130099 0.09968888 0.01739996 -0.001297831 0.100077 0.01739996 -0.001100957 0.100412 0.01739996 -7.63216e-4 0.100603 0.01739996 -7.75e-4 0.09743857 0.01739996 -7.75e-4 0.08856135 0.01739996 6.25e-4 0.08198249 0.01739996 0.001235187 0.08576697 0.01739996 0.001015424 0.08551579 0.01739996 7.08435e-4 0.08538478 0.01739996 7.75e-4 0.08684569 0.01739996 0 0.08214998 0.01739996 3.75e-4 0.08539998 0.01739996 -3.75e-4 0.08539998 0.01739996 -6.25e-4 0.08198249 0.01739996 -0.001082479 0.08152496 0.01739996 -7.63216e-4 0.08539676 0.01739996 -0.001100957 0.08558815 0.01739996 -0.0011096 0.08664876 0.01739996 -0.00130099 0.0863111 0.01739996 0.001082479 0.08027499 0.01739996 6.25e-4 0.07981747 0.01739996 0 0.07964998 0.01739996 -6.25e-4 0.07981747 0.01739996 -0.001297831 0.08592277 0.01739996 -0.001249969 0.08089995 0.01739996 -0.001082479 0.08027499 0.01739996 0.00106877 0.08668726 0.01739996 0.00126481 0.08641719 0.01739996 0.004692792 0.182 0.01739996 0.003874957 0.1509 0.01739996 0.004799962 0.1823999 0.01739996 0.004692792 0.1827999 0.01739996 0.004399955 0.183093 0.01739996 0.003199994 0.1823999 0.01739996 0.003307163 0.1827999 0.01739996 0.003599941 0.183093 0.01739996 0.003874957 0.183167 0.01739996 0.003874957 0.193226 0.01739996 0.003999948 0.1832 0.01739996 0.004399955 0.181707 0.01739996 0.003999948 0.1816 0.01739996 0.003874957 0.1816329 0.01739996 0.003599941 0.181707 0.01739996 0.003307163 0.182 0.01739996 0.002374947 0.193226 0.01739996 0.001437485 0.205907 0.01739996 0.003999948 0.1186 0.01739996 0.003874957 0.118633 0.01739996 0.004692792 0.1198 0.01739996 0.004805803 0.109614 0.01739996 0.002374947 0.1509 0.01739996 0.003599941 0.120093 0.01739996 0.003874957 0.120167 0.01739996 0.004805803 0.1509 0.01739996 0.01084226 0.215125 0.01739996 0.01104998 0.2159 0.01739996 0.01662975 0.21285 0.01739996 0.007999956 0.21745 0.01739996 0.009499967 0.21745 0.01739996 0.01662975 0.21895 0.01739996 0.01027494 0.217242 0.01739996 0.01084226 0.216675 0.01739996 0.007224977 0.214558 0.01739996 0.00665766 0.215125 0.01739996 0.005724966 0.21895 0.01739996 0.006449997 0.2159 0.01739996 0.00665766 0.216675 0.01739996 0.007224977 0.217242 0.01739996 0.01027494 0.214558 0.01739996 0.009499967 0.21435 0.01739996 0.005724966 0.21285 0.01739996 0.007999956 0.21435 0.01739996 0.005724966 0.20613 0.01739996 0.003874957 0.09743857 0.01739996 0.003874957 0.109614 0.01739996 0.003599941 0.118707 0.01739996 0.003874957 0.21285 0.01739996 0.004805803 0.210175 0.01739996 0.003874957 0.21895 0.01739996 0.001549959 0.2064 0.01739996 0.003874957 0.210175 0.01739996 0.004805803 0.193226 0.01739996 0.003874957 0.22824 0.01739996 0.002374947 0.22824 0.01739996 0.002374947 0.221625 0.01739996 0.001437485 0.221625 0.01739996 0.001437485 0.220515 0.01739996 0.001324176 0.08608865 0.01739996 0.001082479 0.08152496 0.01739996 0.001249969 0.08089995 0.01739996 7.75e-4 0.08856135 0.01739996 0.001437485 0.08856135 0.01739996 0.002374947 0.08856135 0.01739996 0.001100957 0.100412 0.01739996 0.001297831 0.100077 0.01739996 0.001437485 0.09743857 0.01739996 0.002374947 0.09743857 0.01739996 0.003874957 0.08856135 0.01739996 0.004805803 0.07589995 0.01739996 0.003307163 0.119 0.01739996 0.002374947 0.109614 0.01739996 0.003199994 0.1194 0.01739996 0.001437485 0.193226 0.01739996 -0.001437485 0.193226 0.01739996 -3.44907e-4 0.2048889 0.01739996 -3.75e-4 0.1006 0.01739996 -0.004650473 0.229155 0.01739996 0.001437485 0.2325299 0.01739996 0.00454998 0.22878 0.01739996 -0.003307163 0.119 0.01739996 -0.003599941 0.118707 0.01739996 -0.003307163 0.1198 0.01739996 -0.001437485 0.109614 0.01739996 -0.004805803 0.09743857 0.01739996 -0.001437485 0.08856135 0.01739996 -0.004805803 0.08856135 0.01739996 -0.004692792 0.119 0.01739996 -0.004805803 0.109614 0.01739996 -0.004805803 0.1509 0.01739996 -0.004799962 0.1194 0.01739996 -0.004692792 0.182 0.01739996 -0.004805803 0.193226 0.01739996 -0.003999948 0.1832 0.01739996 -0.003599941 0.183093 0.01739996 -0.001437485 0.1509 0.01739996 0.001437485 0.1509 0.01739996 0.001437485 0.109614 0.01739996 0.004805803 0.08856135 0.01739996 -0.004399955 0.181707 0.01739996 -0.005133807 0.208508 0.01739996 -0.004891514 0.208229 0.01739996 -0.005724966 0.1509 0.01739996 -0.005724966 0.109614 0.01739996 -0.004805803 0.07589995 0.01739996 -0.004805803 0.215175 0.01739996 -0.005724966 0.21285 0.01739996 -0.004805803 0.221625 0.01739996 -0.005724966 0.21895 0.01739996 -0.004805803 0.21895 0.01739996 -0.007999956 0.21745 0.01739996 -0.007224977 0.217242 0.01739996 -0.009499967 0.21745 0.01739996 -0.006449997 0.2159 0.01739996 -0.00665766 0.216675 0.01739996 -0.01084226 0.215125 0.01739996 -0.01104998 0.2159 0.01739996 -0.01084226 0.216675 0.01739996 -0.01027494 0.217242 0.01739996 -0.00665766 0.215125 0.01739996 -0.007224977 0.214558 0.01739996 -0.007999956 0.21435 0.01739996 -0.009499967 0.21435 0.01739996 -0.01027494 0.214558 0.01739996 -0.01243984 0.21895 0.01739996 -0.01115 0.21895 0.01739996 -0.01115 0.21285 0.01739996 -0.01243984 0.21135 0.01739996 -0.01243984 0.22045 0.01739996 -0.01287978 0.22045 0.01739996 -0.01530379 0.21895 0.01739996 -0.01530379 0.21285 0.01739996 -0.01357924 0.211262 0.01739996 -0.0138489 0.2110199 0.01739996 -0.01662975 0.21285 0.01739996 0.003999948 0.1202 0.01189994 0.004399955 0.120093 0.01189994 0.004399955 0.120093 0.01739996 0.004799962 0.1194 0.01739996 0.004692792 0.119 0.01739996 0.004692792 0.119 0.01189994 0.004399955 0.118707 0.01739996 0.003999948 0.1186 0.01189994 0.003874957 0.118633 0.01189994 0.003307163 0.1198 0.01739996 0.003599941 0.120093 0.01189994 0.003999948 0.1202 0.01739996 0.007224977 0.214558 0.01189994 0.007999956 0.21435 0.01189994 -0.005724966 0.109614 0.01189994 0.003874957 0.109614 0.01189994 0.005999982 0.07589995 0.01189994 0.001437485 0.221625 0.01189994 -0.01392388 0.210321 0.01189994 -0.007670938 0.203271 0.01189994 -0.007396399 0.203398 0.01189994 -0.007973194 0.203263 0.01189994 -0.008620977 0.200099 0.01189994 -0.01177364 0.202285 0.01189994 -0.0116201 0.2064149 0.01189994 -0.0143916 0.205089 0.01189994 -0.01243984 0.21135 0.01189994 -0.0132277 0.21135 0.01189994 -0.01357924 0.211262 0.01189994 -0.0138489 0.2110199 0.01189994 -0.005724966 0.210175 0.01189994 -0.008183658 0.21135 0.01189994 -0.01115 0.21285 0.01189994 -0.004891514 0.208229 0.01189994 -0.004812002 0.207868 0.01189994 -0.005724966 0.20613 0.01189994 -0.004914522 0.207513 0.01189994 -0.01350384 0.221625 0.01189994 -0.01357269 0.221522 0.01189994 -0.01362979 0.221235 0.01189994 -0.01362979 0.2211999 0.01189994 -0.01352936 0.220825 0.01189994 -0.01325476 0.22055 0.01189994 -0.01243984 0.222736 0.01189994 -0.01115 0.224025 0.01189994 -0.01115 0.22824 0.01189994 -0.01117819 0.22824 0.01189994 -0.01115 0.228268 0.01189994 -0.006793677 0.2323009 0.01189994 -0.005724966 0.229404 0.01189994 -0.005621969 0.2294729 0.01189994 -0.005334973 0.22953 0.01189994 -0.005299985 0.22953 0.01189994 -0.004805803 0.22931 0.01189994 -0.001437485 0.221625 0.01189994 -0.004805803 0.2235479 0.01189994 -0.004805803 0.221625 0.01189994 -0.004892289 0.2234539 0.01189994 -0.007825374 0.220541 0.01189994 -0.007554113 0.2207919 0.01189994 -0.0068807 0.221625 0.01189994 -0.01243984 0.22045 0.01189994 -0.01115 0.22045 0.01189994 -0.010625 0.09191745 0.01189994 -0.00999999 0.09174996 0.01189994 -0.009374976 0.09191745 0.01189994 -0.008749961 0.09299999 0.01189994 -0.00891745 0.093625 0.01189994 -0.009374976 0.09408247 0.01189994 -0.01115 0.09743857 0.01189994 -0.00999999 0.09424996 0.01189994 -0.010625 0.09408247 0.01189994 -0.01108247 0.093625 0.01189994 -0.01115 0.09337317 0.01189994 -0.01243984 0.09695649 0.01189994 -0.01243984 0.08856135 0.01189994 -0.01124995 0.09299999 0.01189994 -0.01115 0.09262681 0.01189994 -0.01108247 0.09237498 0.01189994 0.01392388 0.210321 0.01189994 0.01662975 0.210175 0.01189994 0.01397335 0.21068 0.01189994 0.01662975 0.21285 0.01189994 0.0138489 0.2110199 0.01189994 0.008183658 0.21135 0.01189994 0.005724966 0.21285 0.01189994 0.007554113 0.211008 0.01189994 0.007194161 0.203622 0.01189994 0.008620977 0.200099 0.01189994 0.0116201 0.2064149 0.01189994 0.007059216 0.197374 0.01189994 0.007670938 0.203271 0.01189994 0.01662975 0.209637 0.01189994 0.01635575 0.208384 0.01189994 0.006747901 0.210175 0.01189994 0.005724966 0.209118 0.01189994 0.005012989 0.2294729 0.01189994 0.004805803 0.2293339 0.01189994 0.003874957 0.2325299 0.01189994 0.004769623 0.22931 0.01189994 0.01640146 0.222694 0.01189994 0.005299985 0.22953 0.01189994 0.004805803 0.2325299 0.01189994 0.005334973 0.22953 0.01189994 0.005724966 0.232514 0.01189994 0.005865275 0.22931 0.01189994 0.007766962 0.231651 0.01189994 0.007554113 0.2207919 0.01189994 0.01316678 0.220507 0.01189994 0.01341015 0.22067 0.01189994 0.01662975 0.2215459 0.01189994 0.007825374 0.220541 0.01189994 0.008183658 0.22045 0.01189994 0.01287978 0.22045 0.01189994 0.01357269 0.2209129 0.01189994 0.01362979 0.2211999 0.01189994 0.01357269 0.221522 0.01189994 0.01350384 0.221625 0.01189994 0.0068807 0.221625 0.01189994 0.006363928 0.222264 0.01189994 0.005724966 0.221625 0.01189994 0.004892289 0.2234539 0.01189994 0.00454998 0.22824 0.01189994 0.001437485 0.205907 0.01189994 0.001549959 0.2064 0.01189994 0.001549959 0.2078999 0.01189994 -0.001396477 0.205727 0.01189994 -0.001437485 0.193226 0.01189994 -0.001437485 0.205907 0.01189994 0.001437485 0.193226 0.01189994 3.44907e-4 0.2048889 0.01189994 9.66409e-4 0.205188 0.01189994 0.001396477 0.205727 0.01189994 -0.001549959 0.2078999 0.01189994 -0.001437485 0.20832 0.01189994 -0.001342296 0.208675 0.01189994 7.75e-4 0.209242 0.01189994 0 0.20945 0.01189994 -7.75e-4 0.209242 0.01189994 -0.004805803 0.21285 0.01189994 -0.004805803 0.210175 0.01189994 -0.003780126 0.21285 0.01189994 -0.001437485 0.210175 0.01189994 0 0.2208999 0.01189994 -0.004805803 0.21895 0.01189994 -0.003780126 0.21895 0.01189994 0.002499997 0.22023 0.01189994 0.002374947 0.221625 0.01189994 0.003874957 0.212945 0.01189994 0.004999995 0.2159 0.01189994 0.004805803 0.21895 0.01189994 0.004330098 0.2184 0.01189994 0.003874957 0.21895 0.01189994 0.003874957 0.218855 0.01189994 0.003780126 0.21895 0.01189994 0.002374947 0.210175 0.01189994 0.001437485 0.20832 0.01189994 0.001342296 0.208675 0.01189994 -0.002499997 0.21157 0.01189994 0.001437485 0.210175 0.01189994 0.001437485 0.22348 0.01189994 0.001549959 0.2239 0.01189994 0.001549959 0.2254 0.01189994 -0.001549959 0.2254 0.01189994 -0.001549959 0.2239 0.01189994 -0.001437485 0.22348 0.01189994 -0.004641056 0.223725 0.01189994 -0.001342296 0.223125 0.01189994 -7.75e-4 0.222558 0.01189994 0 0.22235 0.01189994 7.75e-4 0.222558 0.01189994 0.001342296 0.223125 0.01189994 0.001437485 0.225893 0.01189994 0.001396477 0.226073 0.01189994 -0.001437485 0.225893 0.01189994 -0.001396477 0.226073 0.01189994 -9.66409e-4 0.226612 0.01189994 9.66409e-4 0.226612 0.01189994 3.44907e-4 0.226911 0.01189994 -3.44907e-4 0.226911 0.01189994 -0.0121417 0.09743857 0.01189994 -0.01399999 0.08856135 0.01189994 -0.01115 0.08856135 0.01189994 0.01399999 0.08051878 0.01189994 0.009374976 0.09191745 0.01189994 0.00999999 0.09174996 0.01189994 0.010625 0.09191745 0.01189994 0.00999999 0.09424996 0.01189994 0.009374976 0.09408247 0.01189994 0.005724966 0.08856135 0.01189994 0.00891745 0.093625 0.01189994 0.008749961 0.09299999 0.01189994 0.00891745 0.09237498 0.01189994 0.01108247 0.093625 0.01189994 0.01124995 0.09299999 0.01189994 0.01108247 0.09237498 0.01189994 0.010625 0.09408247 0.01189994 0.005724966 0.09743857 0.01189994 0.01042288 0.100216 0.01189994 0.005724966 0.193226 0.01189994 0.007185637 0.193226 0.01189994 -0.01530379 0.221625 0.01189994 -0.01575118 0.223667 0.01189994 -0.01530379 0.21895 0.01189994 -0.01662975 0.2215459 0.01189994 -0.01530379 0.210175 0.01189994 -0.001100957 0.100412 0.01189994 -7.63216e-4 0.100603 0.01189994 0.0011096 0.09935116 0.01189994 0.00130099 0.09968888 0.01189994 0.001437485 0.09743857 0.01189994 0.001297831 0.100077 0.01189994 0.001100957 0.100412 0.01189994 7.63216e-4 0.100603 0.01189994 3.75e-4 0.1006 0.01189994 -7.75e-4 0.09743857 0.01189994 -0.0011096 0.09935116 0.01189994 -0.00130099 0.09968888 0.01189994 -0.001437485 0.09743857 0.01189994 -7.75e-4 0.08856135 0.01189994 -0.0011096 0.08664876 0.01189994 6.25e-4 0.07981747 0.01189994 0 0.07964998 0.01189994 -6.25e-4 0.07981747 0.01189994 -0.00130099 0.0863111 0.01189994 -0.001297831 0.08592277 0.01189994 -0.001437485 0.08856135 0.01189994 0.001437485 0.08856135 0.01189994 0.00126481 0.08641719 0.01189994 0.001324176 0.08608865 0.01189994 7.75e-4 0.09743857 0.01189994 7.75e-4 0.08856135 0.01189994 0.00106877 0.08668726 0.01189994 7.75e-4 0.08684569 0.01189994 0.001235187 0.08576697 0.01189994 -0.001082479 0.08152496 0.01189994 -0.001100957 0.08558815 0.01189994 -7.63216e-4 0.08539676 0.01189994 -6.25e-4 0.08198249 0.01189994 0 0.08214998 0.01189994 -3.75e-4 0.08539998 0.01189994 3.75e-4 0.08539998 0.01189994 6.25e-4 0.08198249 0.01189994 7.08435e-4 0.08538478 0.01189994 0.001015424 0.08551579 0.01189994 0.001437485 0.07589995 0.01189994 0.001082479 0.08027499 0.01189994 0.001249969 0.08089995 0.01189994 0.001082479 0.08152496 0.01189994 0.004399955 0.183093 0.01189994 0.003999948 0.1816 0.01189994 0.004399955 0.181707 0.01189994 0.004692792 0.182 0.01189994 0.004799962 0.1823999 0.01189994 0.004805803 0.193226 0.01189994 0.004692792 0.1827999 0.01189994 0.003999948 0.1832 0.01189994 0.003874957 0.183167 0.01189994 0.003599941 0.183093 0.01189994 0.002374947 0.193226 0.01189994 0.003307163 0.1827999 0.01189994 0.003199994 0.1823999 0.01189994 0.003599941 0.181707 0.01189994 0.003307163 0.182 0.01189994 0.003874957 0.1816329 0.01189994 0.004399955 0.118707 0.01189994 0.004799962 0.1194 0.01189994 0.004692792 0.1198 0.01189994 0.003874957 0.120167 0.01189994 0.003874957 0.1509 0.01189994 0.003307163 0.1198 0.01189994 0.002374947 0.109614 0.01189994 0.003199994 0.1194 0.01189994 -0.01530379 0.21285 0.01189994 -0.01027494 0.214558 0.01189994 -0.009499967 0.21435 0.01189994 -0.005724966 0.21285 0.01189994 -0.007999956 0.21435 0.01189994 -0.01084226 0.216675 0.01189994 -0.01243984 0.21285 0.01189994 -0.01243984 0.21895 0.01189994 -0.01104998 0.2159 0.01189994 -0.01084226 0.215125 0.01189994 -0.007224977 0.214558 0.01189994 -0.00665766 0.215125 0.01189994 -0.006449997 0.2159 0.01189994 -0.00665766 0.216675 0.01189994 -0.007224977 0.217242 0.01189994 -0.01115 0.21895 0.01189994 -0.007999956 0.21745 0.01189994 -0.009499967 0.21745 0.01189994 -0.01027494 0.217242 0.01189994 -0.004805803 0.215175 0.01189994 -0.005133807 0.208508 0.01189994 -0.005724966 0.221625 0.01189994 -0.005724966 0.21895 0.01189994 -0.004330098 0.2184 0.01189994 -0.004805803 0.07589995 0.01189994 -0.001249969 0.08089995 0.01189994 -0.001082479 0.08027499 0.01189994 -0.001297831 0.100077 0.01189994 -0.005724966 0.08856135 0.01189994 -0.004805803 0.08856135 0.01189994 -0.005724966 0.07589995 0.01189994 -0.003599941 0.120093 0.01189994 -0.004399955 0.120093 0.01189994 -0.004692792 0.119 0.01189994 -0.004805803 0.109614 0.01189994 -0.004399955 0.118707 0.01189994 -0.003999948 0.1186 0.01189994 -0.00891745 0.09237498 0.01189994 -0.004805803 0.09743857 0.01189994 -0.009975492 0.101703 0.01189994 -0.005724966 0.09743857 0.01189994 -0.003599941 0.118707 0.01189994 -0.003307163 0.119 0.01189994 -0.001437485 0.109614 0.01189994 -0.001437485 0.1509 0.01189994 -0.004692792 0.182 0.01189994 -0.003999948 0.1816 0.01189994 -0.003599941 0.181707 0.01189994 -0.007185637 0.193226 0.01189994 -0.005724966 0.193226 0.01189994 -0.005724966 0.1509 0.01189994 -0.004805803 0.193226 0.01189994 -0.004805803 0.1509 0.01189994 -0.003307163 0.1827999 0.01189994 -0.003999948 0.1832 0.01189994 -0.004399955 0.183093 0.01189994 -0.004799962 0.1823999 0.01189994 -0.003599941 0.183093 0.01189994 -0.001549959 0.2064 0.01189994 -9.66409e-4 0.205188 0.01189994 -3.44907e-4 0.2048889 0.01189994 0.001437485 0.1509 0.01189994 -3.75e-4 0.1006 0.01189994 0.002374947 0.1509 0.01189994 0.001437485 0.109614 0.01189994 0.002374947 0.09743857 0.01189994 0.003307163 0.119 0.01189994 0.003599941 0.118707 0.01189994 0.002374947 0.08856135 0.01189994 0.00454998 0.224084 0.01189994 0.003874957 0.22824 0.01189994 0.004607081 0.229067 0.01189994 0.002374947 0.2325299 0.01189994 0.002374947 0.22824 0.01189994 0.001437485 0.22824 0.01189994 -0.001437485 0.22824 0.01189994 0.003874957 0.09743857 0.01189994 0.004805803 0.09743857 0.01189994 0.003874957 0.08856135 0.01189994 0.003874957 0.07589995 0.01189994 0.004805803 0.08856135 0.01189994 0.004805803 0.07589995 0.01189994 0.003874957 0.193226 0.01189994 0.003874957 0.210175 0.01189994 0.004891514 0.208229 0.01189994 0.004812002 0.207868 0.01189994 0.004805803 0.1509 0.01189994 0.004805803 0.109614 0.01189994 0.005724966 0.1509 0.01189994 0.005724966 0.109614 0.01189994 0.005724966 0.210175 0.01189994 0.004805803 0.21285 0.01189994 0.004805803 0.210175 0.01189994 0.003874957 0.21285 0.01189994 0.002499997 0.21157 0.01189994 0.003780126 0.21285 0.01189994 0.004805803 0.221625 0.01189994 0.003874957 0.221625 0.01189994 0.009499967 0.21435 0.01189994 0.007224977 0.217242 0.01189994 0.00665766 0.216675 0.01189994 0.005724966 0.21895 0.01189994 0.006449997 0.2159 0.01189994 0.00665766 0.215125 0.01189994 0.01027494 0.214558 0.01189994 0.01084226 0.215125 0.01189994 0.01662975 0.21895 0.01189994 0.01104998 0.2159 0.01189994 0.01084226 0.216675 0.01189994 0.01027494 0.217242 0.01189994 0.009499967 0.21745 0.01189994 0.007999956 0.21745 0.01189994 -0.189105 0.09310209 0.01739996 -0.189105 0.09310209 0.01189994 -0.189441 0.09323871 0.01739996 -0.189673 0.0935167 0.01739996 -0.189748 0.09387117 0.01189994 -0.1889359 0.09310358 0.01189994 -0.186184 0.09312909 0.01189994 -0.186184 0.09312909 0.01739996 -0.18457 0.09314399 0.01739996 -0.18457 0.09314399 0.01189994 -0.183968 0.0933389 0.01189994 -0.179939 0.09558075 0.01739996 -0.179846 0.09529328 0.01189994 -0.179846 0.09529328 0.01739996 -0.179873 0.09499216 0.01189994 -0.180018 0.0947265 0.01739996 -0.180018 0.0947265 0.01189994 -0.1802549 0.0945394 0.01739996 -0.181376 0.0981068 0.01739996 -0.182777 0.09987807 0.01739996 -0.182777 0.09987807 0.01189994 -0.182169 0.09950017 0.01189994 -0.183964 0.0996012 0.01739996 -0.186515 0.09896177 0.01189994 -0.186515 0.09896177 0.01739996 -0.187126 0.09858769 0.01739996 -0.186868 0.09885245 0.01189994 -0.188609 0.09601879 0.01739996 -0.198759 0.09926909 0.01739996 -0.199115 0.1005949 0.01739996 -0.201129 0.108114 0.01739996 -0.199587 0.102357 0.01189994 -0.200681 0.110544 0.01189994 -0.200973 0.1105239 0.01739996 -0.200973 0.1105239 0.01189994 -0.201012 0.110505 0.01189994 -0.201236 0.110395 0.01189994 -0.1964899 0.100569 0.01739996 -0.197135 0.09945166 0.01189994 -0.194989 0.103854 0.01189994 -0.194907 0.103494 0.01189994 -0.195007 0.103138 0.01189994 -0.194989 0.103854 0.01739996 -0.195294 0.104992 0.01189994 -0.195294 0.104992 0.01739996 -0.195963 0.10749 0.01739996 -0.196337 0.108101 0.01739996 -0.196337 0.108101 0.01189994 -0.1960009 0.107612 0.01739996 -0.196072 0.107843 0.01189994 -0.200404 0.11045 0.01189994 -0.183098 0.117458 0.01739996 -0.181171 0.117313 0.01739996 -0.180679 0.116061 0.01189994 -0.180883 0.115402 0.01189994 -0.1816329 0.114103 0.01739996 -0.1816329 0.114103 0.01189994 -0.1822 0.113536 0.01189994 -0.1822 0.113536 0.01739996 -0.1829749 0.113328 0.01739996 -0.1843169 0.114103 0.01189994 -0.1843169 0.114103 0.01739996 -0.184525 0.1148779 0.01189994 -0.184525 0.1148779 0.01739996 -0.1843169 0.115653 0.01739996 -0.177254 0.108012 0.01189994 -0.177613 0.108101 0.01189994 -0.177613 0.108101 0.01739996 -0.177886 0.108351 0.01189994 -0.177886 0.108351 0.01739996 -0.1780059 0.1087 0.01189994 -0.178643 0.110931 0.01739996 -0.178643 0.110931 0.01189994 -0.178239 0.109517 0.01189994 -0.178239 0.109517 0.01739996 -0.1780059 0.1087 0.01739996 -0.178961 0.112046 0.01739996 -0.178943 0.112762 0.01189994 -0.178943 0.112762 0.01739996 -0.176421 0.117131 0.01739996 -0.176169 0.117391 0.01189994 -0.175824 0.117504 0.01189994 -0.175468 0.1174409 0.01189994 -0.172001 0.108836 0.01189994 -0.175098 0.117071 0.01739996 -0.172044 0.108537 0.01189994 -0.172202 0.108279 0.01189994 -0.172202 0.108279 0.01739996 -0.1724489 0.108104 0.01739996 -0.1724489 0.108104 0.01189994 -0.172745 0.108041 0.01189994 -0.172745 0.108041 0.01739996 -0.175651 0.108023 0.01189994 -0.185349 0.122496 0.01189994 -0.196223 0.119078 0.01189994 -0.196129 0.119355 0.01739996 -0.196204 0.118786 0.01189994 -0.196204 0.118786 0.01739996 -0.195854 0.11833 0.01739996 -0.195854 0.11833 0.01189994 -0.195387 0.11806 0.01739996 -0.189933 0.116269 0.01739996 -0.184375 0.121754 0.01739996 -0.184375 0.121754 0.01189994 -0.184475 0.122129 0.01739996 -0.186823 0.117312 0.01189994 -0.184475 0.121379 0.01739996 -0.186823 0.117312 0.01739996 -0.1792719 0.105292 0.01739996 -0.1792719 0.105292 0.01189994 -0.181389 0.103175 0.01739996 -0.1815969 0.10395 0.01189994 -0.181389 0.104725 0.01189994 -0.181389 0.104725 0.01739996 -0.180822 0.105292 0.01189994 -0.179523 0.101858 0.01739996 -0.19169 0.109012 0.01739996 -0.1919749 0.10795 0.01189994 -0.1919749 0.10795 0.01739996 -0.190005 0.1041499 0.01189994 -0.190005 0.1041499 0.01739996 -0.1894749 0.10362 0.01739996 -0.18875 0.103426 0.01189994 -0.186975 0.10295 0.01189994 -0.186975 0.10295 0.01739996 -0.186224 0.103151 0.01189994 -0.184475 0.10362 0.01189994 -0.184475 0.10362 0.01739996 -0.183697 0.104398 0.01739996 -0.18226 0.106887 0.01189994 -0.18226 0.106887 0.01739996 -0.182008 0.107825 0.01189994 -0.182008 0.107825 0.01739996 -0.182443 0.109699 0.01189994 -0.182478 0.109828 0.01189994 -0.182645 0.11045 0.01189994 -0.1852 0.112474 0.01189994 -0.1852 0.112474 0.01739996 -0.187597 0.112783 0.01189994 -0.187597 0.112783 0.01739996 -0.187726 0.112749 0.01739996 -0.1894749 0.11228 0.01189994 -0.189566 0.112189 0.01189994 -0.191305 0.11045 0.01189994 -0.192353 0.11195 0.01739996 -0.192561 0.111175 0.01189994 -0.194258 0.110495 0.01189994 -0.193903 0.1104 0.01739996 -0.193903 0.1104 0.01189994 -0.193128 0.113292 0.01189994 -0.195977 0.111358 0.01739996 -0.196348 0.111702 0.01739996 -0.196348 0.111702 0.01189994 -0.196735 0.112469 0.01739996 -0.196735 0.112469 0.01189994 -0.196683 0.113157 0.01739996 -0.1963379 0.113754 0.01739996 -0.1957679 0.114143 0.01739996 -0.1957679 0.114143 0.01189994 -0.195086 0.114246 0.01189994 -0.1949099 0.114191 0.01739996 -0.195086 0.114246 0.01739996 -0.195977 0.111358 0.01189994 -0.07831346 0.05923426 0.01739996 -0.07831346 0.05923426 0.01189994 -0.08157849 0.05913466 0.01739996 -0.06969636 0.05640506 0.01189994 -0.08309 0.05949079 0.01739996 -0.1264449 0.08279025 0.01189994 -0.1637459 0.102836 0.01739996 -0.1637459 0.102836 0.01189994 -0.167401 0.1048 0.01189994 -0.168255 0.105487 0.01189994 -0.168255 0.105487 0.01739996 -0.168806 0.106434 0.01189994 -0.169297 0.111339 0.01739996 -0.1704159 0.1150079 0.01739996 -0.172288 0.118357 0.01189994 -0.173702 0.119489 0.01739996 -0.173236 0.11922 0.01189994 -0.183549 0.1251749 0.01739996 -0.1813009 0.123877 0.01189994 -0.185826 0.125474 0.01189994 -0.184658 0.125551 0.01739996 -0.1836259 0.125201 0.01739996 -0.184658 0.125551 0.01189994 -0.192072 0.123801 0.01739996 -0.198554 0.121154 0.01739996 -0.196732 0.122552 0.01739996 -0.198554 0.121154 0.01189994 -0.2001889 0.118322 0.01189994 -0.200658 0.11751 0.01739996 -0.200658 0.11751 0.01189994 -0.2037799 0.112103 0.01189994 -0.2042 0.111376 0.01739996 -0.204226 0.111299 0.01739996 -0.204226 0.111299 0.01189994 -0.204576 0.110267 0.01739996 -0.204499 0.109099 0.01189994 -0.203261 0.104478 0.01189994 -0.203251 0.104439 0.01739996 -0.202789 0.102716 0.01189994 -0.201577 0.09819257 0.01739996 -0.20024 0.09642428 0.01189994 -0.06273126 0.04314619 0.01189994 -0.06332838 0.04211199 0.01739996 -0.06454378 0.04000675 0.01189994 -0.06645005 0.03670507 0.01189994 -0.06645005 0.03670507 0.01739996 -0.0685938 0.032992 0.01739996 -0.07673126 0.028135 0.01739996 -0.07673126 0.028135 0.01189994 -0.07517117 0.0290358 0.01739996 -0.07517117 0.0290358 0.01189994 -0.07388126 0.02978044 0.01739996 -0.07388126 0.02978044 0.01189994 -0.08369636 0.03215634 0.01189994 -0.08369636 0.03215634 0.01739996 -0.0887832 0.03509318 0.01189994 -0.09134727 0.03986448 0.01189994 -0.09045505 0.03820425 0.01739996 -0.0930655 0.04221266 0.01739996 -0.170931 0.0903899 0.01189994 -0.170931 0.0903899 0.01739996 -0.1744599 0.0925734 0.01739996 -0.177601 0.09258335 0.01189994 -0.1744599 0.0925734 0.01189994 -0.18107 0.09094595 0.01189994 -0.18107 0.09094595 0.01739996 -0.184808 0.09008085 0.01189994 -0.184808 0.09008085 0.01739996 -0.189866 0.09041649 0.01189994 -0.189866 0.09041649 0.01739996 -0.1903319 0.0906856 0.01189994 -0.197931 0.0950731 0.01739996 -0.197931 0.0950731 0.01189994 -0.200179 0.09637099 0.01189994 -0.08625769 0.04890596 0.01189994 -0.08477181 0.04804807 0.01739996 -0.07708388 0.04360949 0.01189994 -0.07559806 0.04275166 0.01189994 -0.0755949 0.04236346 0.01189994 -0.0755949 0.04236346 0.01739996 -0.07539808 0.04202878 0.01739996 -0.07433736 0.04203748 0.01739996 -0.07414609 0.04237514 0.01189994 -0.08548265 0.05024826 0.01739996 -0.0763089 0.04495185 0.01739996 -0.08399677 0.04939049 0.01189994 -0.156363 0.09535688 0.01189994 -0.156363 0.09535688 0.01739996 -0.155963 0.09546411 0.01189994 -0.1555629 0.09535688 0.01189994 -0.1555629 0.09535688 0.01739996 -0.15527 0.0950641 0.01189994 -0.15527 0.0950641 0.01739996 -0.15527 0.09426409 0.01189994 -0.15527 0.09426409 0.01739996 -0.155362 0.09417259 0.01739996 -0.1555629 0.09397131 0.01189994 -0.155963 0.09386408 0.01189994 -0.156363 0.09397131 0.01189994 -0.156363 0.09397131 0.01739996 -0.156656 0.09426409 0.01739996 -0.156763 0.09466409 0.01189994 -0.156656 0.0950641 0.01739996 -0.156689 0.09493905 0.01739996 -0.160656 0.08813589 0.01739996 -0.160363 0.08842867 0.01739996 -0.160363 0.08842867 0.01189994 -0.159963 0.0885359 0.01739996 -0.159563 0.08842867 0.01189994 -0.1592699 0.08813589 0.01739996 -0.1592699 0.08813589 0.01189994 -0.1591629 0.08773589 0.01739996 -0.159563 0.0870431 0.01739996 -0.159963 0.08693587 0.01739996 -0.159963 0.08693587 0.01189994 -0.160363 0.0870431 0.01189994 -0.160363 0.0870431 0.01739996 -0.160656 0.08733588 0.01189994 -0.160656 0.08733588 0.01739996 -0.160763 0.08773589 0.01189994 -0.106096 0.05663585 0.01739996 -0.105403 0.05703586 0.01739996 -0.1050029 0.05692869 0.01189994 -0.1050029 0.05692869 0.01739996 -0.1047109 0.05663585 0.01189994 -0.104603 0.05623584 0.01189994 -0.104603 0.05623584 0.01739996 -0.1047109 0.0558359 0.01189994 -0.1050029 0.05554306 0.01189994 -0.105403 0.05543589 0.01189994 -0.105803 0.05554306 0.01739996 -0.106203 0.05623584 0.01739996 -0.106203 0.05623584 0.01189994 -0.0795589 0.03932267 0.01739996 -0.201059 0.09714275 0.01739996 -0.180047 0.1055 0.01739996 -0.18907 0.11577 0.01739996 -0.188572 0.1166329 0.01739996 -0.200404 0.11045 0.01739996 -0.189254 0.09490168 0.01739996 -0.189648 0.0942195 0.01739996 -0.1889359 0.09310358 0.01739996 -0.189669 0.091834 0.01739996 -0.182022 0.09072577 0.01739996 -0.183968 0.0933389 0.01739996 -0.180384 0.09126991 0.01739996 -0.177601 0.09258335 0.01739996 -0.179873 0.09499216 0.01739996 -0.175482 0.09297007 0.01739996 -0.176577 0.09297358 0.01739996 -0.182169 0.09950017 0.01739996 -0.170201 0.09165489 0.01739996 -0.184879 0.10013 0.01739996 -0.186868 0.09885245 0.01739996 -0.1983799 0.112875 0.01739996 -0.201429 0.110175 0.01739996 -0.201236 0.110395 0.01739996 -0.2037799 0.112103 0.01739996 -0.202095 0.11502 0.01739996 -0.201012 0.110505 0.01739996 -0.203261 0.104478 0.01739996 -0.2014459 0.110145 0.01739996 -0.2015399 0.109868 0.01739996 -0.201532 0.109744 0.01739996 -0.201521 0.109576 0.01739996 -0.204499 0.109099 0.01739996 -0.2032369 0.104464 0.01739996 -0.202789 0.102716 0.01739996 -0.199587 0.102357 0.01739996 -0.19863 0.09900665 0.01739996 -0.19841 0.09881365 0.01739996 -0.197355 0.09907066 0.01739996 -0.197548 0.09885066 0.01739996 -0.197811 0.09872126 0.01739996 -0.198103 0.09870219 0.01739996 -0.1983799 0.09879618 0.01739996 -0.195658 0.106353 0.01739996 -0.195007 0.103138 0.01739996 -0.194907 0.103494 0.01739996 -0.192652 0.1095679 0.01739996 -0.08227139 0.03462445 0.01739996 -0.08679038 0.03783965 0.01739996 -0.08995926 0.03906309 0.01739996 -0.08491539 0.03892225 0.01739996 -0.08616536 0.03675717 0.01739996 -0.08491539 0.03675717 0.01739996 -0.08554035 0.03658968 0.01739996 -0.08579218 0.03665715 0.01739996 -0.08291637 0.03350734 0.01739996 -0.08662289 0.03721469 0.01739996 -0.08643859 0.03703039 0.01739996 -0.09018677 0.037705 0.01739996 -0.164476 0.101571 0.01739996 -0.168806 0.106434 0.01739996 -0.172044 0.108537 0.01739996 -0.172001 0.108836 0.01739996 -0.16898 0.107515 0.01739996 -0.17295 0.1132709 0.01739996 -0.175468 0.1174409 0.01739996 -0.175824 0.117504 0.01739996 -0.172288 0.118357 0.01739996 -0.173236 0.11922 0.01739996 -0.175181 0.117219 0.01739996 -0.1790429 0.112406 0.01739996 -0.176169 0.117391 0.01739996 -0.177254 0.108012 0.01739996 -0.1870819 0.117048 0.01739996 -0.18475 0.122404 0.01739996 -0.18478 0.122421 0.01739996 -0.1813009 0.123877 0.01739996 -0.198501 0.121215 0.01739996 -0.195807 0.11966 0.01739996 -0.197782 0.122034 0.01739996 -0.195656 0.119735 0.01739996 -0.185057 0.122515 0.01739996 -0.185181 0.122507 0.01739996 -0.185826 0.125474 0.01739996 -0.185349 0.122496 0.01739996 -0.194194 0.120126 0.01739996 -0.196223 0.119078 0.01739996 -0.196111 0.119385 0.01739996 -0.195918 0.119605 0.01739996 -0.196206 0.118829 0.01739996 -0.198974 0.120427 0.01739996 -0.199439 0.119621 0.01739996 -0.18953 0.114974 0.01739996 -0.191071 0.115964 0.01739996 -0.191195 0.115936 0.01739996 -0.191431 0.115882 0.01739996 -0.191787 0.1159819 0.01739996 -0.177267 0.102743 0.01739996 -0.168057 0.0953679 0.01739996 -0.17904 0.101709 0.01739996 -0.180829 0.1071439 0.01739996 -0.179692 0.105405 0.01739996 -0.177973 0.104542 0.01739996 -0.180822 0.102608 0.01739996 -0.181129 0.102915 0.01739996 -0.1815969 0.10395 0.01739996 -0.182736 0.103843 0.01739996 -0.181298 0.106332 0.01739996 -0.180822 0.105292 0.01739996 -0.182443 0.109699 0.01739996 -0.180079 0.108443 0.01739996 -0.1894749 0.11228 0.01739996 -0.1876789 0.1128309 0.01739996 -0.187213 0.113637 0.01739996 -0.186975 0.11295 0.01739996 -0.186754 0.114433 0.01739996 -0.184475 0.11228 0.01739996 -0.183944 0.11175 0.01739996 -0.181931 0.110587 0.01739996 -0.182645 0.11045 0.01739996 -0.182478 0.109828 0.01739996 -0.191506 0.106201 0.01739996 -0.1943359 0.106651 0.01739996 -0.192019 0.105313 0.01739996 -0.191305 0.10545 0.01739996 -0.192479 0.104517 0.01739996 -0.181975 0.10795 0.01739996 -0.182645 0.10545 0.01739996 -0.1844199 0.100926 0.01739996 -0.186224 0.103151 0.01739996 -0.186736 0.102263 0.01739996 -0.192561 0.111175 0.01739996 -0.193128 0.110608 0.01739996 -0.192821 0.112985 0.01739996 -0.192561 0.112725 0.01739996 -0.194258 0.110495 0.01739996 -0.194678 0.110608 0.01739996 -0.196072 0.107843 0.01739996 -0.199937 0.11018 0.01739996 -0.196483 0.111827 0.01739996 -0.196943 0.115365 0.01739996 -0.194427 0.114042 0.01739996 -0.1907449 0.112869 0.01739996 -0.193128 0.113292 0.01739996 -0.198685 0.09911775 0.01739996 -0.201741 0.09880369 0.01739996 -0.09206557 0.0597648 0.01739996 -0.1264449 0.08279025 0.01739996 -0.167401 0.1048 0.01739996 -0.0815218 0.05367726 0.01739996 -0.09006088 0.06323695 0.01739996 -0.0749154 0.05407768 0.01739996 -0.07554036 0.05391025 0.01739996 -0.0766229 0.05453526 0.01739996 -0.0766229 0.05578529 0.01739996 -0.0747832 0.05934184 0.01739996 -0.07554036 0.05641025 0.01739996 -0.06969636 0.05640506 0.01739996 -0.0749154 0.05624276 0.01739996 -0.07445776 0.05578529 0.01739996 -0.07429039 0.05516028 0.01739996 -0.07445776 0.05453526 0.01739996 -0.07383388 0.04923868 0.01739996 -0.06273126 0.04314619 0.01739996 -0.06273126 0.05238378 0.01739996 -0.08445775 0.03846466 0.01739996 -0.08429038 0.03783965 0.01739996 -0.08724677 0.04376125 0.01739996 -0.09200137 0.04108166 0.01739996 -0.09134727 0.03986448 0.01739996 -0.134921 0.06810969 0.01739996 -0.09979528 0.04637658 0.01739996 -0.1335459 0.07049196 0.01739996 -0.09779059 0.04984879 0.01739996 -0.186589 0.09005606 0.01739996 -0.188644 0.09002751 0.01739996 -0.08659535 0.04871457 0.01739996 -0.08548575 0.05063647 0.01739996 -0.08568269 0.05097115 0.01739996 -0.08602041 0.05116248 0.01739996 -0.08698368 0.04871779 0.01739996 -0.0873183 0.04891455 0.01739996 -0.08750969 0.04925239 0.01739996 -0.09564685 0.05356186 0.01739996 -0.08750647 0.04964059 0.01739996 -0.08693468 0.05062478 0.01739996 -0.08674329 0.05096244 0.01739996 -0.08640867 0.05115938 0.01739996 -0.07114398 0.03982496 0.01739996 -0.08625769 0.04890596 0.01739996 -0.07708388 0.04360949 0.01739996 -0.07559806 0.04275166 0.01739996 -0.0700615 0.03919994 0.01739996 -0.0750603 0.04183745 0.01739996 -0.0746721 0.04184055 0.01739996 -0.07068645 0.03936749 0.01739996 -0.06943649 0.04153245 0.01739996 -0.06501257 0.03919488 0.01739996 -0.0689789 0.04107499 0.01739996 -0.06881147 0.04044997 0.01739996 -0.0689789 0.03982496 0.01739996 -0.06943649 0.03936749 0.01739996 -0.07414609 0.04237514 0.01739996 -0.07131147 0.04044997 0.01739996 -0.07365876 0.04395318 0.01739996 -0.07355105 0.04363727 0.01739996 -0.07068645 0.04153245 0.01739996 -0.07359117 0.04330587 0.01739996 -0.07114398 0.04107499 0.01739996 -0.07377105 0.04302477 0.01739996 -0.07389289 0.04419118 0.01739996 -0.07482308 0.04409396 0.01739996 -0.074539 0.04426926 0.01739996 -0.074207 0.04430395 0.01739996 -0.1649349 0.100775 0.01739996 -0.155963 0.09546411 0.01739996 -0.156763 0.09466409 0.01739996 -0.155163 0.09466409 0.01739996 -0.129496 0.07750678 0.01739996 -0.1555629 0.09397131 0.01739996 -0.155963 0.09386408 0.01739996 -0.1776019 0.104198 0.01739996 -0.101803 0.06385689 0.01739996 -0.1014029 0.06396406 0.01739996 -0.100603 0.06316405 0.01739996 -0.100711 0.0627641 0.01739996 -0.100802 0.06267255 0.01739996 -0.1014029 0.0623641 0.01739996 -0.102203 0.06316405 0.01739996 -0.128746 0.0788058 0.01739996 -0.12828 0.07961195 0.01739996 -0.102096 0.06356406 0.01739996 -0.18375 0.113536 0.01739996 -0.176019 0.120827 0.01739996 -0.181768 0.117658 0.01739996 -0.180782 0.116744 0.01739996 -0.180679 0.116061 0.01739996 -0.181471 0.111383 0.01739996 -0.180883 0.115402 0.01739996 -0.183567 0.116952 0.01739996 -0.182456 0.1177099 0.01739996 -0.175651 0.108023 0.01739996 -0.127821 0.08040797 0.01739996 -0.09252518 0.05896878 0.01739996 -0.08198136 0.0528813 0.01739996 -0.09299057 0.05816256 0.01739996 -0.1823959 0.109781 0.01739996 -0.179614 0.109249 0.01739996 -0.179154 0.110045 0.01739996 -0.189995 0.114168 0.01739996 -0.187435 0.116938 0.01739996 -0.166151 0.0986697 0.01739996 -0.165401 0.09996867 0.01739996 -0.196474 0.116177 0.01739996 -0.189566 0.112189 0.01739996 -0.190253 0.111502 0.01739996 -0.191214 0.112057 0.01739996 -0.191305 0.11045 0.01739996 -0.0700615 0.04169994 0.01739996 -0.07597768 0.04552555 0.01739996 -0.06454378 0.04000675 0.01739996 -0.08399677 0.04939049 0.01739996 -0.07550889 0.04633748 0.01739996 -0.08366549 0.04996418 0.01739996 -0.06379377 0.04130578 0.01739996 -0.101803 0.06247127 0.01739996 -0.09374058 0.0568636 0.01739996 -0.16662 0.09785777 0.01739996 -0.200681 0.110544 0.01739996 -0.2001889 0.118322 0.01739996 -0.195724 0.117476 0.01739996 -0.196074 0.118523 0.01739996 -0.08510297 0.04747438 0.01739996 -0.07741516 0.0430358 0.01739996 -0.131402 0.0742051 0.01739996 -0.105803 0.05692869 0.01739996 -0.09420937 0.05605167 0.01739996 -0.08730965 0.04997515 0.01739996 -0.1047109 0.05663585 0.01739996 -0.1047109 0.0558359 0.01739996 -0.1050029 0.05554306 0.01739996 -0.105403 0.05543589 0.01739996 -0.133086 0.07128798 0.01739996 -0.106096 0.0558359 0.01739996 -0.159563 0.08842867 0.01739996 -0.1592699 0.08733588 0.01739996 -0.160763 0.08773589 0.01739996 -0.1299639 0.0766949 0.01739996 -0.08244675 0.05207508 0.01739996 -0.08319675 0.05077606 0.01739996 -0.07475888 0.04763656 0.01739996 -0.07429349 0.04844266 0.01739996 -0.06286877 0.04290795 0.01739996 -0.18314 0.09980785 0.01739996 -0.182425 0.09976649 0.01739996 -0.169741 0.09245085 0.01739996 -0.0973311 0.05064475 0.01739996 -0.08678716 0.04455727 0.01739996 -0.07909935 0.04011869 0.01739996 -0.06813418 0.03378796 0.01739996 -0.18875 0.103426 0.01739996 -0.187196 0.101467 0.01739996 -0.185391 0.09924358 0.01739996 -0.194795 0.105855 0.01739996 -0.192317 0.101797 0.01739996 -0.1902 0.102364 0.01739996 -0.190975 0.102572 0.01739996 -0.1917499 0.102364 0.01739996 -0.191494 0.09819006 0.01739996 -0.193067 0.100498 0.01739996 -0.193271 0.09983855 0.01739996 -0.192182 0.09824156 0.01739996 -0.192779 0.09858649 0.01739996 -0.193168 0.09915649 0.01739996 -0.189633 0.101797 0.01739996 -0.189425 0.101022 0.01739996 -0.189633 0.100247 0.01739996 -0.190383 0.09894776 0.01739996 -0.190852 0.09844207 0.01739996 -0.195191 0.09981876 0.01739996 -0.189909 0.09676879 0.01739996 -0.190553 0.09565168 0.01739996 -0.197135 0.09945166 0.01739996 -0.195836 0.09870165 0.01739996 -0.197268 0.0962215 0.01739996 -0.189748 0.09387117 0.01739996 -0.191985 0.09317147 0.01739996 -0.20024 0.09642428 0.01739996 -0.199585 0.09755897 0.01739996 -0.200179 0.09637099 0.01739996 -0.1926479 0.09202307 0.01739996 -0.1903319 0.0906856 0.01739996 -0.101803 0.06385689 0.01189994 -0.101003 0.06385689 0.01189994 -0.101003 0.06385689 0.01739996 -0.100711 0.06356406 0.01739996 -0.100711 0.06356406 0.01189994 -0.101003 0.06247127 0.01739996 -0.100802 0.06267255 0.01189994 -0.101003 0.06247127 0.01189994 -0.1014029 0.0623641 0.01189994 -0.102096 0.0627641 0.01189994 -0.102096 0.0627641 0.01739996 -0.1021299 0.06343907 0.01739996 -0.1335459 0.07049196 0.01189994 -0.09299057 0.05816256 0.01189994 -0.06286877 0.04290795 0.01189994 -0.192561 0.112725 0.01189994 -0.187726 0.112749 0.01189994 -0.189933 0.116269 0.01189994 -0.1802549 0.0945394 0.01189994 -0.176577 0.09297358 0.01189994 -0.175482 0.09297007 0.01189994 -0.180384 0.09126991 0.01189994 -0.182022 0.09072577 0.01189994 -0.189673 0.0935167 0.01189994 -0.189441 0.09323871 0.01189994 -0.189648 0.0942195 0.01189994 -0.190553 0.09565168 0.01189994 -0.191985 0.09317147 0.01189994 -0.183964 0.0996012 0.01189994 -0.184879 0.10013 0.01189994 -0.185391 0.09924358 0.01189994 -0.189909 0.09676879 0.01189994 -0.187126 0.09858769 0.01189994 -0.188609 0.09601879 0.01189994 -0.189254 0.09490168 0.01189994 -0.170201 0.09165489 0.01189994 -0.179939 0.09558075 0.01189994 -0.181376 0.0981068 0.01189994 -0.182425 0.09976649 0.01189994 -0.198685 0.09911775 0.01189994 -0.19863 0.09900665 0.01189994 -0.1983799 0.09879618 0.01189994 -0.19841 0.09881365 0.01189994 -0.198103 0.09870219 0.01189994 -0.197811 0.09872126 0.01189994 -0.197548 0.09885066 0.01189994 -0.197355 0.09907066 0.01189994 -0.199115 0.1005949 0.01189994 -0.203251 0.104439 0.01189994 -0.2032369 0.104464 0.01189994 -0.201129 0.108114 0.01189994 -0.201521 0.109576 0.01189994 -0.204576 0.110267 0.01189994 -0.201532 0.109744 0.01189994 -0.201429 0.110175 0.01189994 -0.2042 0.111376 0.01189994 -0.2014459 0.110145 0.01189994 -0.2015399 0.109868 0.01189994 -0.1983799 0.112875 0.01189994 -0.192652 0.1095679 0.01189994 -0.1960009 0.107612 0.01189994 -0.1943359 0.106651 0.01189994 -0.195963 0.10749 0.01189994 -0.195658 0.106353 0.01189994 -0.194795 0.105855 0.01189994 -0.1964899 0.100569 0.01189994 -0.08491539 0.03892225 0.01189994 -0.08554035 0.03908967 0.01189994 -0.08616536 0.03892225 0.01189994 -0.08662289 0.03846466 0.01189994 -0.08679038 0.03783965 0.01189994 -0.0795589 0.03932267 0.01189994 -0.08445775 0.03721469 0.01189994 -0.08429038 0.03783965 0.01189994 -0.08445775 0.03846466 0.01189994 -0.08662289 0.03721469 0.01189994 -0.08995926 0.03906309 0.01189994 -0.08643859 0.03703039 0.01189994 -0.08616536 0.03675717 0.01189994 -0.08579218 0.03665715 0.01189994 -0.08227139 0.03462445 0.01189994 -0.08554035 0.03658968 0.01189994 -0.08491539 0.03675717 0.01189994 -0.175181 0.117219 0.01189994 -0.176421 0.117131 0.01189994 -0.181471 0.111383 0.01189994 -0.1790429 0.112406 0.01189994 -0.169297 0.111339 0.01189994 -0.16898 0.107515 0.01189994 -0.173702 0.119489 0.01189994 -0.175098 0.117071 0.01189994 -0.17295 0.1132709 0.01189994 -0.1704159 0.1150079 0.01189994 -0.196206 0.118829 0.01189994 -0.199439 0.119621 0.01189994 -0.196129 0.119355 0.01189994 -0.198974 0.120427 0.01189994 -0.196111 0.119385 0.01189994 -0.195918 0.119605 0.01189994 -0.195807 0.11966 0.01189994 -0.198501 0.121215 0.01189994 -0.197782 0.122034 0.01189994 -0.196732 0.122552 0.01189994 -0.195656 0.119735 0.01189994 -0.194194 0.120126 0.01189994 -0.192072 0.123801 0.01189994 -0.187435 0.116938 0.01189994 -0.1870819 0.117048 0.01189994 -0.186754 0.114433 0.01189994 -0.184475 0.121379 0.01189994 -0.184475 0.122129 0.01189994 -0.183549 0.1251749 0.01189994 -0.18475 0.122404 0.01189994 -0.18478 0.122421 0.01189994 -0.1836259 0.125201 0.01189994 -0.185057 0.122515 0.01189994 -0.185181 0.122507 0.01189994 -0.18907 0.11577 0.01189994 -0.191071 0.115964 0.01189994 -0.191195 0.115936 0.01189994 -0.191431 0.115882 0.01189994 -0.189995 0.114168 0.01189994 -0.191787 0.1159819 0.01189994 -0.196074 0.118523 0.01189994 -0.195387 0.11806 0.01189994 -0.180829 0.1071439 0.01189994 -0.177973 0.104542 0.01189994 -0.168057 0.0953679 0.01189994 -0.1776109 0.102146 0.01189994 -0.181129 0.102915 0.01189994 -0.181389 0.103175 0.01189994 -0.179692 0.105405 0.01189994 -0.180047 0.1055 0.01189994 -0.182645 0.10545 0.01189994 -0.186736 0.102263 0.01189994 -0.182736 0.103843 0.01189994 -0.183697 0.104398 0.01189994 -0.190253 0.111502 0.01189994 -0.191214 0.112057 0.01189994 -0.19169 0.109012 0.01189994 -0.191506 0.106201 0.01189994 -0.191305 0.10545 0.01189994 -0.1907449 0.112869 0.01189994 -0.183944 0.11175 0.01189994 -0.186975 0.11295 0.01189994 -0.181931 0.110587 0.01189994 -0.180079 0.108443 0.01189994 -0.192821 0.112985 0.01189994 -0.194678 0.110608 0.01189994 -0.193128 0.110608 0.01189994 -0.192353 0.11195 0.01189994 -0.199937 0.11018 0.01189994 -0.196483 0.111827 0.01189994 -0.1949099 0.114191 0.01189994 -0.196943 0.115365 0.01189994 -0.1963379 0.113754 0.01189994 -0.196683 0.113157 0.01189994 -0.09979528 0.04637658 0.01189994 -0.134921 0.06810969 0.01189994 -0.09045505 0.03820425 0.01189994 -0.09200137 0.04108166 0.01189994 -0.09018677 0.037705 0.01189994 -0.08291637 0.03350734 0.01189994 -0.0685938 0.032992 0.01189994 -0.07383388 0.04923868 0.01189994 -0.07554036 0.05391025 0.01189994 -0.06273126 0.05238378 0.01189994 -0.0749154 0.05407768 0.01189994 -0.07554036 0.05641025 0.01189994 -0.07616537 0.05624276 0.01189994 -0.0766229 0.05578529 0.01189994 -0.07679039 0.05516028 0.01189994 -0.0766229 0.05453526 0.01189994 -0.07616537 0.05407768 0.01189994 -0.07445776 0.05453526 0.01189994 -0.07429039 0.05516028 0.01189994 -0.07445776 0.05578529 0.01189994 -0.0747832 0.05934184 0.01189994 -0.0749154 0.05624276 0.01189994 -0.0815218 0.05367726 0.01189994 -0.08157849 0.05913466 0.01189994 -0.08309 0.05949079 0.01189994 -0.164476 0.101571 0.01189994 -0.127821 0.08040797 0.01189994 -0.09006088 0.06323695 0.01189994 -0.198759 0.09926909 0.01189994 -0.199585 0.09755897 0.01189994 -0.201741 0.09880369 0.01189994 -0.201577 0.09819257 0.01189994 -0.201059 0.09714275 0.01189994 -0.197268 0.0962215 0.01189994 -0.189669 0.091834 0.01189994 -0.186589 0.09005606 0.01189994 -0.08730965 0.04997515 0.01189994 -0.08750647 0.04964059 0.01189994 -0.09564685 0.05356186 0.01189994 -0.08674329 0.05096244 0.01189994 -0.08693468 0.05062478 0.01189994 -0.08548575 0.05063647 0.01189994 -0.08568269 0.05097115 0.01189994 -0.08602041 0.05116248 0.01189994 -0.08640867 0.05115938 0.01189994 -0.08750969 0.04925239 0.01189994 -0.0873183 0.04891455 0.01189994 -0.08510297 0.04747438 0.01189994 -0.08698368 0.04871779 0.01189994 -0.08659535 0.04871457 0.01189994 -0.07539808 0.04202878 0.01189994 -0.07068645 0.03936749 0.01189994 -0.07114398 0.03982496 0.01189994 -0.07131147 0.04044997 0.01189994 -0.0750603 0.04183745 0.01189994 -0.0746721 0.04184055 0.01189994 -0.07114398 0.04107499 0.01189994 -0.07068645 0.04153245 0.01189994 -0.0689789 0.04107499 0.01189994 -0.0700615 0.03919994 0.01189994 -0.06943649 0.03936749 0.01189994 -0.06501257 0.03919488 0.01189994 -0.0689789 0.03982496 0.01189994 -0.06881147 0.04044997 0.01189994 -0.08548265 0.05024826 0.01189994 -0.07597768 0.04552555 0.01189994 -0.0763089 0.04495185 0.01189994 -0.074539 0.04426926 0.01189994 -0.07482308 0.04409396 0.01189994 -0.07365876 0.04395318 0.01189994 -0.07389289 0.04419118 0.01189994 -0.074207 0.04430395 0.01189994 -0.0700615 0.04169994 0.01189994 -0.07433736 0.04203748 0.01189994 -0.07377105 0.04302477 0.01189994 -0.07359117 0.04330587 0.01189994 -0.07355105 0.04363727 0.01189994 -0.06943649 0.04153245 0.01189994 -0.08477181 0.04804807 0.01189994 -0.07741516 0.0430358 0.01189994 -0.155362 0.09417259 0.01189994 -0.155163 0.09466409 0.01189994 -0.156689 0.09493905 0.01189994 -0.156656 0.09426409 0.01189994 -0.100711 0.0627641 0.01189994 -0.100603 0.06316405 0.01189994 -0.1014029 0.06396406 0.01189994 -0.12828 0.07961195 0.01189994 -0.128746 0.0788058 0.01189994 -0.102096 0.06356406 0.01189994 -0.1021299 0.06343907 0.01189994 -0.102203 0.06316405 0.01189994 -0.101803 0.06247127 0.01189994 -0.188644 0.09002751 0.01189994 -0.192779 0.09858649 0.01189994 -0.193168 0.09915649 0.01189994 -0.195191 0.09981876 0.01189994 -0.191494 0.09819006 0.01189994 -0.192479 0.104517 0.01189994 -0.1902 0.102364 0.01189994 -0.189633 0.101797 0.01189994 -0.1926479 0.09202307 0.01189994 -0.195836 0.09870165 0.01189994 -0.192182 0.09824156 0.01189994 -0.190975 0.102572 0.01189994 -0.1917499 0.102364 0.01189994 -0.192317 0.101797 0.01189994 -0.193067 0.100498 0.01189994 -0.193271 0.09983855 0.01189994 -0.190852 0.09844207 0.01189994 -0.190383 0.09894776 0.01189994 -0.189633 0.100247 0.01189994 -0.187196 0.101467 0.01189994 -0.189425 0.101022 0.01189994 -0.08678716 0.04455727 0.01189994 -0.1894749 0.10362 0.01189994 -0.1844199 0.100926 0.01189994 -0.18314 0.09980785 0.01189994 -0.192019 0.105313 0.01189994 -0.106096 0.0558359 0.01189994 -0.105803 0.05692869 0.01189994 -0.133086 0.07128798 0.01189994 -0.106096 0.05663585 0.01189994 -0.105403 0.05703586 0.01189994 -0.0930655 0.04221266 0.01189994 -0.09779059 0.04984879 0.01189994 -0.08724677 0.04376125 0.01189994 -0.0973311 0.05064475 0.01189994 -0.105803 0.05554306 0.01189994 -0.07909935 0.04011869 0.01189994 -0.06813418 0.03378796 0.01189994 -0.160656 0.08813589 0.01189994 -0.159563 0.0870431 0.01189994 -0.1592699 0.08733588 0.01189994 -0.1591629 0.08773589 0.01189994 -0.159963 0.0885359 0.01189994 -0.169741 0.09245085 0.01189994 -0.179523 0.101858 0.01189994 -0.180822 0.102608 0.01189994 -0.131402 0.0742051 0.01189994 -0.1299639 0.0766949 0.01189994 -0.09420937 0.05605167 0.01189994 -0.1776019 0.104198 0.01189994 -0.166151 0.0986697 0.01189994 -0.16662 0.09785777 0.01189994 -0.129496 0.07750678 0.01189994 -0.08366549 0.04996418 0.01189994 -0.09374058 0.0568636 0.01189994 -0.08319675 0.05077606 0.01189994 -0.07550889 0.04633748 0.01189994 -0.06379377 0.04130578 0.01189994 -0.181298 0.106332 0.01189994 -0.156656 0.0950641 0.01189994 -0.195724 0.117476 0.01189994 -0.196474 0.116177 0.01189994 -0.194427 0.114042 0.01189994 -0.202095 0.11502 0.01189994 -0.08244675 0.05207508 0.01189994 -0.09252518 0.05896878 0.01189994 -0.07429349 0.04844266 0.01189994 -0.07475888 0.04763656 0.01189994 -0.165401 0.09996867 0.01189994 -0.1649349 0.100775 0.01189994 -0.09206557 0.0597648 0.01189994 -0.08198136 0.0528813 0.01189994 -0.06332838 0.04211199 0.01189994 -0.178961 0.112046 0.01189994 -0.179154 0.110045 0.01189994 -0.179614 0.109249 0.01189994 -0.1823959 0.109781 0.01189994 -0.181975 0.10795 0.01189994 -0.188572 0.1166329 0.01189994 -0.187213 0.113637 0.01189994 -0.18953 0.114974 0.01189994 -0.1876789 0.1128309 0.01189994 -0.184475 0.11228 0.01189994 -0.18375 0.113536 0.01189994 -0.1829749 0.113328 0.01189994 -0.176019 0.120827 0.01189994 -0.180782 0.116744 0.01189994 -0.181171 0.117313 0.01189994 -0.181768 0.117658 0.01189994 -0.182456 0.1177099 0.01189994 -0.183098 0.117458 0.01189994 -0.183567 0.116952 0.01189994 -0.1843169 0.115653 0.01189994 -0.177467 0.104073 0.01739996 -0.177467 0.104073 0.01189994 -0.177215 0.103431 0.01189994 -0.177215 0.103431 0.01739996 -0.177267 0.102743 0.01189994 -0.1776109 0.102146 0.01739996 -0.1781809 0.101757 0.01189994 -0.1781809 0.101757 0.01739996 -0.17904 0.101709 0.01189994 -0.178863 0.101654 0.01189994 -0.178863 0.101654 0.01739996 -0.177459 -0.115331 0.01189994 -0.176421 -0.117131 0.01739996 -0.1790429 -0.112406 0.01189994 -0.178961 -0.112046 0.01189994 -0.178961 -0.112046 0.01739996 -0.178239 -0.109517 0.01189994 -0.178239 -0.109517 0.01739996 -0.178643 -0.110931 0.01739996 -0.1780059 -0.1087 0.01189994 -0.177886 -0.108351 0.01189994 -0.177613 -0.108101 0.01189994 -0.177254 -0.108012 0.01189994 -0.175181 -0.117219 0.01739996 -0.175098 -0.117071 0.01189994 -0.175098 -0.117071 0.01739996 -0.173744 -0.1146759 0.01189994 -0.17295 -0.1132709 0.01739996 -0.172818 -0.112651 0.01189994 -0.172001 -0.108836 0.01189994 -0.172745 -0.108041 0.01189994 -0.1724489 -0.108104 0.01189994 -0.172202 -0.108279 0.01189994 -0.172044 -0.108537 0.01189994 -0.172044 -0.108537 0.01739996 -0.175651 -0.108023 0.01189994 -0.172745 -0.108041 0.01739996 -0.177254 -0.108012 0.01739996 -0.18478 -0.122421 0.01189994 -0.18478 -0.122421 0.01739996 -0.186675 -0.122141 0.01739996 -0.188437 -0.121669 0.01739996 -0.194194 -0.120126 0.01739996 -0.195656 -0.119735 0.01739996 -0.196129 -0.119355 0.01739996 -0.196129 -0.119355 0.01189994 -0.196129 -0.118605 0.01189994 -0.196186 -0.118817 0.01189994 -0.191787 -0.1159819 0.01739996 -0.195387 -0.11806 0.01189994 -0.195854 -0.11833 0.01189994 -0.191787 -0.1159819 0.01189994 -0.191431 -0.115882 0.01189994 -0.191195 -0.115936 0.01739996 -0.187435 -0.116938 0.01189994 -0.187435 -0.116938 0.01739996 -0.191071 -0.115964 0.01189994 -0.189933 -0.116269 0.01739996 -0.184695 -0.120998 0.01739996 -0.184475 -0.121379 0.01189994 -0.190383 -0.09894776 0.01189994 -0.193067 -0.09894776 0.01189994 -0.193067 -0.09894776 0.01739996 -0.1924999 -0.09838038 0.01189994 -0.191725 -0.09817278 0.01739996 -0.189425 -0.101022 0.01189994 -0.190975 -0.102572 0.01189994 -0.190975 -0.102572 0.01739996 -0.1917499 -0.102364 0.01189994 -0.192317 -0.101797 0.01189994 -0.185391 -0.09924358 0.01189994 -0.185391 -0.09924358 0.01739996 -0.183964 -0.0996012 0.01189994 -0.183964 -0.0996012 0.01739996 -0.18314 -0.09980785 0.01739996 -0.181376 -0.0981068 0.01189994 -0.179939 -0.09558075 0.01189994 -0.181376 -0.0981068 0.01739996 -0.180018 -0.0947265 0.01189994 -0.179873 -0.09499216 0.01189994 -0.180018 -0.0947265 0.01739996 -0.179846 -0.09529328 0.01189994 -0.1889359 -0.09310358 0.01739996 -0.1889359 -0.09310358 0.01189994 -0.18457 -0.09314399 0.01189994 -0.1802549 -0.0945394 0.01189994 -0.189648 -0.0942195 0.01739996 -0.189748 -0.09387117 0.01189994 -0.189748 -0.09387117 0.01739996 -0.189673 -0.0935167 0.01189994 -0.189441 -0.09323871 0.01189994 -0.189648 -0.0942195 0.01189994 -0.198759 -0.09926909 0.01189994 -0.198759 -0.09926909 0.01739996 -0.201129 -0.108114 0.01189994 -0.197355 -0.09907066 0.01739996 -0.195007 -0.103138 0.01739996 -0.195658 -0.106353 0.01189994 -0.195658 -0.106353 0.01739996 -0.194989 -0.103854 0.01189994 -0.199937 -0.11018 0.01739996 -0.196337 -0.108101 0.01189994 -0.196337 -0.108101 0.01739996 -0.187726 -0.112749 0.01189994 -0.187726 -0.112749 0.01739996 -0.1852 -0.112474 0.01739996 -0.184475 -0.11228 0.01739996 -0.182645 -0.11045 0.01739996 -0.181975 -0.10795 0.01739996 -0.18226 -0.106887 0.01739996 -0.182645 -0.10545 0.01739996 -0.182645 -0.10545 0.01189994 -0.183697 -0.104398 0.01189994 -0.183697 -0.104398 0.01739996 -0.186224 -0.103151 0.01189994 -0.186224 -0.103151 0.01739996 -0.186975 -0.10295 0.01189994 -0.18875 -0.103426 0.01739996 -0.1894749 -0.10362 0.01739996 -0.191305 -0.10545 0.01189994 -0.1914719 -0.106072 0.01189994 -0.191305 -0.10545 0.01739996 -0.191506 -0.106201 0.01189994 -0.1914719 -0.106072 0.01739996 -0.1919749 -0.10795 0.01739996 -0.1919749 -0.10795 0.01189994 -0.191941 -0.108075 0.01739996 -0.19169 -0.109012 0.01189994 -0.191305 -0.11045 0.01189994 -0.190253 -0.111502 0.01189994 -0.194427 -0.114042 0.01739996 -0.194427 -0.114042 0.01189994 -0.194847 -0.114155 0.01739996 -0.1952019 -0.11425 0.01739996 -0.1952019 -0.11425 0.01189994 -0.195977 -0.114042 0.01189994 -0.196544 -0.113475 0.01189994 -0.196752 -0.1127 0.01189994 -0.196544 -0.111925 0.01189994 -0.1962839 -0.111665 0.01739996 -0.1962839 -0.111665 0.01189994 -0.196752 -0.1127 0.01739996 -0.08157849 -0.05913466 0.01189994 -0.07831346 -0.05923426 0.01739996 -0.07774686 -0.05925148 0.01739996 -0.07831346 -0.05923426 0.01189994 -0.0747832 -0.05934184 0.01739996 -0.0747832 -0.05934184 0.01189994 -0.0685938 -0.032992 0.01189994 -0.0687313 -0.03275376 0.01739996 -0.06813418 -0.03378796 0.01189994 -0.06691879 -0.0358932 0.01189994 -0.06691879 -0.0358932 0.01739996 -0.06645005 -0.03670507 0.01189994 -0.06501257 -0.03919488 0.01189994 -0.06332838 -0.04211199 0.01189994 -0.06501257 -0.03919488 0.01739996 -0.06286877 -0.04290795 0.01189994 -0.07673126 -0.028135 0.01189994 -0.09200137 -0.04108166 0.01739996 -0.09979528 -0.04637658 0.01739996 -0.0930655 -0.04221266 0.01189994 -0.134921 -0.06810969 0.01739996 -0.170931 -0.0903899 0.01739996 -0.134921 -0.06810969 0.01189994 -0.1744599 -0.0925734 0.01739996 -0.170931 -0.0903899 0.01189994 -0.1744599 -0.0925734 0.01189994 -0.175482 -0.09297007 0.01739996 -0.175482 -0.09297007 0.01189994 -0.184808 -0.09008085 0.01189994 -0.184808 -0.09008085 0.01739996 -0.188644 -0.09002751 0.01189994 -0.1637459 -0.102836 0.01739996 -0.1637459 -0.102836 0.01189994 -0.168806 -0.106434 0.01739996 -0.168806 -0.106434 0.01189994 -0.168255 -0.105487 0.01189994 -0.167401 -0.1048 0.01189994 -0.168255 -0.105487 0.01739996 -0.167401 -0.1048 0.01739996 -0.189866 -0.09041649 0.01739996 -0.189866 -0.09041649 0.01189994 -0.20024 -0.09642428 0.01739996 -0.201059 -0.09714275 0.01739996 -0.201577 -0.09819257 0.01189994 -0.204499 -0.109099 0.01739996 -0.203251 -0.104439 0.01739996 -0.204226 -0.111299 0.01739996 -0.2042 -0.111376 0.01739996 -0.2042 -0.111376 0.01189994 -0.2037799 -0.112103 0.01739996 -0.203314 -0.112909 0.01739996 -0.202564 -0.114208 0.01739996 -0.203314 -0.112909 0.01189994 -0.202095 -0.11502 0.01189994 -0.198974 -0.120427 0.01189994 -0.196732 -0.122552 0.01739996 -0.196732 -0.122552 0.01189994 -0.192111 -0.12379 0.01189994 -0.192072 -0.123801 0.01739996 -0.192072 -0.123801 0.01189994 -0.190349 -0.124262 0.01739996 -0.190349 -0.124262 0.01189994 -0.186437 -0.125311 0.01739996 -0.185826 -0.125474 0.01739996 -0.1836259 -0.125201 0.01189994 -0.183549 -0.1251749 0.01739996 -0.184658 -0.125551 0.01739996 -0.173236 -0.11922 0.01739996 -0.173702 -0.119489 0.01189994 -0.176019 -0.120827 0.01739996 -0.1813009 -0.123877 0.01189994 -0.183549 -0.1251749 0.01189994 -0.1813009 -0.123877 0.01739996 -0.173236 -0.11922 0.01189994 -0.16898 -0.107515 0.01739996 -0.169297 -0.111339 0.01189994 -0.169234 -0.110582 0.01739996 -0.169582 -0.112272 0.01189994 -0.169297 -0.111339 0.01739996 -0.1704159 -0.1150079 0.01189994 -0.08625769 -0.04890596 0.01739996 -0.08625769 -0.04890596 0.01189994 -0.08477181 -0.04804807 0.01739996 -0.08477181 -0.04804807 0.01189994 -0.07559806 -0.04275166 0.01739996 -0.07559806 -0.04275166 0.01189994 -0.07414609 -0.04237514 0.01189994 -0.08548265 -0.05024826 0.01189994 -0.0763089 -0.04495185 0.01739996 -0.08730965 -0.04997515 0.01189994 -0.156656 -0.0950641 0.01189994 -0.156656 -0.09426409 0.01739996 -0.156363 -0.09397131 0.01739996 -0.156363 -0.09397131 0.01189994 -0.155963 -0.09386408 0.01739996 -0.155963 -0.09386408 0.01189994 -0.1555629 -0.09397131 0.01189994 -0.15527 -0.09426409 0.01739996 -0.1555629 -0.09535688 0.01189994 -0.155963 -0.09546411 0.01189994 -0.155963 -0.09546411 0.01739996 -0.102203 -0.06316405 0.01739996 -0.102096 -0.0627641 0.01189994 -0.102096 -0.0627641 0.01739996 -0.101803 -0.06247127 0.01739996 -0.1014029 -0.0623641 0.01739996 -0.101003 -0.06247127 0.01739996 -0.101003 -0.06247127 0.01189994 -0.100711 -0.0627641 0.01189994 -0.100711 -0.0627641 0.01739996 -0.100603 -0.06316405 0.01739996 -0.100711 -0.06356406 0.01739996 -0.101003 -0.06385689 0.01739996 -0.101003 -0.06385689 0.01189994 -0.1014029 -0.06396406 0.01189994 -0.101803 -0.06385689 0.01189994 -0.1014029 -0.06396406 0.01739996 -0.164476 -0.101571 0.01189994 -0.16898 -0.107515 0.01189994 -0.169234 -0.110582 0.01189994 -0.17295 -0.1132709 0.01189994 -0.171286 -0.116563 0.01189994 -0.176421 -0.117131 0.01189994 -0.176169 -0.117391 0.01189994 -0.175824 -0.117504 0.01189994 -0.174365 -0.118341 0.01189994 -0.175468 -0.1174409 0.01189994 -0.175181 -0.117219 0.01189994 -0.179154 -0.110045 0.01189994 -0.178643 -0.110931 0.01189994 -0.178943 -0.112762 0.01189994 -0.176815 -0.116448 0.01189994 -0.179614 -0.109249 0.01189994 -0.185349 -0.122496 0.01189994 -0.185181 -0.122507 0.01189994 -0.185057 -0.122515 0.01189994 -0.18475 -0.122404 0.01189994 -0.18453 -0.122211 0.01189994 -0.1844 -0.121948 0.01189994 -0.181964 -0.122728 0.01189994 -0.184381 -0.121656 0.01189994 -0.183396 -0.120248 0.01189994 -0.186437 -0.125311 0.01189994 -0.186675 -0.122141 0.01189994 -0.188437 -0.121669 0.01189994 -0.197782 -0.122034 0.01189994 -0.195807 -0.11966 0.01189994 -0.194194 -0.120126 0.01189994 -0.1920869 -0.123776 0.01189994 -0.195656 -0.119735 0.01189994 -0.196111 -0.119385 0.01189994 -0.198501 -0.121215 0.01189994 -0.198554 -0.121154 0.01189994 -0.196229 -0.11898 0.01189994 -0.194847 -0.114155 0.01189994 -0.191195 -0.115936 0.01189994 -0.18953 -0.114974 0.01189994 -0.189933 -0.116269 0.01189994 -0.186823 -0.117312 0.01189994 -0.186754 -0.114433 0.01189994 -0.1870819 -0.117048 0.01189994 -0.184695 -0.120998 0.01189994 -0.18534 -0.119881 0.01189994 -0.07445776 -0.05453526 0.01189994 -0.0766229 -0.05453526 0.01189994 -0.07679039 -0.05516028 0.01189994 -0.0815218 -0.05367726 0.01189994 -0.0766229 -0.05578529 0.01189994 -0.07616537 -0.05624276 0.01189994 -0.0749154 -0.05407768 0.01189994 -0.07554036 -0.05641025 0.01189994 -0.07528859 -0.05634278 0.01189994 -0.0749154 -0.05624276 0.01189994 -0.07774686 -0.05925148 0.01189994 -0.07047647 -0.05505394 0.01189994 -0.07464218 -0.05596959 0.01189994 -0.07445776 -0.05578529 0.01189994 -0.07429039 -0.05516028 0.01189994 -0.189105 -0.09310209 0.01189994 -0.1903319 -0.0906856 0.01189994 -0.187196 -0.101467 0.01189994 -0.187126 -0.09858769 0.01189994 -0.186868 -0.09885245 0.01189994 -0.177601 -0.09258335 0.01189994 -0.176577 -0.09297358 0.01189994 -0.18107 -0.09094595 0.01189994 -0.182169 -0.09950017 0.01189994 -0.184879 -0.10013 0.01189994 -0.18314 -0.09980785 0.01189994 -0.200779 -0.11055 0.01189994 -0.200991 -0.110493 0.01189994 -0.2037799 -0.112103 0.01189994 -0.2011539 -0.11045 0.01189994 -0.20024 -0.09642428 0.01189994 -0.201059 -0.09714275 0.01189994 -0.201429 -0.110175 0.01189994 -0.2014459 -0.110145 0.01189994 -0.2015399 -0.109868 0.01189994 -0.204226 -0.111299 0.01189994 -0.201532 -0.109744 0.01189994 -0.204576 -0.110267 0.01189994 -0.201521 -0.109576 0.01189994 -0.204499 -0.109099 0.01189994 -0.203251 -0.104439 0.01189994 -0.192479 -0.104517 0.01189994 -0.194907 -0.103494 0.01189994 -0.195007 -0.103138 0.01189994 -0.197355 -0.09907066 0.01189994 -0.197548 -0.09885066 0.01189994 -0.197811 -0.09872126 0.01189994 -0.198103 -0.09870219 0.01189994 -0.1983799 -0.09879618 0.01189994 -0.200179 -0.09637099 0.01189994 -0.19841 -0.09881365 0.01189994 -0.19863 -0.09900665 0.01189994 -0.198685 -0.09911775 0.01189994 -0.194795 -0.105855 0.01189994 -0.195963 -0.10749 0.01189994 -0.1960009 -0.107612 0.01189994 -0.1943359 -0.106651 0.01189994 -0.196072 -0.107843 0.01189994 -0.200404 -0.11045 0.01189994 -0.199937 -0.11018 0.01189994 -0.179103 -0.101745 0.01189994 -0.179523 -0.101858 0.01189994 -0.180822 -0.102608 0.01189994 -0.178748 -0.1016499 0.01189994 -0.1776649 -0.104235 0.01189994 -0.1774049 -0.1039749 0.01189994 -0.177973 -0.101858 0.01189994 -0.177973 -0.104542 0.01189994 -0.180822 -0.105292 0.01189994 -0.181389 -0.104725 0.01189994 -0.1815969 -0.10395 0.01189994 -0.181389 -0.103175 0.01189994 -0.180047 -0.1055 0.01189994 -0.179692 -0.105405 0.01189994 -0.1792719 -0.105292 0.01189994 -0.182645 -0.11045 0.01189994 -0.182443 -0.109699 0.01189994 -0.181975 -0.10795 0.01189994 -0.181298 -0.106332 0.01189994 -0.1894749 -0.11228 0.01189994 -0.19387 -0.107457 0.01189994 -0.191941 -0.108075 0.01189994 -0.19312 -0.108756 0.01189994 -0.186271 -0.103069 0.01189994 -0.186353 -0.103117 0.01189994 -0.18875 -0.103426 0.01189994 -0.1894749 -0.10362 0.01189994 -0.190005 -0.1041499 0.01189994 -0.191554 -0.106119 0.01189994 -0.184383 -0.103711 0.01189994 -0.182736 -0.103843 0.01189994 -0.181129 -0.102915 0.01189994 -0.18226 -0.106887 0.01189994 -0.193128 -0.113292 0.01189994 -0.192821 -0.112985 0.01189994 -0.191214 -0.112057 0.01189994 -0.192561 -0.111175 0.01189994 -0.192652 -0.1095679 0.01189994 -0.192353 -0.11195 0.01189994 -0.192561 -0.112725 0.01189994 -0.193128 -0.110608 0.01189994 -0.193903 -0.1104 0.01189994 -0.194258 -0.110495 0.01189994 -0.194678 -0.110608 0.01189994 -0.198849 -0.112063 0.01189994 -0.08309 -0.05949079 0.01189994 -0.09006088 -0.06323695 0.01189994 -0.07880926 -0.05837547 0.01189994 -0.08019727 -0.0591768 0.01189994 -0.06273126 -0.05058228 0.01189994 -0.06273126 -0.05238378 0.01189994 -0.06969636 -0.05640506 0.01189994 -0.07112139 -0.05393689 0.01189994 -0.06273126 -0.04909288 0.01189994 -0.0687313 -0.03275376 0.01189994 -0.08429038 -0.03783965 0.01189994 -0.08445775 -0.03721469 0.01189994 -0.08491539 -0.03675717 0.01189994 -0.08369636 -0.03215634 0.01189994 -0.08554035 -0.03658968 0.01189994 -0.08616536 -0.03675717 0.01189994 -0.0887832 -0.03509318 0.01189994 -0.08662289 -0.03721469 0.01189994 -0.08679038 -0.03783965 0.01189994 -0.08662289 -0.03846466 0.01189994 -0.09045505 -0.03820425 0.01189994 -0.08616536 -0.03892225 0.01189994 -0.08724677 -0.04376125 0.01189994 -0.08554035 -0.03908967 0.01189994 -0.08491539 -0.03892225 0.01189994 -0.08445775 -0.03846466 0.01189994 -0.09200137 -0.04108166 0.01189994 -0.09979528 -0.04637658 0.01189994 -0.1335459 -0.07049196 0.01189994 -0.184281 -0.124066 0.01189994 -0.185826 -0.125474 0.01189994 -0.184658 -0.125551 0.01189994 -0.172288 -0.118357 0.01189994 -0.08674329 -0.05096244 0.01189994 -0.08640867 -0.05115938 0.01189994 -0.08548575 -0.05063647 0.01189994 -0.08399677 -0.04939049 0.01189994 -0.08568269 -0.05097115 0.01189994 -0.08602041 -0.05116248 0.01189994 -0.08750647 -0.04964059 0.01189994 -0.08659535 -0.04871457 0.01189994 -0.08698368 -0.04871779 0.01189994 -0.09564685 -0.05356186 0.01189994 -0.0873183 -0.04891455 0.01189994 -0.08750969 -0.04925239 0.01189994 -0.0689789 -0.04107499 0.01189994 -0.07357418 -0.04335939 0.01189994 -0.07068645 -0.04153245 0.01189994 -0.0700615 -0.04169994 0.01189994 -0.06881147 -0.04044997 0.01189994 -0.0689789 -0.03982496 0.01189994 -0.06943649 -0.03936749 0.01189994 -0.07489395 -0.04181379 0.01189994 -0.0745666 -0.04187846 0.01189994 -0.07482308 -0.04409396 0.01189994 -0.0744853 -0.04428535 0.01189994 -0.07409709 -0.04428219 0.01189994 -0.07376235 -0.04408538 0.01189994 -0.06943649 -0.04153245 0.01189994 -0.07357108 -0.0437476 0.01189994 -0.07114398 -0.04107499 0.01189994 -0.07377105 -0.04302477 0.01189994 -0.07131147 -0.04044997 0.01189994 -0.07429957 -0.04207885 0.01189994 -0.07547187 -0.04211318 0.01189994 -0.0700615 -0.03919994 0.01189994 -0.07068645 -0.03936749 0.01189994 -0.07741516 -0.0430358 0.01189994 -0.07708388 -0.04360949 0.01189994 -0.07560777 -0.042418 0.01189994 -0.07521706 -0.04189747 0.01189994 -0.07114398 -0.03982496 0.01189994 -0.1592699 -0.08733588 0.01189994 -0.133086 -0.07128798 0.01189994 -0.159563 -0.0870431 0.01189994 -0.159963 -0.08693587 0.01189994 -0.169741 -0.09245085 0.01189994 -0.160363 -0.0870431 0.01189994 -0.160656 -0.08733588 0.01189994 -0.160763 -0.08773589 0.01189994 -0.160656 -0.08813589 0.01189994 -0.160564 -0.08822739 0.01189994 -0.1685259 -0.09455597 0.01189994 -0.160363 -0.08842867 0.01189994 -0.159963 -0.0885359 0.01189994 -0.159563 -0.08842867 0.01189994 -0.1592699 -0.08813589 0.01189994 -0.105803 -0.05554306 0.01189994 -0.106096 -0.0558359 0.01189994 -0.1591629 -0.08773589 0.01189994 -0.159237 -0.08746087 0.01189994 -0.132621 -0.07209408 0.01189994 -0.0973311 -0.05064475 0.01189994 -0.1050029 -0.05554306 0.01189994 -0.106096 -0.05663585 0.01189994 -0.131871 -0.07339316 0.01189994 -0.1766819 -0.119678 0.01189994 -0.1822 -0.113536 0.01189994 -0.1829749 -0.113328 0.01189994 -0.183 -0.11752 0.01189994 -0.182225 -0.117727 0.01189994 -0.184475 -0.11228 0.01189994 -0.18375 -0.113536 0.01189994 -0.176019 -0.120827 0.01189994 -0.1781139 -0.117198 0.01189994 -0.184041 -0.119131 0.01189994 -0.18145 -0.11752 0.01189994 -0.180883 -0.116952 0.01189994 -0.180675 -0.116177 0.01189994 -0.180883 -0.115402 0.01189994 -0.178759 -0.1160809 0.01189994 -0.181471 -0.111383 0.01189994 -0.1816329 -0.114103 0.01189994 -0.1843169 -0.114103 0.01189994 -0.184525 -0.1148779 0.01189994 -0.1843169 -0.115653 0.01189994 -0.183567 -0.116952 0.01189994 -0.183944 -0.11175 0.01189994 -0.181931 -0.110587 0.01189994 -0.188572 -0.1166329 0.01189994 -0.18907 -0.11577 0.01189994 -0.187213 -0.113637 0.01189994 -0.1852 -0.112474 0.01189994 -0.186975 -0.11295 0.01189994 -0.08366549 -0.04996418 0.01189994 -0.0763089 -0.04495185 0.01189994 -0.07597768 -0.04552555 0.01189994 -0.07429349 -0.04844266 0.01189994 -0.09420937 -0.05605167 0.01189994 -0.06273126 -0.04314619 0.01189994 -0.100603 -0.06316405 0.01189994 -0.100711 -0.06356406 0.01189994 -0.102203 -0.06316405 0.01189994 -0.102096 -0.06356406 0.01189994 -0.1014029 -0.0623641 0.01189994 -0.101803 -0.06247127 0.01189994 -0.1264449 -0.08279025 0.01189994 -0.09206557 -0.0597648 0.01189994 -0.07554036 -0.05391025 0.01189994 -0.07616537 -0.05407768 0.01189994 -0.07383388 -0.04923868 0.01189994 -0.08198136 -0.0528813 0.01189994 -0.09252518 -0.05896878 0.01189994 -0.1649349 -0.100775 0.01189994 -0.156763 -0.09466409 0.01189994 -0.156363 -0.09535688 0.01189994 -0.156656 -0.09426409 0.01189994 -0.16662 -0.09785777 0.01189994 -0.155163 -0.09466409 0.01189994 -0.12828 -0.07961195 0.01189994 -0.15527 -0.09426409 0.01189994 -0.1299639 -0.0766949 0.01189994 -0.127821 -0.08040797 0.01189994 -0.15527 -0.0950641 0.01189994 -0.1771979 -0.1032 0.01189994 -0.1774049 -0.102425 0.01189994 -0.08693468 -0.05062478 0.01189994 -0.168057 -0.0953679 0.01189994 -0.131402 -0.0742051 0.01189994 -0.09611558 -0.05274999 0.01189994 -0.08510297 -0.04747438 0.01189994 -0.08557176 -0.04666244 0.01189994 -0.07788389 -0.04222387 0.01189994 -0.1047109 -0.05663585 0.01189994 -0.09686559 -0.05145084 0.01189994 -0.0786339 -0.04092484 0.01189994 -0.06766879 -0.03459417 0.01189994 -0.199599 -0.110764 0.01189994 -0.195977 -0.111358 0.01189994 -0.1983799 -0.112875 0.01189994 -0.202564 -0.114208 0.01189994 -0.196943 -0.115365 0.01189994 -0.200658 -0.11751 0.01189994 -0.1047109 -0.0558359 0.01189994 -0.08632177 -0.04536336 0.01189994 -0.1832039 -0.103031 0.01189994 -0.1692759 -0.093257 0.01189994 -0.182777 -0.09987807 0.01189994 -0.182425 -0.09976649 0.01189994 -0.170201 -0.09165489 0.01189994 -0.08678716 -0.04455727 0.01189994 -0.09779059 -0.04984879 0.01189994 -0.07909935 -0.04011869 0.01189994 -0.0795589 -0.03932267 0.01189994 -0.186515 -0.09896177 0.01189994 -0.1844199 -0.100926 0.01189994 -0.183954 -0.101732 0.01189994 -0.186736 -0.102263 0.01189994 -0.184475 -0.10362 0.01189994 -0.195294 -0.104992 0.01189994 -0.192019 -0.105313 0.01189994 -0.197931 -0.0950731 0.01189994 -0.193275 -0.0997228 0.01189994 -0.193067 -0.100498 0.01189994 -0.1902 -0.102364 0.01189994 -0.189633 -0.101797 0.01189994 -0.1926479 -0.09202307 0.01189994 -0.189633 -0.100247 0.01189994 -0.19095 -0.09838038 0.01189994 -0.191725 -0.09817278 0.01189994 -0.106203 -0.05623584 0.01739996 -0.106203 -0.05623584 0.01189994 -0.106096 -0.0558359 0.01739996 -0.105803 -0.05554306 0.01739996 -0.105403 -0.05543589 0.01189994 -0.105403 -0.05543589 0.01739996 -0.104677 -0.05596089 0.01739996 -0.104677 -0.05596089 0.01189994 -0.104603 -0.05623584 0.01189994 -0.104603 -0.05623584 0.01739996 -0.1050029 -0.05692869 0.01189994 -0.105403 -0.05703586 0.01189994 -0.106096 -0.05663585 0.01739996 -0.106005 -0.05672734 0.01189994 -0.106005 -0.05672734 0.01739996 -0.105803 -0.05692869 0.01189994 -0.155163 -0.09466409 0.01739996 -0.09252518 -0.05896878 0.01739996 -0.07383388 -0.04923868 0.01739996 -0.08445775 -0.03721469 0.01739996 -0.195854 -0.11833 0.01739996 -0.175468 -0.1174409 0.01739996 -0.175824 -0.117504 0.01739996 -0.176169 -0.117391 0.01739996 -0.171286 -0.116563 0.01739996 -0.1704159 -0.1150079 0.01739996 -0.169582 -0.112272 0.01739996 -0.172818 -0.112651 0.01739996 -0.1724489 -0.108104 0.01739996 -0.172202 -0.108279 0.01739996 -0.164476 -0.101571 0.01739996 -0.172001 -0.108836 0.01739996 -0.1780059 -0.1087 0.01739996 -0.179614 -0.109249 0.01739996 -0.175651 -0.108023 0.01739996 -0.177459 -0.115331 0.01739996 -0.181471 -0.111383 0.01739996 -0.179154 -0.110045 0.01739996 -0.1790429 -0.112406 0.01739996 -0.178943 -0.112762 0.01739996 -0.196186 -0.118817 0.01739996 -0.196129 -0.118605 0.01739996 -0.197782 -0.122034 0.01739996 -0.198501 -0.121215 0.01739996 -0.198554 -0.121154 0.01739996 -0.198974 -0.120427 0.01739996 -0.196229 -0.11898 0.01739996 -0.192111 -0.12379 0.01739996 -0.1920869 -0.123776 0.01739996 -0.184381 -0.121656 0.01739996 -0.185057 -0.122515 0.01739996 -0.1844 -0.121948 0.01739996 -0.18453 -0.122211 0.01739996 -0.18475 -0.122404 0.01739996 -0.191071 -0.115964 0.01739996 -0.18907 -0.11577 0.01739996 -0.188572 -0.1166329 0.01739996 -0.186823 -0.117312 0.01739996 -0.1870819 -0.117048 0.01739996 -0.18953 -0.114974 0.01739996 -0.191214 -0.112057 0.01739996 -0.07616537 -0.05624276 0.01739996 -0.0766229 -0.05578529 0.01739996 -0.0766229 -0.05453526 0.01739996 -0.07616537 -0.05407768 0.01739996 -0.07528859 -0.05634278 0.01739996 -0.07464218 -0.05596959 0.01739996 -0.179846 -0.09529328 0.01739996 -0.170201 -0.09165489 0.01739996 -0.188644 -0.09002751 0.01739996 -0.18107 -0.09094595 0.01739996 -0.18457 -0.09314399 0.01739996 -0.1802549 -0.0945394 0.01739996 -0.177601 -0.09258335 0.01739996 -0.176577 -0.09297358 0.01739996 -0.179873 -0.09499216 0.01739996 -0.1903319 -0.0906856 0.01739996 -0.189105 -0.09310209 0.01739996 -0.189441 -0.09323871 0.01739996 -0.189673 -0.0935167 0.01739996 -0.186868 -0.09885245 0.01739996 -0.187126 -0.09858769 0.01739996 -0.182169 -0.09950017 0.01739996 -0.184879 -0.10013 0.01739996 -0.198103 -0.09870219 0.01739996 -0.197811 -0.09872126 0.01739996 -0.197548 -0.09885066 0.01739996 -0.197931 -0.0950731 0.01739996 -0.194907 -0.103494 0.01739996 -0.200179 -0.09637099 0.01739996 -0.1983799 -0.09879618 0.01739996 -0.201521 -0.109576 0.01739996 -0.204576 -0.110267 0.01739996 -0.201532 -0.109744 0.01739996 -0.19841 -0.09881365 0.01739996 -0.19863 -0.09900665 0.01739996 -0.198685 -0.09911775 0.01739996 -0.201577 -0.09819257 0.01739996 -0.201129 -0.108114 0.01739996 -0.2015399 -0.109868 0.01739996 -0.2014459 -0.110145 0.01739996 -0.201429 -0.110175 0.01739996 -0.2011539 -0.11045 0.01739996 -0.200779 -0.11055 0.01739996 -0.200991 -0.110493 0.01739996 -0.199599 -0.110764 0.01739996 -0.194795 -0.105855 0.01739996 -0.195963 -0.10749 0.01739996 -0.1960009 -0.107612 0.01739996 -0.196072 -0.107843 0.01739996 -0.1776649 -0.104235 0.01739996 -0.177973 -0.104542 0.01739996 -0.177973 -0.101858 0.01739996 -0.1774049 -0.102425 0.01739996 -0.1771979 -0.1032 0.01739996 -0.1774049 -0.1039749 0.01739996 -0.1792719 -0.105292 0.01739996 -0.179692 -0.105405 0.01739996 -0.181298 -0.106332 0.01739996 -0.180047 -0.1055 0.01739996 -0.180822 -0.105292 0.01739996 -0.181389 -0.104725 0.01739996 -0.1815969 -0.10395 0.01739996 -0.181389 -0.103175 0.01739996 -0.1832039 -0.103031 0.01739996 -0.181129 -0.102915 0.01739996 -0.180822 -0.102608 0.01739996 -0.184475 -0.10362 0.01739996 -0.191506 -0.106201 0.01739996 -0.191554 -0.106119 0.01739996 -0.192019 -0.105313 0.01739996 -0.190005 -0.1041499 0.01739996 -0.192479 -0.104517 0.01739996 -0.186736 -0.102263 0.01739996 -0.186975 -0.10295 0.01739996 -0.186353 -0.103117 0.01739996 -0.190253 -0.111502 0.01739996 -0.1894749 -0.11228 0.01739996 -0.187213 -0.113637 0.01739996 -0.186975 -0.11295 0.01739996 -0.184383 -0.103711 0.01739996 -0.182736 -0.103843 0.01739996 -0.182443 -0.109699 0.01739996 -0.192561 -0.111175 0.01739996 -0.192353 -0.11195 0.01739996 -0.194258 -0.110495 0.01739996 -0.193903 -0.1104 0.01739996 -0.193128 -0.110608 0.01739996 -0.192561 -0.112725 0.01739996 -0.192821 -0.112985 0.01739996 -0.191431 -0.115882 0.01739996 -0.193128 -0.113292 0.01739996 -0.195387 -0.11806 0.01739996 -0.196943 -0.115365 0.01739996 -0.195977 -0.114042 0.01739996 -0.1983799 -0.112875 0.01739996 -0.196544 -0.113475 0.01739996 -0.196544 -0.111925 0.01739996 -0.195977 -0.111358 0.01739996 -0.19312 -0.108756 0.01739996 -0.194678 -0.110608 0.01739996 -0.185181 -0.122507 0.01739996 -0.185349 -0.122496 0.01739996 -0.1335459 -0.07049196 0.01739996 -0.0930655 -0.04221266 0.01739996 -0.08724677 -0.04376125 0.01739996 -0.08662289 -0.03846466 0.01739996 -0.08491539 -0.03675717 0.01739996 -0.08679038 -0.03783965 0.01739996 -0.09045505 -0.03820425 0.01739996 -0.08662289 -0.03721469 0.01739996 -0.0887832 -0.03509318 0.01739996 -0.08616536 -0.03675717 0.01739996 -0.0795589 -0.03932267 0.01739996 -0.08491539 -0.03892225 0.01739996 -0.08554035 -0.03908967 0.01739996 -0.08616536 -0.03892225 0.01739996 -0.0685938 -0.032992 0.01739996 -0.08369636 -0.03215634 0.01739996 -0.07673126 -0.028135 0.01739996 -0.07554036 -0.05391025 0.01739996 -0.07112139 -0.05393689 0.01739996 -0.06273126 -0.04909288 0.01739996 -0.06273126 -0.05058228 0.01739996 -0.06969636 -0.05640506 0.01739996 -0.06273126 -0.05238378 0.01739996 -0.07047647 -0.05505394 0.01739996 -0.08309 -0.05949079 0.01739996 -0.0815218 -0.05367726 0.01739996 -0.08157849 -0.05913466 0.01739996 -0.08019727 -0.0591768 0.01739996 -0.07880926 -0.05837547 0.01739996 -0.1264449 -0.08279025 0.01739996 -0.09006088 -0.06323695 0.01739996 -0.09206557 -0.0597648 0.01739996 -0.173744 -0.1146759 0.01739996 -0.172288 -0.118357 0.01739996 -0.08366549 -0.04996418 0.01739996 -0.08510297 -0.04747438 0.01739996 -0.08659535 -0.04871457 0.01739996 -0.08698368 -0.04871779 0.01739996 -0.08548575 -0.05063647 0.01739996 -0.08568269 -0.05097115 0.01739996 -0.08602041 -0.05116248 0.01739996 -0.09420937 -0.05605167 0.01739996 -0.08640867 -0.05115938 0.01739996 -0.08674329 -0.05096244 0.01739996 -0.08693468 -0.05062478 0.01739996 -0.08750647 -0.04964059 0.01739996 -0.08548265 -0.05024826 0.01739996 -0.08399677 -0.04939049 0.01739996 -0.0744853 -0.04428535 0.01739996 -0.07482308 -0.04409396 0.01739996 -0.0689789 -0.03982496 0.01739996 -0.06881147 -0.04044997 0.01739996 -0.0689789 -0.04107499 0.01739996 -0.07068645 -0.03936749 0.01739996 -0.0700615 -0.03919994 0.01739996 -0.06645005 -0.03670507 0.01739996 -0.06943649 -0.03936749 0.01739996 -0.07409709 -0.04428219 0.01739996 -0.07376235 -0.04408538 0.01739996 -0.07357108 -0.0437476 0.01739996 -0.07521706 -0.04189747 0.01739996 -0.06943649 -0.04153245 0.01739996 -0.0700615 -0.04169994 0.01739996 -0.07357418 -0.04335939 0.01739996 -0.07377105 -0.04302477 0.01739996 -0.07068645 -0.04153245 0.01739996 -0.07414609 -0.04237514 0.01739996 -0.07114398 -0.04107499 0.01739996 -0.07489395 -0.04181379 0.01739996 -0.07131147 -0.04044997 0.01739996 -0.0745666 -0.04187846 0.01739996 -0.07429957 -0.04207885 0.01739996 -0.07547187 -0.04211318 0.01739996 -0.07708388 -0.04360949 0.01739996 -0.07741516 -0.0430358 0.01739996 -0.07560777 -0.042418 0.01739996 -0.160763 -0.08773589 0.01739996 -0.160656 -0.08733588 0.01739996 -0.169741 -0.09245085 0.01739996 -0.160363 -0.0870431 0.01739996 -0.159963 -0.08693587 0.01739996 -0.159563 -0.0870431 0.01739996 -0.132621 -0.07209408 0.01739996 -0.1592699 -0.08733588 0.01739996 -0.159237 -0.08746087 0.01739996 -0.1591629 -0.08773589 0.01739996 -0.1592699 -0.08813589 0.01739996 -0.159563 -0.08842867 0.01739996 -0.131871 -0.07339316 0.01739996 -0.179103 -0.101745 0.01739996 -0.178748 -0.1016499 0.01739996 -0.1685259 -0.09455597 0.01739996 -0.159963 -0.0885359 0.01739996 -0.160363 -0.08842867 0.01739996 -0.160564 -0.08822739 0.01739996 -0.160656 -0.08813589 0.01739996 -0.0973311 -0.05064475 0.01739996 -0.1050029 -0.05554306 0.01739996 -0.1047109 -0.0558359 0.01739996 -0.105403 -0.05703586 0.01739996 -0.105803 -0.05692869 0.01739996 -0.133086 -0.07128798 0.01739996 -0.1924999 -0.09838038 0.01739996 -0.189633 -0.101797 0.01739996 -0.1902 -0.102364 0.01739996 -0.1917499 -0.102364 0.01739996 -0.1926479 -0.09202307 0.01739996 -0.19095 -0.09838038 0.01739996 -0.187196 -0.101467 0.01739996 -0.190383 -0.09894776 0.01739996 -0.189633 -0.100247 0.01739996 -0.189425 -0.101022 0.01739996 -0.192317 -0.101797 0.01739996 -0.193067 -0.100498 0.01739996 -0.193275 -0.0997228 0.01739996 -0.179939 -0.09558075 0.01739996 -0.09779059 -0.04984879 0.01739996 -0.08678716 -0.04455727 0.01739996 -0.08632177 -0.04536336 0.01739996 -0.09686559 -0.05145084 0.01739996 -0.186271 -0.103069 0.01739996 -0.186515 -0.09896177 0.01739996 -0.19387 -0.107457 0.01739996 -0.1943359 -0.106651 0.01739996 -0.194989 -0.103854 0.01739996 -0.195294 -0.104992 0.01739996 -0.179523 -0.101858 0.01739996 -0.1692759 -0.093257 0.01739996 -0.183954 -0.101732 0.01739996 -0.1844199 -0.100926 0.01739996 -0.182425 -0.09976649 0.01739996 -0.182777 -0.09987807 0.01739996 -0.198849 -0.112063 0.01739996 -0.192652 -0.1095679 0.01739996 -0.19169 -0.109012 0.01739996 -0.191305 -0.11045 0.01739996 -0.07114398 -0.03982496 0.01739996 -0.07788389 -0.04222387 0.01739996 -0.06766879 -0.03459417 0.01739996 -0.08750969 -0.04925239 0.01739996 -0.0873183 -0.04891455 0.01739996 -0.09564685 -0.05356186 0.01739996 -0.08557176 -0.04666244 0.01739996 -0.0786339 -0.04092484 0.01739996 -0.06813418 -0.03378796 0.01739996 -0.1047109 -0.05663585 0.01739996 -0.1050029 -0.05692869 0.01739996 -0.131402 -0.0742051 0.01739996 -0.168057 -0.0953679 0.01739996 -0.200658 -0.11751 0.01739996 -0.202095 -0.11502 0.01739996 -0.200404 -0.11045 0.01739996 -0.101803 -0.06385689 0.01739996 -0.102096 -0.06356406 0.01739996 -0.08730965 -0.04997515 0.01739996 -0.07429349 -0.04844266 0.01739996 -0.07597768 -0.04552555 0.01739996 -0.1555629 -0.09397131 0.01739996 -0.15527 -0.0950641 0.01739996 -0.1555629 -0.09535688 0.01739996 -0.156363 -0.09535688 0.01739996 -0.1649349 -0.100775 0.01739996 -0.156656 -0.0950641 0.01739996 -0.156763 -0.09466409 0.01739996 -0.16662 -0.09785777 0.01739996 -0.09611558 -0.05274999 0.01739996 -0.07909935 -0.04011869 0.01739996 -0.1299639 -0.0766949 0.01739996 -0.12828 -0.07961195 0.01739996 -0.177886 -0.108351 0.01739996 -0.177613 -0.108101 0.01739996 -0.127821 -0.08040797 0.01739996 -0.08198136 -0.0528813 0.01739996 -0.06332838 -0.04211199 0.01739996 -0.06286877 -0.04290795 0.01739996 -0.181931 -0.110587 0.01739996 -0.183944 -0.11175 0.01739996 -0.186754 -0.114433 0.01739996 -0.180883 -0.115402 0.01739996 -0.1816329 -0.114103 0.01739996 -0.1843169 -0.114103 0.01739996 -0.18375 -0.113536 0.01739996 -0.1829749 -0.113328 0.01739996 -0.1822 -0.113536 0.01739996 -0.180675 -0.116177 0.01739996 -0.180883 -0.116952 0.01739996 -0.18145 -0.11752 0.01739996 -0.178759 -0.1160809 0.01739996 -0.182225 -0.117727 0.01739996 -0.183 -0.11752 0.01739996 -0.183567 -0.116952 0.01739996 -0.1843169 -0.115653 0.01739996 -0.184525 -0.1148779 0.01739996 -0.18534 -0.119881 0.01739996 -0.184041 -0.119131 0.01739996 -0.183396 -0.120248 0.01739996 -0.176815 -0.116448 0.01739996 -0.184475 -0.121379 0.01739996 -0.1781139 -0.117198 0.01739996 -0.1766819 -0.119678 0.01739996 -0.1836259 -0.125201 0.01739996 -0.184281 -0.124066 0.01739996 -0.181964 -0.122728 0.01739996 -0.174365 -0.118341 0.01739996 -0.173702 -0.119489 0.01739996 -0.196111 -0.119385 0.01739996 -0.195807 -0.11966 0.01739996 -0.195918 -0.119605 0.01739996 -0.195918 -0.119605 0.01189994 -0.001999974 0.006858468 0 -0.001999974 0.02637499 0 -0.001999974 0.006858468 0.00119996 -0.001999974 0.02699995 0.00119996 -0.003292202 0.006340265 0.00119996 -0.02249997 0.02744388 0 -0.02232038 0.02651345 0.00119996 -0.02180749 0.02571666 0.00119996 -0.02223128 0.02637499 0 -0.02249997 0.02744388 0.00119996 -0.02149999 0.02999997 0 -0.02249997 0.02899998 0.00119996 -0.01374995 0.02999997 0.00119996 -0.02149999 0.02999997 0.00119996 -0.01374995 0.02999997 0 -0.01274996 0.0324226 0 -0.01274996 0.0330953 0.00119996 -0.01274996 0.03099995 0.00119996 -0.0137763 0.03468096 0.00119996 -0.01396048 0.03656077 0 -0.01396048 0.03656077 0.00119996 -0.01326155 0.03831559 0 -0.01326155 0.03831559 0.00119996 -0.01027679 0.03993266 0 -0.01183539 0.03955399 0.00119996 -0.007249951 0.0330953 0.00119996 -0.006223738 0.03468096 0.00119996 -0.006957173 0.03354758 0 -0.006223738 0.03468096 0 -0.0060395 0.03656077 0.00119996 -0.006738364 0.03831559 0.00119996 -0.0060395 0.03656077 0 -0.008164525 0.03955399 0 -0.008164525 0.03955399 0.00119996 -0.00999999 0.03999996 0.00119996 -0.00999999 0.03999996 0 -0.007249951 0.03099995 0 -0.006249964 0.02999997 0 -0.007249951 0.03099995 0.00119996 -0.006249964 0.02999997 0.00119996 -0.007249951 -0.0330953 0.00119996 -0.006223738 -0.03468096 0.00119996 -0.0060395 -0.03656077 0.00119996 -0.006738364 -0.03831559 0.00119996 -0.006738364 -0.03831559 0 -0.008164525 -0.03955399 0.00119996 -0.00999999 -0.03999996 0.00119996 -0.01027679 -0.03993266 0 -0.01183539 -0.03955399 0 -0.01183539 -0.03955399 0.00119996 -0.01326155 -0.03831559 0 -0.01326155 -0.03831559 0.00119996 -0.01396048 -0.03656077 0.00119996 -0.01396048 -0.03656077 0 -0.0137763 -0.03468096 0.00119996 -0.0137763 -0.03468096 0 -0.01274996 -0.0330953 0.00119996 -0.01374995 -0.02999997 0.00119996 -0.02149999 -0.02999997 0.00119996 -0.02249997 -0.02899998 0.00119996 -0.02249997 -0.02744388 0.00119996 -0.02249997 -0.02744388 0 -0.02180749 -0.02571666 0.00119996 -0.02232038 -0.02651345 0.00119996 -0.01362079 -0.01714926 0 -0.003292202 -0.006340265 0.00119996 -0.001999974 -0.006858468 0.00119996 -0.001999974 -0.02699995 0.00119996 -0.001999974 -0.02637499 0 -0.006249964 -0.02999997 0.00119996 -0.004999995 -0.02999997 0.00119996 -0.006249964 -0.02999997 0 -0.004999995 -0.02999997 0 -0.007249951 -0.03099995 0.00119996 -0.01749998 -0.03499996 0.00119996 -0.01749998 -0.04099994 0.00119996 -0.01849997 -0.04199999 0 -0.02699995 -0.04199999 0.00119996 -0.02324998 -0.04199999 0 -0.01849997 -0.04199999 0.00119996 -0.02799999 -0.03499996 0.00119996 -0.02799999 -0.04099994 0.00119996 -0.01849997 -0.03399997 0.00119996 -0.02699995 -0.03399997 0.00119996 -0.032 -0.02799999 0.00119996 -0.032 -0.02799999 0 -0.037 -0.02799999 0.00119996 -0.037 -0.02999997 0.00119996 -0.032 -0.02999997 0.00119996 -0.01999998 -0.01699995 0 -0.01999998 -0.01699995 0.00119996 -0.01999998 0 0 -0.01999998 0.01699995 0.00119996 -0.02399998 0.01999998 0 -0.02399998 0.01999998 0.00119996 -0.02399998 -0.01714926 0 -0.02399998 -0.01999998 0.00119996 -0.01027679 -0.007859826 0 -0.003261387 -5.18143e-4 0.00119996 -0.003261387 -5.18143e-4 0 -0.01741665 -0.01389199 0.00119996 -0.01741665 -0.01389199 0 -0.01718527 -0.01415926 0.00119996 -0.01685714 -0.01429075 0.00119996 -0.01685714 -0.01429075 0 -0.0165053 -0.01425749 0.00119996 -0.01620775 -0.01406669 0.00119996 -0.01749998 0.01354849 0 -0.01749998 -0.01354849 0.00119996 -0.01620775 0.01406669 0.00119996 -0.0165053 0.01425749 0.00119996 -0.01685714 0.01429075 0.00119996 -0.01718527 0.01415926 0.00119996 -0.01741665 0.01389199 0.00119996 -0.01749998 0.01354849 0.00119996 -0.032 0.02999997 0.00119996 -0.037 0.02999997 0.00119996 -0.037 0.02799999 0.00119996 -0.032 0.02799999 0.00119996 -0.032 0.02799999 0 -0.04541748 -0.02987498 0.00119996 -0.04524999 -0.03049999 0.00119996 -0.04541748 -0.03112494 0 -0.04541748 -0.03112494 0.00119996 -0.04587495 -0.03158247 0.00119996 -0.04587495 -0.03158247 0 -0.04649996 -0.03174996 0 -0.04649996 -0.03174996 0.00119996 -0.04712498 -0.03158247 0.00119996 -0.04758244 -0.03112494 0.00119996 -0.04758244 -0.03112494 0 -0.04774999 -0.03049999 0 -0.04774999 -0.03049999 0.00119996 -0.04758244 -0.02987498 0.00119996 -0.04712498 -0.02941745 0 -0.04712498 -0.02941745 0.00119996 -0.04649996 -0.02924996 0 -0.04649996 -0.02924996 0.00119996 -0.04587495 -0.02941745 0.00119996 -0.04576385 -0.02952855 0 -0.04541748 -0.02987498 0 -0.04524999 -0.03049999 0 -0.04541748 0.03112494 0.00119996 -0.04524999 0.03049999 0 -0.04524999 0.03049999 0.00119996 -0.04541748 0.02987498 0.00119996 -0.04587495 0.02941745 0 -0.04587495 0.02941745 0.00119996 -0.04649996 0.02924996 0.00119996 -0.04649996 0.02924996 0 -0.04712498 0.02941745 0.00119996 -0.04774999 0.03049999 0 -0.04758244 0.02987498 0.00119996 -0.04774999 0.03049999 0.00119996 -0.04758244 0.03112494 0.00119996 -0.04712498 0.03158247 0 -0.04712498 0.03158247 0.00119996 -0.04649996 0.03174996 0.00119996 -0.04587495 0.03158247 0 -0.04587495 0.03158247 0.00119996 -0.04576385 0.03147137 0 -0.04541748 0.03112494 0 -0.04524999 -0.03749996 0.00119996 -0.04541748 -0.03812497 0.00119996 -0.04541748 -0.03812497 0 -0.04587495 -0.0385825 0.00119996 -0.04649996 -0.03874999 0.00119996 -0.04712498 -0.0385825 0.00119996 -0.04712498 -0.0385825 0 -0.04758244 -0.03812497 0 -0.04758244 -0.03812497 0.00119996 -0.04774999 -0.03749996 0.00119996 -0.04758244 -0.03687494 0.00119996 -0.04712498 -0.03641748 0.00119996 -0.04587495 -0.03641748 0 -0.04649996 -0.03624999 0.00119996 -0.04587495 -0.03641748 0.00119996 -0.04541748 -0.03687494 0.00119996 -0.04524999 -0.03749996 0 -0.04524999 0.03749996 0.00119996 -0.04541748 0.03687494 0.00119996 -0.04587495 0.03641748 0 -0.04587495 0.03641748 0.00119996 -0.04649996 0.03624999 0.00119996 -0.04712498 0.03641748 0.00119996 -0.04774999 0.03749996 0 -0.04758244 0.03687494 0.00119996 -0.04774999 0.03749996 0.00119996 -0.04758244 0.03812497 0.00119996 -0.04712498 0.0385825 0.00119996 -0.04712498 0.0385825 0 -0.04649996 0.03874999 0 -0.04649996 0.03874999 0.00119996 -0.04587495 0.0385825 0.00119996 -0.04541748 0.03812497 0.00119996 -0.01849997 0.04199999 0 -0.01849997 0.04199999 0.00119996 -0.02699995 0.04199999 0.00119996 -0.01749998 0.03499996 0.00119996 -0.01749998 0.04099994 0.00119996 -0.02699995 0.03399997 0 -0.02699995 0.03399997 0.00119996 -0.01849997 0.03399997 0.00119996 -0.01849997 0.03399997 0 -0.02799999 0.03499996 0 -0.02799999 0.03499996 0.00119996 -0.02799999 0.04099994 0.00119996 -0.02849996 -0.01714926 0 -0.02849996 0 0 -0.02849996 0.01999998 0.00119996 -0.03024995 0.01999998 0 -0.02849996 0.01999998 0 -0.04199999 0.01999998 0 -0.04199999 0 0 -0.04199999 0.01999998 0.00119996 -0.04199999 -0.01999998 0.00119996 -0.02849996 -0.01999998 0.00119996 0.01849997 0.03399997 0.00119996 0.02699995 0.03399997 0.00119996 0.02799999 0.03499996 0.00119996 0.02799999 0.04099994 0.00119996 0.02799999 0.04099994 0 0.02749997 0.04149997 0 0.02324998 0.04199999 0 0.02699995 0.04199999 0.00119996 0.01849997 0.04199999 0.00119996 0.01849997 0.04199999 0 0.01749998 0.04099994 0.00119996 0.01749998 0.03499996 0 0.01749998 0.03499996 0.00119996 0.04541748 -0.03112494 0.00119996 0.04524999 -0.03049999 0.00119996 0.04541748 -0.02987498 0 0.04541748 -0.02987498 0.00119996 0.04587495 -0.02941745 0.00119996 0.04587495 -0.02941745 0 0.04649996 -0.02924996 0 0.04649996 -0.02924996 0.00119996 0.04712498 -0.02941745 0.00119996 0.04758244 -0.02987498 0.00119996 0.04758244 -0.02987498 0 0.04774999 -0.03049999 0.00119996 0.04758244 -0.03112494 0.00119996 0.04758244 -0.03112494 0 0.04712498 -0.03158247 0.00119996 0.04649996 -0.03174996 0 0.04649996 -0.03174996 0.00119996 0.04587495 -0.03158247 0.00119996 0.04541748 -0.03112494 0 0.01999998 0 0 0.01999998 0.01699995 0.00119996 0.01999998 -0.01699995 0.00119996 0.02399998 -0.01999998 0.00119996 0.02399998 0.01999998 0.00119996 0.01749998 -0.04099994 0.00119996 0.01749998 -0.03499996 0.00119996 0.02699995 -0.03399997 0 0.02324998 -0.03399997 0 0.02699995 -0.03399997 0.00119996 0.01849997 -0.03399997 0.00119996 0.02799999 -0.04099994 0 0.02799999 -0.03499996 0.00119996 0.02749997 -0.04149997 0 0.02699995 -0.04199999 0.00119996 0.02799999 -0.04099994 0.00119996 0.01849997 -0.04199999 0.00119996 0.02324998 -0.04199999 0 0.02699995 -0.04199999 0 0.003292202 0.006340265 0.00119996 0.02180749 0.02571666 0.00119996 0.001999974 0.02637499 0 0.001999974 0.02699995 0.00119996 0.001999974 0.006858468 0.00119996 0.001999974 0.006858468 0 0.006249964 0.02999997 0 0.007249951 0.03099995 0 0.006249964 0.02999997 0.00119996 0.007249951 0.03099995 0.00119996 0.007249951 0.0330953 0.00119996 0.007249951 0.0330953 0 0.006957173 0.03354758 0 0.006223738 0.03468096 0.00119996 0.006223738 0.03468096 0 0.0060395 0.03656077 0 0.0060395 0.03656077 0.00119996 0.006738364 0.03831559 0.00119996 0.008164525 0.03955399 0.00119996 0.00999999 0.03999996 0.00119996 0.01274996 0.0330953 0.00119996 0.0137763 0.03468096 0.00119996 0.0137763 0.03468096 0 0.01396048 0.03656077 0.00119996 0.01326155 0.03831559 0.00119996 0.01183539 0.03955399 0 0.01183539 0.03955399 0.00119996 0.01274996 0.03099995 0.00119996 0.01274996 0.0324226 0 0.01274996 0.0330953 0 0.01374995 0.02999997 0.00119996 0.02149999 0.02999997 0.00119996 -0.05099999 -0.0312286 0.00119996 -0.05099999 -0.04524999 0 -0.05099999 -0.04547345 0.00119996 -0.0521636 -0.04759895 0 -0.05099999 -0.04547345 0 -0.0521636 -0.04759895 0.00119996 -0.05276739 -0.04967749 0.00119996 -0.05243617 -0.0518164 0 -0.05243617 -0.0518164 0.00119996 -0.05147635 -0.05324995 0 -0.05123209 -0.05361497 0.00119996 -0.04517996 -0.05427217 0 -0.04517996 -0.05427217 0.00119996 -0.04576385 -0.05447095 0 -0.04722887 -0.05496978 0.00119996 -0.04722887 -0.05496978 0 -0.04938066 -0.05473607 0.00119996 -0.05123209 -0.05361497 0 -0.02993106 -0.04499995 0 -0.03024995 -0.04519385 0 -0.002776801 -0.04499995 0 -0.02993106 -0.04499995 0.00119996 0 -0.04499995 0 0.02324998 -0.04499995 0 0.02993106 -0.04499995 0.00119996 0.04517996 -0.05427217 0.00119996 0.04938066 -0.05473607 0.00119996 0.04722887 -0.05496978 0.00119996 0.04517996 -0.05427217 0 0.05123209 -0.05361497 0 0.05123209 -0.05361497 0.00119996 0.05147635 -0.05324995 0 0.05243617 -0.0518164 0 0.05243617 -0.0518164 0.00119996 0.05276739 -0.04967749 0 0.05276739 -0.04967749 0.00119996 0.0521636 -0.04759895 0 0.0521636 -0.04759895 0.00119996 0.05099999 -0.04547345 0.00119996 0.05099999 -0.04099994 0 0.05099999 -0.0324226 0 0.05099999 -0.0312286 0.00119996 0.05099999 -0.0312286 0 0.04799997 -0.02822858 0.00119996 0.04799997 -0.02822858 0 0.04449999 -0.02822858 0.00119996 0.04576385 -0.02822858 0 0.04399996 -0.02736246 0 0.04399996 -0.02736246 0.00119996 0.04399996 0 0 0.04399996 0.02736246 0.00119996 0.04399996 0.02736246 0 0.04381698 0.02754557 0.00119996 0.04374998 0.02779555 0.00119996 0.04381698 0.02804559 0.00119996 0.04399996 0.02822858 0.00119996 0.04424995 0.02829557 0.00119996 0.04799997 0.02822858 0.00119996 0.04449999 0.02822858 0.00119996 0.05099999 0.0312286 0.00119996 0.05099999 0.0312286 0 0.05099999 0.03354758 0 0.05099999 0.04099994 0 0.05099999 0.04547345 0.00119996 0.0521636 0.04759895 0 0.0521636 0.04759895 0.00119996 0.05276739 0.04967749 0.00119996 0.05243617 0.0518164 0 0.05243617 0.0518164 0.00119996 0.05123209 0.05361497 0.00119996 0.04938066 0.05473607 0 0.04938066 0.05473607 0.00119996 0.04576385 0.05447095 0 0.04722887 0.05496978 0 0.04722887 0.05496978 0.00119996 0.04851388 0.05483019 0 0.03949999 0.05081838 0 0.02993106 0.04499995 0.00119996 0.04517996 0.05427217 0.00119996 0.02749997 0.04499995 0 -0.002776801 0.04499995 0 -0.02324998 0.04499995 0 -0.02993106 0.04499995 0.00119996 -0.04362499 0.05332666 0 -0.04517996 0.05427217 0.00119996 -0.04576385 0.05447095 0 -0.04722887 0.05496978 0.00119996 -0.04722887 0.05496978 0 -0.04938066 0.05473607 0.00119996 -0.05123209 0.05361497 0.00119996 -0.05243617 0.0518164 0 -0.05243617 0.0518164 0.00119996 -0.05276739 0.04967749 0 -0.05276739 0.04967749 0.00119996 -0.0521636 0.04759895 0 -0.0521636 0.04759895 0.00119996 -0.05099999 0.04547345 0 -0.05099999 0.04547345 0.00119996 -0.05099999 0.0312286 0.00119996 -0.04799997 0.02822858 0.00119996 -0.04449999 0.02822858 0.00119996 -0.04406726 0.028261 0 -0.04428738 0.0282942 0.00119996 -0.04406726 0.028261 0.00119996 -0.0438835 0.02813559 0 -0.04377216 0.02794289 0 -0.0438835 0.02813559 0.00119996 -0.04377216 0.02794289 0.00119996 -0.04375559 0.02772098 0 -0.04375559 0.02772098 0.00119996 -0.04383689 0.02751386 0 -0.04383689 0.02751386 0.00119996 -0.04399996 0.02736246 0.00119996 -0.04399996 -0.02736246 0.00119996 -0.04399996 0.02637499 0 -0.04399996 0 0 -0.04799997 -0.02822858 0.00119996 -0.04576385 -0.02822858 0 -0.04449999 -0.02822858 0.00119996 -0.04449999 -0.02822858 0 0.001999974 -0.006858468 0 0.001999974 -0.01714926 0 0.001999974 -0.006858468 0.00119996 0.001999974 -0.02637499 0 0.001999974 -0.02699995 0.00119996 0.01027679 -0.01364976 0 0.003292202 -0.006340265 0.00119996 0.02232038 -0.02651345 0 0.02249997 -0.02744388 0 0.02232038 -0.02651345 0.00119996 0.02180749 -0.02571666 0.00119996 0.02180749 -0.02571666 0 0.02249997 -0.02744388 0.00119996 0.02249997 -0.02899998 0.00119996 0.02149999 -0.02999997 0.00119996 0.01374995 -0.02999997 0.00119996 0.01274996 -0.0330953 0.00119996 0.0137763 -0.03468096 0.00119996 0.01396048 -0.03656077 0.00119996 0.01326155 -0.03831559 0 0.01326155 -0.03831559 0.00119996 0.01183539 -0.03955399 0 0.01183539 -0.03955399 0.00119996 0.01027679 -0.03993266 0 0.00999999 -0.03999996 0.00119996 0.008164525 -0.03955399 0 0.006738364 -0.03831559 0 0.008164525 -0.03955399 0.00119996 0.006738364 -0.03831559 0.00119996 0.0060395 -0.03656077 0 0.0060395 -0.03656077 0.00119996 0.006223738 -0.03468096 0 0.006223738 -0.03468096 0.00119996 0.007249951 -0.0330953 0 0.007249951 -0.0330953 0.00119996 0.007249951 -0.03099995 0 0.007249951 -0.03099995 0.00119996 0.006249964 -0.02999997 0 0.006249964 -0.02999997 0.00119996 0.004999995 -0.02999997 0.00119996 0.037 -0.02799999 0.00119996 0.032 -0.02799999 0.00119996 0.037 -0.02799999 0 0.032 -0.02799999 0 0.032 -0.02999997 0.00119996 0.037 -0.02999997 0.00119996 0.032 -0.02999997 0 0.003077745 1.88622e-4 0.00119996 0.003261387 5.18143e-4 0.00119996 0.003077745 0 0 0.003077745 -1.88622e-4 0.00119996 0.003077745 -1.88622e-4 0 0.003261387 -5.18143e-4 0.00119996 0.01749998 0.01354849 0.00119996 0.01741665 0.01389199 0.00119996 0.01718527 0.01415926 0 0.01718527 0.01415926 0.00119996 0.01685714 0.01429075 0.00119996 0.01685714 0.01429075 0 0.0165053 0.01425749 0.00119996 0.01620775 0.01406669 0.00119996 0.01749998 -0.01354849 0.00119996 0.037 0.02999997 0.00119996 0.032 0.02999997 0.00119996 0.032 0.02799999 0.00119996 0.037 0.02799999 0.00119996 0.04524999 0.03049999 0 0.04541748 0.03112494 0 0.04524999 0.03049999 0.00119996 0.04541748 0.03112494 0.00119996 0.04587495 0.03158247 0.00119996 0.04587495 0.03158247 0 0.04712498 0.03158247 0 0.04649996 0.03174996 0.00119996 0.04712498 0.03158247 0.00119996 0.04758244 0.03112494 0.00119996 0.04774999 0.03049999 0.00119996 0.04758244 0.02987498 0 0.04712498 0.02941745 0 0.04758244 0.02987498 0.00119996 0.04712498 0.02941745 0.00119996 0.04649996 0.02924996 0.00119996 0.04587495 0.02941745 0.00119996 0.04541748 0.02987498 0.00119996 0.04199999 -0.01999998 0 0.04199999 -0.01714926 0 0.04199999 -0.01999998 0.00119996 0.04199999 0 0 0.04199999 0.01999998 0.00119996 0.02849996 0.01999998 0 0.02849996 0.01999998 0.00119996 0.02849996 -0.01999998 0.00119996 0.02849996 0 0 0.002499997 -0.04099994 0.00119996 0.002499997 -0.04099994 0 0.002499997 -0.03409528 0.00119996 0 -0.04199999 0 -0.00149995 -0.04199999 0.00119996 0.00149995 -0.04199999 0.00119996 -0.002499997 -0.04099994 0.00119996 -0.002499997 -0.03409528 0.00119996 0 -0.0330953 0 0.00149995 -0.0330953 0.00119996 -0.00149995 -0.0330953 0.00119996 0.002499997 0.03409528 0.00119996 0.002499997 0.04099994 0.00119996 -0.00149995 0.0330953 0.00119996 0.00149995 0.0330953 0.00119996 -0.002499997 0.03409528 0.00119996 -0.002499997 0.04099994 0.00119996 0.00149995 0.04199999 0.00119996 0 0.04199999 0 -0.00149995 0.04199999 0.00119996 -0.00149995 0.0330953 0 0.03949999 -0.05081838 0 -0.04362499 -0.04524999 0 0.00149995 0.0330953 0 0.01374995 0.02999997 0 0.01274996 0.03099995 0 0.04576385 -0.03147137 0 0.02799999 0.03499996 0 -0.04399996 -0.02736246 0 -0.001999974 0.02699995 0 -0.002776801 0.02777677 0 -0.004999995 0.02999997 0 -0.002776801 0 0 -0.003077745 0 0 -0.01027679 0.007859826 0 -0.003261387 5.18143e-4 0 -0.003292202 0.006340265 0 -0.003077745 1.88622e-4 0 -0.002994656 0.00614947 0 -0.002776801 0.006128847 0 -0.00264275 0.006116151 0 -0.002314686 0.006247699 0 -0.002083241 0.006514906 0 -0.023 0.01999998 0 -0.02180749 0.02571666 0 -0.01620775 0.01406669 0 -0.01027679 0.01364976 0 -0.01999998 0.01699995 0 -0.0165053 0.01425749 0 -0.01685714 0.01429075 0 -0.01718527 0.01415926 0 -0.02232038 0.02651345 0 -0.02324998 0.0324226 0 -0.02249997 0.02899998 0 -0.01274996 0.03099995 0 -0.01749998 0.03499996 0 -0.01183539 0.03955399 0 -0.0137763 0.03468096 0 -0.007249951 0.0324226 0 -0.006223738 -0.03468096 0 -0.0060395 -0.03656077 0 -0.002776801 -0.04099994 0 -0.008164525 -0.03955399 0 -0.01027679 -0.04099994 0 -0.01749998 -0.03499996 0 -0.02149999 -0.02999997 0 -0.01374995 -0.02999997 0 -0.01274996 -0.03099995 0 -0.02249997 -0.02899998 0 -0.02223128 -0.02637499 0 -0.02232038 -0.02651345 0 -0.01718527 -0.01415926 0 -0.01741665 0.01389199 0 -0.01749998 0 0 -0.01749998 -0.01354849 0 -0.003077745 -1.88622e-4 0 -0.002776801 -0.006128847 0 -0.0165053 -0.01425749 0 -0.01620775 -0.01406669 0 -0.01027679 -0.01364976 0 -0.003292202 -0.006340265 0 -0.002994656 -0.00614947 0 -0.002083241 -0.006514906 0 -0.002314686 -0.006247699 0 -0.00264275 -0.006116151 0 -0.001999974 -0.006858468 0 -0.001999974 -0.01714926 0 -0.007249951 -0.0324226 0 -0.007249951 -0.0330953 0 0 -0.02637499 0 -0.001999974 -0.02699995 0 -0.002776801 -0.02777677 0 0 -0.0324226 0 -0.002776801 -0.0324226 0 -0.007249951 -0.03099995 0 -0.01749998 -0.04099994 0 -0.02324998 -0.04499995 0 -0.02699995 -0.04199999 0 -0.02799999 -0.04099994 0 -0.02824997 -0.04099994 0 -0.01274996 -0.0330953 0 -0.01274996 -0.0324226 0 -0.01849997 -0.03399997 0 -0.02324998 -0.03399997 0 -0.02324998 -0.0324226 0 -0.02699995 -0.03399997 0 -0.02824997 -0.01714926 0 -0.02420097 -0.02399998 0 -0.02420097 -0.02249997 0 -0.02474999 -0.02195096 0 -0.02324998 -0.01999998 0 -0.02625 -0.02195096 0 -0.02679896 -0.02249997 0 -0.02699995 -0.02324998 0 -0.02679896 -0.02399998 0 -0.02824997 -0.02637499 0 -0.02625 -0.02454894 0 -0.02549999 -0.02474999 0 -0.02474999 -0.02454894 0 -0.02324998 -0.02637499 0 -0.02399998 -0.02324998 0 -0.02180749 -0.02571666 0 -0.023 -0.01999998 0 -0.02014929 -0.01714926 0 -0.02625 0.02454894 0 -0.02474999 0.02195096 0 -0.02549999 0.02174997 0 -0.02679896 0.02399998 0 -0.02699995 0.02324998 0 -0.02824997 0 0 -0.02679896 0.02249997 0 -0.02399998 -0.01999998 0 -0.02549999 -0.02174997 0 -0.02399998 0 0 -0.02625 0.02195096 0 -0.02420097 0.02249997 0 -0.02324998 0.01999998 0 -0.02399998 0.02324998 0 -0.02324998 0.02637499 0 -0.02420097 0.02399998 0 -0.02474999 0.02454894 0 -0.04758244 -0.02987498 0 -0.05099999 -0.0312286 0 -0.04712498 -0.03158247 0 -0.04799997 -0.02822858 0 -0.04576385 -0.0324226 0 -0.04399996 -0.02822858 0 -0.04587495 -0.02941745 0 -0.04381698 -0.02804559 0 -0.04362499 -0.0324226 0 -0.04374998 -0.02779555 0 -0.04381698 -0.02754557 0 -0.04576385 -0.03147137 0 -0.04424995 -0.02829557 0 -0.04649996 0.03174996 0 -0.05099999 0.0324226 0 -0.05099999 0.0312286 0 -0.04758244 0.03112494 0 -0.04712498 0.02941745 0 -0.04799997 0.02822858 0 -0.04758244 0.02987498 0 -0.04576385 0.02822858 0 -0.04576385 0.02952855 0 -0.04449999 0.02822858 0 -0.04428738 0.0282942 0 -0.04541748 0.02987498 0 -0.04576385 -0.03652858 0 -0.05099999 -0.0324226 0 -0.04649996 -0.03874999 0 -0.04587495 -0.0385825 0 -0.04649996 -0.03624999 0 -0.04712498 -0.03641748 0 -0.04758244 -0.03687494 0 -0.04774999 -0.03749996 0 -0.04541748 -0.03687494 0 -0.04541748 0.03812497 0 -0.04576385 0.0384714 0 -0.04587495 0.0385825 0 -0.04758244 0.03812497 0 -0.04758244 0.03687494 0 -0.04649996 0.03624999 0 -0.04576385 0.03354758 0 -0.04576385 0.03652858 0 -0.04541748 0.03687494 0 -0.01749998 0.04099994 0 -0.02824997 0.04499995 0 -0.02324998 0.03399997 0 -0.02699995 0.04199999 0 -0.02799999 0.04099994 0 -0.02824997 0.04099994 0 -0.04199999 -0.01999998 0 -0.04362499 -0.01714926 0 -0.04199999 -0.01714926 0 -0.04362499 0 0 -0.03024995 0.02637499 0 -0.03024995 -0.01999998 0 0.02324998 0.03399997 0 0.02699995 0.03399997 0 0.02749997 0.03354758 0 0.01027679 0.03993266 0 0.02699995 0.04199999 0 0.02324998 0.04499995 0 0.01027679 0.04499995 0 0.01396048 0.03656077 0 0.01326155 0.03831559 0 0.01749998 0.04099994 0 0.04576385 -0.0384714 0 0.04587495 -0.0385825 0 0.04851388 -0.04099994 0 0.04649996 -0.03874999 0 0.04712498 -0.0385825 0 0.04758244 -0.03812497 0 0.04774999 -0.03749996 0 0.04712498 -0.03641748 0 0.04758244 -0.03687494 0 0.04649996 -0.03624999 0 0.04587495 -0.03641748 0 0.04576385 -0.03652858 0 0.04576385 -0.0324226 0 0.04541748 -0.03687494 0 0.03949999 -0.04099994 0 0.04541748 -0.03812497 0 0.04587495 -0.03158247 0 0.04712498 -0.03158247 0 0.04774999 -0.03049999 0 0.04712498 -0.02941745 0 0.04399996 -0.02637499 0 0.04381698 -0.02754557 0 0.04374998 -0.02779555 0 0.03949999 -0.02637499 0 0.04381698 -0.02804559 0 0.04399996 -0.02822858 0 0.04424995 -0.02829557 0 0.04576385 -0.02952855 0 0.04449999 -0.02822858 0 0.04524999 -0.03049999 0 0.02625 -0.02454894 0 0.02549999 -0.02474999 0 0.02474999 -0.02454894 0 0.02749997 -0.02637499 0 0.02679896 -0.02399998 0 0.02699995 -0.02324998 0 0.02749997 -0.01714926 0 0.02679896 -0.02249997 0 0.02420097 -0.02249997 0 0.02223128 -0.02637499 0 0.02014929 -0.01714926 0 0.023 -0.01999998 0 0.02399998 -0.02324998 0 0.02420097 -0.02399998 0 0.01362079 -0.01714926 0 0.0165053 -0.01425749 0 0.01999998 -0.01699995 0 0.01685714 -0.01429075 0 0.01999998 0.01699995 0 0.023 0.01999998 0 0.02180749 0.02571666 0 0.01718527 -0.01415926 0 0.01741665 -0.01389199 0 0.01749998 -0.01354849 0 0.01749998 0 0 0.01749998 0.01354849 0 0.01741665 0.01389199 0 0.02549999 0.02474999 0 0.02549999 0.02174997 0 0.02399998 0 0 0.02474999 0.02195096 0 0.02399998 0.01999998 0 0.02420097 0.02249997 0 0.02399998 0.02324998 0 0.02324998 0.01999998 0 0.02420097 0.02399998 0 0.02474999 0.02454894 0 0.02625 0.02195096 0 0.02749997 0 0 0.02679896 0.02249997 0 0.02699995 0.02324998 0 0.02679896 0.02399998 0 0.02625 0.02454894 0 0.02474999 -0.02195096 0 0.02324998 -0.01999998 0 0.02549999 -0.02174997 0 0.02399998 -0.01999998 0 0.02625 -0.02195096 0 0.02399998 -0.01714926 0 0.01749998 -0.03499996 0 0.01396048 -0.03656077 0 0.02749997 -0.0345 0 0.02824997 -0.04099994 0 0.01027679 -0.04099994 0 0.01749998 -0.04099994 0 0.01027679 -0.04499995 0 0.01849997 -0.04199999 0 0.02749997 -0.04499995 0 0.02324998 0.02637499 0 0.02249997 0.02744388 0 0.02324998 0.0324226 0 0.02249997 0.02899998 0 0.02149999 0.02999997 0 0.002083241 0.006514906 0 0.002314686 0.006247699 0 0.00264275 0.006116151 0 0.0165053 0.01425749 0 0.01620775 0.01406669 0 0.01027679 0.01364976 0 0.003292202 0.006340265 0 0.01027679 0.007859826 0 0.003261387 5.18143e-4 0 0.002994656 0.00614947 0 0.004999995 0.02999997 0 0.001999974 0.02699995 0 0.007249951 0.0324226 0 0 0.0324226 0 0 0.0330953 0 0.00195235 0.03354758 0 0.008164525 0.03955399 0 0.002499997 0.04099994 0 0.006738364 0.03831559 0 0.002499997 0.03409528 0 0.01304274 0.03354758 0 0.02324998 0.03354758 0 0.04851388 -0.04869717 0 0.04852777 -0.04870098 0 0.04702776 -0.04870098 0 0.04647868 -0.04924994 0 0.04576385 -0.04524999 0 0.04627776 -0.04999995 0 0.04647868 -0.05074995 0 0.04576385 -0.05324995 0 -0.04777777 -0.05149996 0 -0.04702776 -0.04870098 0 -0.04576385 -0.04099994 0 -0.05099999 -0.04099994 0 -0.04777777 -0.0485 0 -0.04852777 -0.05129897 0 -0.04907679 -0.05074995 0 -0.04927778 -0.04999995 0 -0.05276739 -0.04967749 0 -0.04907679 -0.04924994 0 -0.04852777 -0.04870098 0 -0.04702776 -0.05129897 0 -0.04647868 -0.05074995 0 -0.04627776 -0.04999995 0 -0.04576385 -0.04524999 0 -0.04647868 -0.04924994 0 -0.04576385 -0.05324995 0 -0.04938066 -0.05473607 0 -0.03024995 -0.04099994 0 -0.04349887 -0.05324995 0 -0.03034228 -0.04524999 0 -0.02824997 -0.04499995 0 -0.00999999 -0.03999996 0 -0.01027679 -0.04499995 0 0.04349887 -0.05324995 0 0.04576385 -0.05447095 0 0.04722887 -0.05496978 0 0.04851388 -0.05483019 0 0.04938066 -0.05473607 0 0.04851388 -0.0324226 0 0.04851388 -0.02874249 0 0.04199999 0.01999998 0 0.04449999 0.02822858 0 0.04424995 0.02829557 0 0.04541748 0.02987498 0 0.04399996 0.02822858 0 0.03949999 0.0324226 0 0.04576385 0.03147137 0 0.04399996 0.02637499 0 0.04381698 0.02754557 0 0.04374998 0.02779555 0 0.04381698 0.02804559 0 0.04576385 0.02952855 0 0.04576385 0.02822858 0 0.04587495 0.02941745 0 0.04649996 0.02924996 0 0.04799997 0.02822858 0 0.04774999 0.03049999 0 0.04851388 0.0324226 0 0.04758244 0.03112494 0 0.04576385 0.0324226 0 0.04649996 0.03174996 0 0.04777777 0.05149996 0 0.04851388 0.05130279 0 0.04702776 0.05129897 0 0.04647868 0.05074995 0 0.04627776 0.04999995 0 0.04647868 0.04924994 0 0.04852777 0.05129897 0 0.05123209 0.05361497 0 0.04907679 0.05074995 0 0.04927778 0.04999995 0 0.05276739 0.04967749 0 0.04907679 0.04924994 0 0.04852777 0.04870098 0 0.05099999 0.04547345 0 0.04851388 0.04869717 0 0.04777777 0.0485 0 0.04517996 0.05427217 0 0.02993106 0.04499995 0 0.02824997 0.04499995 0 -0.006738364 0.03831559 0 -0.002776801 0.04099994 0 -0.01027679 0.04099994 0 -0.01027679 0.04499995 0 -0.02324998 0.04199999 0 -0.02993106 0.04499995 0 -0.04362499 0.04099994 0 -0.03024995 0.04519385 0 -0.04702776 0.04870098 0 -0.04576385 0.04099994 0 -0.04647868 0.04924994 0 -0.04517996 0.05427217 0 -0.04627776 0.04999995 0 -0.04647868 0.05074995 0 -0.04702776 0.05129897 0 -0.04777777 0.05149996 0 -0.04938066 0.05473607 0 -0.04852777 0.05129897 0 -0.04852777 0.04870098 0 -0.04907679 0.04924994 0 -0.04927778 0.04999995 0 -0.04907679 0.05074995 0 -0.05123209 0.05361497 0 -0.04777777 0.0485 0 -0.05099999 0.04099994 0 -0.04362499 -0.02637499 0 -0.04399996 -0.02637499 0 -0.04399996 -0.01714926 0 -0.04362499 0.02637499 0 -0.04399996 0.02736246 0 0.004999995 -0.02999997 0 0.001999974 -0.02699995 0 0 0 0 0.003077745 1.88622e-4 0 0.01620775 -0.01406669 0 0.01027679 -0.007859826 0 0 -0.01714926 0 0.002083241 -0.006514906 0 0.003292202 -0.006340265 0 0.003261387 -5.18143e-4 0 0.002994656 -0.00614947 0 0.00264275 -0.006116151 0 0.002314686 -0.006247699 0 0.01274996 -0.03099995 0 0.0137763 -0.03468096 0 0.01849997 -0.03399997 0 0.01274996 -0.0330953 0 0.01274996 -0.0324226 0 0.01374995 -0.02999997 0 0.02324998 -0.0324226 0 0.02149999 -0.02999997 0 0.002499997 -0.03409528 0 0.00999999 -0.03999996 0 0.04702776 0.04870098 0 0.04851388 0.04099994 0 0.04712498 0.03641748 0 0.04851388 0.03354758 0 0.04576385 0.03354758 0 0.04649996 0.03624999 0 0.04758244 0.03687494 0 0.04774999 0.03749996 0 0.04758244 0.03812497 0 0.04712498 0.0385825 0 0.04541748 0.03687494 0 0.04576385 0.03652858 0 0.04587495 0.03641748 0 0.04649996 0.03874999 0 0.04587495 0.0385825 0 0.04576385 0.0384714 0 0.04576385 0.04099994 0 0.03949999 0.04099994 0 0.04541748 0.03812497 0 0.04524999 0.03749996 0 0.02849996 -0.01714926 0 0.02849996 -0.01999998 0 0.04399996 -0.01714926 0 0.03949999 -0.01999998 0 0.02824997 -0.01714926 0 0.03949999 0.01999998 0 0.02824997 0.02637499 0 0.02824997 0 0 0.007249951 -0.0324226 0 0.00149995 -0.0330953 0 0.00149995 -0.04199999 0 -0.00149995 -0.04199999 0 0 -0.04499995 0 -0.002499997 -0.04099994 0 -0.002499997 -0.03409528 0 -0.00149995 -0.0330953 0 -0.002776801 0.03354758 0 -0.007249951 0.0330953 0 -0.002776801 0.0324226 0 0 0.02637499 0 0.00999999 0.03999996 0 0.01027679 0.04099994 0 0.00149995 0.04199999 0 0 0.04499995 0 -0.00149995 0.04199999 0 -0.002499997 0.04099994 0 -0.002499997 0.03409528 0 -0.00195235 0.03354758 0 0.04702776 -0.05129897 0 0.04851388 -0.05130279 0 0.04851388 -0.05324995 0 0.04852777 -0.05129897 0 0.04907679 -0.05074995 0 0.04927778 -0.04999995 0 0.04907679 -0.04924994 0 0.05099999 -0.04547345 0 0.05099999 -0.04524999 0 0.04851388 -0.04524999 0 0.04576385 -0.04099994 0 0.03949999 -0.04524999 0 0.03034228 -0.04524999 0 0.02993106 -0.04499995 0 0.02824997 -0.04499995 0 0.02824997 0.03354758 0 0.02824997 0.04099994 0 0.05099999 0.0324226 0 0.04851388 0.02874249 0 0.03949999 0.03354758 0 0.02824997 0.0324226 0 0.037 0.02999997 0 0.037 0.02799999 0 0.03949999 0.02637499 0 0.032 0.02799999 0 0.032 0.02999997 0 0.037 -0.02999997 0 0.02799999 -0.03499996 0 0.03949999 -0.0324226 0 0.04524999 -0.03749996 0 0.02749997 0.02637499 0 0.02749997 0.0324226 0 0.02749997 0.0345 0 0.01849997 0.03399997 0 0.02249997 -0.02899998 0 0.02324998 -0.02637499 0 0.02749997 -0.0324226 0 0.02824997 -0.02637499 0 0.02824997 -0.0324226 0 -0.02549999 0.02474999 0 -0.02824997 0.02637499 0 -0.02849996 -0.01999998 0 -0.02824997 0.0324226 0 -0.03024995 0.0324226 0 -0.02824997 -0.0324226 0 -0.04524999 0.03749996 0 -0.03024995 0.04099994 0 -0.02824997 0.03354758 0 -0.037 0.02799999 0 -0.037 0.02999997 0 -0.032 0.02999997 0 -0.04362499 0.0324226 0 -0.037 -0.02999997 0 -0.03024995 -0.02637499 0 -0.032 -0.02999997 0 -0.037 -0.02799999 0 -0.03024995 -0.0324226 0 -0.02799999 -0.03499996 0 -0.05099999 0.03354758 0 -0.04712498 0.03641748 0 -0.04576385 0.0324226 0 -0.04362499 0.03354758 0 -0.03024995 0.03354758 0 -0.02324998 0.03354758 0 -0.01304274 0.03354758 0 -0.01274996 0.0330953 0 -0.04362499 -0.05324995 0 -0.04362499 -0.05332666 0 -0.04362499 -0.04099994 0 -0.04576385 -0.0384714 0 0.02249997 0.02899998 0.00119996 0.02223128 0.02637499 0 0.02232038 0.02651345 0.00119996 0.02232038 0.02651345 0 0.02249997 0.02744388 0.00119996 0.07395756 -0.110574 -0.0703299 0.07309156 -0.1122519 -0.069938 0.07309156 -0.110824 -0.07076299 0.07309156 -0.112752 -0.07080399 0.07345759 -0.1115069 -0.07194596 0.07395756 -0.111574 -0.07206195 0.07445758 -0.112936 -0.07112097 0.07445758 -0.1115069 -0.07194596 0.07482355 -0.112752 -0.07080399 0.07482355 -0.110824 -0.07076299 0.05096828 -0.06316035 0.01179206 0.08037215 -0.113416 -0.07195258 0.08037215 -0.111987 -0.07277756 0.08035326 -0.112203 -0.07315218 0.0801534 -0.112395 -0.07348465 0.0801534 -0.113824 -0.07265967 0.07980996 -0.113956 -0.07288789 0.07938736 -0.114002 -0.07296895 0.06290948 -0.06420385 0.01328456 0.06255608 -0.06405568 0.0135414 0.08035326 -0.113632 -0.07232719 0.05908244 -0.06543999 0.01114368 0.05924999 -0.0657525 0.01060235 0.05737495 -0.06521117 0.01153987 0.05799996 -0.06512749 0.01168489 0.05195307 -0.06400245 0.01363348 0.05862498 -0.06521117 0.01153987 0.05908244 -0.06843996 0.00594747 0.06210726 -0.06400245 0.01363348 0.05799996 -0.06812745 0.00648874 0.05908244 -0.06906497 0.004864931 0.07395756 -0.112002 -0.06950485 0.07395756 -0.113003 -0.07123696 0.06923305 -0.114002 -0.07296895 0.07345759 -0.112936 -0.07112097 0.06878429 -0.113949 -0.07287687 0.06843096 -0.113801 -0.07262015 0.05862498 -0.06629377 0.009664893 0.05737495 -0.06821119 0.006343722 0.05096828 -0.06458926 0.01261705 0.05118697 -0.06418108 0.01332408 0.05098706 -0.06437307 0.01299154 0.06309205 -0.06441569 0.01291787 0.07445758 -0.112069 -0.06962096 0.07482355 -0.1122519 -0.069938 0.0749576 -0.112503 -0.07037097 0.05153048 -0.0640493 0.01355236 0.07295757 -0.112503 -0.07037097 0.06824827 -0.113589 -0.0722534 0.07345759 -0.112069 -0.06962096 0.05799996 -0.06669861 0.005663752 0.05737495 -0.06678229 0.005518734 0.05691748 -0.06843996 0.00594747 0.05674999 -0.06875246 0.0054062 0.05674999 -0.06732356 0.004581212 0.05691748 -0.06906497 0.004864931 0.05737495 -0.06929379 0.004468739 0.05737495 -0.06786477 0.003643691 0.05799996 -0.06937748 0.004323661 0.05862498 -0.06929379 0.004468739 0.05862498 -0.06786477 0.003643691 0.05908244 -0.06763607 0.004039943 0.05924999 -0.06875246 0.0054062 0.05908244 -0.06701105 0.005122482 0.05862498 -0.06821119 0.006343722 0.05691748 -0.06701105 0.005122482 0.06923305 -0.112574 -0.073794 0.05691748 -0.06763607 0.004039943 0.06824827 -0.11216 -0.07307839 0.07938736 -0.112574 -0.073794 0.07482355 -0.111324 -0.07162898 0.07980996 -0.112527 -0.07371288 0.05799996 -0.06794857 0.003498673 0.07345759 -0.110641 -0.07044595 0.0749576 -0.111074 -0.07119596 0.06309205 -0.06298667 0.01209288 0.07445758 -0.110641 -0.07044595 0.06843096 -0.112372 -0.0734452 0.06878429 -0.11252 -0.07370185 0.07295757 -0.111074 -0.07119596 0.07309156 -0.111324 -0.07162898 0.06210726 -0.06257361 0.0128085 0.06255608 -0.06262665 0.01271635 0.06290948 -0.06277495 0.01245957 0.05924999 -0.06732356 0.004581212 0.05799996 -0.06494855 0.008694827 0.05908244 -0.06401109 0.01031869 0.05799996 -0.06369858 0.01085984 0.05195307 -0.06257361 0.0128085 0.05862498 -0.06678229 0.005518734 0.05737495 -0.06486475 0.008839845 0.05153048 -0.0626204 0.01272737 0.05118697 -0.06275218 0.01249909 0.05098706 -0.06294405 0.01216655 0.05691748 -0.06401109 0.01031869 0.05737495 -0.06378227 0.01071488 0.05691748 -0.06543999 0.01114368 0.05674999 -0.0657525 0.01060235 0.05674999 -0.0643236 0.009777367 0.05691748 -0.06606495 0.01006108 0.05737495 -0.06629377 0.009664893 0.05691748 -0.06463611 0.009236097 0.05799996 -0.06637746 0.009519815 0.05862498 -0.06486475 0.008839845 0.05908244 -0.06606495 0.01006108 0.05908244 -0.06463611 0.009236097 0.05924999 -0.0643236 0.009777367 0.05862498 -0.06378227 0.01071488 -0.06665539 -0.07932746 -0.01291018 -0.06665539 -0.07789856 -0.01373517 -0.06765127 -0.07761108 -0.01323717 -0.06765127 -0.07903999 -0.01241219 -0.0678054 -0.07875245 -0.01191425 -0.06765127 -0.07703608 -0.0122413 -0.0672304 -0.07825446 -0.01105177 -0.06608039 -0.07682555 -0.01187676 -0.06565946 -0.07761108 -0.01323717 -0.06608039 -0.07782149 -0.01360177 -0.06565946 -0.07903999 -0.01241219 -0.0616554 -0.07789856 -0.01373517 -0.06223034 -0.07782149 -0.01360177 -0.06265127 -0.07903999 -0.01241219 -0.06265127 -0.07703608 -0.0122413 -0.06265127 -0.07846498 -0.01141625 -0.0616554 -0.0767486 -0.01174324 -0.06108039 -0.07825446 -0.01105177 -0.06108039 -0.07682555 -0.01187676 -0.06108039 -0.07782149 -0.01360177 -0.06108039 -0.07925045 -0.01277679 -0.04154235 -0.110641 -0.07044595 -0.04254239 -0.112069 -0.06962096 -0.04290837 -0.1122519 -0.069938 -0.04304236 -0.111074 -0.07119596 -0.04290837 -0.112752 -0.07080399 -0.04204237 -0.113003 -0.07123696 -0.04204237 -0.111574 -0.07206195 -0.04154235 -0.112936 -0.07112097 -0.04154235 -0.1115069 -0.07194596 -0.04117637 -0.112752 -0.07080399 -0.04117637 -0.111324 -0.07162898 -0.04104238 -0.112503 -0.07037097 -0.04154235 -0.112069 -0.06962096 -0.05799996 -0.06369858 0.01085984 -0.05799996 -0.06512749 0.01168489 -0.05862498 -0.06521117 0.01153987 -0.05862498 -0.06378227 0.01071488 -0.05908244 -0.06543999 0.01114368 -0.05908244 -0.06401109 0.01031869 -0.05924999 -0.0643236 0.009777367 -0.05924999 -0.0657525 0.01060235 -0.05908244 -0.06463611 0.009236097 -0.05908244 -0.06606495 0.01006108 -0.05799996 -0.06494855 0.008694827 -0.05691748 -0.06463611 0.009236097 -0.05674999 -0.0657525 0.01060235 -0.05674999 -0.0643236 0.009777367 -0.05691748 -0.06401109 0.01031869 -0.05737495 -0.06521117 0.01153987 -0.04676687 -0.112574 -0.073794 -0.03564667 -0.113632 -0.07232719 -0.03562778 -0.111987 -0.07277756 -0.03564667 -0.112203 -0.07315218 -0.03584659 -0.113824 -0.07265967 -0.03618997 -0.112527 -0.07371288 -0.05290788 -0.06441569 0.01291787 -0.06179147 -0.07377749 -0.003297269 -0.06179147 -0.07234859 -0.004122257 -0.06112557 -0.07566565 -0.006567716 -0.06211036 -0.07625246 -0.007584095 -0.06915539 -0.07482355 -0.008409082 -0.05900967 -0.08166569 -0.01695996 -0.05999445 -0.08125245 -0.01624435 -0.05987769 -0.07983738 -0.01709336 -0.05954569 -0.07987666 -0.01716148 -0.05919235 -0.08002495 -0.01741826 -0.05900967 -0.08023667 -0.01778495 -0.06915539 -0.08125245 -0.01624435 -0.07002139 -0.08100247 -0.01581138 -0.06965535 -0.07975655 -0.01695334 -0.06965535 -0.08118546 -0.01612836 -0.07015538 -0.07932358 -0.0162034 -0.05862498 -0.06786477 0.003643691 -0.06280535 -0.07732355 -0.0127393 -0.05999445 -0.07982355 -0.01706939 -0.06065946 -0.07761108 -0.01323717 -0.06565946 -0.07703608 -0.0122413 -0.06550538 -0.07732355 -0.0127393 -0.0672304 -0.07682555 -0.01187676 -0.0678054 -0.07732355 -0.0127393 -0.07002139 -0.07957357 -0.01663637 -0.0672304 -0.07782149 -0.01360177 -0.06915539 -0.07982355 -0.01706939 -0.06265127 -0.07761108 -0.01323717 -0.06665539 -0.0767486 -0.01174324 -0.06965535 -0.07489049 -0.008525133 -0.06211036 -0.07482355 -0.008409082 -0.06168776 -0.0747767 -0.00832796 -0.06223034 -0.07682555 -0.01187676 -0.06134438 -0.07464498 -0.008099734 -0.06114447 -0.07445299 -0.0077672 -0.06065946 -0.07703608 -0.0122413 -0.04254239 -0.110641 -0.07044595 -0.04290837 -0.110824 -0.07076299 -0.04104238 -0.111074 -0.07119596 -0.04117637 -0.110824 -0.07076299 -0.04960638 -0.07234859 -0.004122257 -0.06050539 -0.07732355 -0.0127393 -0.05987769 -0.07234859 -0.004122257 -0.04254239 -0.1115069 -0.07194596 -0.03661257 -0.112574 -0.073794 -0.03584659 -0.112395 -0.07348465 -0.04290837 -0.111324 -0.07162898 -0.0472157 -0.11252 -0.07370185 -0.04756897 -0.112372 -0.0734452 -0.04775166 -0.11216 -0.07307839 -0.04204237 -0.110574 -0.0703299 -0.05691748 -0.06763607 0.004039943 -0.05908244 -0.06701105 0.005122482 -0.05924999 -0.06732356 0.004581212 -0.05987769 -0.06257361 0.0128085 -0.05290788 -0.06298667 0.01209288 -0.05309045 -0.06277495 0.01245957 -0.05344384 -0.06262665 0.01271635 -0.05862498 -0.06486475 0.008839845 -0.05737495 -0.06678229 0.005518734 -0.05737495 -0.06486475 0.008839845 -0.05389267 -0.06257361 0.0128085 -0.05737495 -0.06378227 0.01071488 -0.05862498 -0.06678229 0.005518734 -0.0650317 -0.06316035 0.01179206 -0.06501287 -0.06294405 0.01216655 -0.06481295 -0.06275218 0.01249909 -0.06112557 -0.07423669 -0.007392704 -0.06404685 -0.06257361 0.0128085 -0.06446945 -0.0626204 0.01272737 -0.05799996 -0.06669861 0.005663752 -0.05908244 -0.06763607 0.004039943 -0.05908244 -0.06906497 0.004864931 -0.05862498 -0.06929379 0.004468739 -0.05799996 -0.06794857 0.003498673 -0.05737495 -0.06929379 0.004468739 -0.05737495 -0.06786477 0.003643691 -0.05674999 -0.06875246 0.0054062 -0.05674999 -0.06732356 0.004581212 -0.05691748 -0.06843996 0.00594747 -0.05691748 -0.06701105 0.005122482 -0.05737495 -0.06821119 0.006343722 -0.06168776 -0.07620567 -0.007502973 -0.06280535 -0.07875245 -0.01191425 -0.06550538 -0.07875245 -0.01191425 -0.0672304 -0.07925045 -0.01277679 -0.06965535 -0.07631945 -0.007700145 -0.06765127 -0.07846498 -0.01141625 -0.07015538 -0.07675248 -0.00845015 -0.07015538 -0.08075249 -0.01537835 -0.0616554 -0.07932746 -0.01291018 -0.06223034 -0.07925045 -0.01277679 -0.06608039 -0.07925045 -0.01277679 -0.06065946 -0.07846498 -0.01141625 -0.06114447 -0.07588189 -0.006942212 -0.0616554 -0.07817751 -0.01091825 -0.06134438 -0.07607388 -0.007274746 -0.06665539 -0.07817751 -0.01091825 -0.06223034 -0.07825446 -0.01105177 -0.06608039 -0.07825446 -0.01105177 -0.06565946 -0.07846498 -0.01141625 -0.05987769 -0.07377749 -0.003297269 -0.06404685 -0.06400245 0.01363348 -0.06446945 -0.0640493 0.01355236 -0.06481295 -0.06418108 0.01332408 -0.0650317 -0.06458926 0.01261705 -0.06501287 -0.06437307 0.01299154 -0.05862498 -0.06629377 0.009664893 -0.05862498 -0.06821119 0.006343722 -0.05799996 -0.06637746 0.009519815 -0.05691748 -0.06606495 0.01006108 -0.05799996 -0.06937748 0.004323661 -0.05799996 -0.06812745 0.00648874 -0.05737495 -0.06629377 0.009664893 -0.05691748 -0.06906497 0.004864931 -0.05987769 -0.06400245 0.01363348 -0.05389267 -0.06400245 0.01363348 -0.05344384 -0.06405568 0.0135414 -0.05691748 -0.06543999 0.01114368 -0.05309045 -0.06420385 0.01328456 -0.05924999 -0.06875246 0.0054062 -0.05908244 -0.06843996 0.00594747 -0.06050539 -0.07875245 -0.01191425 -0.06065946 -0.07903999 -0.01241219 -0.05987769 -0.08126628 -0.01626837 -0.04960638 -0.07377749 -0.003297269 -0.05954569 -0.08130568 -0.0163365 -0.05919235 -0.08145385 -0.01659327 -0.03618997 -0.113956 -0.07288789 -0.04204237 -0.112002 -0.06950485 -0.03562778 -0.113416 -0.07195258 -0.04117637 -0.1122519 -0.069938 -0.03661257 -0.114002 -0.07296895 -0.04676687 -0.114002 -0.07296895 -0.04254239 -0.112936 -0.07112097 -0.0472157 -0.113949 -0.07287687 -0.04756897 -0.113801 -0.07262015 -0.04775166 -0.113589 -0.0722534 -0.04304236 -0.112503 -0.07037097 -0.06915539 -0.07625246 -0.007584095 -0.07002139 -0.07507359 -0.00884211 -0.07002139 -0.0765025 -0.008017122 -0.07015538 -0.07532358 -0.009275138 0.129272 -0.114395 -0.07300537 -0.0907275 -0.114395 -0.07300537 -0.0907275 -0.115935 -0.07320755 0.129272 -0.115935 -0.07320755 -0.0907275 -0.1171669 -0.07415246 -0.0907275 -0.117762 -0.07558697 0.129272 -0.11756 -0.07712668 -0.0907275 -0.11756 -0.07712668 -0.0907275 -0.1166149 -0.078359 -0.0907275 -0.115181 -0.0789538 -0.0907275 -0.113641 -0.07875168 0.129272 -0.113641 -0.07875168 -0.0907275 -0.112409 -0.07780677 0.129272 -0.112409 -0.07780677 0.129272 -0.111814 -0.07637226 0.129272 -0.112016 -0.07483255 -0.0907275 -0.112016 -0.07483255 -0.0907275 -0.112961 -0.07360017 0.145379 -0.112276 -0.068412 0.146024 -0.111304 -0.06943637 0.146906 -0.111064 -0.07069206 0.152323 -0.112391 -0.0692861 0.148433 -0.1158 -0.07218688 0.147788 -0.116773 -0.0711624 0.151546 -0.116352 -0.06797987 0.1504859 -0.116612 -0.06687569 0.146024 -0.116455 -0.06875628 0.148649 -0.114885 -0.06525075 0.148364 -0.11336 -0.06516528 0.141713 -0.11257 -0.07063925 0.142892 -0.111386 -0.0731306 0.147788 -0.111621 -0.07184261 0.148433 -0.112826 -0.07257956 0.1440719 -0.113176 -0.07522928 0.148669 -0.114356 -0.07270556 0.146906 -0.117012 -0.06990671 0.142892 -0.117334 -0.07234525 0.142211 -0.116761 -0.07107287 0.145379 -0.11525 -0.06801927 0.141713 -0.115544 -0.07024657 0.145143 -0.1137199 -0.06789326 0.14153 -0.11401 -0.0700879 0.13774 -0.112785 -0.07227057 0.142211 -0.111609 -0.07175296 0.138543 -0.111622 -0.0749166 0.143573 -0.111959 -0.07440298 0.139006 -0.112207 -0.07627826 0.139346 -0.113432 -0.07716989 0.13947 -0.114969 -0.07735258 0.144254 -0.11471 -0.07538795 0.1440719 -0.11615 -0.07483661 0.139346 -0.116406 -0.07677727 0.139006 -0.117358 -0.07559818 0.143573 -0.117111 -0.07372289 0.138543 -0.11757 -0.0741313 0.138079 -0.116985 -0.07276958 0.137616 -0.114222 -0.07169526 0.133559 -0.112917 -0.07326579 0.138079 -0.111833 -0.07344967 0.1343719 -0.116563 -0.07796108 0.133731 -0.117121 -0.07380455 0.13774 -0.11576 -0.07187795 0.129272 -0.112961 -0.07360017 0.133731 -0.11197 -0.0744847 0.133966 -0.111765 -0.07600605 0.1342 -0.112358 -0.07742226 0.1343719 -0.113588 -0.07835376 0.1344349 -0.115128 -0.07855099 0.129272 -0.115181 -0.0789538 0.129272 -0.1166149 -0.078359 0.1342 -0.117509 -0.07674217 0.133966 -0.117714 -0.07522076 0.129272 -0.117762 -0.07558697 0.129272 -0.1171669 -0.07415246 0.133559 -0.115891 -0.07287305 0.133496 -0.114352 -0.07267588 0.151546 -0.111201 -0.06865996 0.151193 -0.112013 -0.06819605 0.1504859 -0.1116549 -0.06753015 0.1504859 -0.110664 -0.0676611 0.149425 -0.110923 -0.06655687 0.148649 -0.11191 -0.06564337 0.149425 -0.116075 -0.06587678 0.15171 -0.11479 -0.06835168 0.152323 -0.115365 -0.06889337 0.152607 -0.113916 -0.06937146 0.1518999 -0.1138229 -0.06867051 0.149779 -0.115263 -0.06634068 0.1504859 -0.115621 -0.06700658 0.146906 -0.116021 -0.0700376 0.151193 -0.1154479 -0.0677427 0.147924 -0.115213 -0.0715577 0.15171 -0.112807 -0.06861346 0.147494 -0.1124269 -0.07132816 0.146906 -0.112055 -0.07056117 0.149779 -0.111828 -0.06679409 0.1492609 -0.112486 -0.06618505 0.145888 -0.112863 -0.06904107 0.149071 -0.113453 -0.06586641 0.1492609 -0.114469 -0.06592327 0.145888 -0.114846 -0.06877928 0.1421059 -0.115149 -0.0710771 0.146318 -0.115649 -0.06927067 0.1424379 -0.115961 -0.07162785 0.142892 -0.116343 -0.0724762 0.143346 -0.116194 -0.07339459 0.147494 -0.1158609 -0.07087481 0.143679 -0.115553 -0.07413697 0.1438 -0.114593 -0.07450455 0.148082 -0.11425 -0.07190346 0.147924 -0.11323 -0.07181948 0.143679 -0.113571 -0.07439875 0.142892 -0.112377 -0.07299965 0.146318 -0.112215 -0.06972408 0.14573 -0.113826 -0.0686953 0.141984 -0.114127 -0.07097131 0.1380079 -0.115372 -0.07275986 0.138234 -0.116189 -0.07335436 0.139078 -0.115803 -0.0760262 0.143346 -0.11276 -0.073848 0.1424379 -0.1125259 -0.07208126 0.138234 -0.112754 -0.07380777 0.1380079 -0.113389 -0.0730217 0.1421059 -0.113167 -0.07133877 0.137925 -0.114347 -0.07263815 0.133695 -0.115507 -0.07378649 0.133809 -0.116328 -0.07440745 0.138543 -0.1165789 -0.0742622 0.133966 -0.116722 -0.07535165 0.138852 -0.116437 -0.07524007 0.139161 -0.114845 -0.07640969 0.1342779 -0.114998 -0.0775718 0.139078 -0.11382 -0.07628786 0.134236 -0.113972 -0.07744038 0.138852 -0.113003 -0.07569348 0.134122 -0.113152 -0.0768193 0.138543 -0.112613 -0.0747857 0.133809 -0.112893 -0.07486099 0.133695 -0.113524 -0.07404828 0.129272 -0.114526 -0.07399678 0.129272 -0.115553 -0.0741316 0.134122 -0.116586 -0.07636588 0.134236 -0.115955 -0.07717859 0.129272 -0.116006 -0.0775659 0.129272 -0.11505 -0.07796239 0.129272 -0.113202 -0.07719767 0.133966 -0.112757 -0.07587516 0.129272 -0.112805 -0.07624137 0.129272 -0.11294 -0.07521486 0.133653 -0.114481 -0.07365506 0.129272 -0.11357 -0.07439339 -0.0907275 -0.113202 -0.07719767 -0.0907275 -0.114023 -0.07782769 -0.0907275 -0.11505 -0.07796239 0.129272 -0.114023 -0.07782769 -0.0907275 -0.116006 -0.0775659 -0.0907275 -0.116636 -0.07674425 0.129272 -0.116636 -0.07674425 -0.0907275 -0.116771 -0.0757178 0.129272 -0.116771 -0.0757178 0.129272 -0.116374 -0.0747615 -0.0907275 -0.116374 -0.0747615 -0.0907275 -0.114526 -0.07399678 -0.0907275 -0.115553 -0.0741316 -0.0907275 -0.111814 -0.07637226 -0.0907275 -0.112805 -0.07624137 -0.0907275 -0.11294 -0.07521486 -0.0907275 -0.11357 -0.07439339 0.08672219 0.04926079 0.01859998 0.08672219 0.04926079 0.01739996 0.08054035 0.04569166 0.01859998 0.08054035 0.04569166 0.01739996 0.07505857 0.04252678 0.01739996 -7e-4 0.099734 0.01739996 -7e-4 0.09745848 0.01739996 -7e-4 0.099734 0.01859998 -7e-4 0.09745848 0.01859998 -7e-4 0.08626598 0.01739996 7e-4 0.08626598 0.01739996 7e-4 0.08626598 0.01859998 7e-4 0.09745848 0.01739996 7e-4 0.099734 0.01739996 7e-4 0.099734 0.01859998 -0.07505857 0.04252678 0.01739996 -0.08054035 0.04569166 0.01739996 -0.08672219 0.04926079 0.01859998 -0.08254659 0.04684996 0.01739996 -0.01384896 0.07598716 0.01859998 -0.019894 0.07249706 0.01859998 -0.03592747 0.07022815 0.01859998 -0.03340154 0.06585317 0.01859998 -0.03592747 0.07022815 0.01739996 0.03340154 0.06585317 0.01859998 0.01737487 0.08209419 0.01739996 0.03399759 0.07249706 0.01859998 0.0355615 0.07159417 0.01859998 0.01212924 0.09745848 0.01739996 0.01212924 0.09745848 0.01859998 0.01236647 0.09707516 0.01739996 0.0173344 0.08904576 0.01739996 0.006575286 0.106435 0.01739996 0.001724958 0.106435 0.01739996 -0.006575286 0.106435 0.01859998 -0.0173344 0.08904576 0.01859998 -0.04072648 0.07554036 0.01859998 -0.06844866 0.05953496 0.01739996 -0.05639737 0.06649279 0.01859998 -0.04505658 0.07304036 0.01739996 -0.04505658 0.07304036 0.01859998 -0.08054035 0.05916637 0.01739996 -0.06844866 0.05953496 0.01859998 -0.09546309 0.04752308 0.01739996 -0.09178638 0.0538913 0.01739996 -0.08888781 0.05891185 0.01739996 -0.09178638 0.0538913 0.01859998 -0.0887832 0.03509318 0.01859998 -0.09172016 0.04055827 0.01739996 -0.09510135 0.04684996 0.01859998 -0.07673126 0.028135 0.01859998 -0.08054035 0.03033417 0.01859998 -0.0887832 0.03509318 0.01739996 -0.06422537 0.04055827 0.01739996 -0.06422537 0.04055827 0.01859998 -0.005999982 0.07589995 0.01859998 -0.005624949 0.07589995 0.01859998 -0.005999982 0.07589995 0.01739996 -0.001724958 0.07589995 0.01859998 -0.005624949 0.07589995 0.01739996 -0.001724958 0.07589995 0.01739996 0.005999982 0.07589995 0.01859998 0.01189398 0.07249706 0.01859998 0.005999982 0.07589995 0.01739996 0.01189398 0.07249706 0.01739996 0.01236647 0.07222425 0.01859998 0.01236647 0.07222425 0.01739996 0.03189635 0.06094866 0.01859998 0.03812855 0.05735045 0.01859998 0.03189635 0.06094866 0.01739996 0.04412007 0.0538913 0.01739996 0.05444729 0.04792886 0.01859998 0.05444729 0.04792886 0.01739996 0.06422537 0.04055827 0.01739996 0.06422537 0.04055827 0.01859998 0.06273126 0.04314619 0.01739996 0.07673126 0.028135 0.01859998 0.0887832 0.03509318 0.01859998 0.08713126 0.03413939 0.01859998 0.08054035 0.03033417 0.01739996 0.09510135 0.04684996 0.01739996 0.09172016 0.04055827 0.01739996 0.08888781 0.05891185 0.01859998 0.09178638 0.0538913 0.01739996 0.09178638 0.0538913 0.01859998 0.09546309 0.04752308 0.01739996 0.09546309 0.04752308 0.01859998 0.06844866 0.05953496 0.01739996 0.07308501 0.05939358 0.01739996 0.06844866 0.05953496 0.01859998 0.07394945 0.05936729 0.01739996 0.07394945 0.05936729 0.01859998 0.06599998 0.06094866 0.01859998 0.06340569 0.06244647 0.01859998 0.06340569 0.06244647 0.01739996 0.05639737 0.06649279 0.01739996 0.04505658 0.07304036 0.01859998 -0.06599998 0.06094866 0.01739996 -0.044743 0.07249706 0.01739996 -0.010625 0.09191745 0.01739996 -0.04072648 0.07554036 0.01739996 -0.08697217 0.04919379 0.01739996 -0.08672219 0.04926079 0.01739996 -0.08054035 0.04055827 0.01739996 0.07499158 0.04227679 0.01739996 -0.06759047 0.04055827 0.01739996 0.001249969 0.07873487 0.01739996 0.001724958 0.0825901 0.01739996 -0.06059998 0.04706287 0.01739996 -0.05862498 0.05308246 0.01739996 -0.06340569 0.0538913 0.01739996 -0.05908244 0.052625 0.01739996 -0.05639737 0.0538913 0.01739996 -0.05737495 0.05308246 0.01739996 -0.06084996 0.0474959 0.01739996 -0.05922007 0.05211156 0.01739996 -0.06340569 0.05211156 0.01739996 -0.06078296 0.04774588 0.01739996 -0.05924999 0.05199998 0.01739996 -0.05908244 0.05137497 0.01739996 -0.05799996 0.05074995 0.01739996 -0.05737495 0.05091744 0.01739996 -0.05639737 0.05211156 0.01739996 -0.05691748 0.05137497 0.01739996 -0.05674999 0.05199998 0.01739996 -0.06009995 0.04792886 0.01739996 -0.06035 0.04799586 0.01739996 -0.05862498 0.05091744 0.01739996 -0.06059998 0.04792886 0.01739996 0.05862498 0.05308246 0.01739996 0.05691748 0.052625 0.01739996 0.05737495 0.05308246 0.01739996 0.05799996 0.05324995 0.01739996 0.05691748 0.05137497 0.01739996 0.05862498 0.05091744 0.01739996 0.05737495 0.05091744 0.01739996 0.05799996 0.05074995 0.01739996 0.06009995 0.04792886 0.01739996 0.06031256 0.04799449 0.01739996 0.06053268 0.04796135 0.01739996 0.06059998 0.04684996 0.01739996 0.06059998 0.04706287 0.01739996 0.06076306 0.04721426 0.01739996 0.05908244 0.05137497 0.01739996 0.06071645 0.04783594 0.01739996 0.06082779 0.0476433 0.01739996 0.06084436 0.04742139 0.01739996 -0.001249969 0.08306509 0.01739996 0 0.08339995 0.01739996 0.001249969 0.08306509 0.01739996 0.002499997 0.08089995 0.01739996 0.002165019 0.08214998 0.01739996 -0.001249969 0.07873487 0.01739996 0.001724958 0.07589995 0.01739996 0 0.07839995 0.01739996 -0.002499997 0.08089995 0.01739996 -0.002165019 0.08214998 0.01739996 -0.001724958 0.07920986 0.01739996 -0.0700615 0.04294997 0.01739996 -0.07131147 0.04261505 0.01739996 -0.06340569 0.04197806 0.01739996 -0.06789636 0.04169994 0.01739996 -0.07253235 0.04055827 0.01739996 -0.07222646 0.03919994 0.01739996 -0.07308501 0.03024017 0.01739996 -0.07131147 0.03828489 0.01739996 -0.0700615 0.03794997 0.01739996 -0.06881147 0.03828489 0.01739996 -0.0687313 0.03275376 0.01739996 -0.06789636 0.03919994 0.01739996 -0.0675615 0.04044997 0.01739996 0.07222646 0.04169994 0.01739996 0.07131147 0.04261505 0.01739996 0.06340569 0.04684996 0.01739996 0.0700615 0.04294997 0.01739996 0.06881147 0.04261505 0.01739996 0.0675615 0.04044997 0.01739996 0.0725615 0.04044997 0.01739996 0.06789636 0.03919994 0.01739996 0.06881147 0.03828489 0.01739996 0.0700615 0.03794997 0.01739996 0.07308501 0.03024017 0.01739996 0.07131147 0.03828489 0.01739996 0.07435858 0.04373919 0.01739996 0.0797466 0.04684996 0.01739996 0.08722215 0.05012679 0.01739996 0.08713126 0.05028414 0.01739996 0.08713126 0.05211156 0.01739996 0.08702218 0.05047315 0.01739996 0.08695518 0.05072319 0.01739996 0.0867722 0.05090618 0.01739996 0.08652216 0.05097317 0.01739996 0.08602219 0.05047315 0.01739996 0.08054035 0.04730826 0.01739996 0.08608907 0.05072319 0.01739996 0.08054035 0.05211156 0.01739996 0.08627218 0.05090618 0.01739996 0.08713126 0.04923635 0.01739996 0.0874052 0.04944378 0.01739996 0.0874722 0.04969376 0.01739996 0.07405859 0.04252678 0.01739996 0.07412558 0.04227679 0.01739996 0.07430857 0.04209375 0.01739996 0.08713126 0.04055827 0.01739996 0.08254659 0.04684996 0.01739996 0.08713126 0.04684996 0.01739996 0.08697217 0.04919379 0.01739996 0.0741086 0.04380619 0.01739996 0.07394945 0.04684996 0.01739996 0.07394945 0.04376357 0.01739996 0.07308501 0.04684996 0.01739996 0.07385855 0.04373919 0.01739996 0.07253235 0.04055827 0.01739996 0.07360857 0.04330617 0.01739996 0.07367557 0.04355615 0.01739996 0.07367557 0.04305619 0.01739996 0.07385855 0.0428732 0.01739996 0.07394945 0.04055827 0.01739996 0.07394945 0.04271578 0.01739996 -8.83013e-4 0.08608299 0.01739996 -0.001724958 0.09745848 0.01739996 -9.5e-4 0.08583295 0.01739996 -8.83013e-4 0.08558297 0.01739996 -7e-4 0.08539998 0.01739996 8.83013e-4 0.08608299 0.01739996 0.001724958 0.09745848 0.01739996 9.5e-4 0.08583295 0.01739996 8.83013e-4 0.08558297 0.01739996 0.001724958 0.0843665 0.01739996 7e-4 0.08539998 0.01739996 -4.5e-4 0.08533298 0.01739996 -2e-4 0.08539998 0.01739996 2e-4 0.08539998 0.01739996 4.5e-4 0.08533298 0.01739996 -8.83013e-4 0.09991699 0.01739996 -9.5e-4 0.100167 0.01739996 -8.83013e-4 0.100417 0.01739996 -7e-4 0.1006 0.01739996 -2e-4 0.1006 0.01739996 -4.5e-4 0.1006669 0.01739996 8.63119e-4 0.09988528 0.01739996 9.44415e-4 0.100092 0.01739996 8.16526e-4 0.100507 0.01739996 6.32671e-4 0.100632 0.01739996 4.12635e-4 0.100666 0.01739996 2e-4 0.1006 0.01739996 -0.07360857 0.04330617 0.01739996 -0.07222646 0.04169994 0.01739996 -0.07367557 0.04355615 0.01739996 -0.07455855 0.04202675 0.01739996 -0.07430857 0.04209375 0.01739996 -0.07412558 0.04227679 0.01739996 -0.07405859 0.04252678 0.01739996 -0.07308501 0.04055827 0.01739996 -0.07394945 0.04271578 0.01739996 -0.07385855 0.0428732 0.01739996 -0.07367557 0.04305619 0.01739996 -0.07499158 0.04227679 0.01739996 -0.08054035 0.04730826 0.01739996 -0.08602219 0.05047315 0.01739996 -0.08608907 0.05072319 0.01739996 -0.08627218 0.05090618 0.01739996 -0.08695518 0.05072319 0.01739996 -0.08702218 0.05047315 0.01739996 -0.08722215 0.05012679 0.01739996 -0.0874052 0.0499438 0.01739996 -0.0874722 0.04969376 0.01739996 -0.0874052 0.04944378 0.01739996 -0.08722215 0.04926079 0.01739996 -0.07435858 0.04373919 0.01739996 -0.0797466 0.04684996 0.01739996 -0.0741086 0.04380619 0.01739996 -0.07394945 0.04684996 0.01739996 -0.07394945 0.04376357 0.01739996 -0.07385855 0.04373919 0.01739996 -0.04057204 0.06094866 0.01739996 -0.05399996 0.06094866 0.01739996 -0.04599756 0.07249706 0.01739996 -0.04422169 0.06659418 0.01739996 -0.04455655 0.07217437 0.01739996 -0.04285567 0.06622821 0.01739996 -0.04437357 0.07199138 0.01739996 -0.04412358 0.07192438 0.01739996 -0.04387354 0.07199138 0.01739996 -0.0355615 0.07159417 0.01739996 -0.04369056 0.07217437 0.01739996 -0.04362356 0.07242441 0.01739996 -0.04720264 0.05211156 0.01739996 -0.05212008 0.0538913 0.01739996 -0.04069578 0.06048715 0.01739996 -0.05677986 0.05211156 0.01739996 -0.05691748 0.052625 0.01739996 -0.05567878 0.05997949 0.01739996 -0.05604475 0.05861347 0.01739996 -0.05351889 0.05423849 0.01739996 -0.019894 0.07249706 0.01739996 -0.01384896 0.07598716 0.01739996 -0.01236647 0.07249706 0.01739996 -0.01348298 0.07735317 0.01739996 -0.01600885 0.08172816 0.01739996 -0.04369056 0.07267439 0.01739996 -0.04109245 0.0741744 0.01739996 -0.04364305 0.07249706 0.01739996 -0.04090946 0.07399135 0.01739996 -0.03399759 0.07249706 0.01739996 -0.04065948 0.07392436 0.01739996 -0.0404095 0.07399135 0.01739996 -0.04022645 0.0741744 0.01739996 0.001724958 0.07920986 0.01739996 0.002165019 0.07964998 0.01739996 0.019894 0.07249706 0.01739996 0.03203547 0.0654872 0.01739996 0.03340154 0.06585317 0.01739996 0.03812855 0.07704025 0.01739996 0.03812855 0.07249706 0.01739996 0.01236647 0.0843665 0.01739996 0.01600885 0.08172816 0.01739996 0.01236647 0.07249706 0.01739996 0.01348298 0.07735317 0.01739996 0.01384896 0.07598716 0.01739996 0.05399996 0.06094866 0.01739996 0.04285567 0.06622821 0.01739996 0.03812855 0.06094866 0.01739996 0.03592747 0.07022815 0.01739996 0.0355615 0.07159417 0.01739996 0.04505658 0.07304036 0.01739996 0.044743 0.07249706 0.01739996 0.04599756 0.07249706 0.01739996 0.04455655 0.07217437 0.01739996 0.04437357 0.07199138 0.01739996 0.04364305 0.07249706 0.01739996 0.04362356 0.07242441 0.01739996 0.04369056 0.07217437 0.01739996 0.04387354 0.07199138 0.01739996 0.04422169 0.06659418 0.01739996 0.04412358 0.07192438 0.01739996 0.05604475 0.05861347 0.01739996 0.05567878 0.05997949 0.01739996 0.05639737 0.06094866 0.01739996 0.04032975 0.06185317 0.01739996 0.04057204 0.06094866 0.01739996 0.03812855 0.05735045 0.01739996 0.04069578 0.06048715 0.01739996 0.05212008 0.0538913 0.01739996 0.05215275 0.05387234 0.01739996 0.05222338 0.0538913 0.01739996 0.05351889 0.05423849 0.01739996 0.04015946 0.07442438 0.01739996 0.04022645 0.07467436 0.01739996 0.04072648 0.07554036 0.01739996 0.04109245 0.0741744 0.01739996 0.04090946 0.07399135 0.01739996 0.04369056 0.07267439 0.01739996 0.04065948 0.07392436 0.01739996 0.0404095 0.07399135 0.01739996 0.04022645 0.0741744 0.01739996 0.03399759 0.07249706 0.01739996 0.0254392 0.0843665 0.01739996 0.00999999 0.09174996 0.01739996 0.00999999 0.09424996 0.01739996 0.008749961 0.09299999 0.01739996 0.00891745 0.09237498 0.01739996 9.27786e-4 0.100314 0.01739996 -0.005624949 0.106435 0.01739996 -0.006575286 0.106435 0.01739996 -0.01212924 0.09745848 0.01739996 -0.01236647 0.09707516 0.01739996 -0.01236647 0.0843665 0.01739996 -0.01108247 0.09237498 0.01739996 -0.010625 0.09408247 0.01739996 -0.00999999 0.09424996 0.01739996 -0.009374976 0.09408247 0.01739996 -0.005624949 0.09745848 0.01739996 -0.00891745 0.09237498 0.01739996 -0.04015946 0.07442438 0.01739996 -0.04022645 0.07467436 0.01739996 -0.01737487 0.08209419 0.01739996 -0.0254392 0.0843665 0.01739996 -0.0173344 0.08904576 0.01739996 -0.06340569 0.06094866 0.01739996 -0.07394945 0.0538913 0.01739996 -0.07616537 0.05624276 0.01739996 -0.08054035 0.0538913 0.01739996 -0.07679039 0.05516028 0.01739996 -0.07616537 0.05407768 0.01739996 -0.09281396 0.05211156 0.01739996 -0.08652216 0.05097317 0.01739996 -0.0867722 0.05090618 0.01739996 -0.08445775 0.03721469 0.01739996 -0.08054035 0.03033417 0.01739996 -0.07480859 0.04209375 0.01739996 -0.08554035 0.03908967 0.01739996 -0.09510135 0.04684996 0.01739996 -0.08616536 0.03892225 0.01739996 -0.08662289 0.03846466 0.01739996 -0.0725615 0.04044997 0.01739996 -0.07394945 0.02974116 0.01739996 -0.07394945 0.04055827 0.01739996 -0.06078296 0.04724586 0.01739996 -0.06059998 0.04684996 0.01739996 -0.06059998 0.04437667 0.01739996 -0.05222338 0.0538913 0.01739996 -0.05215275 0.05387234 0.01739996 -0.05639737 0.04792886 0.01739996 -0.04032975 0.06185317 0.01739996 -0.03340154 0.06585317 0.01739996 -0.03203547 0.0654872 0.01739996 -0.002165019 0.07964998 0.01739996 0.05677986 0.05211156 0.01739996 0.05674999 0.05199998 0.01739996 0.05639737 0.05211156 0.01739996 0.05639737 0.04792886 0.01739996 0.04720264 0.05211156 0.01739996 0.06059998 0.04437667 0.01739996 0.06340569 0.04197806 0.01739996 0.06789636 0.04169994 0.01739996 0.06759047 0.04055827 0.01739996 0.07455855 0.04202675 0.01739996 0.07480859 0.04209375 0.01739996 0.07222646 0.03919994 0.01739996 0.07308501 0.04055827 0.01739996 0.07394945 0.02974116 0.01739996 0.07673126 0.028135 0.01739996 0.08713126 0.03413939 0.01739996 0.08662289 0.03846466 0.01739996 0.08616536 0.03892225 0.01739996 0.08445775 0.03846466 0.01739996 0.08054035 0.04055827 0.01739996 0.08491539 0.03675717 0.01739996 0.0887832 0.03509318 0.01739996 0.08679038 0.03783965 0.01739996 0.08722215 0.04926079 0.01739996 0.08713126 0.0589655 0.01739996 0.08888781 0.05891185 0.01739996 0.08054035 0.0538913 0.01739996 0.07445776 0.05453526 0.01739996 0.07616537 0.05624276 0.01739996 0.08054035 0.05916637 0.01739996 0.07445776 0.05578529 0.01739996 0.07429039 0.05516028 0.01739996 0.07308501 0.0538913 0.01739996 0.06599998 0.06094866 0.01739996 0.06340569 0.06094866 0.01739996 -0.07394945 0.05211156 0.01739996 -0.08054035 0.05211156 0.01739996 -0.07308501 0.05211156 0.01739996 -0.06881147 0.04261505 0.01739996 -0.06340569 0.04684996 0.01739996 -0.07308501 0.04684996 0.01739996 -0.07308501 0.0538913 0.01739996 -0.07308501 0.05939358 0.01739996 -0.07394945 0.05936729 0.01739996 -0.06340569 0.06244647 0.01739996 -0.05639737 0.06649279 0.01739996 -0.05639737 0.06094866 0.01739996 -0.05799996 0.05324995 0.01739996 -0.001724958 0.106435 0.01739996 -0.005624949 0.0843665 0.01739996 -0.001724958 0.0825901 0.01739996 -0.001724958 0.0843665 0.01739996 0.05639737 0.0538913 0.01739996 0.06340569 0.0538913 0.01739996 0.06340569 0.05211156 0.01739996 0.05924999 0.05199998 0.01739996 0.0874052 0.0499438 0.01739996 0.09281396 0.05211156 0.01739996 0.08713126 0.0538913 0.01739996 0.07394945 0.05211156 0.01739996 0.07394945 0.0538913 0.01739996 0.07308501 0.05211156 0.01739996 0.05922007 0.05211156 0.01739996 0.05908244 0.052625 0.01739996 0.01384896 0.07598716 0.01859998 0.044743 0.07249706 0.01859998 0.01236647 0.09707516 0.01859998 -0.03399759 0.07249706 0.01859998 0.06340569 0.04684996 0.01859998 0.08054035 0.04055827 0.01859998 -0.08602219 0.05047315 0.01859998 -7e-4 0.08626598 0.01859998 0.08722215 0.04926079 0.01859998 0.08713126 0.04923635 0.01859998 0.08697217 0.04919379 0.01859998 0.05677986 0.05211156 0.01859998 -0.05924999 0.05199998 0.01859998 -0.05908244 0.052625 0.01859998 -0.05677986 0.05211156 0.01859998 -0.05691748 0.052625 0.01859998 -0.05737495 0.05308246 0.01859998 -0.06059998 0.04706287 0.01859998 -0.06078296 0.04724586 0.01859998 -0.06084996 0.0474959 0.01859998 -0.05674999 0.05199998 0.01859998 -0.05691748 0.05137497 0.01859998 -0.05908244 0.05137497 0.01859998 -0.06059998 0.04792886 0.01859998 -0.05737495 0.05091744 0.01859998 -0.05799996 0.05074995 0.01859998 -0.06009995 0.04792886 0.01859998 -0.05862498 0.05091744 0.01859998 -0.06035 0.04799586 0.01859998 0.05799996 0.05324995 0.01859998 0.05862498 0.05308246 0.01859998 0.05908244 0.052625 0.01859998 0.05691748 0.052625 0.01859998 0.05737495 0.05308246 0.01859998 0.05639737 0.0538913 0.01859998 0.06059998 0.04706287 0.01859998 0.06059998 0.04684996 0.01859998 0.05799996 0.05074995 0.01859998 0.05737495 0.05091744 0.01859998 0.05922007 0.05211156 0.01859998 0.05924999 0.05199998 0.01859998 0.05908244 0.05137497 0.01859998 0.06076306 0.04721426 0.01859998 0.05674999 0.05199998 0.01859998 0.06053268 0.04796135 0.01859998 0.06071645 0.04783594 0.01859998 0.06082779 0.0476433 0.01859998 0.06084436 0.04742139 0.01859998 0.05862498 0.05091744 0.01859998 0.06009995 0.04792886 0.01859998 0.06031256 0.04799449 0.01859998 0.001724958 0.0843665 0.01859998 0 0.08339995 0.01859998 -0.002165019 0.08214998 0.01859998 -0.001724958 0.0825901 0.01859998 -0.001249969 0.08306509 0.01859998 0.001724958 0.07589995 0.01859998 0 0.07839995 0.01859998 -0.001249969 0.07873487 0.01859998 -0.001724958 0.07920986 0.01859998 -0.002165019 0.07964998 0.01859998 -0.002499997 0.08089995 0.01859998 0.001724958 0.0825901 0.01859998 0.002165019 0.08214998 0.01859998 0.01236647 0.0843665 0.01859998 0.002499997 0.08089995 0.01859998 0.002165019 0.07964998 0.01859998 0.001724958 0.07920986 0.01859998 0.001249969 0.07873487 0.01859998 -0.07222646 0.04169994 0.01859998 -0.07131147 0.04261505 0.01859998 -0.0700615 0.04294997 0.01859998 -0.06340569 0.04684996 0.01859998 -0.06881147 0.04261505 0.01859998 -0.07222646 0.03919994 0.01859998 -0.06789636 0.03919994 0.01859998 -0.06881147 0.03828489 0.01859998 -0.0700615 0.03794997 0.01859998 -0.0687313 0.03275376 0.01859998 -0.07131147 0.03828489 0.01859998 0.07308501 0.04055827 0.01859998 0.07222646 0.04169994 0.01859998 0.07253235 0.04055827 0.01859998 0.0725615 0.04044997 0.01859998 0.06881147 0.03828489 0.01859998 0.06789636 0.03919994 0.01859998 0.0675615 0.04044997 0.01859998 0.06759047 0.04055827 0.01859998 0.06340569 0.04197806 0.01859998 0.06789636 0.04169994 0.01859998 0.06881147 0.04261505 0.01859998 0.0700615 0.04294997 0.01859998 0.07131147 0.04261505 0.01859998 0.07222646 0.03919994 0.01859998 0.0687313 0.03275376 0.01859998 0.07131147 0.03828489 0.01859998 0.0700615 0.03794997 0.01859998 0.07505857 0.04252678 0.01859998 0.07499158 0.04227679 0.01859998 0.07480859 0.04209375 0.01859998 0.07394945 0.04055827 0.01859998 0.07455855 0.04202675 0.01859998 0.07430857 0.04209375 0.01859998 0.0874052 0.04944378 0.01859998 0.0874722 0.04969376 0.01859998 0.09510135 0.04684996 0.01859998 0.0874052 0.0499438 0.01859998 0.08695518 0.05072319 0.01859998 0.08702218 0.05047315 0.01859998 0.08054035 0.05211156 0.01859998 0.08608907 0.05072319 0.01859998 0.08627218 0.05090618 0.01859998 0.08713126 0.05211156 0.01859998 0.08652216 0.05097317 0.01859998 0.0867722 0.05090618 0.01859998 0.07435858 0.04373919 0.01859998 0.0797466 0.04684996 0.01859998 0.07385855 0.04373919 0.01859998 0.07394945 0.04376357 0.01859998 0.0741086 0.04380619 0.01859998 0.07412558 0.04227679 0.01859998 0.07405859 0.04252678 0.01859998 0.07394945 0.04271578 0.01859998 0.07385855 0.0428732 0.01859998 0.07367557 0.04305619 0.01859998 0.07360857 0.04330617 0.01859998 0.07367557 0.04355615 0.01859998 0.07308501 0.04684996 0.01859998 7e-4 0.09745848 0.01859998 -8.83013e-4 0.08558297 0.01859998 -9.5e-4 0.08583295 0.01859998 -4.5e-4 0.08533298 0.01859998 -7e-4 0.08539998 0.01859998 -0.001724958 0.0843665 0.01859998 8.83013e-4 0.08608299 0.01859998 9.5e-4 0.08583295 0.01859998 8.83013e-4 0.08558297 0.01859998 7e-4 0.08539998 0.01859998 4.5e-4 0.08533298 0.01859998 2e-4 0.08539998 0.01859998 -2e-4 0.08539998 0.01859998 -8.83013e-4 0.08608299 0.01859998 -0.001724958 0.09745848 0.01859998 -8.83013e-4 0.09991699 0.01859998 -0.001724958 0.106435 0.01859998 -7e-4 0.1006 0.01859998 -4.5e-4 0.1006669 0.01859998 -2e-4 0.1006 0.01859998 2e-4 0.1006 0.01859998 4.12635e-4 0.100666 0.01859998 6.32671e-4 0.100632 0.01859998 0.001724958 0.106435 0.01859998 8.63119e-4 0.09988528 0.01859998 9.44415e-4 0.100092 0.01859998 -0.08697217 0.04919379 0.01859998 -0.08627218 0.05090618 0.01859998 -0.08652216 0.05097317 0.01859998 -0.08722215 0.05012679 0.01859998 -0.08702218 0.05047315 0.01859998 -0.08695518 0.05072319 0.01859998 -0.0867722 0.05090618 0.01859998 -0.08722215 0.04926079 0.01859998 -0.09546309 0.04752308 0.01859998 -0.0874052 0.04944378 0.01859998 -0.0874722 0.04969376 0.01859998 -0.0874052 0.0499438 0.01859998 -0.07412558 0.04227679 0.01859998 -0.07430857 0.04209375 0.01859998 -0.07455855 0.04202675 0.01859998 -0.07480859 0.04209375 0.01859998 -0.08254659 0.04684996 0.01859998 -0.08054035 0.04569166 0.01859998 -0.08054035 0.04055827 0.01859998 -0.07499158 0.04227679 0.01859998 -0.07505857 0.04252678 0.01859998 -0.0725615 0.04044997 0.01859998 -0.07253235 0.04055827 0.01859998 -0.07367557 0.04355615 0.01859998 -0.07360857 0.04330617 0.01859998 -0.07367557 0.04305619 0.01859998 -0.07308501 0.04055827 0.01859998 -0.07385855 0.0428732 0.01859998 -0.07394945 0.04271578 0.01859998 -0.07405859 0.04252678 0.01859998 -0.07435858 0.04373919 0.01859998 -0.0741086 0.04380619 0.01859998 -0.07394945 0.04684996 0.01859998 -0.07308501 0.04684996 0.01859998 -0.07394945 0.04376357 0.01859998 -0.07385855 0.04373919 0.01859998 -0.08608907 0.05072319 0.01859998 -0.08054035 0.04730826 0.01859998 -0.0797466 0.04684996 0.01859998 0.06340569 0.06094866 0.01859998 0.06340569 0.0538913 0.01859998 0.07308501 0.0538913 0.01859998 0.07308501 0.05939358 0.01859998 0.07554036 0.05641025 0.01859998 0.07616537 0.05624276 0.01859998 0.0766229 0.05578529 0.01859998 0.07679039 0.05516028 0.01859998 0.0766229 0.05453526 0.01859998 0.08054035 0.0538913 0.01859998 0.07616537 0.05407768 0.01859998 0.07554036 0.05391025 0.01859998 0.07394945 0.0538913 0.01859998 0.0749154 0.05407768 0.01859998 0.07445776 0.05453526 0.01859998 0.07429039 0.05516028 0.01859998 0.07445776 0.05578529 0.01859998 0.0749154 0.05624276 0.01859998 0.08054035 0.05916637 0.01859998 0.08713126 0.0538913 0.01859998 0.09281396 0.05211156 0.01859998 0.08713126 0.05028414 0.01859998 0.08722215 0.05012679 0.01859998 0.09172016 0.04055827 0.01859998 0.08491539 0.03892225 0.01859998 0.08554035 0.03908967 0.01859998 0.08616536 0.03892225 0.01859998 0.08616536 0.03675717 0.01859998 0.08554035 0.03658968 0.01859998 0.08445775 0.03846466 0.01859998 0.08713126 0.04055827 0.01859998 0.08254659 0.04684996 0.01859998 0.08713126 0.04684996 0.01859998 0.08491539 0.03675717 0.01859998 0.08054035 0.03033417 0.01859998 0.08445775 0.03721469 0.01859998 0.08429038 0.03783965 0.01859998 0.08662289 0.03846466 0.01859998 0.08679038 0.03783965 0.01859998 0.08662289 0.03721469 0.01859998 0.07308501 0.03024017 0.01859998 0.07394945 0.02974116 0.01859998 0.06059998 0.04437667 0.01859998 0.06273126 0.04314619 0.01859998 0.05639737 0.05211156 0.01859998 0.05222338 0.0538913 0.01859998 0.05215275 0.05387234 0.01859998 0.05639737 0.04792886 0.01859998 0.05691748 0.05137497 0.01859998 0.04720264 0.05211156 0.01859998 0.04412007 0.0538913 0.01859998 0.05212008 0.0538913 0.01859998 0.03812855 0.06094866 0.01859998 0.04069578 0.06048715 0.01859998 0.01236647 0.07249706 0.01859998 0.019894 0.07249706 0.01859998 0.03203547 0.0654872 0.01859998 -0.01236647 0.07222425 0.01859998 -0.044743 0.07249706 0.01859998 -0.04599756 0.07249706 0.01859998 -0.04422169 0.06659418 0.01859998 -0.04455655 0.07217437 0.01859998 -0.03203547 0.0654872 0.01859998 -0.04032975 0.06185317 0.01859998 -0.04285567 0.06622821 0.01859998 -0.04362356 0.07242441 0.01859998 -0.0355615 0.07159417 0.01859998 -0.04369056 0.07217437 0.01859998 -0.04387354 0.07199138 0.01859998 -0.04412358 0.07192438 0.01859998 -0.04437357 0.07199138 0.01859998 -0.04057204 0.06094866 0.01859998 -0.03189635 0.06094866 0.01859998 -0.04069578 0.06048715 0.01859998 -0.05212008 0.0538913 0.01859998 -0.05215275 0.05387234 0.01859998 -0.05222338 0.0538913 0.01859998 -0.05639737 0.05211156 0.01859998 -0.05639737 0.04792886 0.01859998 -0.04720264 0.05211156 0.01859998 -0.05444729 0.04792886 0.01859998 -0.06059998 0.04437667 0.01859998 -0.06059998 0.04684996 0.01859998 -0.06273126 0.04314619 0.01859998 -0.06340569 0.04197806 0.01859998 -0.06789636 0.04169994 0.01859998 -0.06759047 0.04055827 0.01859998 -0.0675615 0.04044997 0.01859998 -0.07308501 0.03024017 0.01859998 -0.07394945 0.02974116 0.01859998 -0.08445775 0.03846466 0.01859998 -0.07394945 0.04055827 0.01859998 -0.08429038 0.03783965 0.01859998 -0.08445775 0.03721469 0.01859998 -0.08491539 0.03675717 0.01859998 -0.08554035 0.03658968 0.01859998 -0.08616536 0.03675717 0.01859998 -0.08662289 0.03721469 0.01859998 -0.09172016 0.04055827 0.01859998 -0.08679038 0.03783965 0.01859998 -0.08662289 0.03846466 0.01859998 -0.08616536 0.03892225 0.01859998 -0.08554035 0.03908967 0.01859998 -0.08491539 0.03892225 0.01859998 -0.08054035 0.0538913 0.01859998 -0.07445776 0.05578529 0.01859998 -0.07445776 0.05453526 0.01859998 -0.0749154 0.05407768 0.01859998 -0.07394945 0.0538913 0.01859998 -0.07554036 0.05391025 0.01859998 -0.07616537 0.05407768 0.01859998 -0.0766229 0.05453526 0.01859998 -0.07679039 0.05516028 0.01859998 -0.08054035 0.05916637 0.01859998 -0.08888781 0.05891185 0.01859998 -0.0766229 0.05578529 0.01859998 -0.07616537 0.05624276 0.01859998 -0.07394945 0.05936729 0.01859998 -0.07554036 0.05641025 0.01859998 -0.0749154 0.05624276 0.01859998 -0.07429039 0.05516028 0.01859998 -0.07308501 0.05939358 0.01859998 -0.06340569 0.0538913 0.01859998 -0.06599998 0.06094866 0.01859998 -0.01600885 0.08172816 0.01859998 -0.01189398 0.07249706 0.01859998 -0.01236647 0.07249706 0.01859998 -0.01348298 0.07735317 0.01859998 -0.04022645 0.07467436 0.01859998 -0.04015946 0.07442438 0.01859998 -0.04022645 0.0741744 0.01859998 -0.0404095 0.07399135 0.01859998 -0.04065948 0.07392436 0.01859998 -0.04364305 0.07249706 0.01859998 -0.04090946 0.07399135 0.01859998 -0.04369056 0.07267439 0.01859998 -0.04109245 0.0741744 0.01859998 -0.0254392 0.0843665 0.01859998 -0.01737487 0.08209419 0.01859998 -0.01212924 0.09745848 0.01859998 -0.010625 0.09408247 0.01859998 -0.009374976 0.09408247 0.01859998 -0.00891745 0.093625 0.01859998 -0.008749961 0.09299999 0.01859998 -0.005624949 0.0843665 0.01859998 -0.00891745 0.09237498 0.01859998 -0.009374976 0.09191745 0.01859998 -0.01236647 0.0843665 0.01859998 -0.00999999 0.09174996 0.01859998 -0.010625 0.09191745 0.01859998 -0.01108247 0.09237498 0.01859998 -0.01124995 0.09299999 0.01859998 -0.01108247 0.093625 0.01859998 -0.01236647 0.09707516 0.01859998 8.16526e-4 0.100507 0.01859998 9.27786e-4 0.100314 0.01859998 0.006575286 0.106435 0.01859998 0.00999999 0.09424996 0.01859998 0.009374976 0.09408247 0.01859998 0.00891745 0.093625 0.01859998 0.010625 0.09408247 0.01859998 0.01108247 0.093625 0.01859998 0.01124995 0.09299999 0.01859998 0.01108247 0.09237498 0.01859998 0.010625 0.09191745 0.01859998 0.001249969 0.08306509 0.01859998 0.00999999 0.09174996 0.01859998 0.009374976 0.09191745 0.01859998 0.00891745 0.09237498 0.01859998 0.001724958 0.09745848 0.01859998 0.008749961 0.09299999 0.01859998 0.0173344 0.08904576 0.01859998 0.0254392 0.0843665 0.01859998 0.03812855 0.07704025 0.01859998 0.03592747 0.07022815 0.01859998 0.01348298 0.07735317 0.01859998 0.01600885 0.08172816 0.01859998 0.01737487 0.08209419 0.01859998 0.04369056 0.07267439 0.01859998 0.04364305 0.07249706 0.01859998 0.04109245 0.0741744 0.01859998 0.0404095 0.07399135 0.01859998 0.04022645 0.0741744 0.01859998 0.04015946 0.07442438 0.01859998 0.04022645 0.07467436 0.01859998 0.04072648 0.07554036 0.01859998 0.04090946 0.07399135 0.01859998 0.04065948 0.07392436 0.01859998 0.04362356 0.07242441 0.01859998 0.04057204 0.06094866 0.01859998 0.04032975 0.06185317 0.01859998 0.04285567 0.06622821 0.01859998 0.05639737 0.06094866 0.01859998 0.05399996 0.06094866 0.01859998 0.04599756 0.07249706 0.01859998 0.04455655 0.07217437 0.01859998 0.04422169 0.06659418 0.01859998 0.04437357 0.07199138 0.01859998 0.04412358 0.07192438 0.01859998 0.04387354 0.07199138 0.01859998 0.04369056 0.07217437 0.01859998 0.03812855 0.07249706 0.01859998 -0.05639737 0.0538913 0.01859998 -0.05351889 0.05423849 0.01859998 -0.05604475 0.05861347 0.01859998 -0.05639737 0.06094866 0.01859998 -0.05567878 0.05997949 0.01859998 -0.05399996 0.06094866 0.01859998 0.05567878 0.05997949 0.01859998 0.05604475 0.05861347 0.01859998 0.05351889 0.05423849 0.01859998 0.07394945 0.04684996 0.01859998 0.07394945 0.05211156 0.01859998 0.08054035 0.04730826 0.01859998 0.08602219 0.05047315 0.01859998 0.08713126 0.0589655 0.01859998 0.07308501 0.05211156 0.01859998 0.06340569 0.05211156 0.01859998 0.05639737 0.06649279 0.01859998 -0.00999999 0.09424996 0.01859998 -0.005624949 0.09745848 0.01859998 -0.005624949 0.106435 0.01859998 -9.5e-4 0.100167 0.01859998 -8.83013e-4 0.100417 0.01859998 -0.06340569 0.06244647 0.01859998 -0.06340569 0.06094866 0.01859998 -0.05799996 0.05324995 0.01859998 -0.05862498 0.05308246 0.01859998 -0.06078296 0.04774588 0.01859998 -0.09281396 0.05211156 0.01859998 -0.08054035 0.05211156 0.01859998 -0.07394945 0.05211156 0.01859998 -0.07308501 0.05211156 0.01859998 -0.07308501 0.0538913 0.01859998 -0.06340569 0.05211156 0.01859998 -0.05922007 0.05211156 0.01859998 -0.01189398 0.07249706 0.01739996 -0.01236647 0.07222425 0.01739996 -0.03189635 0.06094866 0.01739996 -0.04412007 0.0538913 0.01739996 -0.04412007 0.0538913 0.01859998 -0.05444729 0.04792886 0.01739996 -0.04349994 0.0716297 0.01189994 -0.03375959 0.07725328 0.01069998 -0.04449999 0.06466007 0.01189994 -0.04349994 0.06408268 0.01189994 -0.04103589 0.06266009 0.01069998 -0.03637218 0.06535255 0.01189994 -0.03477627 0.0662741 0.01069998 -0.03550976 0.06969666 0.01069998 -0.03548419 0.07008606 0.01069998 -0.03531169 0.070436 0.01189994 -0.03531169 0.070436 0.01069998 -0.03501826 0.07069325 0.01069998 -0.02895605 0.07419329 0.01069998 -0.01537495 0.07747536 0.01069998 -0.01499998 0.07812488 0.01189994 -0.01499998 0.07812488 0.01069998 -0.01499998 0.08412688 0.01189994 -0.01499998 0.08412688 0.01069998 -0.01499998 0.08678519 0.01069998 -0.01510047 0.08716017 0.01189994 -0.01510047 0.08716017 0.01069998 -0.01537495 0.0874347 0.01189994 -0.01612496 0.0874347 0.01189994 -0.01612496 0.0874347 0.01069998 -0.02801787 0.08056825 0.01189994 -0.02185428 0.08412688 0.01189994 -0.02064436 0.08482539 0.01189994 -0.02064436 0.08482539 0.01069998 -0.01671439 0.08709436 0.01189994 -0.02801787 0.08056825 0.01069998 -0.02695298 0.07872378 0.01069998 -0.0211091 0.07872378 0.01189994 -0.02064436 0.078992 0.01069998 -0.02064436 0.078992 0.01189994 -0.01942986 0.07969325 0.01069998 -0.01842987 0.07969325 0.01189994 -0.01806378 0.07932716 0.01189994 -0.04699999 0.03875374 0.01069998 -0.04699999 0.03875374 0.01189994 -0.04699999 0.04373538 0.01069998 -0.04699999 0.04899996 0.01069998 -0.05274999 0.04899996 0.01069998 -0.05274999 0.04373538 0.01069998 0.04699999 0.03875374 0.01189994 0.05274999 0.03875374 0.01189994 0.05274999 0.04899996 0.01189994 0.05037498 0.04899996 0.01069998 0.05037498 0.04899996 0.01189994 0.04699999 0.04899996 0.01189994 -0.007499992 0.0625 0.01069998 -0.007499992 0.06535255 0.01069998 -0.007499992 0.06535255 0.01189994 -0.03049999 0.06181478 0.01069998 -0.02437216 0.06535255 0.01069998 -0.02064436 0.06750488 0.01189994 -0.01671439 0.06977385 0.01189994 -0.02064436 0.06750488 0.01069998 -0.01337498 0.07170188 0.01069998 -0.007874965 0.07487726 0.01069998 -0.007499992 0.0750938 0.01069998 -0.03049999 0.05609047 0.01069998 -0.03049999 0.06174999 0.01069998 -0.02899998 0.0501821 0.01069998 -0.02899998 0.0501821 0.01189994 -0.02064436 0.0547741 0.01189994 -0.02824997 0.05038297 0.01189994 -0.02824997 0.05038297 0.01069998 -0.01199996 0.0625 0.01069998 -0.01337498 0.06214594 0.01189994 -0.01337498 0.06214594 0.01069998 -0.01491338 0.06174999 0.01189994 -0.01491338 0.06174999 0.01069998 -0.01671439 0.06053739 0.01069998 -0.01671439 0.06053739 0.01189994 -0.01834267 0.05900257 0.01069998 -0.01927858 0.05609047 0.01189994 -0.01927858 0.05609047 0.01069998 -0.007874965 0.0625 0.01069998 0.04299998 0.04948955 0.01069998 0.04299998 0.04959785 0.01189994 0.03599995 0.04499995 0.01189994 0.03524994 0.045201 0.01189994 0.03470098 0.04574996 0.01189994 0.03470098 0.04574996 0.01069998 0.0345 0.04649996 0.01069998 0.0345 0.04948955 0.01189994 0.0345 0.05609047 0.01069998 0.0345 0.0595054 0.01189994 0.0345 0.0595054 0.01069998 0.003999948 0.07199996 0.01069998 0.003866016 0.0715 0.01069998 0.003866016 0.0715 0.01189994 0.002999961 0.07099997 0.01069998 0.002999961 0.07099997 0.01189994 0.002499997 0.07113397 0.01069998 0.002133965 0.0715 0.01069998 0.002133965 0.0715 0.01189994 0.001999974 0.074 0.01189994 0.002133965 0.07449996 0.01189994 0.002499997 0.07486599 0.01069998 0.002999961 0.07499998 0.01069998 0.002999961 0.07499998 0.01189994 0.003499984 0.07486599 0.01189994 0.003999948 0.074 0.01069998 0.003999948 0.074 0.01189994 0.001999974 0.07199996 0.01069998 -0.001999974 0.07199996 0.01069998 -0.002133965 0.0715 0.01069998 -0.002133965 0.0715 0.01189994 -0.002499997 0.07113397 0.01189994 -0.002499997 0.07113397 0.01069998 -0.003866016 0.0715 0.01189994 -0.003999948 0.074 0.01189994 -0.003499984 0.07486599 0.01189994 -0.002999961 0.07499998 0.01189994 -0.002999961 0.07499998 0.01069998 -0.002499997 0.07486599 0.01069998 -0.002133965 0.07449996 0.01189994 -0.001999974 0.074 0.01069998 -0.001999974 0.074 0.01189994 -0.003999948 0.074 0.01069998 -0.003999948 0.07199996 0.01069998 0.04699999 0.06099998 0.01069998 0.04786598 0.06049996 0.01189994 0.04449999 0.05913394 0.01069998 0.04413396 0.05949997 0.01069998 0.04413396 0.05949997 0.01189994 0.04399996 0.06 0.01189994 0.04399996 0.06 0.01069998 0.04413396 0.06049996 0.01189994 0.04413396 0.06049996 0.01069998 0.04449999 0.06086599 0.01189994 0.04449999 0.06086599 0.01069998 0.04499995 0.06099998 0.01189994 0.04699999 0.055 0.01069998 0.04699999 0.055 0.01189994 0.04749995 0.05486595 0.01069998 0.04749995 0.05486595 0.01189994 0.04799997 0.05399996 0.01069998 0.04786598 0.05449998 0.01189994 0.04786598 0.05349999 0.01189994 0.04499995 0.05299997 0.01069998 0.04699999 0.05299997 0.01069998 -0.04699999 0.05899995 0.01069998 -0.04749995 0.05913394 0.01069998 -0.04786598 0.05949997 0.01069998 -0.04799997 0.06 0.01189994 -0.04786598 0.06049996 0.01189994 -0.04413396 0.06049996 0.01069998 -0.04449999 0.06086599 0.01189994 -0.04413396 0.05949997 0.01069998 -0.04413396 0.05949997 0.01189994 -0.04449999 0.05913394 0.01189994 -0.04449999 0.05913394 0.01069998 -0.04749995 0.05313396 0.01069998 -0.04749995 0.05313396 0.01189994 -0.04786598 0.05349999 0.01189994 -0.04799997 0.05399996 0.01189994 -0.04786598 0.05449998 0.01189994 -0.04749995 0.05486595 0.01069998 -0.04574996 0.05299997 0.01069998 -0.04499995 0.05299997 0.01069998 0.05974996 0.05098956 0.01069998 0.05949997 0.05084526 0.01069998 0.05949997 0.05084526 0.01189994 0.05799996 0.04997926 0.01189994 0.05799996 0.04224997 0.01069998 0.05737495 0.04208248 0.01189994 0.05691748 0.04162496 0.01189994 0.05674999 0.04099994 0.01189994 0.05691748 0.04037499 0.01189994 0.05691748 0.04037499 0.01069998 0.05737495 0.03991746 0.01069998 0.05799996 0.03974997 0.01189994 0.05862498 0.03991746 0.01069998 0.05908244 0.04037499 0.01189994 0.05924999 0.04099994 0.01189994 0.05862498 0.04208248 0.01069998 -0.05862498 0.04208248 0.01069998 -0.05924999 0.04099994 0.01189994 -0.05924999 0.04099994 0.01069998 -0.05908244 0.04037499 0.01069998 -0.05862498 0.03991746 0.01189994 -0.05862498 0.03991746 0.01069998 -0.05799996 0.03974997 0.01069998 -0.05737495 0.03991746 0.01189994 -0.05691748 0.04037499 0.01189994 -0.05737495 0.04208248 0.01189994 0.07505857 0.04252678 0.01189994 0.07499158 0.04227679 0.01189994 0.07480859 0.04209375 0.01189994 0.07455855 0.04202675 0.01069998 0.07430857 0.04209375 0.01069998 0.07430857 0.04209375 0.01189994 0.07405859 0.04252678 0.01069998 0.07715189 0.04373538 0.01069998 0.08054035 0.04569166 0.01189994 0.07435858 0.04373919 0.01189994 0.07435858 0.04373919 0.01069998 0.08431857 0.04948955 0.01189994 0.08602219 0.05047315 0.01189994 0.08602219 0.05047315 0.01069998 0 0.07887929 0.01069998 0 0.07887929 0.01189994 0.001349985 0.07965868 0.01069998 0.001349985 0.07965868 0.01189994 0.001749992 0.07988959 0.01189994 -0.01174998 0.09198957 0.01069998 -0.00999999 0.09097927 0.01189994 -0.01174998 0.09198957 0.01189994 8.83013e-4 0.08608299 0.01069998 8.83013e-4 0.08608299 0.01189994 9.5e-4 0.08583295 0.01069998 9.5e-4 0.08583295 0.01189994 7e-4 0.08539998 0.01069998 4.5e-4 0.08533298 0.01069998 7e-4 0.08539998 0.01189994 4.5e-4 0.08533298 0.01189994 7e-4 0.099734 0.01069998 7e-4 0.08925718 0.01189994 7e-4 0.08626598 0.01189994 7e-4 0.08626598 0.01069998 -7e-4 0.08925718 0.01069998 -7e-4 0.08626598 0.01069998 -7e-4 0.08925718 0.01189994 -0.07435858 0.04373919 0.01069998 -0.08672219 0.04926079 0.01069998 -0.08672219 0.04926079 0.01189994 -0.07715189 0.04373538 0.01069998 -0.07505857 0.04252678 0.01069998 -0.07405859 0.04252678 0.01189994 -0.07412558 0.04227679 0.01069998 -0.07430857 0.04209375 0.01189994 -0.07455855 0.04202675 0.01189994 -0.07480859 0.04209375 0.01069998 -0.07480859 0.04209375 0.01189994 -0.07499158 0.04227679 0.01189994 -0.07505857 0.04252678 0.01189994 -0.002749979 0.05209529 0.01069998 -0.002749979 0.04948955 0.01189994 -0.002749979 0.04875379 0.01189994 -0.009249985 0.04875379 0.01069998 -0.009249985 0.04948955 0.01189994 -0.009249985 0.05209529 0.01069998 -0.01475 0.05209529 0.01069998 -0.01577627 0.05368095 0.01069998 -0.01596045 0.05556076 0.01189994 -0.01574945 0.05609047 0.01189994 -0.01596045 0.05556076 0.01069998 -0.01574945 0.05609047 0.01069998 -0.01383537 0.05855399 0.01189994 -0.01199996 0.05899995 0.01189994 -0.01199996 0.05899995 0.01069998 -0.01016455 0.05855399 0.01069998 -0.01016455 0.05855399 0.01189994 -0.008738398 0.05731558 0.01069998 -0.008250415 0.05609047 0.01189994 -0.008250415 0.05609047 0.01069998 -0.008039474 0.05556076 0.01189994 -0.008039474 0.05556076 0.01069998 -0.008223712 0.05368095 0.01069998 -0.008223712 0.05368095 0.01189994 -0.02107179 0.04875379 0.01069998 -0.02064436 0.04875379 0.01189994 -0.01671439 0.04875379 0.01189994 -0.01475 0.04875379 0.01189994 -0.01475 0.04875379 0.01069998 -0.02799999 0.04373538 0.01069998 -0.02799999 0.02999997 0.01069998 -0.02799999 0.02999997 0.01189994 -0.04299998 0.02999997 0.01069998 -0.04574996 0.03275376 0.01189994 -0.04349994 0.03275376 0.01069998 -0.05524998 0.03541129 0.01189994 -0.055067 0.03522825 0.01189994 -0.055 0.03497827 0.01069998 -0.05524998 0.0345453 0.01069998 -0.05524998 0.0345453 0.01189994 -0.05649995 0.03541129 0.01069998 -0.06024998 0.03541129 0.01069998 -0.0640307 0.03275376 0.01069998 -0.0640307 0.03275376 0.01189994 -0.0687313 0.03275376 0.01189994 -0.07270997 0.03045678 0.01069998 -0.07369947 0.02988547 0.01189994 -0.09546309 0.04752308 0.01189994 -0.0905168 0.05609047 0.01189994 -0.08863955 0.05934184 0.01189994 -0.0747832 0.05934184 0.01069998 -0.07270997 0.06053876 0.01069998 -0.07270997 0.06053876 0.01189994 -0.07061219 0.06174999 0.01189994 -0.06549996 0.06340247 0.01189994 -0.06549996 0.06073075 0.01069998 -0.06549996 0.06073075 0.01189994 -0.0640307 0.06073075 0.01069998 -0.0640307 0.06073075 0.01189994 -0.06074994 0.06073075 0.01069998 -0.05574995 0.05623078 0.01189994 -0.05574995 0.05623078 0.01069998 -0.05649995 0.05623078 0.01069998 -0.05649995 0.05623078 0.01189994 -0.05524998 0.06073075 0.01189994 -0.05049997 0.07292878 0.01189994 -0.05049997 0.06535255 0.01189994 -0.05049997 0.07292878 0.01069998 -0.03375959 0.08302676 0.01069998 -0.04349994 0.07740318 0.01069998 -0.04710906 0.07531946 0.01189994 -0.04710906 0.07531946 0.01069998 -0.050125 0.07357829 0.01189994 -0.050125 0.07357829 0.01069998 -0.01337498 0.09551757 0.01189994 -0.007071793 0.106435 0.01069998 -0.007071793 0.106435 0.01189994 0.006575286 0.106435 0.01189994 -0.003749966 0.106435 0.01189994 0.01189088 0.09784388 0.01069998 0.01337498 0.09544515 0.01189994 0.02064436 0.09059888 0.01069998 0.02296829 0.08925718 0.01069998 0.02848696 0.08607095 0.01069998 0.02848696 0.08607095 0.01189994 0.03185427 0.08412688 0.01069998 0.03185427 0.08412688 0.01189994 0.03375959 0.08302676 0.01069998 0.04121267 0.07872378 0.01069998 0.04349994 0.07740318 0.01069998 0.04121267 0.07872378 0.01189994 0.04349994 0.07740318 0.01189994 0.05049997 0.07292878 0.01069998 0.05049997 0.07292878 0.01189994 0.05049997 0.06535255 0.01069998 0.05049997 0.06535255 0.01189994 0.05049997 0.06174999 0.01189994 0.05049997 0.06073075 0.01189994 0.05449998 0.06073075 0.01069998 0.05524998 0.05709677 0.01189994 0.05524998 0.06073075 0.01189994 0.05949997 0.05623078 0.01189994 0.05649995 0.05623078 0.01069998 0.05574995 0.05623078 0.01069998 0.06074994 0.05709677 0.01189994 0.06074994 0.05709677 0.01069998 0.06074994 0.06073075 0.01189994 0.06074994 0.06073075 0.01069998 0.06549996 0.06073075 0.01189994 0.0747832 0.05934184 0.01189994 0.07270997 0.06053876 0.01189994 0.0747832 0.05934184 0.01069998 0.08054035 0.05916637 0.01069998 0.08054035 0.05916637 0.01189994 0.0873813 0.05895787 0.01069998 0.0873813 0.05895787 0.01189994 0.08888781 0.05891185 0.01189994 0.08888781 0.05891185 0.01069998 0.0905168 0.05609047 0.01189994 0.09571141 0.04709315 0.01069998 0.0937727 0.04373538 0.01069998 0.0887832 0.03509318 0.01189994 0.0873813 0.03428375 0.01189994 0.07673126 0.028135 0.01069998 0.07673126 0.028135 0.01189994 0.07270997 0.03045678 0.01069998 0.07270997 0.03045678 0.01189994 0.0687313 0.03275376 0.01069998 0.06074994 0.03350377 0.01069998 0.06024998 0.03541129 0.01069998 0.05574995 0.03541129 0.01189994 0.05524998 0.0345453 0.01069998 0.05524998 0.0345453 0.01189994 0.05037498 0.03275376 0.01189994 0.04349994 0.03275376 0.01189994 0.04299998 0.03275376 0.01189994 0.04299998 0.03275376 0.01069998 0.04299998 0.02999997 0.01189994 0.0309596 0.02999997 0.01069998 0.02848696 0.02999997 0.01189994 0.02848696 0.02999997 0.01069998 0.02799999 0.02999997 0.01069998 0.02799999 0.02999997 0.01189994 0.02064436 0.04875379 0.01189994 0.002749979 0.04948955 0.01069998 0.002749979 0.04948955 0.01189994 0.002749979 0.05209529 0.01069998 0.009249985 0.05209529 0.01189994 0.008223712 0.05368095 0.01189994 0.008223712 0.05368095 0.01069998 0.008039474 0.05556076 0.01069998 0.008250415 0.05609047 0.01069998 0.008738398 0.05731558 0.01189994 0.01016455 0.05855399 0.01069998 0.01337498 0.05866587 0.01069998 0.01596045 0.05556076 0.01189994 0.01577627 0.05368095 0.01189994 0.009249985 0.05209529 0.01069998 0.009249985 0.04948955 0.01189994 0.009249985 0.04875379 0.01069998 0.009249985 0.04875379 0.01189994 0.007874965 0.04875379 0.01189994 0.007874965 0.07487726 0.01189994 0.01337498 0.07170188 0.01189994 0.02064436 0.06750488 0.01189994 0.02064436 0.06750488 0.01069998 0.02437216 0.06535255 0.01069998 0.02848696 0.06297689 0.01189994 0.03049999 0.06181478 0.01189994 0.02848696 0.06297689 0.01069998 0.03049999 0.05609047 0.01069998 0.03049999 0.05609047 0.01189994 0.03049999 0.06174999 0.01189994 0.03049999 0.06181478 0.01069998 0.02899998 0.0501821 0.01069998 0.03029894 0.05093199 0.01069998 0.02848696 0.05031949 0.01069998 0.02848696 0.05031949 0.01189994 0.02899998 0.0501821 0.01189994 0.0194869 0.05544239 0.01189994 0.02064436 0.0547741 0.01069998 0.02064436 0.0547741 0.01189994 0.01927858 0.05609047 0.01069998 0.01337498 0.06214594 0.01069998 0.01337498 0.06214594 0.01189994 -0.04299998 0.04948955 0.01069998 -0.04299998 0.04948955 0.01189994 -0.04299998 0.04499995 0.01189994 -0.03866988 0.05709785 0.01189994 -0.03866988 0.05709785 0.01069998 -0.0345 0.04649996 0.01069998 -0.0345 0.04948955 0.01069998 -0.0345 0.05609047 0.01189994 -0.0345 0.0595054 0.01069998 -0.03470098 0.04574996 0.01069998 -0.03470098 0.04574996 0.01189994 -0.03599995 0.04499995 0.01189994 -0.04299998 0.04499995 0.01069998 0.001349985 0.06949996 0.01189994 -0.001874983 0.06949996 0.01189994 -0.003499984 0.06535255 0.01189994 -0.003499984 0.0625 0.01069998 -0.003499984 0.0625 0.01189994 -0.001874983 0.0625 0.01069998 0.001349985 0.0625 0.01189994 0.001349985 0.0625 0.01069998 0.001874983 0.0625 0.01189994 0.001874983 0.0625 0.01069998 0.01499998 0.08678519 0.01189994 0.01499998 0.08412688 0.01069998 0.01499998 0.07872378 0.01069998 0.01499998 0.07812488 0.01069998 0.01499998 0.07872378 0.01189994 0.01612496 0.0874347 0.01069998 0.01574999 0.0875352 0.01189994 0.01537495 0.0874347 0.01189994 0.01574999 0.0875352 0.01069998 0.01510047 0.08716017 0.01069998 0.01510047 0.08716017 0.01189994 0.02064436 0.08482539 0.01189994 0.02801787 0.08056825 0.01069998 0.02695298 0.07872378 0.01069998 0.0157237 0.07727408 0.01189994 0.01622366 0.07714009 0.01069998 0.01672369 0.07727408 0.01069998 0.01708966 0.07764005 0.01189994 0.01708966 0.07764005 0.01069998 0.01942986 0.07969325 0.01069998 0.02064436 0.078992 0.01189994 0.01942986 0.07969325 0.01189994 0.0343104 0.06688129 0.01069998 0.03448289 0.0665313 0.01069998 0.03448289 0.0665313 0.01189994 0.03477627 0.0662741 0.01189994 0.03637218 0.06535255 0.01069998 0.03477627 0.0662741 0.01069998 0.04349994 0.06408268 0.01189994 0.04449999 0.06466007 0.01069998 0.04449999 0.06535255 0.01189994 0.0314821 0.07856827 0.01069998 0.03375959 0.07725328 0.01069998 0.03710907 0.07531946 0.01189994 0.04349994 0.0716297 0.01189994 0.04349994 0.0716297 0.01069998 0.04449999 0.07105237 0.01189994 0.04449999 0.07105237 0.01069998 0.02895605 0.07419329 0.01069998 0.02895605 0.07419329 0.01189994 0.0309596 0.07303661 0.01189994 0.03538429 0.07032728 0.01069998 0.03551828 0.06982725 0.01069998 0.02848696 0.07330936 0.01069998 0.02848696 0.07330936 0.01189994 0.02818816 0.06886309 0.01189994 0.02818816 0.06886309 0.01069998 0.02325999 0.0763272 0.01069998 0.02267819 0.07531946 0.01069998 -0.02818816 0.06886309 0.01069998 -0.02325999 0.0763272 0.01069998 -0.0250054 0.07531946 0.01189994 0.01337498 0.08412688 0.01189994 0.04349994 0.07531946 0.01189994 0.01499998 0.07812488 0.01189994 0.02267819 0.07531946 0.01189994 0.01189088 0.09784388 0.01189994 -0.007874965 0.09784388 0.01189994 -0.009249985 0.05209529 0.01189994 -8.83013e-4 0.08608299 0.01189994 -7e-4 0.08626598 0.01189994 0.0874052 0.04944378 0.01189994 0.0873813 0.04941987 0.01189994 -0.05624997 0.05098956 0.01189994 -0.01337498 0.06174999 0.01189994 -0.0309596 0.07872378 0.01189994 -0.0301882 0.07232719 0.01189994 -0.02549195 0.07619327 0.01189994 -0.03375959 0.08302676 0.01189994 -0.04121267 0.07872378 0.01189994 -0.03710907 0.07531946 0.01189994 -0.04349994 0.07531946 0.01189994 -0.04449999 0.06535255 0.01189994 -0.04574996 0.06535255 0.01189994 -0.04449999 0.07105237 0.01189994 -0.03477627 0.0662741 0.01189994 -0.04103589 0.06266009 0.01189994 -0.03441029 0.06764006 0.01189994 -0.03428477 0.06727057 0.01189994 -0.0343104 0.06688129 0.01189994 -0.03448289 0.0665313 0.01189994 -0.03548419 0.07008606 0.01189994 -0.03550976 0.06969666 0.01189994 -0.03501826 0.07069325 0.01189994 -0.03538429 0.06932729 0.01189994 -0.03375959 0.07141995 0.01189994 -0.03221929 0.06964516 0.01189994 -0.0309596 0.07303661 0.01189994 -0.03181928 0.06953799 0.01189994 -0.0315265 0.06924515 0.01189994 -0.0315265 0.0684452 0.01189994 -0.03181928 0.06815236 0.01189994 -0.03221929 0.06804519 0.01189994 -0.03261929 0.06815236 0.01189994 -0.03375959 0.06535255 0.01189994 -0.03291207 0.0684452 0.01189994 -0.0330193 0.06884515 0.01189994 -0.03291207 0.06924515 0.01189994 -0.03261929 0.06953799 0.01189994 -0.01962888 0.07703799 0.01189994 -0.01922887 0.07714515 0.01189994 -0.01853609 0.07594519 0.01189994 -0.01671439 0.07531946 0.01189994 -0.02064436 0.07531946 0.01189994 -0.01922887 0.07554519 0.01189994 -0.01771539 0.07872378 0.01189994 -0.01708966 0.07764005 0.01189994 -0.01853609 0.07674515 0.01189994 -0.01842886 0.0763452 0.01189994 -0.01962888 0.07565236 0.01189994 -0.01992166 0.07594519 0.01189994 -0.02002888 0.0763452 0.01189994 -0.01992166 0.07674515 0.01189994 -0.01622366 0.07714009 0.01189994 -0.01671439 0.07727158 0.01189994 -0.01672369 0.07727408 0.01189994 -0.01337498 0.08412688 0.01189994 -0.01499998 0.07872378 0.01189994 -0.01504516 0.0778684 0.01189994 -0.01517546 0.07764279 0.01189994 -0.01537495 0.07747536 0.01189994 -0.01574999 0.0875352 0.01189994 -0.01337498 0.08925718 0.01189994 -0.01499998 0.08678519 0.01189994 -0.02064436 0.07872378 0.01189994 -0.01882886 0.07703799 0.01189994 -0.01892989 0.07982718 0.01189994 -0.01942986 0.07969325 0.01189994 -0.04699999 0.04373538 0.01189994 -0.05274999 0.04373538 0.01189994 -0.05449998 0.04948955 0.01189994 0.05274999 0.04373538 0.01189994 0.05449998 0.04373538 0.01189994 0.05037498 0.03875374 0.01189994 0.05037498 0.04948955 0.01189994 0.04699999 0.04373538 0.01189994 0.04349994 0.04373538 0.01189994 -0.0157237 0.07727408 0.01189994 -0.01337498 0.07531946 0.01189994 -0.01337498 0.07170188 0.01189994 -0.01882886 0.07565236 0.01189994 -0.02325999 0.0763272 0.01189994 -0.02125996 0.0728631 0.01189994 -0.02818816 0.06886309 0.01189994 -0.02437216 0.06535255 0.01189994 -0.0309596 0.06174999 0.01189994 -0.03049999 0.06181478 0.01189994 -0.02064436 0.04948955 0.01189994 -0.02974998 0.05038297 0.01189994 -0.03029894 0.05093199 0.01189994 -0.03049999 0.05168205 0.01189994 -0.03049999 0.05609047 0.01189994 -0.0309596 0.05609047 0.01189994 -0.03049999 0.06174999 0.01189994 -0.007874965 0.0625 0.01189994 -0.01199996 0.0625 0.01189994 0.04299998 0.04948955 0.01189994 0.04299998 0.04499995 0.01189994 0.0345 0.05609047 0.01189994 0.03925144 0.05609047 0.01189994 0.03375959 0.05609047 0.01189994 0.03375959 0.04948955 0.01189994 -0.003499984 0.06949996 0.01189994 -0.003499984 0.07113397 0.01189994 -0.003999948 0.07199996 0.01189994 -0.003866016 0.07449996 0.01189994 -0.003749966 0.07461595 0.01189994 -0.002499997 0.07486599 0.01189994 -0.002999961 0.07099997 0.01189994 -0.001874983 0.07531946 0.01189994 -0.001999974 0.07199996 0.01189994 -0.04699999 0.05899995 0.01189994 -0.04699999 0.06099998 0.01189994 -0.04749995 0.05913394 0.01189994 -0.04786598 0.05949997 0.01189994 -0.05049997 0.06073075 0.01189994 -0.04749995 0.06086599 0.01189994 -0.04499995 0.06099998 0.01189994 -0.04574996 0.06174999 0.01189994 -0.04574996 0.06099998 0.01189994 -0.04574996 0.05899995 0.01189994 -0.04574996 0.05609047 0.01189994 -0.04499995 0.05899995 0.01189994 -0.04413396 0.06049996 0.01189994 -0.04349994 0.06174999 0.01189994 -0.04349994 0.05609047 0.01189994 -0.04399996 0.06 0.01189994 -0.04699999 0.05299997 0.01189994 -0.04574996 0.04948955 0.01189994 -0.05274999 0.04899996 0.01189994 -0.04749995 0.05486595 0.01189994 -0.04699999 0.055 0.01189994 -0.04449999 0.05486595 0.01189994 -0.04499995 0.055 0.01189994 -0.04574996 0.055 0.01189994 -0.04574996 0.05299997 0.01189994 -0.04499995 0.05299997 0.01189994 -0.04449999 0.05313396 0.01189994 -0.04413396 0.05449998 0.01189994 -0.04399996 0.05399996 0.01189994 -0.04349994 0.04948955 0.01189994 -0.04413396 0.05349999 0.01189994 -0.0640307 0.05609047 0.01189994 -0.05974996 0.0530104 0.01189994 -0.05974996 0.05098956 0.01189994 -0.05799996 0.0540207 0.01189994 -0.05649995 0.05315464 0.01189994 -0.05624997 0.0530104 0.01189994 0.05449998 0.05609047 0.01189994 0.05624997 0.0530104 0.01189994 0.05649995 0.05084526 0.01189994 0.05449998 0.04948955 0.01189994 0.05649995 0.04948955 0.01189994 0.05949997 0.04948955 0.01189994 0.05649995 0.05315464 0.01189994 0.05799996 0.0540207 0.01189994 0.05949997 0.05315464 0.01189994 0.07270997 0.05609047 0.01189994 0.05974996 0.0530104 0.01189994 0.05974996 0.05098956 0.01189994 0.07729035 0.05414986 0.01189994 0.07554036 0.05313944 0.01189994 0.07379037 0.05414986 0.01189994 0.07379037 0.05609047 0.01189994 0.07379037 0.05617058 0.01189994 0.0741086 0.04380619 0.01189994 0.07715189 0.04373538 0.01189994 0.08054035 0.04373538 0.01189994 0.07367557 0.04355615 0.01189994 0.07405859 0.04252678 0.01189994 0.07385855 0.0428732 0.01189994 0.07367557 0.04305619 0.01189994 0.08054035 0.03033417 0.01189994 0.07455855 0.04202675 0.01189994 0.07412558 0.04227679 0.01189994 0.08722215 0.04926079 0.01189994 0.0873813 0.04373538 0.01189994 0.08697217 0.04919379 0.01189994 0.08672219 0.04926079 0.01189994 0.09571141 0.04709315 0.01189994 0.0873813 0.04996764 0.01189994 0.0874052 0.0499438 0.01189994 0.0943278 0.04948955 0.01189994 0.0867722 0.05090618 0.01189994 0.08695518 0.05072319 0.01189994 0.08054035 0.04730826 0.01189994 0.08054035 0.04948955 0.01189994 0.07729035 0.05609047 0.01189994 0.08702218 0.05047315 0.01189994 0.0873813 0.05609047 0.01189994 0.08722215 0.05012679 0.01189994 0.08608907 0.05072319 0.01189994 0.08054035 0.05609047 0.01189994 0.08627218 0.05090618 0.01189994 0.08652216 0.05097317 0.01189994 0 0.07887929 0.01189994 -0.001749992 0.07988959 0.01189994 -0.001749992 0.08191037 0.01189994 0 0.08292067 0.01189994 0.001349985 0.07872378 0.01189994 8.83013e-4 0.08558297 0.01189994 2e-4 0.08539998 0.01189994 -2e-4 0.08539998 0.01189994 -0.001874983 0.08412688 0.01189994 -4.5e-4 0.08533298 0.01189994 -7e-4 0.08539998 0.01189994 -9.5e-4 0.08583295 0.01189994 -8.83013e-4 0.08558297 0.01189994 4.12635e-4 0.100666 0.01189994 7e-4 0.099734 0.01189994 8.63119e-4 0.09988528 0.01189994 0.001349985 0.09784388 0.01189994 -8.83013e-4 0.100417 0.01189994 -0.001874983 0.106435 0.01189994 -9.5e-4 0.100167 0.01189994 -8.83013e-4 0.09991699 0.01189994 -7e-4 0.1006 0.01189994 0.001349985 0.106435 0.01189994 -4.5e-4 0.1006669 0.01189994 -2e-4 0.1006 0.01189994 2e-4 0.1006 0.01189994 6.32671e-4 0.100632 0.01189994 8.16526e-4 0.100507 0.01189994 9.27786e-4 0.100314 0.01189994 -0.001874983 0.08925718 0.01189994 -7e-4 0.09784388 0.01189994 -0.001874983 0.09784388 0.01189994 -7e-4 0.099734 0.01189994 -0.08554035 0.03986048 0.01189994 -0.08554035 0.03581899 0.01189994 -0.0872904 0.03682935 0.01189994 -0.0872904 0.03885006 0.01189994 -0.07412558 0.04227679 0.01189994 -0.08379036 0.03885006 0.01189994 -0.08379036 0.03682935 0.01189994 -0.07369947 0.04358005 0.01189994 -0.07367557 0.04355615 0.01189994 -0.07360857 0.04330617 0.01189994 -0.07367557 0.04305619 0.01189994 -0.07369947 0.04303228 0.01189994 -0.07385855 0.0428732 0.01189994 -0.07385468 0.04373538 0.01189994 -0.07369947 0.04373538 0.01189994 -0.07385855 0.04373919 0.01189994 -0.0741086 0.04380619 0.01189994 -0.07435858 0.04373919 0.01189994 -0.0874722 0.04969376 0.01189994 -0.08652216 0.05097317 0.01189994 -0.07729035 0.05609047 0.01189994 -0.0943278 0.04948955 0.01189994 -0.0874052 0.0499438 0.01189994 -0.08722215 0.05012679 0.01189994 -0.08702218 0.05047315 0.01189994 -0.08695518 0.05072319 0.01189994 -0.0867722 0.05090618 0.01189994 -0.07379037 0.05414986 0.01189994 -0.07554036 0.05313944 0.01189994 -0.08431857 0.04948955 0.01189994 -0.08602219 0.05047315 0.01189994 -0.07729035 0.05414986 0.01189994 -0.08608907 0.05072319 0.01189994 -0.08627218 0.05090618 0.01189994 -0.08722215 0.04926079 0.01189994 -0.0874052 0.04944378 0.01189994 -0.07715189 0.04373538 0.01189994 -0.09342759 0.04373538 0.01189994 -0.08697217 0.04919379 0.01189994 -0.08741748 0.04948955 0.01189994 -0.07729035 0.05617058 0.01189994 -0.07554036 0.057181 0.01189994 -0.07379037 0.05617058 0.01189994 -0.07369947 0.05609047 0.01189994 -0.07379037 0.05609047 0.01189994 0.002749979 0.05209529 0.01189994 0.003776252 0.05368095 0.01189994 0.00396049 0.05556076 0.01189994 0.003749489 0.05609047 0.01189994 0.003261566 0.05731558 0.01189994 -0.003261566 0.05731558 0.01189994 -0.001874983 0.05851966 0.01189994 -0.001835405 0.05855399 0.01189994 -0.001874983 0.06174999 0.01189994 0 0.05899995 0.01189994 0.001349985 0.05867195 0.01189994 -0.003749966 0.05608928 0.01189994 -0.003749966 0.05609047 0.01189994 -0.003749489 0.05609047 0.01189994 -0.003776252 0.05368095 0.01189994 -0.003749966 0.04875379 0.01189994 -0.003749966 0.04948955 0.01189994 -0.003749966 0.05364036 0.01189994 -0.002749979 0.05209529 0.01189994 -0.009249985 0.04875379 0.01189994 -0.007874965 0.04875379 0.01189994 -0.007874965 0.04948955 0.01189994 -0.007874965 0.06174999 0.01189994 -0.007874965 0.05609047 0.01189994 -0.01577627 0.05368095 0.01189994 -0.01834267 0.05900257 0.01189994 -0.01671439 0.05609047 0.01189994 -0.01526159 0.05731558 0.01189994 -0.01562148 0.06156766 0.01189994 -0.01337498 0.05866587 0.01189994 -0.008738398 0.05731558 0.01189994 -0.01475 0.05209529 0.01189994 -0.01475 0.04948955 0.01189994 -0.0194869 0.05544239 0.01189994 -0.01671439 0.04948955 0.01189994 -0.02799999 0.04475378 0.01189994 -0.02107179 0.04875379 0.01189994 -0.02799999 0.04373538 0.01189994 -0.04574996 0.04373538 0.01189994 -0.05574995 0.03541129 0.01189994 -0.05549997 0.03547829 0.01189994 -0.05274999 0.03875374 0.01189994 -0.05449998 0.04373538 0.01189994 -0.055 0.03497827 0.01189994 -0.05514949 0.03312879 0.01189994 -0.05524998 0.03350377 0.01189994 -0.05487495 0.03285425 0.01189994 -0.05449998 0.03275376 0.01189994 -0.055067 0.03472828 0.01189994 -0.05799996 0.04224997 0.01189994 -0.06093299 0.03472828 0.01189994 -0.06099998 0.03497827 0.01189994 -0.06093299 0.03522825 0.01189994 -0.06121295 0.03281086 0.01189994 -0.06096965 0.03297346 0.01189994 -0.05674999 0.04099994 0.01189994 -0.05649995 0.04373538 0.01189994 -0.05691748 0.04162496 0.01189994 -0.06074994 0.0345453 0.01189994 -0.06149995 0.03275376 0.01189994 -0.06074994 0.03350377 0.01189994 -0.06080704 0.03321677 0.01189994 -0.06074994 0.03541129 0.01189994 -0.06049996 0.03547829 0.01189994 -0.05908244 0.04162496 0.01189994 -0.05649995 0.03541129 0.01189994 -0.05799996 0.03974997 0.01189994 -0.06024998 0.03541129 0.01189994 -0.05908244 0.04037499 0.01189994 -0.07270997 0.04373538 0.01189994 -0.07181149 0.03943955 0.01189994 -0.0700615 0.03842926 0.01189994 -0.07270997 0.03045678 0.01189994 -0.06831145 0.03943955 0.01189994 -0.06831145 0.04146039 0.01189994 -0.0640307 0.04373538 0.01189994 -0.06549996 0.06174999 0.01189994 -0.06574815 0.06395977 0.01189994 -0.06601816 0.06411576 0.01189994 -0.06662499 0.06405198 0.01189994 -0.0663284 0.06414836 0.01189994 -0.06556481 0.06370747 0.01189994 -0.06093299 0.05641376 0.01189994 -0.06074994 0.05709677 0.01189994 -0.06074994 0.06073075 0.01189994 -0.06024998 0.05623078 0.01189994 -0.05649995 0.05609047 0.01189994 -0.06049996 0.05616378 0.01189994 -0.06074994 0.05623078 0.01189994 -0.05524998 0.05709677 0.01189994 -0.05449998 0.06073075 0.01189994 -0.055067 0.05691379 0.01189994 -0.05449998 0.05609047 0.01189994 -0.055 0.05666375 0.01189994 -0.055067 0.05641376 0.01189994 -0.05524998 0.05623078 0.01189994 -0.05549997 0.05616378 0.01189994 -0.05049997 0.06174999 0.01189994 -0.04574996 0.07531946 0.01189994 -0.04349994 0.07740318 0.01189994 -0.04574996 0.07610416 0.01189994 -0.05039948 0.07330375 0.01189994 -0.02296829 0.08925718 0.01189994 -0.0309596 0.08464336 0.01189994 -0.03185427 0.08412688 0.01189994 -0.0314821 0.07856827 0.01189994 -0.03375959 0.07872378 0.01189994 -0.03375959 0.07725328 0.01189994 -0.03141927 0.06884515 0.01189994 -0.0309596 0.06535255 0.01189994 -0.02895605 0.07419329 0.01189994 -0.0296064 0.07531946 0.01189994 -0.0309596 0.07766336 0.01189994 -0.02695298 0.07872378 0.01189994 -0.0309596 0.08412688 0.01189994 -0.02064436 0.08925718 0.01189994 -0.01671439 0.08925718 0.01189994 -0.02064436 0.09059888 0.01189994 -0.01671439 0.09286791 0.01189994 -0.008249998 0.09198957 0.01189994 -0.008249998 0.09401035 0.01189994 -0.00999999 0.09502071 0.01189994 -0.01203185 0.09784388 0.01189994 -0.01174998 0.09401035 0.01189994 0.01174998 0.09198957 0.01189994 0.00999999 0.09097927 0.01189994 0.008249998 0.09401035 0.01189994 0.00999999 0.09502071 0.01189994 0.001874983 0.106435 0.01189994 0.001874983 0.09784388 0.01189994 0.007874965 0.104335 0.01189994 0.007874965 0.09784388 0.01189994 0.008249998 0.09198957 0.01189994 0.01174998 0.09401035 0.01189994 0.02064436 0.09059888 0.01189994 0.0309596 0.08412688 0.01189994 0.03375959 0.08302676 0.01189994 0.05039948 0.07330375 0.01189994 0.05037498 0.07332825 0.01189994 0.05037498 0.06535255 0.01189994 0.05449998 0.06073075 0.01189994 0.055067 0.05691379 0.01189994 0.055067 0.05641376 0.01189994 0.055 0.05666375 0.01189994 0.05574995 0.05623078 0.01189994 0.05549997 0.05616378 0.01189994 0.05524998 0.05623078 0.01189994 0.05949997 0.05609047 0.01189994 0.05649995 0.05609047 0.01189994 0.05649995 0.05623078 0.01189994 0.07729035 0.05617058 0.01189994 0.07554036 0.057181 0.01189994 0.06093299 0.05641376 0.01189994 0.06074994 0.05623078 0.01189994 0.06049996 0.05616378 0.01189994 0.06024998 0.05623078 0.01189994 0.06093299 0.05691379 0.01189994 0.06099998 0.05666375 0.01189994 0.06556481 0.06370747 0.01189994 0.0663284 0.06414836 0.01189994 0.06601816 0.06411576 0.01189994 0.06662499 0.06405198 0.01189994 0.06574815 0.06395977 0.01189994 0.06549996 0.06340247 0.01189994 0.07061219 0.06174999 0.01189994 0.06549996 0.06174999 0.01189994 0.0937727 0.04373538 0.01189994 0.0872904 0.03885006 0.01189994 0.0874722 0.04969376 0.01189994 0.08741748 0.04948955 0.01189994 0.0872904 0.03682935 0.01189994 0.08554035 0.03581899 0.01189994 0.08379036 0.03682935 0.01189994 0.08379036 0.03885006 0.01189994 0.08554035 0.03986048 0.01189994 0.07270997 0.04373538 0.01189994 0.0700615 0.04247069 0.01189994 0.07181149 0.04146039 0.01189994 0.07181149 0.03943955 0.01189994 0.06024998 0.03541129 0.01189994 0.05949997 0.04373538 0.01189994 0.06049996 0.03547829 0.01189994 0.06831145 0.04146039 0.01189994 0.0608505 0.03312879 0.01189994 0.06112498 0.03285425 0.01189994 0.06074994 0.03541129 0.01189994 0.06093299 0.03522825 0.01189994 0.06831145 0.03943955 0.01189994 0.06099998 0.03497827 0.01189994 0.0700615 0.03842926 0.01189994 0.07360857 0.04330617 0.01189994 0.06093299 0.03472828 0.01189994 0.06074994 0.0345453 0.01189994 0.0687313 0.03275376 0.01189994 0.06074994 0.03350377 0.01189994 0.06149995 0.03275376 0.01189994 0.05799996 0.04224997 0.01189994 0.05862498 0.04208248 0.01189994 0.05908244 0.04162496 0.01189994 0.05949997 0.03541129 0.01189994 0.05862498 0.03991746 0.01189994 0.05649995 0.03541129 0.01189994 0.05737495 0.03991746 0.01189994 0.05524998 0.03541129 0.01189994 0.05549997 0.03547829 0.01189994 0.05487495 0.03285425 0.01189994 0.05514949 0.03312879 0.01189994 0.05524998 0.03350377 0.01189994 0.055067 0.03522825 0.01189994 0.05449998 0.03275376 0.01189994 0.055 0.03497827 0.01189994 0.055067 0.03472828 0.01189994 0.03375959 0.02999997 0.01189994 0.0309596 0.02999997 0.01189994 0.02799999 0.04373538 0.01189994 0.02848696 0.04948955 0.01189994 0.02107179 0.04875379 0.01189994 0.02064436 0.04948955 0.01189994 0.01927858 0.05609047 0.01189994 0.01475 0.04875379 0.01189994 0.01475 0.04948955 0.01189994 0.01475 0.05209529 0.01189994 0.01574945 0.05609047 0.01189994 0.01526159 0.05731558 0.01189994 0.01383537 0.05855399 0.01189994 0.01337498 0.05866587 0.01189994 0.01491338 0.06174999 0.01189994 0.01562148 0.06156766 0.01189994 0.01834267 0.05900257 0.01189994 0.008250415 0.05609047 0.01189994 0.007874965 0.06174999 0.01189994 0.01016455 0.05855399 0.01189994 0.01337498 0.06174999 0.01189994 0.01199996 0.05899995 0.01189994 0.007874965 0.04948955 0.01189994 0.007874965 0.05609047 0.01189994 0.008039474 0.05556076 0.01189994 0.002749979 0.04875379 0.01189994 0.02824997 0.05038297 0.01189994 0.02974998 0.05038297 0.01189994 0.03029894 0.05093199 0.01189994 0.03049999 0.05168205 0.01189994 0.0309596 0.06174999 0.01189994 0.007499992 0.0750938 0.01189994 0.002499997 0.07486599 0.01189994 0.003499984 0.07113397 0.01189994 0.001874983 0.06949996 0.01189994 0.002499997 0.07113397 0.01189994 0.001999974 0.07199996 0.01189994 0.003866016 0.07449996 0.01189994 0.003999948 0.07199996 0.01189994 0.007499992 0.06535255 0.01189994 0.003499984 0.06949996 0.01189994 0.003499984 0.06535255 0.01189994 0.001874983 0.06174999 0.01189994 0.001874983 0.05851966 0.01189994 0.001835405 0.05855399 0.01189994 0.01199996 0.0625 0.01189994 0.007874965 0.0625 0.01189994 -0.0345 0.04649996 0.01189994 -0.03375959 0.04373538 0.01189994 -0.03524994 0.045201 0.01189994 -0.04299998 0.04959785 0.01189994 -0.03925144 0.05609047 0.01189994 -0.0345 0.0595054 0.01189994 -0.0345 0.04948955 0.01189994 0.001349985 0.07531946 0.01189994 0.001874983 0.07531946 0.01189994 -0.003749966 0.06174999 0.01189994 -0.003749966 0.06535255 0.01189994 -0.003749966 0.07138395 0.01189994 0.003499984 0.0625 0.01189994 0.001349985 0.06174999 0.01189994 -0.001874983 0.0625 0.01189994 0.02549195 0.07619327 0.01189994 0.0250054 0.07531946 0.01189994 0.02695298 0.07872378 0.01189994 0.02801787 0.08056825 0.01189994 0.02848696 0.08412688 0.01189994 0.02064436 0.08925718 0.01189994 0.02296829 0.08925718 0.01189994 0.01337498 0.08925718 0.01189994 0.02185428 0.08412688 0.01189994 0.01612496 0.0874347 0.01189994 0.01922887 0.07714515 0.01189994 0.01962888 0.07703799 0.01189994 0.02064436 0.07872378 0.01189994 0.01992166 0.07674515 0.01189994 0.02002888 0.0763452 0.01189994 0.02064436 0.07531946 0.01189994 0.01992166 0.07594519 0.01189994 0.01962888 0.07565236 0.01189994 0.01771539 0.07872378 0.01189994 0.01882886 0.07703799 0.01189994 0.01853609 0.07674515 0.01189994 0.01672369 0.07727408 0.01189994 0.01842886 0.0763452 0.01189994 0.0301882 0.07232719 0.01189994 0.02848696 0.06938076 0.01189994 0.02437216 0.06535255 0.01189994 0.02125996 0.0728631 0.01189994 0.01337498 0.07531946 0.01189994 0.01922887 0.07554519 0.01189994 0.01517546 0.07764279 0.01189994 0.01853609 0.07594519 0.01189994 0.01882886 0.07565236 0.01189994 0.01622366 0.07714009 0.01189994 0.01537495 0.07747536 0.01189994 0.01892989 0.07982718 0.01189994 0.01842987 0.07969325 0.01189994 0.01806378 0.07932716 0.01189994 0.0211091 0.07872378 0.01189994 0.02325999 0.0763272 0.01189994 0.03637218 0.06535255 0.01189994 0.0343104 0.06688129 0.01189994 0.03428477 0.06727057 0.01189994 0.03551828 0.06982725 0.01189994 0.03375959 0.07141995 0.01189994 0.03441029 0.06764006 0.01189994 0.03538429 0.06932729 0.01189994 0.03501826 0.07069325 0.01189994 0.03538429 0.07032728 0.01189994 0.04449999 0.06466007 0.01189994 0.04349994 0.06174999 0.01189994 0.04103589 0.06266009 0.01189994 0.03375959 0.06535255 0.01189994 0.03866988 0.05709785 0.01189994 0.050125 0.07357829 0.01189994 0.04710906 0.07531946 0.01189994 0.03375959 0.07725328 0.01189994 0.0314821 0.07856827 0.01189994 0.03375959 0.07872378 0.01189994 0.0309596 0.07872378 0.01189994 0.0309596 0.07766336 0.01189994 0.02848696 0.06535255 0.01189994 0.02848696 0.07531946 0.01189994 0.0296064 0.07531946 0.01189994 0.03261929 0.06953799 0.01189994 0.03221929 0.06964516 0.01189994 0.03181928 0.06953799 0.01189994 0.03221929 0.06804519 0.01189994 0.03181928 0.06815236 0.01189994 0.0330193 0.06884515 0.01189994 0.03291207 0.06924515 0.01189994 0.0315265 0.0684452 0.01189994 0.03141927 0.06884515 0.01189994 0.0309596 0.06535255 0.01189994 0.0315265 0.06924515 0.01189994 0.05649995 0.04373538 0.01189994 0.07385468 0.04373538 0.01189994 0.07270997 0.04948955 0.01189994 0.07385855 0.04373919 0.01189994 0.04413396 0.05349999 0.01189994 0.04349994 0.04948955 0.01189994 0.04399996 0.05399996 0.01189994 0.04413396 0.05449998 0.01189994 0.04449999 0.05486595 0.01189994 0.04499995 0.055 0.01189994 0.05624997 0.05098956 0.01189994 0.05037498 0.05609047 0.01189994 0.04799997 0.05399996 0.01189994 0.04749995 0.05313396 0.01189994 0.04699999 0.05299997 0.01189994 0.04499995 0.05299997 0.01189994 0.04449999 0.05313396 0.01189994 0.04699999 0.06099998 0.01189994 0.04749995 0.06086599 0.01189994 0.05037498 0.06174999 0.01189994 0.04799997 0.06 0.01189994 0.04786598 0.05949997 0.01189994 0.04749995 0.05913394 0.01189994 0.04699999 0.05899995 0.01189994 0.04349994 0.05609047 0.01189994 0.04499995 0.05899995 0.01189994 0.04449999 0.05913394 0.01189994 0.03291207 0.0684452 0.01189994 0.03261929 0.06815236 0.01189994 0.03375959 0.06174999 0.01189994 0.0309596 0.05609047 0.01189994 0.02799999 0.04475378 0.01189994 0.02848696 0.04373538 0.01189994 0.0309596 0.04373538 0.01189994 0.0309596 0.04948955 0.01189994 0.03375959 0.04373538 0.01189994 0.0345 0.04649996 0.01189994 0.0309596 0.08464336 0.01189994 0.02848696 0.07872378 0.01189994 0.001874983 0.08412688 0.01189994 0.001349985 0.08925718 0.01189994 0.001349985 0.08412688 0.01189994 0.001349985 0.08214128 0.01189994 0.001749992 0.08191037 0.01189994 7e-4 0.09784388 0.01189994 0.001874983 0.08925718 0.01189994 0.007874965 0.08412688 0.01189994 0.01499998 0.08412688 0.01189994 0.01337498 0.07872378 0.01189994 0.007874965 0.08925718 0.01189994 9.44415e-4 0.100092 0.01189994 0.01504516 0.0778684 0.01189994 0.007874965 0.07872378 0.01189994 0.007874965 0.07531946 0.01189994 0.001874983 0.07872378 0.01189994 -0.003749966 0.09784388 0.01189994 -0.003749966 0.08925718 0.01189994 -0.003749966 0.08412688 0.01189994 -0.001874983 0.07872378 0.01189994 -0.007499992 0.0625 0.01189994 -0.00396049 0.05556076 0.01189994 -0.007874965 0.07487726 0.01189994 -0.007874965 0.07531946 0.01189994 -0.007499992 0.0750938 0.01189994 -0.003749966 0.07531946 0.01189994 -0.007874965 0.07872378 0.01189994 -0.003749966 0.07872378 0.01189994 -0.007874965 0.08412688 0.01189994 -0.007874965 0.08925718 0.01189994 -0.007874965 0.105044 0.01189994 -0.01337498 0.07872378 0.01189994 -0.03375959 0.06174999 0.01189994 -0.03375959 0.05609047 0.01189994 -0.0309596 0.04948955 0.01189994 -0.0309596 0.04373538 0.01189994 -0.03375959 0.04948955 0.01189994 -0.0309596 0.02999997 0.01189994 -0.03375959 0.02999997 0.01189994 -0.04299998 0.02999997 0.01189994 -0.04299998 0.03275376 0.01189994 -0.04349994 0.03275376 0.01189994 -0.04349994 0.04373538 0.01189994 -0.04699999 0.04899996 0.01189994 -0.05649995 0.05084526 0.01189994 -0.05799996 0.04997926 0.01189994 -0.0640307 0.04948955 0.01189994 -0.05649995 0.04948955 0.01189994 -0.05862498 0.04208248 0.01189994 -0.07181149 0.04146039 0.01189994 -0.0700615 0.04247069 0.01189994 -0.06099998 0.05666375 0.01189994 -0.06093299 0.05691379 0.01189994 -0.07369947 0.05996757 0.01189994 -0.07270997 0.05609047 0.01189994 -0.07270997 0.04948955 0.01189994 -0.07369947 0.04948955 0.01189994 -0.02267819 0.07531946 0.01189994 0.04499995 0.05899995 0.01069998 -0.01337498 0.08412688 0.01069998 0.01853609 0.07594519 0.01069998 -0.07385468 0.04373538 0.01069998 -0.007874965 0.105044 0.01069998 0.05049997 0.06073075 0.01069998 0.0874052 0.0499438 0.01069998 0.0873813 0.04996764 0.01069998 0.0943278 0.04948955 0.01069998 -0.01499998 0.07872378 0.01069998 -0.03637218 0.06535255 0.01069998 -0.03448289 0.0665313 0.01069998 -0.0343104 0.06688129 0.01069998 -0.03375959 0.07141995 0.01069998 -0.03428477 0.06727057 0.01069998 -0.03441029 0.06764006 0.01069998 -0.03538429 0.06932729 0.01069998 -0.04449999 0.06535255 0.01069998 -0.04349994 0.07531946 0.01069998 -0.04349994 0.0716297 0.01069998 -0.04121267 0.07872378 0.01069998 -0.03710907 0.07531946 0.01069998 -0.03375959 0.07872378 0.01069998 -0.0314821 0.07856827 0.01069998 -0.0211091 0.07872378 0.01069998 -0.0301882 0.07232719 0.01069998 -0.0315265 0.06924515 0.01069998 -0.0309596 0.07303661 0.01069998 -0.03181928 0.06815236 0.01069998 -0.0315265 0.0684452 0.01069998 -0.03181928 0.06953799 0.01069998 -0.03221929 0.06964516 0.01069998 -0.03261929 0.06953799 0.01069998 -0.03291207 0.06924515 0.01069998 -0.0330193 0.06884515 0.01069998 -0.03291207 0.0684452 0.01069998 -0.04449999 0.06466007 0.01069998 -0.04349994 0.06408268 0.01069998 -0.03375959 0.06535255 0.01069998 -0.03261929 0.06815236 0.01069998 -0.03221929 0.06804519 0.01069998 -0.03141927 0.06884515 0.01069998 -0.0250054 0.07531946 0.01069998 -0.02549195 0.07619327 0.01069998 -0.0296064 0.07531946 0.01069998 -0.0309596 0.07766336 0.01069998 -0.0309596 0.07872378 0.01069998 -0.01671439 0.08709436 0.01069998 -0.01537495 0.0874347 0.01069998 -0.01574999 0.0875352 0.01069998 -0.01504516 0.0778684 0.01069998 -0.0157237 0.07727408 0.01069998 -0.01517546 0.07764279 0.01069998 -0.01922887 0.07554519 0.01069998 -0.01671439 0.07531946 0.01069998 -0.01622366 0.07714009 0.01069998 -0.01671439 0.07727158 0.01069998 -0.01882886 0.07565236 0.01069998 -0.01672369 0.07727408 0.01069998 -0.01853609 0.07594519 0.01069998 -0.01842886 0.0763452 0.01069998 -0.01708966 0.07764005 0.01069998 -0.01853609 0.07674515 0.01069998 -0.01882886 0.07703799 0.01069998 -0.01771539 0.07872378 0.01069998 -0.01922887 0.07714515 0.01069998 -0.01962888 0.07703799 0.01069998 -0.01992166 0.07674515 0.01069998 -0.02002888 0.0763452 0.01069998 -0.01992166 0.07594519 0.01069998 -0.01962888 0.07565236 0.01069998 -0.01892989 0.07982718 0.01069998 -0.01842987 0.07969325 0.01069998 -0.01806378 0.07932716 0.01069998 -0.02064436 0.07872378 0.01069998 -0.05449998 0.04373538 0.01069998 -0.04574996 0.04948955 0.01069998 -0.04574996 0.03275376 0.01069998 -0.05274999 0.03875374 0.01069998 0.05037498 0.04948955 0.01069998 -0.02974998 0.05038297 0.01069998 -0.0309596 0.04948955 0.01069998 -0.03049999 0.05168205 0.01069998 -0.03029894 0.05093199 0.01069998 -0.0309596 0.06174999 0.01069998 -0.007874965 0.07531946 0.01069998 -0.01337498 0.07531946 0.01069998 -0.01671439 0.06977385 0.01069998 -0.02064436 0.07531946 0.01069998 -0.003749966 0.07138395 0.01069998 -0.003749966 0.07461595 0.01069998 -0.003866016 0.07449996 0.01069998 -0.003866016 0.0715 0.01069998 -0.003749966 0.06535255 0.01069998 -0.01337498 0.06174999 0.01069998 -0.01337498 0.05866587 0.01069998 -0.01383537 0.05855399 0.01069998 -0.01562148 0.06156766 0.01069998 -0.02064436 0.04948955 0.01069998 -0.02064436 0.0547741 0.01069998 -0.01671439 0.04948955 0.01069998 -0.0194869 0.05544239 0.01069998 -0.01671439 0.05609047 0.01069998 0.03375959 0.05609047 0.01069998 0.03375959 0.04948955 0.01069998 0.03524994 0.045201 0.01069998 0.03375959 0.04373538 0.01069998 0.04349994 0.04373538 0.01069998 0.03599995 0.04499995 0.01069998 0.04299998 0.04499995 0.01069998 0.04299998 0.04959785 0.01069998 0.03925144 0.05609047 0.01069998 0.04349994 0.06174999 0.01069998 0.03866988 0.05709785 0.01069998 0.0345 0.04948955 0.01069998 0.008738398 0.05731558 0.01069998 0.01574945 0.05609047 0.01069998 0.01834267 0.05900257 0.01069998 0.01526159 0.05731558 0.01069998 0.01562148 0.06156766 0.01069998 0.01383537 0.05855399 0.01069998 0.01491338 0.06174999 0.01069998 0.01199996 0.05899995 0.01069998 0.007874965 0.06174999 0.01069998 0.01475 0.05209529 0.01069998 0.0194869 0.05544239 0.01069998 0.01577627 0.05368095 0.01069998 0.01596045 0.05556076 0.01069998 0.01475 0.04875379 0.01069998 0.02064436 0.04875379 0.01069998 0.02064436 0.04948955 0.01069998 0.02107179 0.04875379 0.01069998 0.02848696 0.04373538 0.01069998 0.02799999 0.04475378 0.01069998 0.02799999 0.04373538 0.01069998 0.04299998 0.02999997 0.01069998 0.03375959 0.02999997 0.01069998 0.04349994 0.03275376 0.01069998 0.05524998 0.03541129 0.01069998 0.055067 0.03522825 0.01069998 0.055 0.03497827 0.01069998 0.055067 0.03472828 0.01069998 0.05514949 0.03312879 0.01069998 0.05487495 0.03285425 0.01069998 0.05524998 0.03350377 0.01069998 0.05908244 0.04162496 0.01069998 0.05924999 0.04099994 0.01069998 0.05737495 0.04208248 0.01069998 0.05691748 0.04162496 0.01069998 0.05649995 0.04373538 0.01069998 0.05674999 0.04099994 0.01069998 0.05799996 0.03974997 0.01069998 0.05649995 0.03541129 0.01069998 0.05949997 0.03541129 0.01069998 0.05549997 0.03547829 0.01069998 0.05574995 0.03541129 0.01069998 0.05908244 0.04037499 0.01069998 0.06074994 0.0345453 0.01069998 0.06093299 0.03472828 0.01069998 0.06831145 0.04146039 0.01069998 0.0700615 0.04247069 0.01069998 0.07181149 0.04146039 0.01069998 0.07181149 0.03943955 0.01069998 0.06112498 0.03285425 0.01069998 0.0608505 0.03312879 0.01069998 0.06149995 0.03275376 0.01069998 0.06099998 0.03497827 0.01069998 0.06831145 0.03943955 0.01069998 0.06093299 0.03522825 0.01069998 0.06074994 0.03541129 0.01069998 0.05949997 0.04373538 0.01069998 0.06049996 0.03547829 0.01069998 0.07385468 0.04373538 0.01069998 0.07367557 0.04355615 0.01069998 0.07270997 0.04373538 0.01069998 0.0700615 0.03842926 0.01069998 0.07360857 0.04330617 0.01069998 0.07367557 0.04305619 0.01069998 0.07385855 0.0428732 0.01069998 0.07412558 0.04227679 0.01069998 0.08054035 0.03033417 0.01069998 0.07480859 0.04209375 0.01069998 0.07499158 0.04227679 0.01069998 0.08554035 0.03581899 0.01069998 0.0872904 0.03682935 0.01069998 0.08379036 0.03682935 0.01069998 0.08379036 0.03885006 0.01069998 0.08554035 0.03986048 0.01069998 0.0872904 0.03885006 0.01069998 0.0873813 0.03428375 0.01069998 0.0887832 0.03509318 0.01069998 0.0905168 0.05609047 0.01069998 0.0874722 0.04969376 0.01069998 0.06074994 0.05623078 0.01069998 0.06049996 0.05616378 0.01069998 0.06024998 0.05623078 0.01069998 0.06093299 0.05691379 0.01069998 0.06549996 0.06073075 0.01069998 0.06099998 0.05666375 0.01069998 0.06093299 0.05641376 0.01069998 0.07270997 0.06053876 0.01069998 0.06549996 0.06174999 0.01069998 0.07061219 0.06174999 0.01069998 0.06662499 0.06405198 0.01069998 0.06601816 0.06411576 0.01069998 0.0663284 0.06414836 0.01069998 0.06574815 0.06395977 0.01069998 0.06556481 0.06370747 0.01069998 0.06549996 0.06340247 0.01069998 0.05949997 0.05623078 0.01069998 0.05649995 0.05609047 0.01069998 0.05524998 0.06073075 0.01069998 0.05524998 0.05709677 0.01069998 0.055067 0.05691379 0.01069998 0.05449998 0.05609047 0.01069998 0.055 0.05666375 0.01069998 0.055067 0.05641376 0.01069998 0.05524998 0.05623078 0.01069998 0.05549997 0.05616378 0.01069998 0.05037498 0.07332825 0.01069998 0.05039948 0.07330375 0.01069998 0.04349994 0.07531946 0.01069998 0.03710907 0.07531946 0.01069998 0.03375959 0.07872378 0.01069998 0.0309596 0.08464336 0.01069998 0.0309596 0.08412688 0.01069998 0.01399999 0.09443509 0.01069998 0.02064436 0.08925718 0.01069998 0.01337498 0.08925718 0.01069998 0.01337498 0.09544515 0.01069998 0.008249998 0.09198957 0.01069998 0.008249998 0.09401035 0.01069998 0.007874965 0.09784388 0.01069998 0.00999999 0.09502071 0.01069998 0.01174998 0.09401035 0.01069998 0.01174998 0.09198957 0.01069998 0.001874983 0.09784388 0.01069998 -0.003749966 0.106435 0.01069998 -0.001874983 0.106435 0.01069998 -0.008249998 0.09198957 0.01069998 -0.007874965 0.08925718 0.01069998 -0.007874965 0.09784388 0.01069998 -0.01203185 0.09784388 0.01069998 -0.008249998 0.09401035 0.01069998 -0.00999999 0.09502071 0.01069998 -0.01337498 0.09551757 0.01069998 -0.01174998 0.09401035 0.01069998 -0.00999999 0.09097927 0.01069998 -0.02296829 0.08925718 0.01069998 -0.02064436 0.09059888 0.01069998 -0.03185427 0.08412688 0.01069998 -0.0309596 0.08412688 0.01069998 -0.0309596 0.08464336 0.01069998 -0.02185428 0.08412688 0.01069998 -0.02064436 0.08925718 0.01069998 -0.01671439 0.08925718 0.01069998 -0.01671439 0.09286791 0.01069998 -0.01399999 0.09443509 0.01069998 -0.01337498 0.08925718 0.01069998 -0.04574996 0.07610416 0.01069998 -0.05039948 0.07330375 0.01069998 -0.04574996 0.06174999 0.01069998 -0.04699999 0.06099998 0.01069998 -0.04574996 0.07531946 0.01069998 -0.04449999 0.07105237 0.01069998 -0.04574996 0.06535255 0.01069998 -0.05049997 0.06535255 0.01069998 -0.05049997 0.06174999 0.01069998 -0.05049997 0.06073075 0.01069998 -0.04749995 0.06086599 0.01069998 -0.04786598 0.06049996 0.01069998 -0.04799997 0.06 0.01069998 -0.05524998 0.05709677 0.01069998 -0.05524998 0.06073075 0.01069998 -0.05549997 0.05616378 0.01069998 -0.05524998 0.05623078 0.01069998 -0.055067 0.05641376 0.01069998 -0.06093299 0.05691379 0.01069998 -0.06074994 0.05709677 0.01069998 -0.06099998 0.05666375 0.01069998 -0.06093299 0.05641376 0.01069998 -0.06074994 0.05623078 0.01069998 -0.06024998 0.05623078 0.01069998 -0.06556481 0.06370747 0.01069998 -0.06601816 0.06411576 0.01069998 -0.06574815 0.06395977 0.01069998 -0.0663284 0.06414836 0.01069998 -0.06662499 0.06405198 0.01069998 -0.06549996 0.06340247 0.01069998 -0.07379037 0.05617058 0.01069998 -0.0905168 0.05609047 0.01069998 -0.07729035 0.05617058 0.01069998 -0.07554036 0.057181 0.01069998 -0.08863955 0.05934184 0.01069998 -0.07369947 0.05609047 0.01069998 -0.07369947 0.05996757 0.01069998 -0.07270997 0.05609047 0.01069998 -0.07061219 0.06174999 0.01069998 -0.06549996 0.06174999 0.01069998 -0.07554036 0.05313944 0.01069998 -0.08627218 0.05090618 0.01069998 -0.07729035 0.05609047 0.01069998 -0.08695518 0.05072319 0.01069998 -0.08702218 0.05047315 0.01069998 -0.08722215 0.05012679 0.01069998 -0.08652216 0.05097317 0.01069998 -0.0867722 0.05090618 0.01069998 -0.08431857 0.04948955 0.01069998 -0.08602219 0.05047315 0.01069998 -0.08608907 0.05072319 0.01069998 -0.08697217 0.04919379 0.01069998 -0.0874052 0.0499438 0.01069998 -0.0943278 0.04948955 0.01069998 -0.0874722 0.04969376 0.01069998 -0.08741748 0.04948955 0.01069998 -0.0874052 0.04944378 0.01069998 -0.09546309 0.04752308 0.01069998 -0.08722215 0.04926079 0.01069998 -0.09342759 0.04373538 0.01069998 -0.08379036 0.03682935 0.01069998 -0.07673126 0.028135 0.01069998 -0.08554035 0.03986048 0.01069998 -0.0872904 0.03885006 0.01069998 -0.0887832 0.03509318 0.01069998 -0.0872904 0.03682935 0.01069998 -0.08554035 0.03581899 0.01069998 -0.08379036 0.03885006 0.01069998 -0.07430857 0.04209375 0.01069998 -0.07405859 0.04252678 0.01069998 -0.07499158 0.04227679 0.01069998 -0.07369947 0.02988547 0.01069998 -0.07455855 0.04202675 0.01069998 -0.07385855 0.0428732 0.01069998 -0.07369947 0.04303228 0.01069998 -0.07369947 0.04358005 0.01069998 -0.07367557 0.04355615 0.01069998 -0.0700615 0.03842926 0.01069998 -0.0687313 0.03275376 0.01069998 -0.07367557 0.04305619 0.01069998 -0.07360857 0.04330617 0.01069998 -0.06831145 0.03943955 0.01069998 -0.06831145 0.04146039 0.01069998 -0.07270997 0.04373538 0.01069998 -0.0700615 0.04247069 0.01069998 -0.07181149 0.04146039 0.01069998 -0.07181149 0.03943955 0.01069998 -0.05691748 0.04162496 0.01069998 -0.05737495 0.04208248 0.01069998 -0.05799996 0.04224997 0.01069998 -0.06149995 0.03275376 0.01069998 -0.06093299 0.03472828 0.01069998 -0.05737495 0.03991746 0.01069998 -0.05691748 0.04037499 0.01069998 -0.05908244 0.04162496 0.01069998 -0.06096965 0.03297346 0.01069998 -0.06121295 0.03281086 0.01069998 -0.06080704 0.03321677 0.01069998 -0.06074994 0.03350377 0.01069998 -0.06074994 0.0345453 0.01069998 -0.06099998 0.03497827 0.01069998 -0.06093299 0.03522825 0.01069998 -0.06074994 0.03541129 0.01069998 -0.06049996 0.03547829 0.01069998 -0.055067 0.03522825 0.01069998 -0.05524998 0.03541129 0.01069998 -0.05674999 0.04099994 0.01069998 -0.05574995 0.03541129 0.01069998 -0.05549997 0.03547829 0.01069998 -0.05487495 0.03285425 0.01069998 -0.05514949 0.03312879 0.01069998 -0.05449998 0.03275376 0.01069998 -0.05524998 0.03350377 0.01069998 -0.055067 0.03472828 0.01069998 -0.04299998 0.03275376 0.01069998 -0.03375959 0.02999997 0.01069998 -0.0309596 0.02999997 0.01069998 -0.0309596 0.04373538 0.01069998 -0.02799999 0.04475378 0.01069998 -0.02064436 0.04875379 0.01069998 -0.01671439 0.04875379 0.01069998 -0.01475 0.04948955 0.01069998 -0.01526159 0.05731558 0.01069998 -0.007874965 0.06174999 0.01069998 -0.009249985 0.04948955 0.01069998 -0.007874965 0.04948955 0.01069998 -0.007874965 0.04875379 0.01069998 -0.003749966 0.04875379 0.01069998 -0.003749966 0.04948955 0.01069998 -0.002749979 0.04875379 0.01069998 -0.003749966 0.05364036 0.01069998 -0.002749979 0.04948955 0.01069998 -0.003776252 0.05368095 0.01069998 -0.00396049 0.05556076 0.01069998 -0.007874965 0.05609047 0.01069998 -0.003749966 0.05608928 0.01069998 0.001349985 0.06174999 0.01069998 -0.003749489 0.05609047 0.01069998 -0.003261566 0.05731558 0.01069998 -0.001874983 0.05851966 0.01069998 -0.001874983 0.06174999 0.01069998 -0.001835405 0.05855399 0.01069998 0.001835405 0.05855399 0.01069998 0.001349985 0.05867195 0.01069998 0 0.05899995 0.01069998 0.003776252 0.05368095 0.01069998 0.007874965 0.04948955 0.01069998 0.007874965 0.05609047 0.01069998 0.00396049 0.05556076 0.01069998 0.003749489 0.05609047 0.01069998 0.001874983 0.06174999 0.01069998 0.003261566 0.05731558 0.01069998 0.001874983 0.05851966 0.01069998 0.002749979 0.04875379 0.01069998 0.009249985 0.04948955 0.01069998 0.007874965 0.04875379 0.01069998 -0.003499984 0.07113397 0.01069998 -0.002999961 0.07099997 0.01069998 -0.002133965 0.07449996 0.01069998 -0.001874983 0.07531946 0.01069998 -0.003499984 0.07486599 0.01069998 -0.04574996 0.05609047 0.01069998 -0.04574996 0.05899995 0.01069998 -0.04499995 0.05899995 0.01069998 -0.04349994 0.05609047 0.01069998 -0.04399996 0.06 0.01069998 -0.04349994 0.06174999 0.01069998 -0.04449999 0.06086599 0.01069998 -0.04499995 0.06099998 0.01069998 -0.04574996 0.06099998 0.01069998 -0.04349994 0.04948955 0.01069998 -0.04449999 0.05313396 0.01069998 -0.04413396 0.05349999 0.01069998 -0.04399996 0.05399996 0.01069998 -0.04413396 0.05449998 0.01069998 -0.04449999 0.05486595 0.01069998 -0.04499995 0.055 0.01069998 -0.04574996 0.055 0.01069998 -0.04699999 0.055 0.01069998 -0.055 0.05666375 0.01069998 -0.05449998 0.06073075 0.01069998 -0.055067 0.05691379 0.01069998 -0.04786598 0.05449998 0.01069998 -0.05449998 0.05609047 0.01069998 -0.05449998 0.04948955 0.01069998 -0.04799997 0.05399996 0.01069998 -0.04786598 0.05349999 0.01069998 -0.04699999 0.05299997 0.01069998 0.0873813 0.05609047 0.01069998 0.08722215 0.05012679 0.01069998 0.08702218 0.05047315 0.01069998 0.08695518 0.05072319 0.01069998 0.0867722 0.05090618 0.01069998 0.08652216 0.05097317 0.01069998 0.08054035 0.05609047 0.01069998 0.08627218 0.05090618 0.01069998 0.08608907 0.05072319 0.01069998 0.08697217 0.04919379 0.01069998 0.08722215 0.04926079 0.01069998 0.0873813 0.04941987 0.01069998 0.0874052 0.04944378 0.01069998 0.08741748 0.04948955 0.01069998 0.07505857 0.04252678 0.01069998 0.08054035 0.04373538 0.01069998 0.08054035 0.04569166 0.01069998 0.0873813 0.04373538 0.01069998 0.08672219 0.04926079 0.01069998 0.0741086 0.04380619 0.01069998 0.08431857 0.04948955 0.01069998 0.08054035 0.04730826 0.01069998 0.08054035 0.04948955 0.01069998 0.07270997 0.04948955 0.01069998 -7e-4 0.099734 0.01069998 -8.83013e-4 0.09991699 0.01069998 -7e-4 0.09784388 0.01069998 -7e-4 0.1006 0.01069998 4.12635e-4 0.100666 0.01069998 6.32671e-4 0.100632 0.01069998 8.16526e-4 0.100507 0.01069998 2e-4 0.1006 0.01069998 -2e-4 0.1006 0.01069998 -4.5e-4 0.1006669 0.01069998 8.63119e-4 0.09988528 0.01069998 0.001349985 0.09784388 0.01069998 0.001349985 0.106435 0.01069998 9.44415e-4 0.100092 0.01069998 9.27786e-4 0.100314 0.01069998 7e-4 0.09784388 0.01069998 -8.83013e-4 0.08608299 0.01069998 -9.5e-4 0.08583295 0.01069998 -8.83013e-4 0.08558297 0.01069998 2e-4 0.08539998 0.01069998 -7e-4 0.08539998 0.01069998 -4.5e-4 0.08533298 0.01069998 -2e-4 0.08539998 0.01069998 7e-4 0.08925718 0.01069998 0.001349985 0.08925718 0.01069998 8.83013e-4 0.08558297 0.01069998 -0.07385855 0.04373919 0.01069998 -0.07729035 0.05414986 0.01069998 -0.0741086 0.04380619 0.01069998 -0.06049996 0.05616378 0.01069998 -0.05974996 0.0530104 0.01069998 -0.05974996 0.05098956 0.01069998 -0.05649995 0.04948955 0.01069998 -0.05799996 0.04997926 0.01069998 -0.05649995 0.05084526 0.01069998 -0.05624997 0.05098956 0.01069998 -0.05624997 0.0530104 0.01069998 -0.05649995 0.05315464 0.01069998 -0.05649995 0.05609047 0.01069998 -0.05799996 0.0540207 0.01069998 0.05649995 0.04948955 0.01069998 0.05799996 0.04997926 0.01069998 0.05974996 0.0530104 0.01069998 0.05949997 0.05315464 0.01069998 0.05949997 0.05609047 0.01069998 0.05799996 0.0540207 0.01069998 0.05649995 0.05315464 0.01069998 0.05624997 0.0530104 0.01069998 0.05624997 0.05098956 0.01069998 0.05649995 0.05084526 0.01069998 0.07379037 0.05617058 0.01069998 0.07379037 0.05609047 0.01069998 0.07270997 0.05609047 0.01069998 0.07379037 0.05414986 0.01069998 0.07554036 0.05313944 0.01069998 0.07729035 0.05414986 0.01069998 0.07729035 0.05609047 0.01069998 0.07729035 0.05617058 0.01069998 0.07554036 0.057181 0.01069998 0 0.08292067 0.01069998 0.001349985 0.08412688 0.01069998 0.001349985 0.08214128 0.01069998 0.001749992 0.08191037 0.01069998 0.001349985 0.07872378 0.01069998 0 0.07887929 0.01069998 0.003499984 0.0625 0.01069998 0.007499992 0.06535255 0.01069998 0.003499984 0.06535255 0.01069998 0.003866016 0.07449996 0.01069998 0.003499984 0.07486599 0.01069998 0.003499984 0.06949996 0.01069998 0.003499984 0.07113397 0.01069998 0.007499992 0.0750938 0.01069998 0.002133965 0.07449996 0.01069998 0.001999974 0.074 0.01069998 0.03049999 0.06174999 0.01069998 0.02848696 0.06535255 0.01069998 0.02974998 0.05038297 0.01069998 0.03049999 0.05168205 0.01069998 0.01475 0.04948955 0.01069998 0.02824997 0.05038297 0.01069998 0.01337498 0.06174999 0.01069998 0.01199996 0.0625 0.01069998 -0.0345 0.05609047 0.01069998 -0.04349994 0.04373538 0.01069998 -0.03375959 0.04373538 0.01069998 -0.03599995 0.04499995 0.01069998 -0.03524994 0.045201 0.01069998 -0.03375959 0.04948955 0.01069998 -0.03925144 0.05609047 0.01069998 -0.04299998 0.04959785 0.01069998 -0.003499984 0.06949996 0.01069998 -0.003499984 0.06535255 0.01069998 -0.003749966 0.06174999 0.01069998 0.001874983 0.06949996 0.01069998 0.001349985 0.06949996 0.01069998 0.001349985 0.07531946 0.01069998 -0.001874983 0.06949996 0.01069998 0.01882886 0.07565236 0.01069998 0.01922887 0.07554519 0.01069998 0.01962888 0.07565236 0.01069998 0.01992166 0.07594519 0.01069998 0.01337498 0.07872378 0.01069998 0.01504516 0.0778684 0.01069998 0.01517546 0.07764279 0.01069998 0.01537495 0.07747536 0.01069998 0.0157237 0.07727408 0.01069998 0.02002888 0.0763452 0.01069998 0.01992166 0.07674515 0.01069998 0.01962888 0.07703799 0.01069998 0.01853609 0.07674515 0.01069998 0.01842886 0.0763452 0.01069998 0.02064436 0.08482539 0.01069998 0.01537495 0.0874347 0.01069998 0.01499998 0.08678519 0.01069998 0.01337498 0.08412688 0.01069998 0.01771539 0.07872378 0.01069998 0.01922887 0.07714515 0.01069998 0.01882886 0.07703799 0.01069998 0.01842987 0.07969325 0.01069998 0.01892989 0.07982718 0.01069998 0.01806378 0.07932716 0.01069998 0.02064436 0.07872378 0.01069998 0.02064436 0.078992 0.01069998 0.02848696 0.06938076 0.01069998 0.02125996 0.0728631 0.01069998 0.02064436 0.07531946 0.01069998 0.01337498 0.07170188 0.01069998 0.0296064 0.07531946 0.01069998 0.02848696 0.07531946 0.01069998 0.0301882 0.07232719 0.01069998 0.0309596 0.07766336 0.01069998 0.02549195 0.07619327 0.01069998 0.0250054 0.07531946 0.01069998 0.0211091 0.07872378 0.01069998 0.04710906 0.07531946 0.01069998 0.050125 0.07357829 0.01069998 0.04449999 0.06535255 0.01069998 0.05037498 0.06174999 0.01069998 0.04349994 0.06408268 0.01069998 0.04103589 0.06266009 0.01069998 0.03375959 0.06174999 0.01069998 0.03375959 0.06535255 0.01069998 0.03501826 0.07069325 0.01069998 0.03538429 0.06932729 0.01069998 0.03221929 0.06804519 0.01069998 0.03261929 0.06815236 0.01069998 0.03441029 0.06764006 0.01069998 0.03428477 0.06727057 0.01069998 0.03291207 0.0684452 0.01069998 0.0330193 0.06884515 0.01069998 0.03291207 0.06924515 0.01069998 0.03261929 0.06953799 0.01069998 0.03375959 0.07141995 0.01069998 0.0309596 0.07303661 0.01069998 0.03221929 0.06964516 0.01069998 0.03181928 0.06953799 0.01069998 0.0315265 0.06924515 0.01069998 0.03141927 0.06884515 0.01069998 0.0315265 0.0684452 0.01069998 0.03181928 0.06815236 0.01069998 -0.0640307 0.05609047 0.01069998 -0.07379037 0.05414986 0.01069998 -0.07379037 0.05609047 0.01069998 -0.05649995 0.04373538 0.01069998 -0.0640307 0.04373538 0.01069998 -0.0640307 0.04948955 0.01069998 -0.07270997 0.04948955 0.01069998 -0.07369947 0.04948955 0.01069998 -0.07369947 0.04373538 0.01069998 -0.04574996 0.04373538 0.01069998 -0.0309596 0.05609047 0.01069998 -0.03375959 0.05609047 0.01069998 -0.03375959 0.06174999 0.01069998 -0.0309596 0.06535255 0.01069998 -0.02125996 0.0728631 0.01069998 -0.02267819 0.07531946 0.01069998 -0.003749966 0.05609047 0.01069998 -0.001749992 0.08191037 0.01069998 -0.001749992 0.07988959 0.01069998 -0.001874983 0.08412688 0.01069998 -0.003749966 0.08412688 0.01069998 -0.003749966 0.08925718 0.01069998 -0.001874983 0.08925718 0.01069998 -0.007874965 0.08412688 0.01069998 -0.007874965 0.07872378 0.01069998 -0.01337498 0.07872378 0.01069998 -0.003749966 0.09784388 0.01069998 -0.001874983 0.09784388 0.01069998 -9.5e-4 0.100167 0.01069998 -8.83013e-4 0.100417 0.01069998 -0.003749966 0.07531946 0.01069998 -0.003749966 0.07872378 0.01069998 -0.001874983 0.07872378 0.01069998 0.001874983 0.07531946 0.01069998 0.001874983 0.106435 0.01069998 0.001874983 0.08412688 0.01069998 0.001749992 0.07988959 0.01069998 0.006575286 0.106435 0.01069998 0.007874965 0.104335 0.01069998 0.001874983 0.08925718 0.01069998 0.007874965 0.07872378 0.01069998 0.001874983 0.07872378 0.01069998 0.007874965 0.07531946 0.01069998 0.00999999 0.09097927 0.01069998 0.007874965 0.08925718 0.01069998 0.007874965 0.08412688 0.01069998 0.01337498 0.07531946 0.01069998 0.007874965 0.07487726 0.01069998 0.02848696 0.04948955 0.01069998 0.0309596 0.07872378 0.01069998 0.02848696 0.07872378 0.01069998 0.02848696 0.08412688 0.01069998 0.02185428 0.08412688 0.01069998 0.0309596 0.06535255 0.01069998 0.0309596 0.06174999 0.01069998 0.0309596 0.05609047 0.01069998 0.0309596 0.04948955 0.01069998 0.0309596 0.04373538 0.01069998 0.04449999 0.05313396 0.01069998 0.04349994 0.04948955 0.01069998 0.04413396 0.05349999 0.01069998 0.05449998 0.04373538 0.01069998 0.05274999 0.03875374 0.01069998 0.05449998 0.03275376 0.01069998 0.05037498 0.03875374 0.01069998 0.05037498 0.03275376 0.01069998 0.04699999 0.03875374 0.01069998 0.04699999 0.04373538 0.01069998 0.04699999 0.04899996 0.01069998 0.04399996 0.05399996 0.01069998 0.04749995 0.05313396 0.01069998 0.04786598 0.05349999 0.01069998 0.04786598 0.05449998 0.01069998 0.04499995 0.055 0.01069998 0.04349994 0.05609047 0.01069998 0.04449999 0.05486595 0.01069998 0.04413396 0.05449998 0.01069998 0.05037498 0.05609047 0.01069998 0.04699999 0.05899995 0.01069998 0.04749995 0.05913394 0.01069998 0.04786598 0.05949997 0.01069998 0.04799997 0.06 0.01069998 0.04786598 0.06049996 0.01069998 0.04749995 0.06086599 0.01069998 0.04499995 0.06099998 0.01069998 0.05037498 0.06535255 0.01069998 0.05049997 0.06174999 0.01069998 0.05449998 0.04948955 0.01069998 0.07385855 0.04373919 0.01069998 0.05949997 0.04948955 0.01069998 0.05274999 0.04373538 0.01069998 0.05274999 0.04899996 0.01069998 0.007499992 0.0625 0.01069998 0.007874965 0.0625 0.01069998 0.007499992 0.0625 0.01189994 0.07613849 0.0530951 0.0097 0.0757184 0.05415076 0.0097 0.07579946 0.0530259 0.0097 0.07766246 0.05550509 0.0097 0.07653766 0.05539655 0.0097 0.07656538 0.05516028 0.0097 0.07511025 0.05726677 0.0097 0.07545375 0.05730849 0.0097 0.07548075 0.05618345 0.0097 0.0757184 0.05616968 0.0097 0.0761525 0.05433809 0.0097 0.07676166 0.0533908 0.0097 0.07594627 0.05421906 0.0097 0.07646209 0.05321776 0.0097 0.07725918 0.05645179 0.0097 0.07632559 0.05581909 0.0097 0.0764563 0.05562025 0.0097 0.07744407 0.05615937 0.0097 0.07757967 0.05584108 0.0097 0.07579946 0.05729454 0.0097 0.07613849 0.0572254 0.0097 0.07646209 0.05710268 0.0097 0.07594627 0.05610138 0.0097 0.0761525 0.05598235 0.0097 0.07676166 0.05692964 0.0097 0.0770297 0.05671077 0.0097 0.07345277 0.05567479 0.0097 0.07356238 0.05600297 0.0097 0.07457715 0.05551075 0.0097 0.07468396 0.05572348 0.0097 0.07769036 0.05516028 0.0097 0.07766246 0.05481535 0.0097 0.07653766 0.05492389 0.0097 0.0764563 0.05470019 0.0097 0.07757967 0.05447936 0.0097 0.07744407 0.05416107 0.0097 0.07725918 0.05386865 0.0097 0.07632559 0.05450135 0.0097 0.0770297 0.05360966 0.0097 0.07372319 0.0563094 0.0097 0.07483696 0.05590575 0.0097 0.07393109 0.05658596 0.0097 0.0741806 0.05682569 0.0097 0.07502788 0.05604785 0.0097 0.07446539 0.05702215 0.0097 0.07524639 0.05614215 0.0097 0.07477796 0.05717045 0.0097 0.07545375 0.05301195 0.0097 0.07511025 0.05305367 0.0097 0.07548075 0.05413699 0.0097 0.07524639 0.05417829 0.0097 0.07477796 0.05314999 0.0097 0.07502788 0.05427259 0.0097 0.07446539 0.05329829 0.0097 0.0741806 0.05349487 0.0097 0.07393109 0.05373448 0.0097 0.07483696 0.05441468 0.0097 0.07468396 0.05459696 0.0097 0.07372319 0.05401116 0.0097 0.07356238 0.05431747 0.0097 0.07457715 0.05480968 0.0097 0.07345277 0.05464565 0.0097 0.07452225 0.05504125 0.0097 0.07452225 0.05527919 0.0097 0.07339727 0.05498725 0.0097 0.07339727 0.05533325 0.0097 0.08605289 -0.0387274 0.01169997 0.08581596 -0.038827 0.0097 0.08581596 -0.038827 0.01169997 0.08556181 -0.03886449 0.0097 0.08556181 -0.03886449 0.01169997 0.08530628 -0.03883767 0.01169997 0.08506548 -0.03874808 0.01169997 0.08485448 -0.03860145 0.01169997 0.08468657 -0.03840696 0.01169997 0.08457237 -0.03817677 0.01169997 0.08451896 -0.03792548 0.01169997 0.08452969 -0.03766876 0.0097 0.08452969 -0.03766876 0.01169997 0.08460396 -0.03742277 0.01169997 0.08473706 -0.03720307 0.0097 0.08473706 -0.03720307 0.01169997 0.08492058 -0.0370233 0.01169997 0.0851432 -0.03689479 0.0097 0.0851432 -0.03689479 0.01169997 0.08539056 -0.03682565 0.01169997 0.08564746 -0.03682035 0.0097 0.08564746 -0.03682035 0.01169997 0.08612525 -0.03699809 0.0097 0.08589756 -0.036879 0.01169997 0.08612525 -0.03699809 0.01169997 0.08631628 -0.03716999 0.01169997 0.08631628 -0.03716999 0.0097 0.0864585 -0.03738397 0.0097 0.0864585 -0.03738397 0.01169997 0.08654296 -0.03762656 0.0097 0.08654296 -0.03762656 0.01169997 0.08656448 -0.03788268 0.0097 0.08656448 -0.03788268 0.01169997 0.08652156 -0.038136 0.0097 0.08652156 -0.038136 0.01169997 0.08641707 -0.03837066 0.01169997 0.08625745 -0.03857207 0.01169997 0.08625745 -0.03857207 0.0097 0.08530628 -0.03883767 0.0097 0.08506548 -0.03874808 0.0097 0.08595246 -0.03994989 0.0097 0.0855996 -0.03998887 0.0097 0.08489859 -0.03989166 0.0097 0.08399927 -0.03933888 0.0097 0.08485448 -0.03860145 0.0097 0.08605289 -0.0387274 0.0097 0.08629417 -0.03985315 0.0097 0.08451896 -0.03792548 0.0097 0.08339357 -0.03772127 0.0097 0.08767729 -0.03760319 0.0097 0.08468657 -0.03840696 0.0097 0.08457237 -0.03817677 0.0097 0.0834034 -0.03807628 0.0097 0.08768707 -0.0379582 0.0097 0.08641707 -0.03837066 0.0097 0.08589756 -0.036879 0.0097 0.08651119 -0.03592139 0.0097 0.08681368 -0.03610736 0.0097 0.08460396 -0.03742277 0.0097 0.08391898 -0.03642767 0.0097 0.08492058 -0.0370233 0.0097 0.08730715 -0.03661465 0.0097 0.08748465 -0.03692215 0.0097 0.08760917 -0.03725469 0.0097 0.08539056 -0.03682565 0.0097 0.0854811 -0.0356906 0.0097 0.08469879 -0.03559207 0.01069998 0.08508026 -0.03548425 0.01069998 0.08508026 -0.03548425 0.009949982 0.08547419 -0.03544068 0.01069998 0.08547419 -0.03544068 0.009949982 0.08586996 -0.03546249 0.01069998 0.0862568 -0.03554916 0.009949982 0.0862568 -0.03554916 0.01069998 0.08662396 -0.03569829 0.01069998 0.08696168 -0.03590589 0.01069998 0.08696168 -0.03590589 0.009949982 0.0872606 -0.03616619 0.01069998 0.0872606 -0.03616619 0.009949982 0.08751255 -0.0364722 0.01069998 0.08771079 -0.03681546 0.009949982 0.08771079 -0.03681546 0.01069998 0.08784979 -0.03718668 0.01069998 0.08792579 -0.03757566 0.01069998 0.08792579 -0.03757566 0.009949982 0.08793669 -0.03797197 0.01069998 0.08793669 -0.03797197 0.009949982 0.08788228 -0.03836458 0.01069998 0.08776396 -0.03874289 0.01069998 0.08776396 -0.03874289 0.009949982 0.08758497 -0.03909659 0.01069998 0.08735018 -0.03941595 0.01069998 0.08735018 -0.03941595 0.009949982 0.08706605 -0.03969228 0.01069998 0.08674037 -0.03991818 0.01069998 0.08706605 -0.03969228 0.009949982 0.08638185 -0.0400874 0.01069998 0.0860005 -0.04019516 0.01069998 0.08560645 -0.04023879 0.01069998 0.08521068 -0.04021698 0.01069998 0.08521068 -0.04021698 0.009949982 0.0848239 -0.04013025 0.009949982 0.0848239 -0.04013025 0.01069998 0.08445668 -0.03998118 0.009949982 0.08445668 -0.03998118 0.01069998 0.08411896 -0.03977358 0.01069998 0.0838201 -0.03951328 0.01069998 0.0838201 -0.03951328 0.009949982 0.08356809 -0.03920727 0.01069998 0.08336991 -0.03886395 0.01069998 0.08336991 -0.03886395 0.009949982 0.08323085 -0.03849279 0.01069998 0.08323085 -0.03849279 0.009949982 0.08315485 -0.03810375 0.01069998 0.083144 -0.03770744 0.01069998 0.083144 -0.03770744 0.009949982 0.08319848 -0.03731489 0.01069998 0.08319848 -0.03731489 0.009949982 0.0833168 -0.03693658 0.01069998 0.08349579 -0.03658288 0.01069998 0.08349579 -0.03658288 0.009949982 0.08373045 -0.03626346 0.01069998 0.08401459 -0.03598707 0.01069998 0.08373045 -0.03626346 0.009949982 0.08434039 -0.03576129 0.01069998 0.08401459 -0.03598707 0.009949982 0.08417356 -0.03618007 0.0097 0.0833168 -0.03693658 0.009949982 0.0837087 -0.03671377 0.0097 0.08354836 -0.03703069 0.0097 0.08344238 -0.03736954 0.0097 0.08315485 -0.03810375 0.009949982 0.08347147 -0.03842478 0.0097 0.08359599 -0.03875726 0.0097 0.08356809 -0.03920727 0.009949982 0.08377349 -0.03906476 0.0097 0.08411896 -0.03977358 0.009949982 0.08426707 -0.03957206 0.0097 0.08456957 -0.03975808 0.0097 0.08524507 -0.03996938 0.0097 0.08560645 -0.04023879 0.009949982 0.0860005 -0.04019516 0.009949982 0.08638185 -0.0400874 0.009949982 0.08674037 -0.03991818 0.009949982 0.08661538 -0.0397017 0.0097 0.0869072 -0.0394994 0.0097 0.08716166 -0.0392518 0.0097 0.087372 -0.03896558 0.0097 0.08758497 -0.03909659 0.009949982 0.08753228 -0.03864878 0.0097 0.08763825 -0.03830987 0.0097 0.08788228 -0.03836458 0.009949982 0.08784979 -0.03718668 0.009949982 0.08751255 -0.0364722 0.009949982 0.08708137 -0.03634059 0.0097 0.08662396 -0.03569829 0.009949982 0.08586996 -0.03546249 0.009949982 0.08618217 -0.03578776 0.0097 0.08583569 -0.03571009 0.0097 0.08512818 -0.03572958 0.0097 0.08469879 -0.03559207 0.009949982 0.08478647 -0.03582614 0.0097 0.08434039 -0.03576129 0.009949982 0.08446538 -0.03597778 0.0097 0.009724318 -0.09398716 0.01169997 0.009282827 -0.09373229 0.0097 0.00948745 -0.09388768 0.01169997 0.009282827 -0.09373229 0.01169997 0.009123206 -0.09353095 0.01169997 0.009018719 -0.09329628 0.01169997 0.008975863 -0.09304291 0.01169997 0.00899738 -0.0927869 0.01169997 0.0090819 -0.09254425 0.01169997 0.009224057 -0.09233015 0.0097 0.009224057 -0.09233015 0.01169997 0.00941497 -0.09215825 0.01169997 0.00964266 -0.09203928 0.01169997 0.009892821 -0.09198057 0.01169997 0.01014965 -0.091986 0.01169997 0.01039719 -0.09205508 0.0097 0.01039719 -0.09205508 0.01169997 0.01061969 -0.09218358 0.01169997 0.01061969 -0.09218358 0.0097 0.01080328 -0.09236329 0.0097 0.01080328 -0.09236329 0.01169997 0.01093637 -0.09258306 0.0097 0.01093637 -0.09258306 0.01169997 0.01101058 -0.0928291 0.01169997 0.01102137 -0.09308576 0.0097 0.01102137 -0.09308576 0.01169997 0.01096796 -0.09333705 0.01169997 0.01085364 -0.09356719 0.01169997 0.01068586 -0.09376168 0.01169997 0.01047486 -0.09390836 0.0097 0.01047486 -0.09390836 0.01169997 0.01023405 -0.09399789 0.01169997 0.009978473 -0.09402477 0.0097 0.009978473 -0.09402477 0.01169997 0.00941497 -0.09215825 0.0097 0.00964266 -0.09203928 0.0097 0.009358167 -0.09094798 0.0097 0.009892821 -0.09198057 0.0097 0.01014965 -0.091986 0.0097 0.01068586 -0.09376168 0.0097 0.01023405 -0.09399789 0.0097 0.01085364 -0.09356719 0.0097 0.01176679 -0.0942251 0.0097 0.01154106 -0.09449917 0.0097 0.009724318 -0.09398716 0.0097 0.00948745 -0.09388768 0.0097 0.01206886 -0.09358495 0.0097 0.01096796 -0.09333705 0.0097 0.01194435 -0.0939176 0.0097 0.008233129 -0.09177488 0.0097 0.007863044 -0.09276348 0.0097 0.00899738 -0.0927869 0.0097 0.0090819 -0.09254425 0.0097 0.009018719 -0.09329628 0.0097 0.008975863 -0.09304291 0.0097 0.007902026 -0.09347015 0.0097 0.008378624 -0.09441196 0.0097 0.008168339 -0.09412586 0.0097 0.009123206 -0.09353095 0.0097 0.01101058 -0.0928291 0.0097 0.01214665 -0.09288156 0.0097 0.01107496 -0.091138 0.0097 0.01152569 -0.09114736 0.01069998 0.01119995 -0.09092146 0.009949982 0.01180988 -0.0914238 0.01069998 0.01180988 -0.0914238 0.009949982 0.01204454 -0.09174317 0.009949982 0.01204454 -0.09174317 0.01069998 0.0122236 -0.09209686 0.01069998 0.01234185 -0.09247517 0.01069998 0.01234185 -0.09247517 0.009949982 0.01239639 -0.09286779 0.01069998 0.01238536 -0.09326398 0.01069998 0.01238536 -0.09326398 0.009949982 0.01230937 -0.09365296 0.01069998 0.01230937 -0.09365296 0.009949982 0.01217049 -0.0940243 0.01069998 0.01217049 -0.0940243 0.009949982 0.01197224 -0.0943675 0.01069998 0.01172029 -0.09467345 0.01069998 0.01197224 -0.0943675 0.009949982 0.01172029 -0.09467345 0.009949982 0.01142138 -0.0949338 0.009949982 0.01142138 -0.0949338 0.01069998 0.01108366 -0.09514141 0.009949982 0.01108366 -0.09514141 0.01069998 0.01071637 -0.0952906 0.009949982 0.01071637 -0.0952906 0.01069998 0.0103296 -0.09537726 0.009949982 0.0103296 -0.09537726 0.01069998 0.009933829 -0.09539908 0.01069998 0.009933829 -0.09539908 0.009949982 0.009539842 -0.09535551 0.01069998 0.009539842 -0.09535551 0.009949982 0.009158432 -0.09524756 0.01069998 0.00879997 -0.09507846 0.01069998 0.009158432 -0.09524756 0.009949982 0.00847423 -0.09485256 0.01069998 0.00847423 -0.09485256 0.009949982 0.008190095 -0.09457617 0.01069998 0.007955372 -0.09425675 0.01069998 0.007776379 -0.09390306 0.01069998 0.007658064 -0.09352475 0.01069998 0.007658064 -0.09352475 0.009949982 0.007603585 -0.09313219 0.01069998 0.007614552 -0.092736 0.01069998 0.007603585 -0.09313219 0.009949982 0.007690548 -0.09234696 0.01069998 0.007829487 -0.09197568 0.01069998 0.008027672 -0.09163248 0.01069998 0.008279681 -0.09132647 0.009949982 0.008279681 -0.09132647 0.01069998 0.008578598 -0.09106618 0.01069998 0.008916318 -0.09085857 0.01069998 0.008578598 -0.09106618 0.009949982 0.008916318 -0.09085857 0.009949982 0.009283542 -0.09070938 0.009949982 0.009283542 -0.09070938 0.01069998 0.009670317 -0.09062266 0.01069998 0.01006609 -0.0906009 0.01069998 0.01046007 -0.09064447 0.01069998 0.01006609 -0.0906009 0.009949982 0.01046007 -0.09064447 0.009949982 0.01084148 -0.09075236 0.009949982 0.01084148 -0.09075236 0.01069998 0.01119995 -0.09092146 0.01069998 0.01041215 -0.09088987 0.0097 0.01005917 -0.09085077 0.0097 0.009670317 -0.09062266 0.009949982 0.009704649 -0.09087038 0.0097 0.00902915 -0.09108167 0.0097 0.008726656 -0.09126758 0.0097 0.008458912 -0.09150075 0.0097 0.008027672 -0.09163248 0.009949982 0.007829487 -0.09197568 0.009949982 0.008055627 -0.09208238 0.0097 0.007690548 -0.09234696 0.009949982 0.007931113 -0.09241497 0.0097 0.007614552 -0.092736 0.009949982 0.007853209 -0.09311836 0.0097 0.007776379 -0.09390306 0.009949982 0.008008003 -0.09380906 0.0097 0.007955372 -0.09425675 0.009949982 0.008190095 -0.09457617 0.009949982 0.008633136 -0.09465956 0.0097 0.00879997 -0.09507846 0.009949982 0.008924961 -0.09486198 0.0097 0.00924611 -0.09501349 0.0097 0.009587764 -0.09511005 0.0097 0.009940743 -0.09514915 0.0097 0.01029527 -0.0951296 0.0097 0.01064175 -0.095052 0.0097 0.01097077 -0.09491831 0.0097 0.01127326 -0.0947324 0.0097 0.01213699 -0.0932365 0.0097 0.01239639 -0.09286779 0.009949982 0.01209795 -0.09252977 0.0097 0.01199197 -0.09219086 0.0097 0.0122236 -0.09209686 0.009949982 0.01183158 -0.09187406 0.0097 0.01162129 -0.09158796 0.0097 0.01152569 -0.09114736 0.009949982 0.01136678 -0.09134036 0.0097 0.01075387 -0.09098649 0.0097 -0.07653319 -0.05490529 0.0097 -0.07751828 -0.05431747 0.0097 -0.0764386 -0.05466645 0.0097 -0.0764386 -0.05565404 0.0097 -0.07653319 -0.05541515 0.0097 -0.07762789 -0.05567479 0.0097 -0.07608956 -0.05602568 0.0097 -0.07628756 -0.05586189 0.0097 -0.07735747 -0.0563094 0.0097 -0.0758571 -0.05613505 0.0097 -0.07630276 -0.05717045 0.0097 -0.07768338 -0.05533325 0.0097 -0.07769036 -0.05516028 0.0097 -0.07656538 -0.05516028 0.0097 -0.07762789 -0.05464565 0.0097 -0.07471108 -0.0545578 0.0097 -0.07458728 -0.05478286 0.0097 -0.07452338 -0.05503177 0.0097 -0.07628756 -0.05445855 0.0097 -0.07690006 -0.05349487 0.0097 -0.07608956 -0.05429476 0.0097 -0.0758571 -0.05418539 0.0097 -0.07534825 -0.05616706 0.0097 -0.0752812 -0.05729454 0.0097 -0.07560467 -0.05618315 0.0097 -0.07339036 -0.05516028 0.0097 -0.07452338 -0.05528867 0.0097 -0.07510387 -0.05423277 0.0097 -0.07488697 -0.05437046 0.0097 -0.07405096 -0.05360966 0.0097 -0.0738216 -0.05386865 0.0097 -0.07534825 -0.05415338 0.0097 -0.07494217 -0.0530951 0.0097 -0.07630276 -0.05314999 0.0097 -0.07597041 -0.05305367 0.0097 -0.07560467 -0.05413728 0.0097 -0.0756269 -0.05301195 0.0097 -0.074319 -0.05692964 0.0097 -0.07510387 -0.05608767 0.0097 -0.07494217 -0.0572254 0.0097 -0.07458728 -0.05553758 0.0097 -0.07363659 -0.05615937 0.0097 -0.07471108 -0.05576264 0.0097 -0.07488697 -0.05594998 0.0097 -0.0738216 -0.05645179 0.0097 -0.07405096 -0.05671077 0.0097 -0.0779404 -0.05516028 0.009949982 -0.0779404 -0.05516028 0.01069998 -0.07793259 -0.0549671 0.01069998 -0.0778706 -0.05458587 0.01069998 -0.07774829 -0.05421948 0.01069998 -0.07774829 -0.05421948 0.009949982 -0.07756876 -0.05387747 0.01069998 -0.07756876 -0.05387747 0.009949982 -0.07733678 -0.05356878 0.01069998 -0.07705819 -0.05330115 0.009949982 -0.07705819 -0.05330115 0.01069998 -0.07674038 -0.05308175 0.01069998 -0.07639139 -0.05291616 0.01069998 -0.07674038 -0.05308175 0.009949982 -0.07639139 -0.05291616 0.009949982 -0.07602035 -0.05280876 0.01069998 -0.07563698 -0.05276215 0.009949982 -0.07563698 -0.05276215 0.01069998 -0.0752511 -0.05277776 0.01069998 -0.07487255 -0.05285495 0.01069998 -0.07487255 -0.05285495 0.009949982 -0.07451146 -0.05299198 0.01069998 -0.07417696 -0.0531851 0.01069998 -0.07417696 -0.0531851 0.009949982 -0.07387781 -0.05342936 0.01069998 -0.07362169 -0.05371844 0.009949982 -0.07362169 -0.05371844 0.01069998 -0.07341527 -0.0540449 0.01069998 -0.07326388 -0.05440026 0.01069998 -0.07317137 -0.05477529 0.01069998 -0.07314038 -0.05516028 0.01069998 -0.07317137 -0.05554515 0.01069998 -0.07326388 -0.0559203 0.01069998 -0.07326388 -0.0559203 0.009949982 -0.07341527 -0.0562756 0.009949982 -0.07341527 -0.0562756 0.01069998 -0.07362169 -0.056602 0.01069998 -0.07387781 -0.05689108 0.01069998 -0.07362169 -0.056602 0.009949982 -0.07387781 -0.05689108 0.009949982 -0.07417696 -0.0571354 0.01069998 -0.07417696 -0.0571354 0.009949982 -0.07451146 -0.05732846 0.01069998 -0.07487255 -0.05746549 0.01069998 -0.07487255 -0.05746549 0.009949982 -0.0752511 -0.0575428 0.009949982 -0.0752511 -0.0575428 0.01069998 -0.07563698 -0.05755829 0.01069998 -0.07602035 -0.05751174 0.01069998 -0.07639139 -0.05740427 0.01069998 -0.07674038 -0.05723869 0.01069998 -0.07639139 -0.05740427 0.009949982 -0.07674038 -0.05723869 0.009949982 -0.07705819 -0.05701929 0.01069998 -0.07705819 -0.05701929 0.009949982 -0.07733678 -0.05675166 0.01069998 -0.07756876 -0.05644297 0.01069998 -0.07756876 -0.05644297 0.009949982 -0.07774829 -0.05610096 0.01069998 -0.07774829 -0.05610096 0.009949982 -0.0778706 -0.05573457 0.009949982 -0.0778706 -0.05573457 0.01069998 -0.07793259 -0.0553534 0.01069998 -0.07793259 -0.0553534 0.009949982 -0.07326388 -0.05440026 0.009949982 -0.0734182 -0.05481535 0.0097 -0.07350099 -0.05447936 0.0097 -0.07341527 -0.0540449 0.009949982 -0.07363659 -0.05416107 0.0097 -0.07387781 -0.05342936 0.009949982 -0.074319 -0.0533908 0.0097 -0.07451146 -0.05299198 0.009949982 -0.07461869 -0.05321776 0.0097 -0.0752511 -0.05277776 0.009949982 -0.0752812 -0.0530259 0.0097 -0.07602035 -0.05280876 0.009949982 -0.07661539 -0.05329829 0.0097 -0.07714968 -0.05373448 0.0097 -0.07733678 -0.05356878 0.009949982 -0.07735747 -0.05401116 0.0097 -0.0778706 -0.05458587 0.009949982 -0.07793259 -0.0549671 0.009949982 -0.07768338 -0.05498725 0.0097 -0.07751828 -0.05600297 0.0097 -0.07733678 -0.05675166 0.009949982 -0.07714968 -0.05658596 0.0097 -0.07690006 -0.05682569 0.0097 -0.07661539 -0.05702215 0.0097 -0.07602035 -0.05751174 0.009949982 -0.07597041 -0.05726677 0.0097 -0.07563698 -0.05755829 0.009949982 -0.0756269 -0.05730849 0.0097 -0.07451146 -0.05732846 0.009949982 -0.07461869 -0.05710268 0.0097 -0.07317137 -0.05554515 0.009949982 -0.07350099 -0.05584108 0.0097 -0.0734182 -0.05550509 0.0097 -0.07314038 -0.05516028 0.009949982 -0.07317137 -0.05477529 0.009949982 -0.08605289 0.0387274 0.01169997 -0.08581596 0.038827 0.01169997 -0.08556181 0.03886449 0.01169997 -0.08556181 0.03886449 0.0097 -0.08530628 0.03883767 0.01169997 -0.08506548 0.03874808 0.01169997 -0.08485448 0.03860145 0.01169997 -0.08468657 0.03840696 0.01169997 -0.08457237 0.03817677 0.01169997 -0.08457237 0.03817677 0.0097 -0.08451896 0.03792548 0.01169997 -0.08451896 0.03792548 0.0097 -0.08452969 0.03766876 0.0097 -0.08452969 0.03766876 0.01169997 -0.08460396 0.03742277 0.01169997 -0.08473706 0.03720307 0.01169997 -0.08492058 0.0370233 0.01169997 -0.0851432 0.03689479 0.01169997 -0.08539056 0.03682565 0.01169997 -0.08564746 0.03682035 0.01169997 -0.08612525 0.03699809 0.0097 -0.08589756 0.036879 0.01169997 -0.08612525 0.03699809 0.01169997 -0.08631628 0.03716999 0.01169997 -0.0864585 0.03738397 0.01169997 -0.08654296 0.03762656 0.01169997 -0.08656448 0.03788268 0.01169997 -0.08652156 0.038136 0.0097 -0.08652156 0.038136 0.01169997 -0.08641707 0.03837066 0.01169997 -0.08625745 0.03857207 0.01169997 -0.08605289 0.0387274 0.0097 -0.08473706 0.03720307 0.0097 -0.08651119 0.03592139 0.0097 -0.08339357 0.03772127 0.0097 -0.08344238 0.03736954 0.0097 -0.08460396 0.03742277 0.0097 -0.0854811 0.0356906 0.0097 -0.08564746 0.03682035 0.0097 -0.08583569 0.03571009 0.0097 -0.08589756 0.036879 0.0097 -0.08446538 0.03597778 0.0097 -0.08492058 0.0370233 0.0097 -0.0851432 0.03689479 0.0097 -0.08539056 0.03682565 0.0097 -0.08512818 0.03572958 0.0097 -0.08468657 0.03840696 0.0097 -0.08347147 0.03842478 0.0097 -0.08656448 0.03788268 0.0097 -0.08631628 0.03716999 0.0097 -0.08708137 0.03634059 0.0097 -0.0864585 0.03738397 0.0097 -0.08654296 0.03762656 0.0097 -0.08506548 0.03874808 0.0097 -0.08485448 0.03860145 0.0097 -0.08399927 0.03933888 0.0097 -0.08530628 0.03883767 0.0097 -0.08641707 0.03837066 0.0097 -0.08629417 0.03985315 0.0097 -0.08581596 0.038827 0.0097 -0.08625745 0.03857207 0.0097 -0.0869072 0.0394994 0.0097 -0.08661538 0.0397017 0.0097 -0.08469879 0.03559207 0.01069998 -0.08508026 0.03548425 0.01069998 -0.08547419 0.03544068 0.01069998 -0.08586996 0.03546249 0.01069998 -0.0862568 0.03554916 0.01069998 -0.08662396 0.03569829 0.01069998 -0.08696168 0.03590589 0.01069998 -0.0872606 0.03616619 0.01069998 -0.0872606 0.03616619 0.009949982 -0.08751255 0.0364722 0.01069998 -0.08771079 0.03681546 0.01069998 -0.08784979 0.03718668 0.01069998 -0.08792579 0.03757566 0.01069998 -0.08793669 0.03797197 0.01069998 -0.08792579 0.03757566 0.009949982 -0.08793669 0.03797197 0.009949982 -0.08788228 0.03836458 0.01069998 -0.08776396 0.03874289 0.01069998 -0.08788228 0.03836458 0.009949982 -0.08776396 0.03874289 0.009949982 -0.08758497 0.03909659 0.01069998 -0.08735018 0.03941595 0.01069998 -0.08735018 0.03941595 0.009949982 -0.08706605 0.03969228 0.01069998 -0.08674037 0.03991818 0.01069998 -0.08706605 0.03969228 0.009949982 -0.08674037 0.03991818 0.009949982 -0.08638185 0.0400874 0.009949982 -0.08638185 0.0400874 0.01069998 -0.0860005 0.04019516 0.01069998 -0.08560645 0.04023879 0.01069998 -0.08521068 0.04021698 0.01069998 -0.0848239 0.04013025 0.01069998 -0.08445668 0.03998118 0.01069998 -0.08411896 0.03977358 0.01069998 -0.0838201 0.03951328 0.009949982 -0.0838201 0.03951328 0.01069998 -0.08356809 0.03920727 0.009949982 -0.08356809 0.03920727 0.01069998 -0.08336991 0.03886395 0.01069998 -0.08323085 0.03849279 0.01069998 -0.08315485 0.03810375 0.01069998 -0.083144 0.03770744 0.01069998 -0.083144 0.03770744 0.009949982 -0.08319848 0.03731489 0.01069998 -0.08319848 0.03731489 0.009949982 -0.0833168 0.03693658 0.01069998 -0.0833168 0.03693658 0.009949982 -0.08349579 0.03658288 0.01069998 -0.08373045 0.03626346 0.01069998 -0.08373045 0.03626346 0.009949982 -0.08401459 0.03598707 0.01069998 -0.08401459 0.03598707 0.009949982 -0.08434039 0.03576129 0.01069998 -0.08391898 0.03642767 0.0097 -0.08349579 0.03658288 0.009949982 -0.0837087 0.03671377 0.0097 -0.08354836 0.03703069 0.0097 -0.08315485 0.03810375 0.009949982 -0.0834034 0.03807628 0.0097 -0.08323085 0.03849279 0.009949982 -0.08359599 0.03875726 0.0097 -0.08336991 0.03886395 0.009949982 -0.08377349 0.03906476 0.0097 -0.08426707 0.03957206 0.0097 -0.08411896 0.03977358 0.009949982 -0.08445668 0.03998118 0.009949982 -0.08456957 0.03975808 0.0097 -0.08489859 0.03989166 0.0097 -0.0848239 0.04013025 0.009949982 -0.08521068 0.04021698 0.009949982 -0.08524507 0.03996938 0.0097 -0.08560645 0.04023879 0.009949982 -0.0855996 0.03998887 0.0097 -0.08595246 0.03994989 0.0097 -0.0860005 0.04019516 0.009949982 -0.08716166 0.0392518 0.0097 -0.087372 0.03896558 0.0097 -0.08758497 0.03909659 0.009949982 -0.08753228 0.03864878 0.0097 -0.08763825 0.03830987 0.0097 -0.08768707 0.0379582 0.0097 -0.08767729 0.03760319 0.0097 -0.08784979 0.03718668 0.009949982 -0.08760917 0.03725469 0.0097 -0.08771079 0.03681546 0.009949982 -0.08751255 0.0364722 0.009949982 -0.08748465 0.03692215 0.0097 -0.08730715 0.03661465 0.0097 -0.08696168 0.03590589 0.009949982 -0.08681368 0.03610736 0.0097 -0.08662396 0.03569829 0.009949982 -0.0862568 0.03554916 0.009949982 -0.08618217 0.03578776 0.0097 -0.08586996 0.03546249 0.009949982 -0.08547419 0.03544068 0.009949982 -0.08508026 0.03548425 0.009949982 -0.08469879 0.03559207 0.009949982 -0.08478647 0.03582614 0.0097 -0.08434039 0.03576129 0.009949982 -0.08417356 0.03618007 0.0097 0.06910836 0.04007267 0.0097 0.06923216 0.04105246 0.0097 0.06904447 0.04032146 0.0097 0.06904447 0.04057848 0.0097 0.06793928 0.04079484 0.0097 0.06910836 0.04082727 0.0097 0.06802207 0.04113078 0.0097 0.07012575 0.04147297 0.0097 0.07049149 0.04255658 0.0097 0.07037818 0.04142475 0.0097 0.0708239 0.04246026 0.0097 0.0706107 0.04131537 0.0097 0.06986939 0.04145675 0.0097 0.06940805 0.04123979 0.0097 0.0685721 0.04200059 0.0097 0.06962496 0.04137736 0.0097 0.06884008 0.0422194 0.0097 0.06946325 0.04251509 0.0097 0.0706107 0.03958457 0.0097 0.07095968 0.03995615 0.0097 0.07187855 0.03930085 0.0097 0.07080858 0.03974825 0.0097 0.06962496 0.03952258 0.0097 0.06940805 0.03966015 0.0097 0.0685721 0.03889936 0.0097 0.06923216 0.03984749 0.0097 0.06815767 0.03945076 0.0097 0.07108646 0.04044997 0.0097 0.07105427 0.0407049 0.0097 0.07220447 0.04062294 0.0097 0.07037818 0.0394752 0.0097 0.07049149 0.03834348 0.0097 0.07012575 0.03942698 0.0097 0.06986939 0.03944319 0.0097 0.07220447 0.040277 0.0097 0.07105427 0.04019504 0.0097 0.07203936 0.03960728 0.0097 0.07113647 0.04231196 0.0097 0.0714212 0.04211539 0.0097 0.07080858 0.0411517 0.0097 0.07167077 0.04187566 0.0097 0.07095968 0.0409438 0.0097 0.07246148 0.04044997 0.01069998 0.07246148 0.04044997 0.009949982 0.07245367 0.04025685 0.01069998 0.07245367 0.04025685 0.009949982 0.07239168 0.03987556 0.01069998 0.07226938 0.03950929 0.01069998 0.07226938 0.03950929 0.009949982 0.07208991 0.03916728 0.01069998 0.07208991 0.03916728 0.009949982 0.07185786 0.03885847 0.01069998 0.07185786 0.03885847 0.009949982 0.07157927 0.03859084 0.009949982 0.07157927 0.03859084 0.01069998 0.07126146 0.0383715 0.009949982 0.07126146 0.0383715 0.01069998 0.07091248 0.03820598 0.009949982 0.07091248 0.03820598 0.01069998 0.0705415 0.03809845 0.01069998 0.07015806 0.0380519 0.01069998 0.06977218 0.03806746 0.01069998 0.07015806 0.0380519 0.009949982 0.06939369 0.03814476 0.01069998 0.06939369 0.03814476 0.009949982 0.0690326 0.03828167 0.01069998 0.0686981 0.03847479 0.01069998 0.0686981 0.03847479 0.009949982 0.06839889 0.03871905 0.009949982 0.06839889 0.03871905 0.01069998 0.06814277 0.0390082 0.01069998 0.06793636 0.03933465 0.01069998 0.06793636 0.03933465 0.009949982 0.06778496 0.03968995 0.01069998 0.06769245 0.04006499 0.01069998 0.06769245 0.04006499 0.009949982 0.06766146 0.04044997 0.01069998 0.06769245 0.04083496 0.01069998 0.06769245 0.04083496 0.009949982 0.06778496 0.04120999 0.01069998 0.06793636 0.04156529 0.01069998 0.06814277 0.04189175 0.01069998 0.06839889 0.04218089 0.01069998 0.0686981 0.04242515 0.01069998 0.06839889 0.04218089 0.009949982 0.0686981 0.04242515 0.009949982 0.0690326 0.04261827 0.01069998 0.0690326 0.04261827 0.009949982 0.06939369 0.04275518 0.01069998 0.06939369 0.04275518 0.009949982 0.06977218 0.04283249 0.01069998 0.06977218 0.04283249 0.009949982 0.07015806 0.04284805 0.01069998 0.07015806 0.04284805 0.009949982 0.0705415 0.04280149 0.01069998 0.07091248 0.04269397 0.01069998 0.07091248 0.04269397 0.009949982 0.07126146 0.04252845 0.01069998 0.07126146 0.04252845 0.009949982 0.07157927 0.0423091 0.01069998 0.07185786 0.04204148 0.009949982 0.07185786 0.04204148 0.01069998 0.07208991 0.04173266 0.01069998 0.07208991 0.04173266 0.009949982 0.07226938 0.04139065 0.01069998 0.07239168 0.04102438 0.01069998 0.07226938 0.04139065 0.009949982 0.07245367 0.04064309 0.01069998 0.06793928 0.0401051 0.0097 0.06802207 0.03976917 0.0097 0.06778496 0.03968995 0.009949982 0.06814277 0.0390082 0.009949982 0.06834268 0.0391584 0.0097 0.0690326 0.03828167 0.009949982 0.06884008 0.03868055 0.0097 0.06913977 0.03850758 0.0097 0.06977218 0.03806746 0.009949982 0.06946325 0.03838485 0.0097 0.06980228 0.03831565 0.0097 0.07014799 0.03830164 0.0097 0.0705415 0.03809845 0.009949982 0.0708239 0.03843969 0.0097 0.07113647 0.03858798 0.0097 0.0714212 0.03878456 0.0097 0.07167077 0.03902429 0.0097 0.07214897 0.03993546 0.0097 0.07239168 0.03987556 0.009949982 0.0722115 0.04044997 0.0097 0.07245367 0.04064309 0.009949982 0.07239168 0.04102438 0.009949982 0.07214897 0.04096448 0.0097 0.07203936 0.04129266 0.0097 0.07187855 0.04159909 0.0097 0.07157927 0.0423091 0.009949982 0.0705415 0.04280149 0.009949982 0.07014799 0.04259824 0.0097 0.06980228 0.0425843 0.0097 0.06913977 0.04239237 0.0097 0.06814277 0.04189175 0.009949982 0.06793636 0.04156529 0.009949982 0.06834268 0.04174154 0.0097 0.06815767 0.04144918 0.0097 0.06778496 0.04120999 0.009949982 0.06766146 0.04044997 0.009949982 0.0679115 0.04044997 0.0097 0.06909346 -0.0407871 0.0097 0.06898647 -0.04231196 0.0097 0.06958657 -0.04135835 0.0097 0.07033705 -0.04143714 0.0097 0.0703206 -0.0425843 0.0097 0.06997489 -0.04259824 0.0097 0.0700829 -0.04147475 0.0097 0.06982737 -0.04144787 0.0097 0.0707786 -0.04118227 0.0097 0.07093816 -0.04098099 0.0097 0.07178026 -0.04174154 0.0097 0.0706464 -0.03960829 0.0097 0.07083737 -0.03978019 0.0097 0.07178026 -0.0391584 0.0097 0.06824427 -0.03930085 0.0097 0.06925815 -0.03981328 0.0097 0.06904006 -0.04053574 0.0097 0.06905078 -0.04027909 0.0097 0.06912505 -0.0400331 0.0097 0.06808346 -0.03960728 0.0097 0.06937557 -0.04121166 0.0097 0.06845217 -0.04187566 0.0097 0.06920766 -0.04101717 0.0097 0.06824427 -0.04159909 0.0097 0.07057398 -0.04133766 0.0097 0.07108557 -0.04049289 0.0097 0.07104265 -0.04074627 0.0097 0.07210075 -0.04113078 0.0097 0.07097959 -0.03999418 0.0097 0.07106405 -0.04023689 0.0097 0.07016855 -0.03943055 0.0097 0.07041865 -0.03948926 0.0097 0.07065957 -0.03838485 0.0097 0.07098311 -0.03850758 0.0097 0.06898647 -0.03858798 0.0097 0.06944167 -0.03963357 0.0097 0.06966429 -0.03950506 0.0097 0.06991165 -0.03943598 0.0097 0.07142478 -0.04242515 0.01069998 0.07126146 -0.04252845 0.01069998 0.07109028 -0.04261827 0.01069998 0.07109028 -0.04261827 0.009949982 0.07072919 -0.04275518 0.01069998 0.0703507 -0.04283249 0.01069998 0.06996476 -0.04284805 0.01069998 0.0703507 -0.04283249 0.009949982 0.06958138 -0.04280149 0.01069998 0.06958138 -0.04280149 0.009949982 0.06921041 -0.04269397 0.01069998 0.06886148 -0.04252845 0.01069998 0.06854355 -0.0423091 0.01069998 0.06826496 -0.04204148 0.01069998 0.06803297 -0.04173266 0.01069998 0.06785351 -0.04139065 0.01069998 0.0677312 -0.04102438 0.01069998 0.0677312 -0.04102438 0.009949982 0.06766915 -0.04064309 0.009949982 0.06766915 -0.04064309 0.01069998 0.06766915 -0.04025685 0.01069998 0.06766915 -0.04025685 0.009949982 0.0677312 -0.03987556 0.01069998 0.06785351 -0.03950929 0.01069998 0.0677312 -0.03987556 0.009949982 0.06785351 -0.03950929 0.009949982 0.06803297 -0.03916728 0.01069998 0.06803297 -0.03916728 0.009949982 0.06826496 -0.03885847 0.01069998 0.06854355 -0.03859084 0.01069998 0.06826496 -0.03885847 0.009949982 0.06886148 -0.0383715 0.01069998 0.06921041 -0.03820598 0.01069998 0.06921041 -0.03820598 0.009949982 0.06958138 -0.03809845 0.01069998 0.06958138 -0.03809845 0.009949982 0.06996476 -0.0380519 0.01069998 0.0703507 -0.03806746 0.009949982 0.0703507 -0.03806746 0.01069998 0.07072919 -0.03814476 0.01069998 0.07072919 -0.03814476 0.009949982 0.07109028 -0.03828167 0.009949982 0.07109028 -0.03828167 0.01069998 0.07142478 -0.03847479 0.009949982 0.07142478 -0.03847479 0.01069998 0.07172399 -0.03871905 0.01069998 0.07172399 -0.03871905 0.009949982 0.07198005 -0.0390082 0.009949982 0.07198005 -0.0390082 0.01069998 0.07218658 -0.03933465 0.01069998 0.07218658 -0.03933465 0.009949982 0.07233786 -0.03968995 0.01069998 0.07233786 -0.03968995 0.009949982 0.07243037 -0.04006499 0.01069998 0.07246148 -0.04044997 0.01069998 0.07243037 -0.04083496 0.009949982 0.07243037 -0.04083496 0.01069998 0.07233786 -0.04120999 0.01069998 0.07218658 -0.04156529 0.01069998 0.07198005 -0.04189175 0.01069998 0.07172399 -0.04218089 0.01069998 0.07126146 -0.04252845 0.009949982 0.06870168 -0.03878456 0.0097 0.06845217 -0.03902429 0.0097 0.06797391 -0.03993546 0.0097 0.06791836 -0.040277 0.0097 0.06791836 -0.04062294 0.0097 0.06797391 -0.04096448 0.0097 0.06785351 -0.04139065 0.009949982 0.06808346 -0.04129266 0.0097 0.06803297 -0.04173266 0.009949982 0.06826496 -0.04204148 0.009949982 0.06870168 -0.04211539 0.0097 0.06854355 -0.0423091 0.009949982 0.06886148 -0.04252845 0.009949982 0.06921041 -0.04269397 0.009949982 0.0692991 -0.04246026 0.0097 0.06996476 -0.04284805 0.009949982 0.06963139 -0.04255658 0.0097 0.07072919 -0.04275518 0.009949982 0.07065957 -0.04251509 0.0097 0.07098311 -0.04239237 0.0097 0.07113647 -0.04231196 0.0097 0.07142478 -0.04242515 0.009949982 0.0712828 -0.0422194 0.0097 0.07172399 -0.04218089 0.009949982 0.07155078 -0.04200059 0.0097 0.07198005 -0.04189175 0.009949982 0.07218658 -0.04156529 0.009949982 0.07196515 -0.04144918 0.0097 0.07233786 -0.04120999 0.009949982 0.0721836 -0.04079484 0.0097 0.0722115 -0.04044997 0.0097 0.07246148 -0.04044997 0.009949982 0.07243037 -0.04006499 0.009949982 0.0721836 -0.0401051 0.0097 0.07210075 -0.03976917 0.0097 0.07196515 -0.03945076 0.0097 0.07155078 -0.03889936 0.0097 0.0712828 -0.03868055 0.0097 0.0703206 -0.03831565 0.0097 0.06996476 -0.0380519 0.009949982 0.06997489 -0.03830164 0.0097 0.06963139 -0.03834348 0.0097 0.0692991 -0.03843969 0.0097 0.06886148 -0.0383715 0.009949982 0.06854355 -0.03859084 0.009949982 -2.75643e-4 -0.08188718 0.0097 -5.98168e-4 -0.08296507 0.0097 4.74878e-4 -0.08180838 0.0097 2.3406e-4 -0.08189785 0.0097 4.30055e-4 -0.08300656 0.0097 -2.1466e-5 -0.08192479 0.0097 8.65718e-5 -0.08304828 0.0097 -2.59154e-4 -0.08303427 0.0097 -3.57286e-4 -0.0799393 0.0097 -1.07142e-4 -0.07988059 0.0097 -2.59154e-4 -0.07876569 0.0097 4.30055e-4 -0.07879346 0.0097 1.49735e-4 -0.07988595 0.0097 7.62401e-4 -0.07888966 0.0097 3.97203e-4 -0.0799551 0.0097 0.001074969 -0.07903796 0.0097 6.19714e-4 -0.0800836 0.0097 -0.001074969 -0.082762 0.0097 -5.125e-4 -0.0817877 0.0097 8.03286e-4 -0.08026325 0.0097 9.36384e-4 -0.08048307 0.0097 0.00197792 -0.08005726 0.0097 -0.001489341 -0.07934939 0.0097 -5.84981e-4 -0.08005827 0.0097 -9.21689e-4 -0.07895755 0.0097 -0.001024067 -0.08094286 0.0097 -0.002149999 -0.08089995 0.0097 -0.001221299 -0.08266937 0.0097 -0.001489341 -0.08245056 0.0097 -7.17155e-4 -0.08163225 0.0097 -0.001718759 -0.08219158 0.0097 -8.76748e-4 -0.08143097 0.0097 -9.81253e-4 -0.0811963 0.0097 0.001609265 -0.08232569 0.0097 6.85859e-4 -0.0816617 0.0097 0.001359701 -0.08256536 0.0097 7.62401e-4 -0.08291029 0.0097 -0.00100255 -0.08068686 0.0097 -9.18105e-4 -0.08044415 0.0097 -7.7592e-4 -0.08023017 0.0097 -0.001903712 -0.0799008 0.0097 0.001021385 -0.08098578 0.0097 9.67986e-4 -0.08123707 0.0097 0.00197792 -0.0817427 0.0097 8.53744e-4 -0.08146721 0.0097 0.001010596 -0.08072906 0.0097 0.002143025 -0.08107298 0.0097 4.80062e-4 -0.07854849 0.009949982 9.66383e-5 -0.07850188 0.009949982 8.65718e-5 -0.07875168 0.0097 -2.89288e-4 -0.07851749 0.009949982 -6.67722e-4 -0.0785948 0.009949982 -5.98168e-4 -0.07883489 0.0097 -0.001028835 -0.07873165 0.009949982 -0.001363337 -0.07892477 0.009949982 -0.001662492 -0.07916909 0.009949982 -0.001221299 -0.07913058 0.0097 -0.001918613 -0.07945817 0.009949982 -0.001718759 -0.07960838 0.0097 -0.002125084 -0.07978469 0.009949982 -0.00227648 -0.08013999 0.009949982 -0.002039313 -0.0802192 0.0097 -0.002368867 -0.08051496 0.009949982 -0.002122104 -0.08055508 0.0097 -0.002399981 -0.08089995 0.009949982 -0.002368867 -0.08128499 0.009949982 -0.002122104 -0.08124488 0.0097 -0.00227648 -0.08165997 0.009949982 -0.002039313 -0.08158075 0.0097 -0.002125084 -0.08201527 0.009949982 -0.001918613 -0.08234179 0.009949982 -0.001903712 -0.08189916 0.0097 -0.001662492 -0.08263087 0.009949982 -0.001363337 -0.08287519 0.009949982 -0.00119996 -0.08297848 0.009949982 -9.21689e-4 -0.0828424 0.0097 -0.001028835 -0.08306831 0.009949982 -6.67722e-4 -0.08320516 0.009949982 -2.89288e-4 -0.08328247 0.009949982 9.66383e-5 -0.08329808 0.009949982 4.80062e-4 -0.08325147 0.009949982 8.51052e-4 -0.083144 0.009949982 0.00119996 -0.08297848 0.009949982 0.001074969 -0.082762 0.0097 0.001517832 -0.08275908 0.009949982 0.001796424 -0.08249145 0.009949982 0.002028405 -0.0821827 0.009949982 0.001817107 -0.08204907 0.0097 0.002207934 -0.08184069 0.009949982 0.002330243 -0.08147436 0.009949982 0.002087473 -0.08141446 0.0097 0.002392172 -0.08109307 0.009949982 0.002392172 -0.08070689 0.009949982 0.002143025 -0.08072698 0.0097 0.002330243 -0.0803256 0.009949982 0.002087473 -0.0803855 0.0097 0.002207934 -0.07995927 0.009949982 0.001817107 -0.07975089 0.0097 0.002028405 -0.07961726 0.009949982 0.001796424 -0.0793085 0.009949982 0.001609265 -0.07947427 0.0097 0.001517832 -0.07904088 0.009949982 0.001359701 -0.0792346 0.0097 0.00119996 -0.07882148 0.009949982 8.51052e-4 -0.07865595 0.009949982 -0.07105427 -0.04019504 0.0097 -0.07108646 -0.04044997 0.0097 -0.0722115 -0.04044997 0.0097 -0.06946325 -0.04251509 0.0097 -0.06986939 -0.04145675 0.0097 -0.07012575 -0.04147297 0.0097 -0.0706107 -0.04131537 0.0097 -0.07080858 -0.0411517 0.0097 -0.07095968 -0.0409438 0.0097 -0.06962496 -0.04137736 0.0097 -0.07187855 -0.04159909 0.0097 -0.07203936 -0.04129266 0.0097 -0.07105427 -0.0407049 0.0097 -0.07214897 -0.04096448 0.0097 -0.07014799 -0.04259824 0.0097 -0.07049149 -0.04255658 0.0097 -0.07037818 -0.04142475 0.0097 -0.0708239 -0.04246026 0.0097 -0.0714212 -0.04211539 0.0097 -0.06962496 -0.03952258 0.0097 -0.06940805 -0.03966015 0.0097 -0.06904447 -0.04032146 0.0097 -0.0679115 -0.04044997 0.0097 -0.06904447 -0.04057848 0.0097 -0.0685721 -0.03889936 0.0097 -0.06834268 -0.0391584 0.0097 -0.06923216 -0.03984749 0.0097 -0.06815767 -0.03945076 0.0097 -0.06910836 -0.04007267 0.0097 -0.06802207 -0.03976917 0.0097 -0.06793928 -0.0401051 0.0097 -0.07080858 -0.03974825 0.0097 -0.0706107 -0.03958457 0.0097 -0.06802207 -0.04113078 0.0097 -0.06910836 -0.04082727 0.0097 -0.06815767 -0.04144918 0.0097 -0.06923216 -0.04105246 0.0097 -0.06834268 -0.04174154 0.0097 -0.06940805 -0.04123979 0.0097 -0.0685721 -0.04200059 0.0097 -0.06986939 -0.03944319 0.0097 -0.06913977 -0.03850758 0.0097 -0.07214897 -0.03993546 0.0097 -0.07095968 -0.03995615 0.0097 -0.07187855 -0.03930085 0.0097 -0.07167077 -0.03902429 0.0097 -0.07037818 -0.0394752 0.0097 -0.07012575 -0.03942698 0.0097 -0.07246148 -0.04044997 0.01069998 -0.07246148 -0.04044997 0.009949982 -0.07245367 -0.04064309 0.01069998 -0.07245367 -0.04025685 0.01069998 -0.07245367 -0.04025685 0.009949982 -0.07239168 -0.03987556 0.01069998 -0.07239168 -0.03987556 0.009949982 -0.07226938 -0.03950929 0.01069998 -0.07208991 -0.03916728 0.01069998 -0.07185786 -0.03885847 0.01069998 -0.07185786 -0.03885847 0.009949982 -0.07157927 -0.03859084 0.01069998 -0.07157927 -0.03859084 0.009949982 -0.07126146 -0.0383715 0.01069998 -0.07091248 -0.03820598 0.009949982 -0.07091248 -0.03820598 0.01069998 -0.0705415 -0.03809845 0.01069998 -0.0705415 -0.03809845 0.009949982 -0.07015806 -0.0380519 0.01069998 -0.07015806 -0.0380519 0.009949982 -0.06977218 -0.03806746 0.01069998 -0.06977218 -0.03806746 0.009949982 -0.06939369 -0.03814476 0.01069998 -0.0690326 -0.03828167 0.01069998 -0.0686981 -0.03847479 0.01069998 -0.0690326 -0.03828167 0.009949982 -0.0686981 -0.03847479 0.009949982 -0.06839889 -0.03871905 0.01069998 -0.06839889 -0.03871905 0.009949982 -0.06814277 -0.0390082 0.01069998 -0.06793636 -0.03933465 0.01069998 -0.06778496 -0.03968995 0.01069998 -0.06769245 -0.04006499 0.01069998 -0.06766146 -0.04044997 0.01069998 -0.06769245 -0.04083496 0.01069998 -0.06778496 -0.04120999 0.01069998 -0.06793636 -0.04156529 0.01069998 -0.06793636 -0.04156529 0.009949982 -0.06814277 -0.04189175 0.01069998 -0.06814277 -0.04189175 0.009949982 -0.06839889 -0.04218089 0.01069998 -0.06839889 -0.04218089 0.009949982 -0.0686981 -0.04242515 0.01069998 -0.0686981 -0.04242515 0.009949982 -0.0690326 -0.04261827 0.01069998 -0.0690326 -0.04261827 0.009949982 -0.06939369 -0.04275518 0.01069998 -0.06939369 -0.04275518 0.009949982 -0.06977218 -0.04283249 0.01069998 -0.06977218 -0.04283249 0.009949982 -0.07015806 -0.04284805 0.01069998 -0.0705415 -0.04280149 0.01069998 -0.0705415 -0.04280149 0.009949982 -0.07091248 -0.04269397 0.01069998 -0.07091248 -0.04269397 0.009949982 -0.07126146 -0.04252845 0.009949982 -0.07126146 -0.04252845 0.01069998 -0.07157927 -0.0423091 0.01069998 -0.07185786 -0.04204148 0.01069998 -0.07208991 -0.04173266 0.01069998 -0.07226938 -0.04139065 0.01069998 -0.07208991 -0.04173266 0.009949982 -0.07239168 -0.04102438 0.01069998 -0.07226938 -0.04139065 0.009949982 -0.07245367 -0.04064309 0.009949982 -0.06778496 -0.03968995 0.009949982 -0.06793636 -0.03933465 0.009949982 -0.06814277 -0.0390082 0.009949982 -0.06884008 -0.03868055 0.0097 -0.06946325 -0.03838485 0.0097 -0.06939369 -0.03814476 0.009949982 -0.06980228 -0.03831565 0.0097 -0.07014799 -0.03830164 0.0097 -0.07049149 -0.03834348 0.0097 -0.0708239 -0.03843969 0.0097 -0.07126146 -0.0383715 0.009949982 -0.07113647 -0.03858798 0.0097 -0.0714212 -0.03878456 0.0097 -0.07208991 -0.03916728 0.009949982 -0.07226938 -0.03950929 0.009949982 -0.07203936 -0.03960728 0.0097 -0.07220447 -0.040277 0.0097 -0.07220447 -0.04062294 0.0097 -0.07239168 -0.04102438 0.009949982 -0.07185786 -0.04204148 0.009949982 -0.07167077 -0.04187566 0.0097 -0.07157927 -0.0423091 0.009949982 -0.07113647 -0.04231196 0.0097 -0.07015806 -0.04284805 0.009949982 -0.06980228 -0.0425843 0.0097 -0.06913977 -0.04239237 0.0097 -0.06884008 -0.0422194 0.0097 -0.06778496 -0.04120999 0.009949982 -0.06769245 -0.04083496 0.009949982 -0.06793928 -0.04079484 0.0097 -0.06766146 -0.04044997 0.009949982 -0.06769245 -0.04006499 0.009949982 -0.06904006 0.04053574 0.0097 -0.06791836 0.040277 0.0097 -0.06905078 0.04027909 0.0097 -0.06912505 0.0400331 0.0097 -0.06797391 0.04096448 0.0097 -0.06845217 0.04187566 0.0097 -0.06920766 0.04101717 0.0097 -0.06909346 0.0407871 0.0097 -0.06808346 0.04129266 0.0097 -0.07033705 0.04143714 0.0097 -0.0700829 0.04147475 0.0097 -0.0703206 0.0425843 0.0097 -0.06997489 0.04259824 0.0097 -0.06982737 0.04144787 0.0097 -0.0721836 0.04079484 0.0097 -0.07104265 0.04074627 0.0097 -0.07097959 0.03999418 0.0097 -0.07106405 0.04023689 0.0097 -0.0721836 0.0401051 0.0097 -0.07108557 0.04049289 0.0097 -0.0722115 0.04044997 0.0097 -0.07155078 0.03889936 0.0097 -0.07083737 0.03978019 0.0097 -0.07178026 0.0391584 0.0097 -0.07196515 0.03945076 0.0097 -0.07210075 0.03976917 0.0097 -0.07016855 0.03943055 0.0097 -0.06963139 0.04255658 0.0097 -0.06958657 0.04135835 0.0097 -0.06937557 0.04121166 0.0097 -0.07057398 0.04133766 0.0097 -0.07093816 0.04098099 0.0097 -0.07178026 0.04174154 0.0097 -0.0707786 0.04118227 0.0097 -0.07041865 0.03948926 0.0097 -0.0706464 0.03960829 0.0097 -0.07098311 0.03850758 0.0097 -0.06898647 0.03858798 0.0097 -0.06966429 0.03950506 0.0097 -0.0692991 0.03843969 0.0097 -0.06963139 0.03834348 0.0097 -0.06991165 0.03943598 0.0097 -0.06797391 0.03993546 0.0097 -0.06925815 0.03981328 0.0097 -0.06944167 0.03963357 0.0097 -0.06870168 0.03878456 0.0097 -0.07113647 0.04231196 0.0097 -0.07126146 0.04252845 0.01069998 -0.07126146 0.04252845 0.009949982 -0.07142478 0.04242515 0.01069998 -0.07109028 0.04261827 0.01069998 -0.07109028 0.04261827 0.009949982 -0.07072919 0.04275518 0.01069998 -0.07072919 0.04275518 0.009949982 -0.0703507 0.04283249 0.01069998 -0.06996476 0.04284805 0.01069998 -0.06996476 0.04284805 0.009949982 -0.06958138 0.04280149 0.01069998 -0.06921041 0.04269397 0.01069998 -0.06958138 0.04280149 0.009949982 -0.06886148 0.04252845 0.01069998 -0.06886148 0.04252845 0.009949982 -0.06854355 0.0423091 0.01069998 -0.06854355 0.0423091 0.009949982 -0.06826496 0.04204148 0.01069998 -0.06803297 0.04173266 0.01069998 -0.06803297 0.04173266 0.009949982 -0.06785351 0.04139065 0.01069998 -0.0677312 0.04102438 0.01069998 -0.06766915 0.04064309 0.009949982 -0.06766915 0.04064309 0.01069998 -0.06766915 0.04025685 0.01069998 -0.0677312 0.03987556 0.01069998 -0.0677312 0.03987556 0.009949982 -0.06785351 0.03950929 0.01069998 -0.06785351 0.03950929 0.009949982 -0.06803297 0.03916728 0.01069998 -0.06803297 0.03916728 0.009949982 -0.06826496 0.03885847 0.01069998 -0.06854355 0.03859084 0.01069998 -0.06854355 0.03859084 0.009949982 -0.06886148 0.0383715 0.01069998 -0.06886148 0.0383715 0.009949982 -0.06921041 0.03820598 0.01069998 -0.06958138 0.03809845 0.01069998 -0.06996476 0.0380519 0.01069998 -0.0703507 0.03806746 0.01069998 -0.06996476 0.0380519 0.009949982 -0.0703507 0.03806746 0.009949982 -0.07072919 0.03814476 0.01069998 -0.07072919 0.03814476 0.009949982 -0.07109028 0.03828167 0.009949982 -0.07109028 0.03828167 0.01069998 -0.07142478 0.03847479 0.01069998 -0.07142478 0.03847479 0.009949982 -0.07172399 0.03871905 0.01069998 -0.07172399 0.03871905 0.009949982 -0.07198005 0.0390082 0.009949982 -0.07198005 0.0390082 0.01069998 -0.07218658 0.03933465 0.009949982 -0.07218658 0.03933465 0.01069998 -0.07233786 0.03968995 0.01069998 -0.07233786 0.03968995 0.009949982 -0.07243037 0.04006499 0.009949982 -0.07243037 0.04006499 0.01069998 -0.07246148 0.04044997 0.01069998 -0.07243037 0.04083496 0.01069998 -0.07246148 0.04044997 0.009949982 -0.07233786 0.04120999 0.01069998 -0.07233786 0.04120999 0.009949982 -0.07218658 0.04156529 0.01069998 -0.07218658 0.04156529 0.009949982 -0.07198005 0.04189175 0.01069998 -0.07172399 0.04218089 0.01069998 -0.06826496 0.03885847 0.009949982 -0.06845217 0.03902429 0.0097 -0.06824427 0.03930085 0.0097 -0.06808346 0.03960728 0.0097 -0.06766915 0.04025685 0.009949982 -0.06791836 0.04062294 0.0097 -0.0677312 0.04102438 0.009949982 -0.06785351 0.04139065 0.009949982 -0.06824427 0.04159909 0.0097 -0.06826496 0.04204148 0.009949982 -0.06870168 0.04211539 0.0097 -0.06898647 0.04231196 0.0097 -0.06921041 0.04269397 0.009949982 -0.0692991 0.04246026 0.0097 -0.0703507 0.04283249 0.009949982 -0.07065957 0.04251509 0.0097 -0.07098311 0.04239237 0.0097 -0.07142478 0.04242515 0.009949982 -0.0712828 0.0422194 0.0097 -0.07172399 0.04218089 0.009949982 -0.07198005 0.04189175 0.009949982 -0.07155078 0.04200059 0.0097 -0.07196515 0.04144918 0.0097 -0.07243037 0.04083496 0.009949982 -0.07210075 0.04113078 0.0097 -0.0712828 0.03868055 0.0097 -0.07065957 0.03838485 0.0097 -0.0703206 0.03831565 0.0097 -0.06958138 0.03809845 0.009949982 -0.06997489 0.03830164 0.0097 -0.06921041 0.03820598 0.009949982 0.08653318 0.03809469 0.01169997 0.08656537 0.03783965 0.01169997 0.08653318 0.03758478 0.01169997 0.08643859 0.03734588 0.01169997 0.08628755 0.0371381 0.01169997 0.08608961 0.03697425 0.01169997 0.08585709 0.03686487 0.01169997 0.08560466 0.03681677 0.0097 0.0853483 0.03683286 0.0097 0.08560466 0.03681677 0.01169997 0.0853483 0.03683286 0.01169997 0.08510386 0.03691226 0.0097 0.08510386 0.03691226 0.01169997 0.08471107 0.03723728 0.0097 0.08488696 0.03704994 0.01169997 0.08458727 0.03746235 0.0097 0.08471107 0.03723728 0.01169997 0.08458727 0.03746235 0.01169997 0.08452337 0.03771126 0.01169997 0.08452337 0.03796815 0.01169997 0.08458727 0.03821706 0.01169997 0.08471107 0.03844219 0.0097 0.08471107 0.03844219 0.01169997 0.08488696 0.03862947 0.01169997 0.08510386 0.03876715 0.01169997 0.0853483 0.03884655 0.01169997 0.08560466 0.0388627 0.0097 0.08560466 0.0388627 0.01169997 0.08585709 0.0388146 0.01169997 0.08585709 0.0388146 0.0097 0.08628755 0.03854137 0.0097 0.08608961 0.03870517 0.01169997 0.08643859 0.03833347 0.0097 0.08628755 0.03854137 0.01169997 0.08643859 0.03833347 0.01169997 0.08452337 0.03796815 0.0097 0.08341968 0.03819358 0.0097 0.08766096 0.03748589 0.0097 0.08653318 0.03758478 0.0097 0.0853483 0.03884655 0.0097 0.08571785 0.03998237 0.0097 0.08640396 0.03980869 0.0097 0.08608961 0.03870517 0.0097 0.08510386 0.03876715 0.0097 0.08436435 0.03963965 0.0097 0.08467668 0.03980869 0.0097 0.08501255 0.03992396 0.0097 0.08536279 0.03998237 0.0097 0.08458727 0.03821706 0.0097 0.08364945 0.038863 0.0097 0.08488696 0.03862947 0.0097 0.08408415 0.03942155 0.0097 0.08501255 0.03575545 0.0097 0.08699649 0.03942155 0.0097 0.087237 0.03916025 0.0097 0.08452337 0.03771126 0.0097 0.08341968 0.03748589 0.0097 0.08436435 0.03603976 0.0097 0.08488696 0.03704994 0.0097 0.08408415 0.03625786 0.0097 0.0838437 0.03651916 0.0097 0.08585709 0.03686487 0.0097 0.08606815 0.03575545 0.0097 0.08571785 0.0356971 0.0097 0.08757388 0.03714156 0.0097 0.08643859 0.03734588 0.0097 0.087237 0.03651916 0.0097 0.08628755 0.0371381 0.0097 0.08699649 0.03625786 0.0097 0.08608961 0.03697425 0.0097 0.08671629 0.03603976 0.0097 0.08653318 0.03809469 0.0097 0.08766096 0.03819358 0.0097 0.08656537 0.03783965 0.0097 0.08769035 0.03783965 0.0097 0.08317309 0.03744465 0.009949982 0.08314037 0.03783965 0.009949982 0.08317309 0.03823477 0.01069998 0.08327037 0.03861898 0.01069998 0.08327037 0.03861898 0.009949982 0.08342957 0.03898197 0.01069998 0.08364635 0.03931385 0.01069998 0.08391487 0.03960549 0.01069998 0.08422768 0.03984886 0.01069998 0.0845763 0.04003757 0.01069998 0.08495116 0.04016625 0.01069998 0.08534216 0.04023146 0.01069998 0.08534216 0.04023146 0.009949982 0.08573859 0.04023146 0.01069998 0.08612948 0.04016625 0.01069998 0.08650439 0.04003757 0.01069998 0.08650439 0.04003757 0.009949982 0.08685296 0.03984886 0.01069998 0.08716577 0.03960549 0.01069998 0.08743429 0.03931385 0.01069998 0.08716577 0.03960549 0.009949982 0.08765107 0.03898197 0.01069998 0.08765107 0.03898197 0.009949982 0.08781027 0.03861898 0.01069998 0.08781027 0.03861898 0.009949982 0.08790755 0.03823477 0.01069998 0.08790755 0.03823477 0.009949982 0.08794039 0.03783965 0.01069998 0.08794039 0.03783965 0.009949982 0.08790755 0.03744465 0.01069998 0.08781027 0.03706049 0.01069998 0.08790755 0.03744465 0.009949982 0.08765107 0.03669744 0.01069998 0.08765107 0.03669744 0.009949982 0.08743429 0.03636556 0.009949982 0.08743429 0.03636556 0.01069998 0.08716577 0.03607398 0.01069998 0.08685296 0.03583049 0.01069998 0.08685296 0.03583049 0.009949982 0.08650439 0.03564184 0.01069998 0.08650439 0.03564184 0.009949982 0.08612948 0.03551316 0.01069998 0.08612948 0.03551316 0.009949982 0.08573859 0.03544789 0.01069998 0.08573859 0.03544789 0.009949982 0.08534216 0.03544789 0.009949982 0.08534216 0.03544789 0.01069998 0.08495116 0.03551316 0.009949982 0.08495116 0.03551316 0.01069998 0.0845763 0.03564184 0.01069998 0.0845763 0.03564184 0.009949982 0.08422768 0.03583049 0.01069998 0.08422768 0.03583049 0.009949982 0.08391487 0.03607398 0.01069998 0.08364635 0.03636556 0.01069998 0.08364635 0.03636556 0.009949982 0.08342957 0.03669744 0.01069998 0.08327037 0.03706049 0.01069998 0.08327037 0.03706049 0.009949982 0.08317309 0.03744465 0.01069998 0.08314037 0.03783965 0.01069998 0.08350688 0.03714156 0.0097 0.08342957 0.03669744 0.009949982 0.08364945 0.03681647 0.0097 0.08391487 0.03607398 0.009949982 0.08467668 0.03587079 0.0097 0.08536279 0.0356971 0.0097 0.08640396 0.03587079 0.0097 0.08716577 0.03607398 0.009949982 0.08743119 0.03681647 0.0097 0.08781027 0.03706049 0.009949982 0.08757388 0.0385378 0.0097 0.08743119 0.038863 0.0097 0.08743429 0.03931385 0.009949982 0.08685296 0.03984886 0.009949982 0.08671629 0.03963965 0.0097 0.08612948 0.04016625 0.009949982 0.08606815 0.03992396 0.0097 0.08573859 0.04023146 0.009949982 0.08495116 0.04016625 0.009949982 0.0845763 0.04003757 0.009949982 0.08422768 0.03984886 0.009949982 0.08391487 0.03960549 0.009949982 0.08364635 0.03931385 0.009949982 0.08342957 0.03898197 0.009949982 0.0838437 0.03916025 0.0097 0.08350688 0.0385378 0.0097 0.08317309 0.03823477 0.009949982 0.08339035 0.03783965 0.0097 0.07757967 -0.05447936 0.0097 0.07654297 -0.05494707 0.0097 0.07393109 -0.05658596 0.0097 0.07468658 -0.05572748 0.0097 0.07457238 -0.05549728 0.0097 0.07506549 -0.05606859 0.0097 0.07446539 -0.05702215 0.0097 0.07485449 -0.05592197 0.0097 0.07556176 -0.05618494 0.0097 0.07530629 -0.05615818 0.0097 0.07477796 -0.05717045 0.0097 0.0760529 -0.05604785 0.0097 0.07581597 -0.05614745 0.0097 0.07613849 -0.0572254 0.0097 0.07579946 -0.05729454 0.0097 0.07676166 -0.05692964 0.0097 0.07661539 -0.05702215 0.0097 0.07646209 -0.05710268 0.0097 0.07656449 -0.05520319 0.0097 0.07769036 -0.05516028 0.0097 0.07652157 -0.05545645 0.0097 0.07641708 -0.05569118 0.0097 0.07631629 -0.05449044 0.0097 0.07725918 -0.05386865 0.0097 0.07645845 -0.05470448 0.0097 0.07757967 -0.05584108 0.0097 0.07744407 -0.05615937 0.0097 0.07725918 -0.05645179 0.0097 0.07625746 -0.05589258 0.0097 0.07589757 -0.05419945 0.0097 0.07612526 -0.05431854 0.0097 0.0770297 -0.05360966 0.0097 0.07473707 -0.05452358 0.0097 0.07492059 -0.05434376 0.0097 0.07345277 -0.05567479 0.0097 0.07339727 -0.05498725 0.0097 0.07451897 -0.05524599 0.0097 0.0745297 -0.05498927 0.0097 0.07460397 -0.05474328 0.0097 0.07564747 -0.05414086 0.0097 0.07646209 -0.05321776 0.0097 0.0741806 -0.05349487 0.0097 0.07446539 -0.05329829 0.0097 0.07514315 -0.05421525 0.0097 0.07539057 -0.05414617 0.0097 0.07477796 -0.05314999 0.0097 0.07674038 -0.05723869 0.01069998 0.07674038 -0.05723869 0.009949982 0.0769037 -0.0571354 0.01069998 0.07656919 -0.05732846 0.01069998 0.07620805 -0.05746549 0.01069998 0.07656919 -0.05732846 0.009949982 0.07620805 -0.05746549 0.009949982 0.07582956 -0.0575428 0.01069998 0.07544368 -0.05755829 0.01069998 0.07544368 -0.05755829 0.009949982 0.0750603 -0.05751174 0.01069998 0.07468926 -0.05740427 0.009949982 0.07468926 -0.05740427 0.01069998 0.0743404 -0.05723869 0.01069998 0.07402247 -0.05701929 0.01069998 0.07402247 -0.05701929 0.009949982 0.07374387 -0.05675166 0.01069998 0.07351189 -0.05644297 0.01069998 0.07333236 -0.05610096 0.009949982 0.07333236 -0.05610096 0.01069998 0.07321006 -0.05573457 0.01069998 0.07321006 -0.05573457 0.009949982 0.07314807 -0.0553534 0.01069998 0.07314807 -0.0549671 0.01069998 0.07321006 -0.05458587 0.009949982 0.07321006 -0.05458587 0.01069998 0.07333236 -0.05421948 0.01069998 0.07333236 -0.05421948 0.009949982 0.07351189 -0.05387747 0.01069998 0.07374387 -0.05356878 0.01069998 0.07402247 -0.05330115 0.01069998 0.07402247 -0.05330115 0.009949982 0.0743404 -0.05308175 0.01069998 0.07468926 -0.05291616 0.01069998 0.0750603 -0.05280876 0.01069998 0.07544368 -0.05276215 0.009949982 0.07544368 -0.05276215 0.01069998 0.07582956 -0.05277776 0.01069998 0.07620805 -0.05285495 0.01069998 0.07582956 -0.05277776 0.009949982 0.07620805 -0.05285495 0.009949982 0.07656919 -0.05299198 0.009949982 0.07656919 -0.05299198 0.01069998 0.0769037 -0.0531851 0.01069998 0.07720285 -0.05342936 0.01069998 0.07745897 -0.05371844 0.009949982 0.07745897 -0.05371844 0.01069998 0.0776655 -0.0540449 0.009949982 0.0776655 -0.0540449 0.01069998 0.0778169 -0.05440026 0.01069998 0.0778169 -0.05440026 0.009949982 0.07790929 -0.05477529 0.01069998 0.0779404 -0.05516028 0.01069998 0.07790929 -0.05554515 0.01069998 0.0778169 -0.0559203 0.01069998 0.0778169 -0.0559203 0.009949982 0.0776655 -0.0562756 0.01069998 0.0776655 -0.0562756 0.009949982 0.07745897 -0.056602 0.01069998 0.07720285 -0.05689108 0.01069998 0.07374387 -0.05356878 0.009949982 0.07351189 -0.05387747 0.009949982 0.07393109 -0.05373448 0.0097 0.07372319 -0.05401116 0.0097 0.07356238 -0.05431747 0.0097 0.07345277 -0.05464565 0.0097 0.07314807 -0.0549671 0.009949982 0.07314807 -0.0553534 0.009949982 0.07339727 -0.05533325 0.0097 0.07356238 -0.05600297 0.0097 0.07372319 -0.0563094 0.0097 0.07351189 -0.05644297 0.009949982 0.07374387 -0.05675166 0.009949982 0.0741806 -0.05682569 0.0097 0.0743404 -0.05723869 0.009949982 0.0750603 -0.05751174 0.009949982 0.07511025 -0.05726677 0.0097 0.07582956 -0.0575428 0.009949982 0.07545375 -0.05730849 0.0097 0.0769037 -0.0571354 0.009949982 0.07720285 -0.05689108 0.009949982 0.0770297 -0.05671077 0.0097 0.07745897 -0.056602 0.009949982 0.07790929 -0.05554515 0.009949982 0.07766246 -0.05550509 0.0097 0.0779404 -0.05516028 0.009949982 0.07790929 -0.05477529 0.009949982 0.07766246 -0.05481535 0.0097 0.07744407 -0.05416107 0.0097 0.07720285 -0.05342936 0.009949982 0.0769037 -0.0531851 0.009949982 0.07676166 -0.0533908 0.0097 0.07613849 -0.0530951 0.0097 0.07579946 -0.0530259 0.0097 0.07545375 -0.05301195 0.0097 0.0750603 -0.05280876 0.009949982 0.07468926 -0.05291616 0.009949982 0.07511025 -0.05305367 0.0097 0.0743404 -0.05308175 0.009949982 -0.01051247 -0.09388768 0.01169997 -0.01071715 -0.09373229 0.0097 -0.01071715 -0.09373229 0.01169997 -0.01087665 -0.09353095 0.01169997 -0.01098126 -0.09329628 0.0097 -0.01098126 -0.09329628 0.01169997 -0.01102405 -0.09304291 0.0097 -0.01102405 -0.09304291 0.01169997 -0.0110026 -0.0927869 0.01169997 -0.01091808 -0.09254425 0.01169997 -0.01077586 -0.09233015 0.0097 -0.01058495 -0.09215825 0.0097 -0.01077586 -0.09233015 0.01169997 -0.01058495 -0.09215825 0.01169997 -0.01035726 -0.09203928 0.0097 -0.01035726 -0.09203928 0.01169997 -0.0101071 -0.09198057 0.0097 -0.0101071 -0.09198057 0.01169997 -0.009850203 -0.091986 0.01169997 -0.009602785 -0.09205508 0.01169997 -0.00938028 -0.09218358 0.01169997 -0.009196698 -0.09236329 0.01169997 -0.009063601 -0.09258306 0.01169997 -0.009063601 -0.09258306 0.0097 -0.008989334 -0.0928291 0.01169997 -0.008978545 -0.09308576 0.01169997 -0.009032011 -0.09333705 0.0097 -0.009032011 -0.09333705 0.01169997 -0.009146213 -0.09356719 0.0097 -0.009146213 -0.09356719 0.01169997 -0.00952512 -0.09390836 0.0097 -0.009314119 -0.09376168 0.01169997 -0.00952512 -0.09390836 0.01169997 -0.009765923 -0.09399789 0.01169997 -0.01002144 -0.09402477 0.01169997 -0.01002144 -0.09402477 0.0097 -0.0102756 -0.09398716 0.01169997 -0.009765923 -0.09399789 0.0097 -0.0102756 -0.09398716 0.0097 -0.01097077 -0.09108167 0.0097 -0.01136678 -0.09465956 0.0097 -0.01005917 -0.09514915 0.0097 -0.01075387 -0.09501349 0.0097 -0.01051247 -0.09388768 0.0097 -0.01064175 -0.09094798 0.0097 -0.01029527 -0.09087038 0.0097 -0.009850203 -0.091986 0.0097 -0.009587764 -0.09088987 0.0097 -0.01176679 -0.09177488 0.0097 -0.008008003 -0.09219086 0.0097 -0.0110026 -0.0927869 0.0097 -0.01091808 -0.09254425 0.0097 -0.01183158 -0.09412586 0.0097 -0.01087665 -0.09353095 0.0097 -0.01209795 -0.09347015 0.0097 -0.00902915 -0.09491831 0.0097 -0.009704649 -0.0951296 0.0097 -0.008055627 -0.0939176 0.0097 -0.009314119 -0.09376168 0.0097 -0.008233129 -0.0942251 0.0097 -0.008458912 -0.09449917 0.0097 -0.008726656 -0.0947324 0.0097 -0.008989334 -0.0928291 0.0097 -0.007853209 -0.09288156 0.0097 -0.008978545 -0.09308576 0.0097 -0.007863044 -0.0932365 0.0097 -0.009602785 -0.09205508 0.0097 -0.00938028 -0.09218358 0.0097 -0.008924961 -0.091138 0.0097 -0.009196698 -0.09236329 0.0097 -0.008378624 -0.09158796 0.0097 -0.008168339 -0.09187406 0.0097 -0.00879997 -0.09092146 0.009949982 -0.00847423 -0.09114736 0.01069998 -0.00847423 -0.09114736 0.009949982 -0.008190095 -0.0914238 0.01069998 -0.007955372 -0.09174317 0.01069998 -0.007955372 -0.09174317 0.009949982 -0.007776379 -0.09209686 0.009949982 -0.007776379 -0.09209686 0.01069998 -0.007658064 -0.09247517 0.01069998 -0.007603585 -0.09286779 0.01069998 -0.007614552 -0.09326398 0.01069998 -0.007690548 -0.09365296 0.009949982 -0.007690548 -0.09365296 0.01069998 -0.007829487 -0.0940243 0.01069998 -0.007829487 -0.0940243 0.009949982 -0.008027672 -0.0943675 0.01069998 -0.008279681 -0.09467345 0.01069998 -0.008027672 -0.0943675 0.009949982 -0.008279681 -0.09467345 0.009949982 -0.008578598 -0.0949338 0.01069998 -0.008578598 -0.0949338 0.009949982 -0.008916318 -0.09514141 0.009949982 -0.008916318 -0.09514141 0.01069998 -0.009283542 -0.0952906 0.01069998 -0.009670317 -0.09537726 0.01069998 -0.01006609 -0.09539908 0.009949982 -0.01006609 -0.09539908 0.01069998 -0.01046007 -0.09535551 0.01069998 -0.01046007 -0.09535551 0.009949982 -0.01084148 -0.09524756 0.01069998 -0.01119995 -0.09507846 0.01069998 -0.01119995 -0.09507846 0.009949982 -0.01152569 -0.09485256 0.01069998 -0.01180988 -0.09457617 0.01069998 -0.01204454 -0.09425675 0.01069998 -0.01180988 -0.09457617 0.009949982 -0.0122236 -0.09390306 0.01069998 -0.0122236 -0.09390306 0.009949982 -0.01234185 -0.09352475 0.01069998 -0.01239639 -0.09313219 0.009949982 -0.01239639 -0.09313219 0.01069998 -0.01238536 -0.092736 0.01069998 -0.01230937 -0.09234696 0.01069998 -0.01217049 -0.09197568 0.01069998 -0.01217049 -0.09197568 0.009949982 -0.01197224 -0.09163248 0.01069998 -0.01172029 -0.09132647 0.01069998 -0.01142138 -0.09106618 0.01069998 -0.01172029 -0.09132647 0.009949982 -0.01142138 -0.09106618 0.009949982 -0.01108366 -0.09085857 0.01069998 -0.01108366 -0.09085857 0.009949982 -0.01071637 -0.09070938 0.01069998 -0.0103296 -0.09062266 0.009949982 -0.0103296 -0.09062266 0.01069998 -0.009933829 -0.0906009 0.01069998 -0.009933829 -0.0906009 0.009949982 -0.009539842 -0.09064447 0.01069998 -0.009158432 -0.09075236 0.01069998 -0.00879997 -0.09092146 0.01069998 -0.009158432 -0.09075236 0.009949982 -0.009539842 -0.09064447 0.009949982 -0.00924611 -0.09098649 0.0097 -0.009940743 -0.09085077 0.0097 -0.01071637 -0.09070938 0.009949982 -0.01127326 -0.09126758 0.0097 -0.01197224 -0.09163248 0.009949982 -0.01154106 -0.09150075 0.0097 -0.01194435 -0.09208238 0.0097 -0.01230937 -0.09234696 0.009949982 -0.01206886 -0.09241497 0.0097 -0.01238536 -0.092736 0.009949982 -0.01213699 -0.09276348 0.0097 -0.01214665 -0.09311836 0.0097 -0.01234185 -0.09352475 0.009949982 -0.01199197 -0.09380906 0.0097 -0.01204454 -0.09425675 0.009949982 -0.01162129 -0.09441196 0.0097 -0.01152569 -0.09485256 0.009949982 -0.01084148 -0.09524756 0.009949982 -0.01107496 -0.09486198 0.0097 -0.01041215 -0.09511005 0.0097 -0.009670317 -0.09537726 0.009949982 -0.009283542 -0.0952906 0.009949982 -0.009358167 -0.095052 0.0097 -0.007931113 -0.09358495 0.0097 -0.007614552 -0.09326398 0.009949982 -0.007603585 -0.09286779 0.009949982 -0.007658064 -0.09247517 0.009949982 -0.007902026 -0.09252977 0.0097 -0.008190095 -0.0914238 0.009949982 -0.008633136 -0.09134036 0.0097 -0.08517688 -0.03879809 0.0097 -0.08541679 -0.03885728 0.0097 -0.08501255 -0.03992396 0.0097 -0.08408415 -0.03942155 0.0097 -0.08436435 -0.03963965 0.0097 -0.08467668 -0.03980869 0.0097 -0.08606815 -0.03575545 0.0097 -0.08566385 -0.03682219 0.0097 -0.08571785 -0.0356971 0.0097 -0.08757388 -0.03714156 0.0097 -0.08644795 -0.03736335 0.0097 -0.08653557 -0.03808498 0.0097 -0.08766096 -0.03819358 0.0097 -0.08769035 -0.03783965 0.0097 -0.08766096 -0.03748589 0.0097 -0.08653557 -0.03759437 0.0097 -0.08699649 -0.03942155 0.0097 -0.087237 -0.03916025 0.0097 -0.08644795 -0.03831607 0.0097 -0.08743119 -0.038863 0.0097 -0.08757388 -0.0385378 0.0097 -0.08536279 -0.03998237 0.0097 -0.08571785 -0.03998237 0.0097 -0.08606815 -0.03992396 0.0097 -0.08640396 -0.03980869 0.0097 -0.08612257 -0.03868329 0.0097 -0.08671629 -0.03963965 0.0097 -0.08341968 -0.03748589 0.0097 -0.08743119 -0.03681647 0.0097 -0.087237 -0.03651916 0.0097 -0.08630758 -0.03715997 0.0097 -0.08699649 -0.03625786 0.0097 -0.08612257 -0.03699618 0.0097 -0.08671629 -0.03603976 0.0097 -0.08640396 -0.03587079 0.0097 -0.08590376 -0.03688138 0.0097 -0.08339035 -0.03783965 0.0097 -0.08341968 -0.03819358 0.0097 -0.08350688 -0.0385378 0.0097 -0.08463275 -0.03831607 0.0097 -0.08364945 -0.038863 0.0097 -0.0838437 -0.03916025 0.0097 -0.08408415 -0.03625786 0.0097 -0.08477306 -0.03715997 0.0097 -0.0838437 -0.03651916 0.0097 -0.08364945 -0.03681647 0.0097 -0.08350688 -0.03714156 0.0097 -0.08536279 -0.0356971 0.0097 -0.08541679 -0.03682219 0.0097 -0.08517688 -0.03688138 0.0097 -0.08501255 -0.03575545 0.0097 -0.08467668 -0.03587079 0.0097 -0.08436435 -0.03603976 0.0097 -0.08656537 -0.03783965 0.0097 -0.08656537 -0.03783965 0.01169997 -0.08653557 -0.03759437 0.01169997 -0.08644795 -0.03736335 0.01169997 -0.08630758 -0.03715997 0.01169997 -0.08612257 -0.03699618 0.01169997 -0.08590376 -0.03688138 0.01169997 -0.08566385 -0.03682219 0.01169997 -0.08541679 -0.03682219 0.01169997 -0.08495807 -0.03699618 0.0097 -0.08517688 -0.03688138 0.01169997 -0.08495807 -0.03699618 0.01169997 -0.08477306 -0.03715997 0.01169997 -0.08463275 -0.03736335 0.0097 -0.08463275 -0.03736335 0.01169997 -0.08454519 -0.03759437 0.0097 -0.08454519 -0.03759437 0.01169997 -0.08451539 -0.03783965 0.0097 -0.08451539 -0.03783965 0.01169997 -0.08454519 -0.03808498 0.0097 -0.08454519 -0.03808498 0.01169997 -0.08463275 -0.03831607 0.01169997 -0.08477306 -0.03851938 0.0097 -0.08495807 -0.03868329 0.0097 -0.08477306 -0.03851938 0.01169997 -0.08495807 -0.03868329 0.01169997 -0.08517688 -0.03879809 0.01169997 -0.08541679 -0.03885728 0.01169997 -0.08566385 -0.03885728 0.01169997 -0.08566385 -0.03885728 0.0097 -0.08590376 -0.03879809 0.0097 -0.08590376 -0.03879809 0.01169997 -0.08612257 -0.03868329 0.01169997 -0.08630758 -0.03851938 0.0097 -0.08630758 -0.03851938 0.01169997 -0.08644795 -0.03831607 0.01169997 -0.08653557 -0.03808498 0.01169997 -0.08794039 -0.03783965 0.01069998 -0.08793258 -0.03764659 0.009949982 -0.08793258 -0.03764659 0.01069998 -0.08787059 -0.03726536 0.009949982 -0.08787059 -0.03726536 0.01069998 -0.08774828 -0.03689897 0.009949982 -0.08774828 -0.03689897 0.01069998 -0.08756875 -0.03655695 0.01069998 -0.08756875 -0.03655695 0.009949982 -0.08733677 -0.03624826 0.01069998 -0.08733677 -0.03624826 0.009949982 -0.08705818 -0.0359807 0.01069998 -0.08674037 -0.03576129 0.01069998 -0.08705818 -0.0359807 0.009949982 -0.08639138 -0.03559565 0.01069998 -0.08674037 -0.03576129 0.009949982 -0.08639138 -0.03559565 0.009949982 -0.08602041 -0.03548818 0.009949982 -0.08602041 -0.03548818 0.01069998 -0.08563697 -0.03544169 0.01069998 -0.08563697 -0.03544169 0.009949982 -0.08525109 -0.03545719 0.01069998 -0.08525109 -0.03545719 0.009949982 -0.0848726 -0.0355345 0.01069998 -0.08451145 -0.03567147 0.01069998 -0.0848726 -0.0355345 0.009949982 -0.08451145 -0.03567147 0.009949982 -0.08417695 -0.03586459 0.01069998 -0.08417695 -0.03586459 0.009949982 -0.0838778 -0.03610885 0.01069998 -0.08362168 -0.03639799 0.01069998 -0.0838778 -0.03610885 0.009949982 -0.08362168 -0.03639799 0.009949982 -0.08341526 -0.03672438 0.01069998 -0.08341526 -0.03672438 0.009949982 -0.08326387 -0.03707969 0.01069998 -0.08326387 -0.03707969 0.009949982 -0.08317136 -0.03745478 0.009949982 -0.08317136 -0.03745478 0.01069998 -0.08314037 -0.03783965 0.01069998 -0.08314037 -0.03783965 0.009949982 -0.08317136 -0.03822469 0.009949982 -0.08317136 -0.03822469 0.01069998 -0.08326387 -0.03859966 0.009949982 -0.08326387 -0.03859966 0.01069998 -0.08341526 -0.03895509 0.01069998 -0.08341526 -0.03895509 0.009949982 -0.08362168 -0.03928148 0.01069998 -0.0838778 -0.03957056 0.01069998 -0.08362168 -0.03928148 0.009949982 -0.0838778 -0.03957056 0.009949982 -0.08417695 -0.03981488 0.01069998 -0.08417695 -0.03981488 0.009949982 -0.08451145 -0.04000794 0.01069998 -0.0848726 -0.04014497 0.01069998 -0.08451145 -0.04000794 0.009949982 -0.0848726 -0.04014497 0.009949982 -0.08525109 -0.04022216 0.01069998 -0.08525109 -0.04022216 0.009949982 -0.08563697 -0.04023778 0.01069998 -0.08563697 -0.04023778 0.009949982 -0.08602041 -0.04019117 0.01069998 -0.08602041 -0.04019117 0.009949982 -0.08639138 -0.04008376 0.01069998 -0.08639138 -0.04008376 0.009949982 -0.08674037 -0.03991818 0.01069998 -0.08674037 -0.03991818 0.009949982 -0.08705818 -0.03969877 0.01069998 -0.08733677 -0.03943115 0.01069998 -0.08705818 -0.03969877 0.009949982 -0.08733677 -0.03943115 0.009949982 -0.08756875 -0.03912246 0.01069998 -0.08774828 -0.03878045 0.01069998 -0.08756875 -0.03912246 0.009949982 -0.08774828 -0.03878045 0.009949982 -0.08787059 -0.03841406 0.01069998 -0.08787059 -0.03841406 0.009949982 -0.08793258 -0.03803288 0.009949982 -0.08793258 -0.03803288 0.01069998 -0.08794039 -0.03783965 0.009949982 -0.07762789 0.05464565 0.0097 -0.07655841 0.05504125 0.0097 -0.07768338 0.05498725 0.0097 -0.07350099 0.05447936 0.0097 -0.07462435 0.05470019 0.0097 -0.07363659 0.05416107 0.0097 -0.07513439 0.05421906 0.0097 -0.07494217 0.0530951 0.0097 -0.0752812 0.0530259 0.0097 -0.07536238 0.05415076 0.0097 -0.07559996 0.05413699 0.0097 -0.0738216 0.05645179 0.0097 -0.07475519 0.05581909 0.0097 -0.0763967 0.05459696 0.0097 -0.07714968 0.05373448 0.0097 -0.07735747 0.05401116 0.0097 -0.07650345 0.05480968 0.0097 -0.07751828 0.05431747 0.0097 -0.0738216 0.05386865 0.0097 -0.07475519 0.05450135 0.0097 -0.07405096 0.05360966 0.0097 -0.07492828 0.05433809 0.0097 -0.074319 0.0533908 0.0097 -0.07461869 0.05321776 0.0097 -0.07462435 0.05562025 0.0097 -0.07363659 0.05615937 0.0097 -0.07350099 0.05584108 0.0097 -0.0734182 0.05550509 0.0097 -0.07454299 0.05539655 0.0097 -0.0745154 0.05516028 0.0097 -0.07339036 0.05516028 0.0097 -0.07454299 0.05492389 0.0097 -0.0734182 0.05481535 0.0097 -0.07494217 0.0572254 0.0097 -0.07513439 0.05610138 0.0097 -0.07461869 0.05710268 0.0097 -0.074319 0.05692964 0.0097 -0.07492828 0.05598235 0.0097 -0.07405096 0.05671077 0.0097 -0.0763967 0.05572348 0.0097 -0.07624375 0.05590575 0.0097 -0.07714968 0.05658596 0.0097 -0.07690006 0.05682569 0.0097 -0.0760529 0.05604785 0.0097 -0.07661539 0.05702215 0.0097 -0.07768338 0.05533325 0.0097 -0.07762789 0.05567479 0.0097 -0.07655841 0.05527919 0.0097 -0.07650345 0.05551075 0.0097 -0.07751828 0.05600297 0.0097 -0.07735747 0.0563094 0.0097 -0.0756269 0.05301195 0.0097 -0.07583427 0.05417829 0.0097 -0.07597041 0.05305367 0.0097 -0.07630276 0.05314999 0.0097 -0.0760529 0.05427259 0.0097 -0.07661539 0.05329829 0.0097 -0.07624375 0.05441468 0.0097 -0.07690006 0.05349487 0.0097 -0.07583427 0.05614215 0.0097 -0.07630276 0.05717045 0.0097 -0.07597041 0.05726677 0.0097 -0.07559996 0.05618345 0.0097 -0.0756269 0.05730849 0.0097 -0.07536238 0.05616968 0.0097 -0.0752812 0.05729454 0.0097 0.05808657 -0.05414825 0.0097 0.05789285 -0.0530194 0.0097 0.05774074 -0.05413424 0.0097 0.0558778 -0.05165505 0.0097 0.05701869 -0.05170369 0.0097 0.05596059 -0.05131918 0.0097 0.05764269 -0.05296069 0.0097 0.0570783 -0.05394238 0.0097 0.05741494 -0.05284166 0.0097 0.05861967 -0.05281639 0.0097 0.05907499 -0.05386197 0.0097 0.05839717 -0.05294489 0.0097 0.05814969 -0.05301398 0.0097 0.05843007 -0.05410647 0.0097 0.05893635 -0.05241686 0.0097 0.05880326 -0.05263668 0.0097 0.05960929 -0.05342566 0.0097 0.05935978 -0.05366539 0.0097 0.05901056 -0.05217087 0.0097 0.0600875 -0.05251449 0.0097 0.05997794 -0.05284267 0.0097 0.05748748 -0.05111229 0.0097 0.0571233 -0.05146896 0.0097 0.0572828 -0.05126768 0.0097 0.05596059 -0.05268079 0.0097 0.05699735 -0.05221307 0.0097 0.0558778 -0.05234485 0.0097 0.05584996 -0.05199998 0.0097 0.0569759 -0.05195707 0.0097 0.06014299 -0.05182695 0.0097 0.05902135 -0.05191415 0.0097 0.06014299 -0.05217295 0.0097 0.05823409 -0.05100208 0.0097 0.05847489 -0.05109155 0.0097 0.05774074 -0.04986566 0.0097 0.05797845 -0.0509752 0.0097 0.05808657 -0.04985165 0.0097 0.05843007 -0.04989337 0.0097 0.05651056 -0.0535506 0.0097 0.05628114 -0.05329155 0.0097 0.05722409 -0.05266976 0.0097 0.05708187 -0.05245566 0.0097 0.05868589 -0.05123829 0.0097 0.05960929 -0.0505743 0.0097 0.05885368 -0.05143278 0.0097 0.05981719 -0.05085086 0.0097 0.05896794 -0.05166286 0.0097 0.0600875 -0.05148547 0.0097 0.05677866 -0.05023056 0.0097 0.05692499 -0.05013799 0.0097 0.0570783 -0.05005759 0.0097 0.05772435 -0.05101275 0.0097 0.05740177 -0.04993486 0.0097 0.05679994 -0.04992145 0.01069998 0.05697107 -0.04983168 0.01069998 0.05697107 -0.04983168 0.009949982 0.05733227 -0.04969477 0.01069998 0.05733227 -0.04969477 0.009949982 0.05771064 -0.04961746 0.01069998 0.05809658 -0.04960185 0.01069998 0.05848008 -0.04964846 0.01069998 0.05848008 -0.04964846 0.009949982 0.05885106 -0.04975599 0.01069998 0.05919998 -0.04992145 0.01069998 0.05919998 -0.04992145 0.009949982 0.05951786 -0.05014085 0.01069998 0.05951786 -0.05014085 0.009949982 0.05979639 -0.05040848 0.01069998 0.06002849 -0.05071729 0.01069998 0.06020796 -0.0510593 0.01069998 0.06002849 -0.05071729 0.009949982 0.06020796 -0.0510593 0.009949982 0.06033027 -0.05142557 0.01069998 0.0603922 -0.05180686 0.01069998 0.06033027 -0.05142557 0.009949982 0.0603922 -0.05180686 0.009949982 0.0603922 -0.0521931 0.01069998 0.0603922 -0.0521931 0.009949982 0.06033027 -0.05257439 0.01069998 0.06020796 -0.05294066 0.01069998 0.06020796 -0.05294066 0.009949982 0.06002849 -0.05328267 0.01069998 0.05979639 -0.05359148 0.01069998 0.05979639 -0.05359148 0.009949982 0.05951786 -0.05385905 0.01069998 0.05919998 -0.05407845 0.01069998 0.05919998 -0.05407845 0.009949982 0.05885106 -0.05424398 0.01069998 0.05848008 -0.05435144 0.01069998 0.05809658 -0.05439805 0.01069998 0.05771064 -0.0543825 0.01069998 0.05733227 -0.05430519 0.01069998 0.05733227 -0.05430519 0.009949982 0.05697107 -0.05416828 0.01069998 0.05663657 -0.05397516 0.01069998 0.05663657 -0.05397516 0.009949982 0.05633747 -0.0537309 0.01069998 0.05633747 -0.0537309 0.009949982 0.05608129 -0.05344176 0.01069998 0.05608129 -0.05344176 0.009949982 0.05587488 -0.05311524 0.01069998 0.05587488 -0.05311524 0.009949982 0.05572348 -0.05275994 0.009949982 0.05572348 -0.05275994 0.01069998 0.0556311 -0.05238497 0.01069998 0.0556311 -0.05238497 0.009949982 0.05559998 -0.05199998 0.01069998 0.05559998 -0.05199998 0.009949982 0.0556311 -0.05161499 0.01069998 0.05572348 -0.05123996 0.01069998 0.05587488 -0.05088466 0.009949982 0.05587488 -0.05088466 0.01069998 0.05608129 -0.05055814 0.01069998 0.05633747 -0.05026906 0.01069998 0.05633747 -0.05026906 0.009949982 0.05663657 -0.05002474 0.01069998 0.05679994 -0.04992145 0.009949982 0.06002849 -0.05328267 0.009949982 0.05981719 -0.0531491 0.0097 0.06033027 -0.05257439 0.009949982 0.05997794 -0.05115729 0.0097 0.05979639 -0.05040848 0.009949982 0.05935978 -0.05033457 0.0097 0.05907499 -0.05013799 0.0097 0.05885106 -0.04975599 0.009949982 0.05876237 -0.0499897 0.0097 0.05809658 -0.04960185 0.009949982 0.05771064 -0.04961746 0.009949982 0.05663657 -0.05002474 0.009949982 0.05651056 -0.05044937 0.0097 0.05608129 -0.05055814 0.009949982 0.05628114 -0.05070835 0.0097 0.05572348 -0.05123996 0.009949982 0.05609625 -0.05100077 0.0097 0.0556311 -0.05161499 0.009949982 0.05609625 -0.05299919 0.0097 0.05697107 -0.05416828 0.009949982 0.05677866 -0.05376935 0.0097 0.05771064 -0.0543825 0.009949982 0.05740177 -0.05406504 0.0097 0.05809658 -0.05439805 0.009949982 0.05848008 -0.05435144 0.009949982 0.05885106 -0.05424398 0.009949982 0.05876237 -0.05401027 0.0097 0.05951786 -0.05385905 0.009949982 -0.002999961 -0.09689998 0.02029997 -0.01037275 -0.09597676 0.02029997 -0.002999961 -0.09689998 0.01909995 -0.01037275 -0.09597676 0.01909995 -0.01037275 -0.09002315 0.01909995 -0.01120626 -0.09025317 0.01909995 -0.01120626 -0.09025317 0.02029997 -0.0119397 -0.09071135 0.01909995 -0.01251184 -0.09135967 0.01909995 -0.01251184 -0.09135967 0.02029997 -0.01287537 -0.09214431 0.01909995 -0.01299995 -0.09299999 0.01909995 -0.01299995 -0.09299999 0.02029997 -0.01287537 -0.09385567 0.01909995 -0.01251184 -0.09464025 0.01909995 -0.01251184 -0.09464025 0.02029997 -0.0119397 -0.09528857 0.02029997 -0.0119397 -0.09528857 0.01909995 -0.01120626 -0.09574675 0.01909995 0.01037275 -0.09597676 0.02029997 0.01037275 -0.09597676 0.01909995 0.002999961 -0.09689998 0.01909995 0.009721815 -0.09178125 0.02029997 0.01027816 -0.09178125 0.02029997 0.01120626 -0.09025317 0.02029997 0.01077938 -0.09202265 0.02029997 0.0119397 -0.09071135 0.02029997 -0.00887376 -0.09354239 0.02029997 -0.0092206 -0.09397727 0.02029997 0.01251184 -0.09135967 0.02029997 0.01112616 -0.09245759 0.02029997 0.01287537 -0.09214431 0.02029997 0.01299995 -0.09299999 0.02029997 0.01124995 -0.09299999 0.02029997 0.01287537 -0.09385567 0.02029997 0.01037275 -0.09002315 0.02029997 0.002999961 -0.0891 0.02029997 0.0092206 -0.09202265 0.02029997 -0.009721815 -0.09421867 0.02029997 -0.01027816 -0.09421867 0.02029997 -0.01077938 -0.09397727 0.02029997 -0.01077938 -0.09202265 0.02029997 -0.01027816 -0.09178125 0.02029997 -0.01037275 -0.09002315 0.02029997 -0.009721815 -0.09178125 0.02029997 0.01251184 -0.09464025 0.02029997 0.01112616 -0.09354239 0.02029997 0.0119397 -0.09528857 0.02029997 0.01120626 -0.09574675 0.02029997 0.01077938 -0.09397727 0.02029997 0.01027816 -0.09421867 0.02029997 0.009721815 -0.09421867 0.02029997 -0.01287537 -0.09385567 0.02029997 -0.01112616 -0.09354239 0.02029997 -0.01120626 -0.09574675 0.02029997 -0.0092206 -0.09202265 0.02029997 -0.002999961 -0.0891 0.02029997 -0.00887376 -0.09245759 0.02029997 -0.008749961 -0.09299999 0.02029997 0.00887376 -0.09245759 0.02029997 0.0092206 -0.09397727 0.02029997 0.002999961 -0.09689998 0.02029997 0.00887376 -0.09354239 0.02029997 0.008749961 -0.09299999 0.02029997 -0.0119397 -0.09071135 0.02029997 -0.01112616 -0.09245759 0.02029997 -0.01287537 -0.09214431 0.02029997 -0.01124995 -0.09299999 0.02029997 -0.07508367 -0.05399668 0.02029997 -0.074624 -0.05430996 0.02029997 -0.07277595 -0.05399465 0.02029997 -0.07434588 -0.05479174 0.02029997 -0.0725584 -0.05483156 0.02029997 -0.07450759 -0.05586439 0.02029997 -0.07286387 -0.05651545 0.02029997 -0.0725885 -0.05569577 0.02029997 -0.07430428 -0.05534654 0.02029997 -0.08616536 -0.03675717 0.02029997 -0.08657318 -0.0371356 0.02029997 -0.08677637 -0.03765338 0.02029997 -0.08821678 -0.03648447 0.02029997 -0.08849215 -0.03730416 0.02029997 -0.08852225 -0.03816837 0.02029997 -0.08563375 -0.03659319 0.02029997 -0.08704036 -0.03524166 0.02029997 -0.08771908 -0.03577739 0.02029997 -0.08430427 -0.03802597 0.02029997 -0.08434587 -0.03747129 0.02029997 -0.08314877 -0.0360285 0.02029997 -0.08462399 -0.03698945 0.02029997 -0.08376479 -0.03542155 0.02029997 -0.08508366 -0.03667616 0.02029997 -0.0845282 -0.03501558 0.02029997 -0.08537578 -0.03484427 0.02029997 -0.08623695 -0.03492176 0.02029997 -0.08599698 -0.03900325 0.02029997 -0.08830469 -0.03900527 0.02029997 -0.08645665 -0.03868997 0.02029997 -0.08673477 -0.03820818 0.02029997 -0.07677638 -0.05497395 0.02029997 -0.0824179 -0.05104809 0.02029997 -0.07673478 -0.0555287 0.02029997 -0.07793188 -0.05697137 0.02029997 -0.07731598 -0.05757838 0.02029997 -0.07645666 -0.05601048 0.02029997 -0.07655251 -0.05798435 0.02029997 -0.07599699 -0.05632376 0.02029997 -0.07570487 -0.05815565 0.02029997 -0.0748437 -0.05807816 0.02029997 -0.0754469 -0.05640679 0.02029997 -0.0749154 -0.05624276 0.02029997 -0.07404035 -0.05775827 0.02029997 -0.07336157 -0.0572226 0.02029997 -0.07616537 -0.05407768 0.02029997 -0.07563376 -0.05391365 0.02029997 -0.07566291 -0.04714804 0.02029997 -0.08491539 -0.03892225 0.02029997 -0.08541786 -0.04585188 0.02029997 -0.08544689 -0.03908628 0.02029997 -0.08450758 -0.03854387 0.02029997 -0.07866287 -0.04195189 0.02029997 -0.07657319 -0.05445605 0.02029997 -0.07277595 0.05399465 0.02029997 -0.07277595 0.05399465 0.01909995 -0.0726369 0.05440527 0.01909995 -0.0726369 0.05440527 0.02029997 -0.0725584 0.05483156 0.01909995 -0.07254219 0.05526477 0.01909995 -0.0725584 0.05483156 0.02029997 -0.07254219 0.05526477 0.02029997 -0.0725885 0.05569577 0.01909995 -0.0725885 0.05569577 0.02029997 -0.0726965 0.05611556 0.01909995 -0.0726965 0.05611556 0.02029997 -0.07286387 0.05651545 0.02029997 -0.07286387 0.05651545 0.01909995 -0.07308715 0.05688697 0.01909995 -0.07308715 0.05688697 0.02029997 -0.07336157 0.0572226 0.01909995 -0.07336157 0.0572226 0.02029997 -0.07368159 0.05751496 0.01909995 -0.07404035 0.05775827 0.01909995 -0.07368159 0.05751496 0.02029997 -0.07404035 0.05775827 0.02029997 -0.07443046 0.05794739 0.01909995 -0.0748437 0.05807816 0.01909995 -0.07443046 0.05794739 0.02029997 -0.0748437 0.05807816 0.02029997 -0.07527148 0.0581482 0.01909995 -0.07527148 0.0581482 0.02029997 -0.07570487 0.05815565 0.01909995 -0.07570487 0.05815565 0.02029997 -0.07613486 0.0581007 0.01909995 -0.07655251 0.05798435 0.01909995 -0.07613486 0.0581007 0.02029997 -0.07655251 0.05798435 0.02029997 -0.07694888 0.05780899 0.02029997 -0.07694888 0.05780899 0.01909995 -0.07731598 0.05757838 0.01909995 -0.07731598 0.05757838 0.02029997 -0.07764589 0.05729717 0.01909995 -0.07764589 0.05729717 0.02029997 -0.07793188 0.05697137 0.01909995 -0.07793188 0.05697137 0.02029997 -0.08830469 0.03900527 0.02029997 -0.08830469 0.03900527 0.01909995 -0.08541786 0.04585188 0.02029997 -0.08541786 0.04585188 0.01909995 0.002999961 0.09689998 0.01909995 0.01037275 0.09597676 0.02029997 0.01037275 0.09597676 0.01909995 -0.01037275 0.09597676 0.02029997 -0.01037275 0.09597676 0.01909995 -0.002999961 0.09689998 0.01909995 -0.01112616 0.09245759 0.02029997 -0.01287537 0.09214431 0.02029997 -0.01251184 0.09135967 0.02029997 -0.01077938 0.09202265 0.02029997 0.01027816 0.09421867 0.02029997 0.01077938 0.09397727 0.02029997 -0.01112616 0.09354239 0.02029997 -0.01124995 0.09299999 0.02029997 -0.01287537 0.09385567 0.02029997 -0.01299995 0.09299999 0.02029997 -0.002999961 0.09689998 0.02029997 -0.009721815 0.09421867 0.02029997 -0.01027816 0.09421867 0.02029997 -0.01120626 0.09574675 0.02029997 -0.01077938 0.09397727 0.02029997 -0.0119397 0.09528857 0.02029997 -0.01251184 0.09464025 0.02029997 0.01112616 0.09354239 0.02029997 0.01287537 0.09385567 0.02029997 0.01251184 0.09464025 0.02029997 0.0119397 0.09528857 0.02029997 0.01120626 0.09574675 0.02029997 0.01124995 0.09299999 0.02029997 0.01287537 0.09214431 0.02029997 0.01299995 0.09299999 0.02029997 0.0092206 0.09202265 0.02029997 0.009721815 0.09178125 0.02029997 0.01037275 0.09002315 0.02029997 0.01027816 0.09178125 0.02029997 0.01120626 0.09025317 0.02029997 0.01077938 0.09202265 0.02029997 0.01112616 0.09245759 0.02029997 0.0092206 0.09397727 0.02029997 0.009721815 0.09421867 0.02029997 -0.0119397 0.09071135 0.02029997 -0.01027816 0.09178125 0.02029997 -0.01120626 0.09025317 0.02029997 -0.009721815 0.09178125 0.02029997 -0.01037275 0.09002315 0.02029997 -0.0092206 0.09202265 0.02029997 -0.008749961 0.09299999 0.02029997 -0.002999961 0.0891 0.02029997 -0.00887376 0.09245759 0.02029997 0.008749961 0.09299999 0.02029997 0.002999961 0.09689998 0.02029997 0.00887376 0.09354239 0.02029997 0.00887376 0.09245759 0.02029997 0.002999961 0.0891 0.02029997 -0.00887376 0.09354239 0.02029997 -0.0092206 0.09397727 0.02029997 0.08541786 0.04585188 0.01909995 0.08830469 0.03900527 0.01909995 0.08434587 0.03747129 0.02029997 0.08430427 0.03802597 0.02029997 0.08450758 0.03854387 0.02029997 0.08599698 0.03900325 0.02029997 0.0754469 0.05640679 0.02029997 0.07570487 0.05815565 0.02029997 0.08830469 0.03900527 0.02029997 0.08645665 0.03868997 0.02029997 0.08673477 0.03820818 0.02029997 0.08677637 0.03765338 0.02029997 0.08852225 0.03816837 0.02029997 0.08849215 0.03730416 0.02029997 0.08821678 0.03648447 0.02029997 0.08657318 0.0371356 0.02029997 0.08771908 0.03577739 0.02029997 0.07434588 0.05479174 0.02029997 0.07566291 0.04714804 0.02029997 0.07277595 0.05399465 0.02029997 0.07508367 0.05399668 0.02029997 0.074624 0.05430996 0.02029997 0.0748437 0.05807816 0.02029997 0.07404035 0.05775827 0.02029997 0.0749154 0.05624276 0.02029997 0.07336157 0.0572226 0.02029997 0.07450759 0.05586439 0.02029997 0.07286387 0.05651545 0.02029997 0.07430428 0.05534654 0.02029997 0.0725885 0.05569577 0.02029997 0.0725584 0.05483156 0.02029997 0.07655251 0.05798435 0.02029997 0.07599699 0.05632376 0.02029997 0.07645666 0.05601048 0.02029997 0.07731598 0.05757838 0.02029997 0.07793188 0.05697137 0.02029997 0.07673478 0.0555287 0.02029997 0.07677638 0.05497395 0.02029997 0.07657319 0.05445605 0.02029997 0.07616537 0.05407768 0.02029997 0.0824179 0.05104809 0.02029997 0.08491539 0.03892225 0.02029997 0.08541786 0.04585188 0.02029997 0.08544689 0.03908628 0.02029997 0.08704036 0.03524166 0.02029997 0.08616536 0.03675717 0.02029997 0.08563375 0.03659319 0.02029997 0.08623695 0.03492176 0.02029997 0.08537578 0.03484427 0.02029997 0.0845282 0.03501558 0.02029997 0.08508366 0.03667616 0.02029997 0.08462399 0.03698945 0.02029997 0.08376479 0.03542155 0.02029997 0.08314877 0.0360285 0.02029997 0.07866287 0.04195189 0.02029997 0.07563376 0.05391365 0.02029997 0.185846 0.112409 0.02884995 0.185145 0.11217 0.02884995 0.185145 0.11217 0.02824997 0.184492 0.111822 0.02824997 0.183903 0.111374 0.02824997 0.184492 0.111822 0.02884995 0.183903 0.111374 0.02884995 0.183393 0.110837 0.02824997 0.183393 0.110837 0.02884995 0.182977 0.110225 0.02884995 0.182977 0.110225 0.02824997 0.182664 0.109554 0.02824997 0.182664 0.109554 0.02884995 0.182462 0.108842 0.02824997 0.1823779 0.108106 0.02824997 0.182462 0.108842 0.02884995 0.1823779 0.108106 0.02884995 0.182412 0.107367 0.02824997 0.182412 0.107367 0.02884995 0.182565 0.106642 0.02824997 0.182832 0.105952 0.02824997 0.182565 0.106642 0.02884995 0.182832 0.105952 0.02884995 0.183206 0.105313 0.02824997 0.183206 0.105313 0.02884995 0.183677 0.104743 0.02824997 0.183677 0.104743 0.02884995 0.184235 0.104255 0.02824997 0.184863 0.103864 0.02824997 0.184235 0.104255 0.02884995 0.184863 0.103864 0.02884995 0.185546 0.103578 0.02824997 0.185546 0.103578 0.02884995 0.186266 0.1034049 0.02824997 0.186266 0.1034049 0.02884995 0.187004 0.10335 0.02824997 0.187004 0.10335 0.02884995 0.187741 0.1034139 0.02824997 0.187741 0.1034139 0.02884995 0.188459 0.103596 0.02824997 0.188459 0.103596 0.02884995 0.1891379 0.10389 0.02824997 0.189761 0.10429 0.02824997 0.1891379 0.10389 0.02884995 0.190312 0.104784 0.02824997 0.189761 0.10429 0.02884995 0.190312 0.104784 0.02884995 0.190777 0.105361 0.02884995 0.190777 0.105361 0.02824997 0.191143 0.1060039 0.02824997 0.191401 0.106698 0.02824997 0.191143 0.1060039 0.02884995 0.191401 0.106698 0.02884995 0.191545 0.107424 0.02824997 0.191545 0.107424 0.02884995 0.19157 0.108164 0.02824997 0.19157 0.108164 0.02884995 0.191476 0.108898 0.02824997 0.191476 0.108898 0.02884995 0.191266 0.109608 0.02884995 0.191266 0.109608 0.02824997 0.190944 0.110275 0.02824997 0.190944 0.110275 0.02884995 0.1905199 0.110882 0.02884995 0.1905199 0.110882 0.02824997 0.190004 0.111412 0.02824997 0.190004 0.111412 0.02884995 0.189409 0.111853 0.02824997 0.188751 0.112193 0.02824997 0.189409 0.111853 0.02884995 0.188751 0.112193 0.02884995 0.188048 0.112423 0.02884995 0.188048 0.112423 0.02824997 0.187316 0.112537 0.02824997 0.187316 0.112537 0.02884995 0.186576 0.112533 0.02884995 0.186576 0.112533 0.02824997 0.185846 0.112409 0.02824997 0.185384 0.11162 0.01739996 0.185384 0.11162 0.02139997 0.18601 0.111832 0.01739996 0.18601 0.111832 0.02139997 0.186662 0.1119379 0.02139997 0.186662 0.1119379 0.01739996 0.187322 0.111935 0.01739996 0.187322 0.111935 0.02139997 0.187974 0.111823 0.02139997 0.187974 0.111823 0.01739996 0.188597 0.111606 0.02139997 0.188597 0.111606 0.01739996 0.189177 0.111289 0.02139997 0.189177 0.111289 0.01739996 0.189697 0.110881 0.01739996 0.189697 0.110881 0.02139997 0.190142 0.110393 0.01739996 0.190142 0.110393 0.02139997 0.190501 0.109839 0.02139997 0.190501 0.109839 0.01739996 0.190764 0.109232 0.01739996 0.190764 0.109232 0.02139997 0.190923 0.108591 0.01739996 0.190923 0.108591 0.02139997 0.190975 0.107933 0.02139997 0.190975 0.107933 0.01739996 0.190917 0.107275 0.02139997 0.190917 0.107275 0.01739996 0.190753 0.106635 0.01739996 0.190753 0.106635 0.02139997 0.190485 0.106031 0.01739996 0.190485 0.106031 0.02139997 0.1901209 0.10548 0.02139997 0.1901209 0.10548 0.01739996 0.189671 0.104995 0.01739996 0.189671 0.104995 0.02139997 0.189148 0.104592 0.01739996 0.189148 0.104592 0.02139997 0.188566 0.1042799 0.01739996 0.188566 0.1042799 0.02139997 0.18794 0.104068 0.01739996 0.18794 0.104068 0.02139997 0.187288 0.103962 0.01739996 0.186627 0.103965 0.01739996 0.187288 0.103962 0.02139997 0.186627 0.103965 0.02139997 0.185976 0.104077 0.01739996 0.185976 0.104077 0.02139997 0.185352 0.104294 0.01739996 0.185352 0.104294 0.02139997 0.184773 0.104611 0.01739996 0.184773 0.104611 0.02139997 0.184253 0.105019 0.02139997 0.184253 0.105019 0.01739996 0.183808 0.105507 0.01739996 0.183808 0.105507 0.02139997 0.183449 0.106061 0.02139997 0.183449 0.106061 0.01739996 0.1831859 0.106668 0.01739996 0.1831859 0.106668 0.02139997 0.183027 0.107309 0.01739996 0.183027 0.107309 0.02139997 0.1829749 0.107967 0.02139997 0.1829749 0.107967 0.01739996 0.183032 0.108625 0.02139997 0.183032 0.108625 0.01739996 0.183197 0.109265 0.01739996 0.183197 0.109265 0.02139997 0.183465 0.109869 0.01739996 0.183465 0.109869 0.02139997 0.183829 0.11042 0.01739996 0.183829 0.11042 0.02139997 0.184278 0.110905 0.01739996 0.184278 0.110905 0.02139997 0.1848019 0.111308 0.02139997 0.1848019 0.111308 0.01739996 0.190963 0.115638 0.01739996 0.19147 0.116041 0.01889997 0.19147 0.116041 0.01739996 0.191708 0.1166419 0.01889997 0.191708 0.1166419 0.01739996 0.1903229 0.115543 0.01739996 0.190963 0.115638 0.01889997 0.189462 0.11753 0.01739996 0.189224 0.116928 0.01739996 0.189319 0.116288 0.01739996 0.189463 0.116108 0.01889997 0.189722 0.115781 0.01739996 0.189722 0.115781 0.01889997 0.191613 0.117282 0.01739996 0.191211 0.117789 0.01739996 0.190609 0.118027 0.01739996 0.190609 0.118027 0.01889997 0.189969 0.117932 0.01739996 0.189969 0.117932 0.01889997 0.1897889 0.117789 0.01889997 0.189224 0.116928 0.01889997 0.184689 0.121476 0.02109998 0.183797 0.1207309 0.02109998 0.180524 0.120056 0.02109998 0.179819 0.119007 0.02109998 0.187851 0.120984 0.02085828 0.187607 0.121546 0.02085858 0.187589 0.121058 0.02099108 0.187348 0.121614 0.02099108 0.188215 0.120912 0.01952677 0.188259 0.121009 0.01975518 0.188509 0.120431 0.01975518 0.18849 0.120546 0.02000707 0.18841 0.120661 0.02024477 0.188021 0.121352 0.0204789 0.188102 0.120877 0.02066057 0.18804 0.120162 0.01903849 0.187943 0.120763 0.01913899 0.188106 0.120827 0.01931416 0.188355 0.120253 0.01931416 0.187228 0.120691 0.01889997 0.187489 0.120695 0.01892679 0.187731 0.120135 0.0189265 0.198973 0.112385 0.01900887 0.199559 0.111837 0.02109998 0.200125 0.111849 0.02109736 0.1999419 0.112274 0.02099108 0.19934 0.112343 0.02099108 0.199651 0.1126919 0.02068579 0.199497 0.112841 0.02048009 0.199037 0.112763 0.02068579 0.198878 0.1129119 0.02047926 0.1993449 0.112941 0.02024477 0.198722 0.113013 0.02024477 0.199213 0.112984 0.020006 0.199019 0.112899 0.01952606 0.198473 0.1130419 0.01975518 0.198969 0.112771 0.01931416 0.198337 0.112667 0.01913875 0.20015 0.111769 0.02109998 0.199975 0.110062 0.02109998 0.200145 0.107893 0.02109998 0.200684 0.107484 0.02109998 0.200432 0.105291 0.02109998 0.199413 0.10362 0.02109998 0.199831 0.1031669 0.02109998 0.19758 0.100396 0.0195263 0.197017 0.10038 0.01975518 0.197642 0.100308 0.01975518 0.197266 0.100352 0.02024477 0.19775 0.100268 0.02000635 0.197888 0.10028 0.02024477 0.198058 0.100343 0.02047848 0.198243 0.100453 0.02068579 0.197629 0.100524 0.02068579 0.197826 0.100675 0.0208593 0.198622 0.100795 0.02099108 0.198347 0.101307 0.02109998 0.1977559 0.101133 0.01892668 0.1971499 0.101202 0.01892656 0.1976529 0.100906 0.01900887 0.197041 0.100977 0.01900887 0.19697 0.100777 0.01913845 0.197587 0.100705 0.01913905 0.175566 0.102186 0.01898735 0.175695 0.102 0.01892137 0.1763769 0.101742 0.01785719 0.175433 0.102343 0.01909875 0.175518 0.103522 0.01785719 0.175301 0.102461 0.01925247 0.175178 0.10253 0.01944005 0.174982 0.102509 0.0198611 0.1740559 0.102957 0.02139997 0.174916 0.10243 0.02007198 0.174847 0.102177 0.02045458 0.174861 0.101833 0.02076917 0.174957 0.101435 0.02099364 0.17751 0.100122 0.01785719 0.178888 0.09870547 0.01785719 0.182232 0.09662038 0.01785719 0.180232 0.09713649 0.01889997 0.180476 0.09752798 0.01785719 0.185259 0.09493488 0.0197677 0.185227 0.0950663 0.01948308 0.184996 0.09467935 0.02042227 0.183745 0.09448188 0.02139997 0.184041 0.09457075 0.02105426 0.184298 0.0945574 0.02096515 0.184753 0.094603 0.0206784 0.185068 0.09521615 0.01919859 0.184755 0.09536468 0.01898097 0.1845549 0.09542858 0.01892119 0.1841109 0.09600627 0.01785719 0.1840029 0.09555757 0.01889997 0.1816779 0.0952968 0.02109998 0.183695 0.09463059 0.02109998 0.183777 0.09461635 0.02108919 0.177943 0.09762549 0.02109998 0.179717 0.09631037 0.02109998 0.179646 0.09619778 0.02139997 0.181626 0.09517437 0.02139997 0.175024 0.10095 0.02139997 0.17514 0.1010169 0.02109736 0.176302 0.09912329 0.02139997 0.175181 0.100945 0.02109998 0.1764039 0.09920787 0.02109998 0.1868979 0.120232 0.01785719 0.187736 0.120719 0.01900887 0.1882399 0.121122 0.02000588 0.188161 0.121236 0.02024477 0.187833 0.121457 0.02068579 0.181199 0.118789 0.01785719 0.18209 0.119219 0.01785719 0.183012 0.119576 0.01785719 0.1828629 0.120012 0.01889997 0.1849279 0.120061 0.01785719 0.184852 0.120516 0.01889997 0.177729 0.11672 0.01889997 0.179535 0.117722 0.01785719 0.1765609 0.115943 0.0197677 0.176472 0.116299 0.02042227 0.176926 0.117481 0.02139997 0.175527 0.115746 0.02139997 0.176854 0.117179 0.02105396 0.176716 0.116966 0.02096569 0.176527 0.116549 0.02067887 0.1766909 0.115906 0.01948314 0.1769 0.115969 0.01919907 0.1771849 0.116164 0.01898127 0.177341 0.116307 0.01892119 0.178063 0.116402 0.01785719 0.177503 0.116475 0.01889997 0.17708 0.1174499 0.02109998 0.177026 0.117386 0.02108907 0.1786659 0.1188639 0.02109998 0.186888 0.1218 0.02139997 0.1868889 0.121666 0.02109736 0.186805 0.121666 0.02109998 0.1825489 0.120934 0.02109998 0.198486 0.103667 0.01785719 0.198051 0.101648 0.01889997 0.19765 0.101876 0.01785719 0.196538 0.100242 0.01785719 0.197561 0.100531 0.01931416 0.198433 0.100605 0.02085876 0.199024 0.105569 0.01785719 0.1989189 0.103506 0.01889997 0.199711 0.107517 0.01889997 0.19925 0.107533 0.01785719 0.199158 0.109507 0.01785719 0.198751 0.111441 0.01785719 0.19945 0.113966 0.02139997 0.199802 0.112501 0.02085918 0.1989549 0.112596 0.01913899 0.1990219 0.112141 0.0189265 0.200581 0.1096889 0.02109998 0.200562 0.105265 0.02139997 0.200713 0.109706 0.02139997 0.198896 0.101167 0.02109736 0.198938 0.101239 0.02109998 0.1999559 0.10312 0.02139997 0.176494 0.116037 0.02001869 0.176823 0.114863 0.01785719 0.1736479 0.11172 0.02139997 0.175846 0.113145 0.01785719 0.1751559 0.111293 0.01785719 0.174773 0.109354 0.01785719 0.174706 0.107378 0.01785719 0.174956 0.105418 0.01785719 0.17507 0.102545 0.01964676 0.199099 0.1129699 0.01975518 0.198038 0.113285 0.01785719 0.198323 0.115889 0.02139997 0.197039 0.114991 0.01785719 0.195779 0.116514 0.01785719 0.1942909 0.117815 0.01785719 0.193334 0.120254 0.02139997 0.192614 0.118861 0.01785719 0.191278 0.121115 0.02139997 0.190791 0.119624 0.01785719 0.1891109 0.121634 0.02139997 0.1888689 0.120085 0.01785719 0.185212 0.09482938 0.02001816 0.185947 0.0941382 0.02139997 0.186064 0.09570145 0.01785719 0.188176 0.09415221 0.02139997 0.190374 0.0945236 0.02139997 0.18804 0.09571397 0.01785719 0.189989 0.09604328 0.01785719 0.19186 0.09668099 0.01785719 0.193605 0.09761059 0.01785719 0.195177 0.09880799 0.01785719 0.197758 0.0992583 0.02139997 0.181466 0.120657 0.02139997 0.180461 0.120173 0.02139997 0.1785849 0.11897 0.02139997 0.174425 0.113809 0.02139997 0.1738629 0.110196 0.02139997 0.173216 0.109533 0.02139997 0.1731399 0.107305 0.02139997 0.173422 0.105094 0.02139997 0.176442 0.0998243 0.02139997 0.177923 0.09820139 0.02139997 0.177856 0.09752547 0.02139997 0.183654 0.09506797 0.02139997 0.185819 0.09469705 0.02139997 0.1880159 0.09468758 0.02139997 0.190185 0.0950399 0.02139997 0.192484 0.09524267 0.02139997 0.194203 0.09678167 0.02139997 0.194451 0.09629088 0.02139997 0.196224 0.09764111 0.02139997 0.1959429 0.09812378 0.02139997 0.1990129 0.101101 0.02139997 0.200278 0.107893 0.02139997 0.200817 0.107479 0.02139997 0.200106 0.110083 0.02139997 0.200254 0.111887 0.02139997 0.196027 0.117699 0.02139997 0.196903 0.1176069 0.02139997 0.195225 0.119074 0.02139997 0.184667 0.121606 0.02139997 0.182506 0.121059 0.02139997 0.176547 0.09990531 0.02109998 0.178013 0.09829866 0.02109998 0.179724 0.09695518 0.02109998 0.179651 0.09684437 0.02139997 0.181632 0.09591168 0.02109998 0.1815789 0.09579038 0.02139997 0.183687 0.0951966 0.02109998 0.1853049 0.0951544 0.02049809 0.18534 0.09577059 0.01910698 0.1859149 0.09579908 0.01889997 0.185145 0.09585046 0.01899075 0.185115 0.09591007 0.01889997 0.1849229 0.09591686 0.01892215 0.185551 0.09529638 0.02011227 0.185618 0.09538459 0.01989769 0.185495 0.09567916 0.01926767 0.185595 0.09558039 0.01946336 0.184949 0.09506726 0.0208075 0.184518 0.09504687 0.02101939 0.18405 0.0951085 0.02109998 0.196956 0.100468 0.0195263 0.196939 0.100603 0.01931416 0.197438 0.09973388 0.02139997 0.198192 0.101073 0.02107119 0.198019 0.100864 0.02099108 0.197441 0.100415 0.02048009 0.197126 0.10034 0.02000659 0.197034 0.101077 0.01889997 0.198647 0.101568 0.02139997 0.198531 0.1016319 0.02109998 0.199539 0.103576 0.02139997 0.200087 0.105704 0.02139997 0.1999559 0.105726 0.02109998 0.199576 0.112215 0.02139997 0.198361 0.112455 0.01900887 0.1984159 0.112211 0.01892656 0.198347 0.112842 0.01931416 0.198394 0.112971 0.0195266 0.198589 0.113056 0.02000647 0.199194 0.112571 0.0208587 0.199431 0.112166 0.02105468 0.188277 0.120775 0.02046757 0.188464 0.120335 0.0195263 0.188847 0.119962 0.01889997 0.188215 0.120199 0.01915979 0.187977 0.120157 0.01901578 0.1880789 0.12089 0.02068579 0.179747 0.119118 0.02139997 0.1817359 0.120034 0.02109998 0.181684 0.120156 0.02139997 0.1837649 0.12086 0.02139997 0.185944 0.12108 0.02109998 0.1859329 0.121212 0.02139997 0.188131 0.121203 0.02139997 0.1870419 0.12112 0.02109998 0.187324 0.121103 0.02107065 0.176512 0.116166 0.02139997 0.177127 0.116674 0.0210675 0.178007 0.117776 0.02139997 0.177317 0.116904 0.02109998 0.178097 0.117678 0.02109998 0.176757 0.115432 0.01995676 0.175302 0.114332 0.02139997 0.176715 0.1156229 0.02028828 0.176768 0.115965 0.02066439 0.176907 0.116313 0.02091449 0.177541 0.115705 0.01893389 0.1773819 0.115483 0.01889997 0.176928 0.114795 0.01889997 0.177334 0.115521 0.01903849 0.177116 0.11538 0.01923495 0.176932 0.115329 0.01949834 0.175431 0.103048 0.01967775 0.175239 0.1028 0.02029955 0.175339 0.102999 0.01991248 0.175213 0.102582 0.0205549 0.175536 0.101423 0.02109998 0.175383 0.101741 0.02105468 0.175248 0.101669 0.02139997 0.1752499 0.102186 0.02086186 0.175565 0.103029 0.01941758 0.175742 0.102903 0.0191648 0.175953 0.102651 0.018974 0.176174 0.102284 0.01889997 0.185635 0.09548056 0.01967775 0.174374 0.103685 0.02139997 0.173844 0.105817 0.02139997 0.173672 0.108007 0.02139997 0.1749359 0.105994 0.01889997 0.17684 0.115348 0.01969259 0.175456 0.1119599 0.01889997 0.1744109 0.1123239 0.02139997 0.1749359 0.1098099 0.01889997 0.1902959 0.120832 0.02139997 0.192371 0.12011 0.02139997 0.191922 0.119098 0.01889997 0.194299 0.119056 0.02139997 0.193847 0.118008 0.01889997 0.19369 0.118132 0.01889997 0.198702 0.114231 0.02139997 0.197508 0.116076 0.02139997 0.1952739 0.116888 0.01889997 0.193602 0.09771049 0.01889997 0.192266 0.09574431 0.02139997 0.174782 0.108045 0.01889997 0.177101 0.09990531 0.01889997 0.193373 0.107214 0.01889997 0.199575 0.106333 0.01889997 0.194148 0.103817 0.01889997 0.179112 0.109759 0.01889997 0.178915 0.109837 0.01889997 0.1880339 0.120101 0.01889997 0.189319 0.116288 0.01889997 0.189462 0.11753 0.01889997 0.19002 0.119761 0.01889997 0.191211 0.117789 0.01889997 0.191613 0.117282 0.01889997 0.1916469 0.117054 0.01889997 0.189541 0.114444 0.01889997 0.1907359 0.115604 0.01889997 0.1903229 0.115543 0.01889997 0.177743 0.115921 0.01889997 0.17879 0.109886 0.01889997 0.1783879 0.110393 0.01889997 0.177568 0.110951 0.01889997 0.178293 0.111033 0.01889997 0.179642 0.108535 0.01889997 0.180032 0.1097429 0.01889997 0.180654 0.108974 0.01889997 0.180539 0.110146 0.01889997 0.180706 0.109424 0.01889997 0.178531 0.111635 0.01889997 0.179038 0.112037 0.01889997 0.179678 0.112132 0.01889997 0.1799989 0.112005 0.01889997 0.180279 0.111894 0.01889997 0.180727 0.110623 0.01889997 0.181215 0.11083 0.01889997 0.180777 0.110747 0.01889997 0.181218 0.110836 0.01889997 0.193951 0.103895 0.01889997 0.19367 0.104006 0.01889997 0.192301 0.104348 0.01889997 0.192362 0.104421 0.01889997 0.193268 0.104513 0.01889997 0.1930299 0.105758 0.01889997 0.193173 0.105153 0.01889997 0.193127 0.106171 0.01889997 0.1933619 0.10563 0.01889997 0.193306 0.106931 0.01889997 0.1934109 0.105754 0.01889997 0.195419 0.104265 0.01889997 0.194912 0.103863 0.01889997 0.194272 0.103768 0.01889997 0.199477 0.10548 0.01889997 0.199407 0.105234 0.01889997 0.193918 0.106157 0.01889997 0.194558 0.106252 0.01889997 0.194838 0.106141 0.01889997 0.199596 0.109658 0.01889997 0.199616 0.109566 0.01889997 0.19516 0.106014 0.01889997 0.195562 0.105507 0.01889997 0.195657 0.104867 0.01889997 0.193053 0.0999754 0.01889997 0.193004 0.09905785 0.01889997 0.194783 0.09862148 0.01889997 0.192767 0.100848 0.01889997 0.18958 0.10194 0.01889997 0.192727 0.103364 0.01889997 0.190476 0.102145 0.01889997 0.191385 0.102012 0.01889997 0.191641 0.101867 0.01889997 0.192185 0.101559 0.01889997 0.188199 0.09886819 0.01889997 0.188078 0.099779 0.01889997 0.188225 0.100386 0.01889997 0.18639 0.100617 0.01889997 0.1882939 0.100672 0.01889997 0.188819 0.101426 0.01889997 0.189343 0.09747087 0.01889997 0.188446 0.0958743 0.01889997 0.190212 0.09717297 0.01889997 0.1892859 0.0960108 0.01889997 0.192627 0.09821999 0.01889997 0.191973 0.09757471 0.01889997 0.181665 0.111517 0.01889997 0.180682 0.111387 0.01889997 0.184413 0.1138589 0.01889997 0.18312 0.113109 0.01889997 0.181223 0.112536 0.01889997 0.182034 0.112081 0.01889997 0.180711 0.106453 0.01889997 0.180535 0.107938 0.01889997 0.183139 0.102777 0.01889997 0.185964 0.1016 0.01889997 0.185868 0.101606 0.01889997 0.191403 0.103274 0.01889997 0.190205 0.102379 0.01889997 0.1888329 0.101784 0.01889997 0.187361 0.101522 0.01889997 0.192349 0.111499 0.01889997 0.193022 0.110164 0.01889997 0.19337 0.108709 0.01889997 0.189879 0.113664 0.01889997 0.19097 0.115063 0.01889997 0.190185 0.113533 0.01889997 0.190549 0.113263 0.01889997 0.191386 0.112642 0.01889997 0.185845 0.1142899 0.01889997 0.18756 0.115283 0.01889997 0.1873379 0.11438 0.01889997 0.188002 0.114264 0.01889997 0.188804 0.114124 0.01889997 0.188811 0.114123 0.01889997 0.1836259 0.1003569 0.01889997 0.184435 0.102032 0.01889997 0.183391 0.102632 0.01889997 0.183214 0.100296 0.01889997 0.182389 0.102198 0.01889997 0.182986 0.100262 0.01889997 0.18243 0.0997349 0.01889997 0.182479 0.09985947 0.01889997 0.183341 0.09787297 0.01889997 0.184328 0.09548407 0.01889997 0.1886399 0.09806257 0.01889997 0.186765 0.09975278 0.01889997 0.184676 0.0988475 0.01889997 0.1879299 0.09579038 0.01889997 0.184487 0.09837019 0.01889997 0.183981 0.09796798 0.01889997 0.184688 0.09596925 0.01889997 0.184161 0.09811121 0.01889997 0.184228 0.100119 0.01889997 0.184487 0.09979248 0.01889997 0.18463 0.09961199 0.01889997 0.184725 0.09897196 0.01889997 0.17723 0.09996145 0.01889997 0.18007 0.102278 0.01889997 0.179228 0.101913 0.01889997 0.178309 0.101877 0.01889997 0.176916 0.10613 0.01889997 0.174898 0.106478 0.01889997 0.176391 0.105376 0.01889997 0.1761749 0.104483 0.01889997 0.1787779 0.10816 0.01889997 0.1802819 0.106263 0.01889997 0.181225 0.105049 0.01889997 0.182049 0.103801 0.01889997 0.18115 0.104679 0.01889997 0.181525 0.101823 0.01889997 0.180889 0.10329 0.01889997 0.185805 0.115665 0.01889997 0.185854 0.116582 0.01889997 0.185428 0.114827 0.01889997 0.184774 0.114181 0.01889997 0.1839309 0.113816 0.01889997 0.183013 0.11378 0.01889997 0.183277 0.118751 0.01889997 0.184186 0.118618 0.01889997 0.185275 0.120553 0.01889997 0.184985 0.118166 0.01889997 0.185567 0.117455 0.01889997 0.182144 0.114078 0.01889997 0.181441 0.114669 0.01889997 0.181 0.1154749 0.01889997 0.178938 0.117805 0.01889997 0.1808789 0.1163859 0.01889997 0.181095 0.117279 0.01889997 0.179255 0.11809 0.01889997 0.1809819 0.119197 0.01889997 0.181619 0.118033 0.01889997 0.182381 0.118547 0.01889997 0.186895 0.120693 0.01889997 0.186834 0.120688 0.01889997 0.1874679 0.120137 0.01889997 0.188921 0.115873 0.01889997 0.195241 0.116914 0.01889997 0.1990939 0.111891 0.01889997 0.198494 0.1119599 0.01889997 0.194047 0.109374 0.01889997 0.194308 0.107365 0.01889997 0.199193 0.111572 0.01889997 0.197708 0.110961 0.01889997 0.197757 0.111878 0.01889997 0.197331 0.110123 0.01889997 0.196677 0.1094779 0.01889997 0.195834 0.109112 0.01889997 0.194916 0.109076 0.01889997 0.192998 0.112575 0.01889997 0.193522 0.113329 0.01889997 0.196305 0.115759 0.01889997 0.194284 0.113843 0.01889997 0.1951799 0.114048 0.01889997 0.196632 0.1154 0.01889997 0.197727 0.113709 0.01889997 0.196089 0.113915 0.01889997 0.196888 0.113462 0.01889997 0.19747 0.112751 0.01889997 0.1933439 0.109965 0.01889997 0.19156 0.1137019 0.01889997 0.192903 0.110771 0.01889997 0.192782 0.1116819 0.01889997 0.197282 0.101429 0.01889997 0.195892 0.1037099 0.01889997 0.197883 0.10136 0.01889997 0.195546 0.104587 0.01889997 0.1955299 0.104546 0.01889997 0.196568 0.100417 0.01889997 0.194463 0.10309 0.01889997 0.195923 0.09972256 0.01889997 0.195197 0.0989409 0.01889997 0.193102 0.1025 0.01889997 0.19113 0.09720927 0.01889997 0.194109 0.09810149 0.01889997 0.189918 0.0961135 0.01889997 0.191826 0.09675925 0.01889997 0.177154 0.0998283 0.01889997 0.177395 0.09958118 0.01889997 0.182242 0.0992577 0.01889997 0.178584 0.09835815 0.01889997 0.182303 0.09884548 0.01889997 0.179541 0.09764838 0.01889997 0.182337 0.09861767 0.01889997 0.182739 0.09811079 0.01889997 0.180459 0.09701919 0.01889997 0.1828629 0.09806156 0.01889997 0.182054 0.0961948 0.01889997 0.183216 0.0979222 0.01889997 0.184267 0.0954979 0.01889997 0.175422 0.104039 0.01889997 0.175814 0.101799 0.01889997 0.175979 0.101509 0.01889997 0.176738 0.102766 0.01889997 0.175368 0.104257 0.01889997 0.174778 0.108003 0.01889997 0.178188 0.109522 0.01889997 0.179392 0.109648 0.01889997 0.174953 0.110009 0.01889997 0.17842 0.111354 0.01889997 0.178404 0.111313 0.01889997 0.176309 0.113855 0.01889997 0.176273 0.113801 0.01889997 0.1761749 0.104483 0.01749408 0.1762959 0.103572 0.01889997 0.1762959 0.103572 0.01757097 0.1761929 0.104022 0.01754516 0.177064 0.102436 0.01749366 0.176738 0.102766 0.01754516 0.1764799 0.103147 0.01757085 0.179482 0.106715 0.01739996 0.179399 0.106728 0.01889997 0.179482 0.106715 0.01889997 0.1802819 0.106263 0.01739996 0.180864 0.105552 0.01739996 0.18115 0.104679 0.01739996 0.180864 0.105552 0.01889997 0.181101 0.103762 0.01889997 0.181101 0.103762 0.01739996 0.180724 0.102924 0.01739996 0.180724 0.102924 0.01889997 0.18007 0.102278 0.01739996 0.179228 0.101913 0.01739996 0.178309 0.101877 0.01739996 0.177524 0.102129 0.01739996 0.17744 0.1021749 0.01889997 0.17744 0.1021749 0.01741856 0.176266 0.105032 0.01739996 0.176391 0.105376 0.01739996 0.176916 0.10613 0.01739996 0.177677 0.106644 0.01889997 0.177677 0.106644 0.01739996 0.178573 0.106848 0.01739996 0.178573 0.106848 0.01889997 0.1842899 0.112138 0.02884995 0.183652 0.111653 0.02884995 0.184014 0.111948 0.02974998 0.183656 0.111649 0.02974998 0.183102 0.111072 0.02884995 0.183185 0.111173 0.02974998 0.183106 0.111069 0.02974998 0.182322 0.109712 0.02974998 0.182554 0.110231 0.02974998 0.182651 0.11041 0.02884995 0.182657 0.110407 0.02974998 0.182312 0.109685 0.02884995 0.182094 0.108914 0.02884995 0.182044 0.108613 0.02974998 0.182006 0.108119 0.02974998 0.182022 0.107479 0.02974998 0.182003 0.108119 0.02884995 0.1820009 0.108046 0.02974998 0.182205 0.106536 0.02884995 0.1822119 0.1065379 0.02974998 0.182108 0.106917 0.02974998 0.18204 0.1073189 0.02884995 0.182047 0.10732 0.02974998 0.182469 0.105842 0.02974998 0.182494 0.105789 0.02884995 0.182738 0.105342 0.02974998 0.182898 0.105098 0.02884995 0.1834099 0.104483 0.02974998 0.183439 0.10445 0.02974998 0.183409 0.104481 0.02884995 0.183861 0.10407 0.02974998 0.184011 0.103954 0.02884995 0.185346 0.103249 0.02974998 0.185429 0.1032209 0.02884995 0.184691 0.10353 0.02884995 0.186209 0.103042 0.02974998 0.186208 0.103035 0.02884995 0.186453 0.103002 0.02974998 0.1870059 0.102976 0.02974998 0.187021 0.102975 0.02974998 0.1870059 0.102975 0.02884995 0.187804 0.103045 0.02884995 0.18858 0.103241 0.02884995 0.1881459 0.103115 0.02974998 0.187588 0.103013 0.02974998 0.189211 0.103506 0.02974998 0.189315 0.103559 0.02884995 0.18869 0.10328 0.02974998 0.188578 0.103246 0.02974998 0.189312 0.103564 0.02974998 0.189989 0.103992 0.02884995 0.190584 0.104526 0.02884995 0.190584 0.1045269 0.02974998 0.191483 0.105846 0.02884995 0.19108 0.105154 0.02974998 0.191087 0.10515 0.02884995 0.19172 0.106456 0.02974998 0.191519 0.105925 0.02974998 0.191762 0.106596 0.02884995 0.191479 0.105848 0.02974998 0.191259 0.10542 0.02974998 0.19191 0.1073819 0.02974998 0.191917 0.107381 0.02884995 0.191944 0.108182 0.02884995 0.191935 0.10757 0.02974998 0.191843 0.108976 0.02884995 0.191775 0.109259 0.02974998 0.191353 0.110312 0.02974998 0.191268 0.110465 0.02884995 0.191615 0.1097429 0.02884995 0.191613 0.109742 0.02974998 0.190803 0.111117 0.02974998 0.190809 0.1111209 0.02884995 0.190705 0.1112419 0.02974998 0.19025 0.111695 0.02884995 0.1903049 0.1116459 0.02974998 0.190248 0.111692 0.02974998 0.189603 0.112165 0.02974998 0.189607 0.112171 0.02884995 0.188332 0.112736 0.02974998 0.188896 0.112539 0.02884995 0.188895 0.112538 0.02974998 0.189381 0.112304 0.02974998 0.188133 0.112781 0.02974998 0.1877779 0.11286 0.02974998 0.188135 0.112788 0.02884995 0.186645 0.112914 0.02974998 0.187344 0.112911 0.02884995 0.187213 0.112919 0.02974998 0.186543 0.112906 0.02884995 0.1860809 0.112844 0.02974998 0.186544 0.112902 0.02974998 0.184996 0.112515 0.02884995 0.185754 0.112773 0.02884995 0.191537 0.107601 0.03014999 0.190975 0.107971 0.03014999 0.185384 0.11162 0.03014999 0.186065 0.111845 0.03014999 0.183079 0.105551 0.03014999 0.183751 0.1055819 0.03014999 0.183727 0.110284 0.03014999 0.183175 0.1104969 0.03014999 0.183362 0.109667 0.03014999 0.185155 0.112148 0.03014999 0.184754 0.111277 0.03014999 0.1841959 0.110827 0.03014999 0.184252 0.111626 0.03014999 0.18349 0.110914 0.03014999 0.191497 0.108643 0.03014999 0.190907 0.108684 0.03014999 0.191389 0.109154 0.03014999 0.190713 0.109375 0.03014999 0.190398 0.110019 0.03014999 0.191339 0.106576 0.03014999 0.1907269 0.106564 0.03014999 0.190914 0.107256 0.03014999 0.191467 0.107083 0.03014999 0.183378 0.105123 0.03014999 0.184226 0.105045 0.03014999 0.183724 0.104731 0.03014999 0.184788 0.1046 0.03014999 0.1831139 0.108994 0.03014999 0.1825399 0.109072 0.03014999 0.1910009 0.110122 0.03014999 0.190419 0.105916 0.03014999 0.1825 0.107 0.03014999 0.183125 0.106866 0.03014999 0.182637 0.106496 0.03014999 0.18338 0.106196 0.03014999 0.182831 0.106011 0.03014999 0.1881909 0.111761 0.03014999 0.1874909 0.111917 0.03014999 0.1907269 0.110567 0.03014999 0.189974 0.110597 0.03014999 0.189453 0.11109 0.03014999 0.18963 0.111676 0.03014999 0.188852 0.111482 0.03014999 0.188717 0.1121799 0.03014999 0.18823 0.104152 0.03014999 0.188888 0.104437 0.03014999 0.1824409 0.108559 0.03014999 0.182989 0.108288 0.03014999 0.182401 0.108038 0.03014999 0.1829929 0.107571 0.03014999 0.18242 0.107516 0.03014999 0.189485 0.104836 0.03014999 0.190001 0.105334 0.03014999 0.190285 0.1047919 0.03014999 0.190623 0.10519 0.03014999 0.186816 0.103953 0.03014999 0.187532 0.103989 0.03014999 0.185422 0.104264 0.03014999 0.184994 0.103826 0.03014999 0.185477 0.103627 0.03014999 0.186105 0.104046 0.03014999 0.186495 0.1034 0.03014999 0.186775 0.111945 0.03014999 0.184294 0.1121309 0.02974998 0.184032 0.111923 0.02990305 0.183598 0.111562 0.02990305 0.183577 0.111584 0.02974998 0.183208 0.111153 0.02990305 0.182868 0.110703 0.02990305 0.182842 0.11072 0.02974998 0.182581 0.110217 0.02990305 0.1823509 0.109701 0.02990305 0.182314 0.109684 0.02974998 0.182152 0.10917 0.02974998 0.182102 0.108913 0.02974998 0.182074 0.108609 0.02990305 0.182258 0.106369 0.02974998 0.182496 0.105855 0.02990305 0.182496 0.10579 0.02974998 0.182905 0.105103 0.02974998 0.183063 0.104876 0.02974998 0.18388 0.104094 0.02990305 0.184015 0.10396 0.02974998 0.184324 0.10374 0.02974998 0.1846939 0.103536 0.02974998 0.184834 0.103493 0.02990305 0.184821 0.103465 0.02974998 0.1854299 0.103225 0.02974998 0.185899 0.103124 0.02990305 0.1858929 0.103094 0.02974998 0.186457 0.103033 0.02990305 0.18702 0.103006 0.02990305 0.187802 0.103052 0.02974998 0.188139 0.103144 0.02990305 0.188679 0.103309 0.02990305 0.189703 0.10379 0.02974998 0.189984 0.103998 0.02974998 0.190159 0.104128 0.02974998 0.19014 0.104151 0.02990305 0.190574 0.104516 0.02974998 0.190942 0.104948 0.02974998 0.190918 0.1049669 0.02990305 0.191756 0.106597 0.02974998 0.19183 0.107013 0.02990305 0.19186 0.107007 0.02974998 0.191946 0.108138 0.02974998 0.191916 0.108137 0.02990305 0.191942 0.1081809 0.02974998 0.191862 0.108699 0.02990305 0.191893 0.108703 0.02974998 0.191835 0.108974 0.02974998 0.191594 0.109798 0.02974998 0.191327 0.110298 0.02990305 0.191262 0.1104609 0.02974998 0.1906819 0.111222 0.02990305 0.191056 0.110796 0.02974998 0.190285 0.111624 0.02990305 0.189844 0.111977 0.02990305 0.189862 0.112002 0.02974998 0.189366 0.112278 0.02990305 0.1888689 0.11255 0.02974998 0.188324 0.112707 0.02990305 0.187343 0.112906 0.02974998 0.1866469 0.112884 0.02990305 0.185756 0.112765 0.02974998 0.1855379 0.112681 0.02990305 0.1855289 0.1127099 0.02974998 0.185008 0.112487 0.02990305 0.184996 0.112515 0.02974998 0.184504 0.112233 0.02990305 0.184489 0.112259 0.02974998 0.186087 0.112814 0.02990305 0.187212 0.112889 0.02990305 0.187773 0.11283 0.02990305 0.187759 0.112744 0.03003275 0.1883 0.112623 0.03003275 0.188858 0.112522 0.02990305 0.189325 0.112202 0.03003275 0.190226 0.111559 0.03003275 0.190617 0.111165 0.03003275 0.191031 0.110778 0.02990305 0.190959 0.110729 0.03003275 0.191566 0.109786 0.02990305 0.191485 0.109754 0.03003275 0.191745 0.109251 0.02990305 0.191662 0.109228 0.03003275 0.191905 0.107572 0.02990305 0.191691 0.106465 0.02990305 0.191745 0.107029 0.03003275 0.191609 0.106492 0.03003275 0.191491 0.105938 0.02990305 0.191233 0.105436 0.02990305 0.1905519 0.104537 0.02990305 0.190849 0.105019 0.03003275 0.1900849 0.104218 0.03003275 0.189686 0.103815 0.02990305 0.189197 0.103533 0.02990305 0.1881189 0.103229 0.03003275 0.187584 0.103043 0.02990305 0.186466 0.103119 0.03003275 0.185356 0.103278 0.02990305 0.18434 0.103766 0.02990305 0.184386 0.103839 0.03003275 0.183461 0.104471 0.02990305 0.183087 0.104895 0.02990305 0.1827639 0.105358 0.02990305 0.182287 0.106379 0.02990305 0.182575 0.105891 0.03003275 0.182138 0.106923 0.02990305 0.182223 0.106941 0.03003275 0.182053 0.107481 0.02990305 0.182031 0.108046 0.02990305 0.182139 0.10749 0.03003275 0.18216 0.108597 0.03003275 0.182181 0.109163 0.02990305 0.18294 0.110655 0.03003275 0.183274 0.111097 0.03003275 0.183657 0.111499 0.03003275 0.186102 0.112729 0.03003275 0.186653 0.112797 0.03003275 0.186661 0.112668 0.03011959 0.187207 0.112802 0.03003275 0.187201 0.112673 0.03011959 0.187738 0.112616 0.03011959 0.188265 0.1124989 0.03011959 0.188825 0.112442 0.03003275 0.189262 0.112088 0.03011959 0.189794 0.111906 0.03003275 0.189719 0.111801 0.03011959 0.19014 0.111463 0.03011959 0.190519 0.111079 0.03011959 0.1908529 0.110655 0.03011959 0.19125 0.110257 0.03003275 0.191365 0.109706 0.03011959 0.191777 0.108686 0.03003275 0.191536 0.109194 0.03011959 0.191648 0.108666 0.03011959 0.191829 0.108133 0.03003275 0.191819 0.107579 0.03003275 0.191689 0.107589 0.03011959 0.191617 0.107054 0.03011959 0.191294 0.106026 0.03011959 0.191412 0.105973 0.03003275 0.1911579 0.10548 0.03003275 0.1910459 0.1055459 0.03011959 0.190746 0.105097 0.03011959 0.19049 0.104597 0.03003275 0.189639 0.103888 0.03003275 0.189568 0.103996 0.03011959 0.189158 0.103611 0.03003275 0.1886489 0.10339 0.03003275 0.187573 0.103129 0.03003275 0.18702 0.103092 0.03003275 0.187018 0.103222 0.03011959 0.185918 0.103208 0.03003275 0.186479 0.103248 0.03011959 0.185947 0.103335 0.03011959 0.185385 0.1033599 0.03003275 0.185427 0.103482 0.03011959 0.184872 0.1035709 0.03003275 0.183935 0.104161 0.03003275 0.184455 0.103949 0.03011959 0.184016 0.104262 0.03011959 0.1835229 0.104532 0.03003275 0.183155 0.104948 0.03003275 0.182838 0.105403 0.03003275 0.182692 0.105946 0.03011959 0.1823689 0.106406 0.03003275 0.18235 0.106968 0.03011959 0.1821179 0.108044 0.03003275 0.1822479 0.108041 0.03011959 0.182265 0.109142 0.03003275 0.182391 0.1091099 0.03011959 0.1824319 0.1096709 0.03003275 0.1825529 0.109625 0.03011959 0.182658 0.110177 0.03003275 0.1827729 0.110118 0.03011959 0.184083 0.111854 0.03003275 0.183746 0.111404 0.03011959 0.184161 0.111749 0.03011959 0.184547 0.112158 0.03003275 0.184612 0.112045 0.03011959 0.185043 0.112407 0.03003275 0.1850939 0.1122879 0.03011959 0.185563 0.112598 0.03003275 0.1856009 0.112474 0.03011959 0.1861259 0.112601 0.03011959 0.1861529 0.112451 0.03014999 0.186672 0.112515 0.03014999 0.187194 0.11252 0.03014999 0.187713 0.112465 0.03014999 0.188223 0.112351 0.03014999 0.188775 0.112322 0.03011959 0.189188 0.111954 0.03014999 0.190037 0.111349 0.03014999 0.190405 0.110978 0.03014999 0.191136 0.110195 0.03011959 0.191223 0.109649 0.03014999 0.1917 0.108129 0.03011959 0.191547 0.108123 0.03014999 0.191485 0.10653 0.03011959 0.191154 0.106088 0.03014999 0.190914 0.105624 0.03014999 0.190396 0.104686 0.03011959 0.189903 0.104435 0.03014999 0.190001 0.104318 0.03011959 0.1891 0.103726 0.03011959 0.189484 0.104124 0.03014999 0.189031 0.103863 0.03014999 0.188552 0.103655 0.03014999 0.188605 0.103512 0.03011959 0.1880879 0.103355 0.03011959 0.1880519 0.103504 0.03014999 0.187557 0.103258 0.03011959 0.187538 0.10341 0.03014999 0.187017 0.103375 0.03014999 0.18598 0.103485 0.03014999 0.1849279 0.103688 0.03011959 0.1845369 0.104079 0.03014999 0.183615 0.104624 0.03011959 0.184112 0.104382 0.03014999 0.183257 0.105028 0.03011959 0.182949 0.105471 0.03011959 0.182492 0.106448 0.03011959 0.182268 0.107502 0.03011959 0.182289 0.10858 0.03011959 0.182696 0.10957 0.03014999 0.182909 0.1100479 0.03014999 0.183048 0.110583 0.03011959 0.183373 0.111013 0.03011959 0.1838499 0.111292 0.03014999 0.184689 0.111913 0.03014999 0.1856459 0.112328 0.03014999 0.185146 0.103323 0.02039998 0.188803 0.112577 0.02324998 0.188803 0.112577 0.02039998 0.1883929 0.1127189 0.02039998 0.182348 0.109778 0.02039998 0.1892 0.1123999 0.02324998 0.191917 0.107381 0.02324998 0.191917 0.107381 0.02824997 0.191941 0.108248 0.02824997 0.191941 0.108248 0.02324998 0.191814 0.109106 0.02824997 0.191814 0.109106 0.02324998 0.191539 0.109929 0.02324998 0.191126 0.110691 0.02324998 0.191539 0.109929 0.02824997 0.191126 0.110691 0.02824997 0.190587 0.111371 0.02824997 0.190587 0.111371 0.02324998 0.189938 0.111946 0.02324998 0.189938 0.111946 0.02824997 0.1892 0.1123999 0.02824997 0.1883929 0.1127189 0.02824997 0.191602 0.106122 0.02039998 0.18475 0.1035 0.02324998 0.182032 0.108519 0.02324998 0.182032 0.108519 0.02824997 0.182009 0.107652 0.02324998 0.182009 0.107652 0.02824997 0.1821359 0.1067939 0.02324998 0.18241 0.105971 0.02324998 0.1821359 0.1067939 0.02824997 0.182823 0.105209 0.02324998 0.18241 0.105971 0.02824997 0.182823 0.105209 0.02824997 0.183362 0.104529 0.02324998 0.183362 0.104529 0.02824997 0.184011 0.103954 0.02824997 0.184011 0.103954 0.02324998 0.18475 0.1035 0.02824997 0.185146 0.103323 0.02324998 0.185557 0.103181 0.02039998 0.185557 0.103181 0.02824997 0.186406 0.103008 0.02039998 0.186406 0.103008 0.02824997 0.187273 0.102984 0.02039998 0.188131 0.103111 0.02039998 0.187273 0.102984 0.02824997 0.188131 0.103111 0.02824997 0.1889539 0.103385 0.02039998 0.189716 0.103798 0.02039998 0.1889539 0.103385 0.02824997 0.189716 0.103798 0.02824997 0.190396 0.104338 0.02039998 0.190396 0.104338 0.02824997 0.190971 0.104986 0.02039998 0.190971 0.104986 0.02824997 0.191425 0.105725 0.02824997 0.191425 0.105725 0.02039998 0.191602 0.106122 0.02324998 0.191743 0.106532 0.02324998 0.191743 0.106532 0.02824997 0.187543 0.112892 0.02039998 0.186677 0.112916 0.02039998 0.187543 0.112892 0.02824997 0.186677 0.112916 0.02824997 0.185819 0.112789 0.02039998 0.184996 0.112515 0.02039998 0.185819 0.112789 0.02824997 0.184996 0.112515 0.02824997 0.184234 0.112102 0.02039998 0.184234 0.112102 0.02824997 0.1835539 0.111562 0.02039998 0.182979 0.110914 0.02039998 0.1835539 0.111562 0.02824997 0.182979 0.110914 0.02824997 0.182525 0.110175 0.02039998 0.182525 0.110175 0.02824997 0.182206 0.109368 0.02824997 0.182348 0.109778 0.02324998 0.182206 0.109368 0.02324998 0.184678 0.112391 0.03444999 0.183565 0.111607 0.03444999 0.182705 0.1105509 0.03444999 0.191889 0.10727 0.03744995 0.1913509 0.106902 0.03794997 0.191299 0.109195 0.03794997 0.191524 0.109922 0.03744995 0.1898379 0.112002 0.03744995 0.189449 0.112295 0.03744995 0.185091 0.103319 0.03444999 0.19156 0.105955 0.03444999 0.185954 0.103055 0.03444999 0.187313 0.102961 0.03444999 0.185772 0.103614 0.03794997 0.1916429 0.106159 0.03744995 0.181988 0.1079519 0.03744995 0.181976 0.107837 0.03744995 0.182476 0.107848 0.03794997 0.182164 0.106605 0.03744995 0.18265 0.106705 0.03794997 0.18217 0.106567 0.03744995 0.182705 0.105358 0.03744995 0.183475 0.1043789 0.03744995 0.183825 0.104736 0.03794997 0.1847479 0.104039 0.03794997 0.188178 0.112286 0.03794997 0.188859 0.112581 0.03744995 0.182307 0.109741 0.03444999 0.182307 0.109741 0.03744995 0.182988 0.110036 0.03794997 0.182599 0.108998 0.03794997 0.185496 0.1077 0.03794997 0.1908389 0.110255 0.03794997 0.1831099 0.105645 0.03794997 0.185781 0.107041 0.03794997 0.18634 0.106591 0.03794997 0.187045 0.106452 0.03794997 0.1877329 0.106656 0.03794997 0.190962 0.105864 0.03794997 0.191474 0.108052 0.03794997 0.188351 0.108547 0.03794997 0.1872659 0.109422 0.03794997 0.1892009 0.111861 0.03794997 0.190124 0.111164 0.03794997 0.188471 0.107839 0.03794997 0.1884289 0.1075839 0.03484797 0.188471 0.107839 0.03014999 0.188248 0.107156 0.03014999 0.188358 0.10737 0.03507494 0.188248 0.107156 0.03794997 0.187916 0.109118 0.03794997 0.188187 0.108834 0.03690576 0.187912 0.109112 0.03672796 0.186549 0.109388 0.03794997 0.187361 0.109399 0.03612339 0.187497 0.109356 0.03507494 0.187916 0.109118 0.03466236 0.1872659 0.109422 0.03014999 0.187702 0.109262 0.03484815 0.188351 0.108547 0.03014999 0.188449 0.108229 0.0344944 0.187916 0.109118 0.03014999 0.1872659 0.109422 0.03550356 0.185929 0.109025 0.03794997 0.186549 0.109388 0.03014999 0.185929 0.109025 0.03014999 0.185549 0.108416 0.03794997 0.185549 0.108416 0.03014999 0.185496 0.1077 0.03014999 0.185599 0.107353 0.03014999 0.185781 0.107041 0.03014999 0.18634 0.106591 0.03014999 0.187045 0.106452 0.03014999 0.1877329 0.106656 0.03014999 0.191907 0.108772 0.03537625 0.1910229 0.110885 0.03632497 0.187973 0.109059 0.03462725 0.188187 0.108834 0.03449416 0.191424 0.110232 0.03449255 0.1910229 0.110885 0.03507494 0.187238 0.109427 0.03569996 0.1909199 0.111022 0.03569996 0.187362 0.109399 0.03527617 0.190946 0.110988 0.03602397 0.187497 0.109356 0.03632497 0.1872659 0.109422 0.03589636 0.187702 0.109262 0.03655189 0.187977 0.109066 0.0367825 0.191139 0.110718 0.03658407 0.188471 0.107839 0.03673756 0.191775 0.10935 0.0367825 0.188466 0.10792 0.03677266 0.188449 0.1082299 0.03690576 0.191682 0.109637 0.03690719 0.188351 0.108547 0.03694999 0.188297 0.107241 0.03612387 0.188358 0.10737 0.03632497 0.1884289 0.107583 0.03655177 0.188248 0.107156 0.03550356 0.188233 0.107133 0.03569996 0.191914 0.108729 0.03569996 0.188248 0.107156 0.03589636 0.188297 0.107241 0.03527665 0.188351 0.108547 0.03444999 0.188475 0.107919 0.03461748 0.188464 0.10784 0.03467196 0.191884 0.108898 0.03507494 0.185091 0.103319 0.03744995 0.184675 0.10352 0.03744995 0.185954 0.103055 0.03344994 0.188646 0.103238 0.03444999 0.188646 0.103238 0.03344994 0.189855 0.103863 0.03444999 0.190851 0.1047919 0.03344994 0.190851 0.1047919 0.03444999 0.190962 0.104974 0.03344994 0.1916429 0.106159 0.03444999 0.191837 0.1067849 0.03744995 0.1898609 0.112033 0.03344994 0.188859 0.112581 0.03444999 0.1886529 0.11266 0.03444999 0.1873199 0.112938 0.03444999 0.1873199 0.112938 0.03344994 0.185961 0.112846 0.03444999 0.183565 0.111607 0.03344994 0.190824 0.111077 0.03744995 0.190946 0.110987 0.03537559 0.191138 0.110718 0.0348162 0.191842 0.109096 0.03481608 0.191929 0.108627 0.03344994 0.191278 0.1104969 0.03461748 0.190856 0.1111029 0.03344994 0.1915619 0.109939 0.03444999 0.191682 0.109637 0.03449285 0.191775 0.10935 0.03461748 0.191907 0.108772 0.03602379 0.191884 0.108898 0.03632497 0.191842 0.109097 0.03658396 0.191888 0.108621 0.03744995 0.19178 0.109333 0.03744995 0.1915619 0.109939 0.03694999 0.191269 0.110512 0.03744995 0.191424 0.110232 0.03690719 0.191278 0.1104969 0.0367825 0.191928 0.107266 0.03344994 0.191974 0.108063 0.03744995 0.18356 0.104298 0.03344994 0.1845009 0.103605 0.03744995 0.183254 0.104675 0.03344994 0.183568 0.104309 0.03744995 0.182701 0.105355 0.03344994 0.182681 0.105388 0.03744995 0.182159 0.106604 0.03344994 0.182112 0.109115 0.03744995 0.18217 0.1093 0.03744995 0.190474 0.111521 0.03744995 0.190716 0.111234 0.03344994 0.181634 0.115352 0.03214997 0.181634 0.115352 0.03344994 0.1816419 0.1161839 0.03214997 0.181988 0.11694 0.03214997 0.182611 0.1174899 0.03344994 0.184231 0.117645 0.03214997 0.183405 0.11774 0.03344994 0.184947 0.117222 0.03214997 0.184231 0.117645 0.03344994 0.185429 0.116544 0.03214997 0.185429 0.116544 0.03344994 0.184193 0.1138409 0.03214997 0.184193 0.1138409 0.03344994 0.183365 0.113762 0.03344994 0.1819649 0.114589 0.03214997 0.193771 0.115717 0.03214997 0.1918489 0.116768 0.03344994 0.1918489 0.116768 0.03214997 0.1910549 0.116519 0.03344994 0.190432 0.115969 0.03214997 0.1902469 0.115564 0.03344994 0.190086 0.115212 0.03214997 0.190151 0.114147 0.03214997 0.190078 0.114381 0.03344994 0.190203 0.113982 0.03214997 0.190409 0.113618 0.03344994 0.190409 0.113618 0.03214997 0.191021 0.113055 0.03214997 0.191388 0.112932 0.03344994 0.19181 0.11279 0.03214997 0.193873 0.115573 0.03344994 0.193873 0.115573 0.03214997 0.194038 0.114758 0.03214997 0.193906 0.114164 0.03214997 0.193857 0.113946 0.03344994 0.193459 0.106582 0.03214997 0.196056 0.108875 0.03214997 0.19523 0.10897 0.03344994 0.193813 0.10817 0.03344994 0.194436 0.10872 0.03214997 0.193813 0.10817 0.03214997 0.193459 0.106582 0.03344994 0.193584 0.106183 0.03214997 0.193669 0.106032 0.03214997 0.19379 0.105819 0.03344994 0.19379 0.105819 0.03214997 0.194339 0.105314 0.03344994 0.1960189 0.1050699 0.03214997 0.196743 0.105479 0.03344994 0.196772 0.108452 0.03344994 0.197287 0.106365 0.03214997 0.197343 0.106616 0.03344994 0.197238 0.106147 0.03214997 0.1909919 0.102047 0.03344994 0.191709 0.101624 0.03214997 0.1909919 0.102047 0.03214997 0.1901659 0.102142 0.03344994 0.1901659 0.102142 0.03214997 0.189373 0.101893 0.03214997 0.189373 0.101893 0.03344994 0.188749 0.101343 0.03344994 0.188749 0.101343 0.03214997 0.188521 0.09935575 0.03214997 0.188395 0.09975469 0.03344994 0.189339 0.09842908 0.03344994 0.189339 0.09842908 0.03214997 0.190127 0.09816437 0.03344994 0.190127 0.09816437 0.03214997 0.190955 0.09824317 0.03214997 0.192356 0.100132 0.03344994 0.192175 0.09931987 0.03214997 0.1922709 0.100548 0.03214997 0.192191 0.100947 0.03344994 0.180928 0.102865 0.03344994 0.180928 0.102865 0.03214997 0.1799589 0.101558 0.03344994 0.1799589 0.101558 0.03214997 0.179951 0.100726 0.03344994 0.1802819 0.09996306 0.03344994 0.180832 0.09945827 0.03344994 0.180894 0.09940057 0.03214997 0.180894 0.09940057 0.03344994 0.182539 0.10302 0.03214997 0.182548 0.1030189 0.03344994 0.183746 0.101918 0.03214997 0.183781 0.101745 0.03214997 0.18373 0.100291 0.03214997 0.1837249 0.100284 0.03214997 0.183235 0.09962338 0.03214997 0.179883 0.110395 0.03344994 0.179581 0.110573 0.03344994 0.179167 0.110817 0.03214997 0.179158 0.110818 0.03214997 0.1765699 0.108525 0.03214997 0.176644 0.108292 0.03214997 0.176696 0.108126 0.03214997 0.176901 0.107762 0.03344994 0.177514 0.107199 0.03214997 0.178302 0.106935 0.03344994 0.178302 0.106935 0.03214997 0.17913 0.107013 0.03344994 0.180366 0.109717 0.03344994 0.180366 0.109717 0.03214997 0.18053 0.108902 0.03214997 0.18053 0.108902 0.03344994 0.179854 0.107422 0.03214997 0.194674 0.0991404 0.03194999 0.194718 0.09917879 0.03194999 0.197161 0.09849178 0.03194999 0.19616 0.100702 0.03194999 0.198579 0.100297 0.03194999 0.1996459 0.102235 0.03194999 0.184945 0.09642738 0.03194999 0.187035 0.09625017 0.03194999 0.186915 0.0940501 0.03194999 0.18812 0.0965262 0.03344994 0.1878409 0.09744775 0.03344994 0.1878409 0.09744775 0.03214997 0.1872349 0.09819579 0.03214997 0.187062 0.09829026 0.03214997 0.186936 0.09835946 0.03214997 0.1863909 0.09865909 0.03214997 0.1863909 0.09865909 0.03344994 0.185434 0.09876906 0.03344994 0.1837469 0.0979188 0.03214997 0.188211 0.09561181 0.03344994 0.18812 0.0965262 0.03214997 0.188361 0.09411931 0.03194999 0.196122 0.09748387 0.03194999 0.195441 0.0969761 0.03194999 0.1951349 0.09861338 0.03344994 0.194066 0.09781569 0.03344994 0.1935999 0.09746819 0.03344994 0.194401 0.09620016 0.03194999 0.19453 0.09930527 0.03344994 0.194674 0.0991404 0.03214997 0.194729 0.1027989 0.03344994 0.19744 0.103229 0.03214997 0.195552 0.103298 0.03214997 0.195552 0.103298 0.03344994 0.194653 0.102697 0.03214997 0.193917 0.101093 0.03214997 0.194048 0.100139 0.03344994 0.19764 0.103139 0.03194999 0.19764 0.103139 0.03214997 0.198278 0.102852 0.03344994 0.1984069 0.103208 0.03344994 0.200612 0.110639 0.03194999 0.199141 0.1103489 0.03344994 0.200798 0.106743 0.03194999 0.200419 0.104483 0.03194999 0.200374 0.104254 0.03194999 0.198929 0.104653 0.03344994 0.191465 0.121105 0.03194999 0.187964 0.119608 0.03194999 0.1858659 0.119597 0.03194999 0.187035 0.12185 0.03194999 0.185808 0.119592 0.03194999 0.199728 0.113479 0.03194999 0.196474 0.114781 0.03194999 0.198644 0.1155019 0.03194999 0.195637 0.113951 0.03344994 0.195369 0.113251 0.03344994 0.1952919 0.113052 0.03214997 0.1952919 0.113052 0.03344994 0.195313 0.112089 0.03344994 0.1956959 0.111206 0.03344994 0.1956959 0.111206 0.03214997 0.196582 0.110453 0.03214997 0.196385 0.1105329 0.03344994 0.19826 0.116066 0.03194999 0.197042 0.11519 0.03344994 0.195807 0.116654 0.03344994 0.196875 0.117706 0.03194999 0.195544 0.1188639 0.03194999 0.193635 0.120132 0.03194999 0.19274 0.118928 0.03344994 0.190981 0.119685 0.03344994 0.1907539 0.119023 0.03194999 0.1858299 0.119374 0.03214997 0.1858299 0.119374 0.03344994 0.186109 0.118452 0.03214997 0.186715 0.117704 0.03214997 0.187559 0.117241 0.03344994 0.188516 0.117131 0.03214997 0.1894429 0.11739 0.03214997 0.190203 0.117981 0.03344994 0.185589 0.121781 0.03194999 0.185808 0.119592 0.03214997 0.185739 0.120288 0.03344994 0.183476 0.121402 0.03194999 0.183853 0.119951 0.03344994 0.182532 0.121077 0.03194999 0.178815 0.117287 0.03344994 0.178508 0.118924 0.03194999 0.18035 0.118432 0.03344994 0.182043 0.119327 0.03344994 0.173337 0.105261 0.03194999 0.175306 0.100398 0.03194999 0.177476 0.101119 0.03194999 0.1742219 0.102421 0.03024995 0.174652 0.1038089 0.03024995 0.174129 0.105952 0.03024995 0.173976 0.108151 0.03024995 0.174197 0.110345 0.03024995 0.1731269 0.109157 0.03024995 0.174786 0.11247 0.03024995 0.175725 0.1144649 0.03024995 0.176988 0.116272 0.03024995 0.175371 0.115603 0.03024995 0.176789 0.117408 0.03024995 0.178538 0.117841 0.03024995 0.178485 0.118956 0.03024995 0.180331 0.119124 0.03024995 0.182315 0.120086 0.03024995 0.182518 0.121116 0.03024995 0.184433 0.120699 0.03024995 0.186624 0.120945 0.03024995 0.188826 0.120818 0.03024995 0.1893219 0.12165 0.03024995 0.1909739 0.12032 0.03024995 0.1930069 0.119466 0.03024995 0.194866 0.118281 0.03024995 0.19556 0.118882 0.03024995 0.196498 0.1167989 0.03024995 0.197857 0.1150619 0.03024995 0.198644 0.1155019 0.03024995 0.198902 0.113121 0.03024995 0.199605 0.111031 0.03024995 0.200464 0.111304 0.03024995 0.199944 0.108852 0.03024995 0.199909 0.106647 0.03024995 0.200435 0.10448 0.03024995 0.199503 0.10448 0.03024995 0.198737 0.1024129 0.03024995 0.19968 0.102312 0.03024995 0.197632 0.100504 0.03024995 0.19622 0.09881055 0.03024995 0.197161 0.09849178 0.03024995 0.194542 0.09737956 0.03024995 0.192647 0.09625279 0.03024995 0.190589 0.09546238 0.03024995 0.188426 0.09503126 0.03024995 0.186222 0.09497177 0.03024995 0.18404 0.09528565 0.03024995 0.181942 0.09596389 0.03024995 0.1824049 0.0948227 0.03024995 0.179988 0.09698688 0.03024995 0.178236 0.09832537 0.03024995 0.180307 0.0957539 0.03024995 0.176735 0.09994065 0.03024995 0.175529 0.101786 0.03024995 0.200864 0.108507 0.03194999 0.200784 0.106361 0.03194999 0.2008219 0.106743 0.03024995 0.199674 0.102314 0.03194999 0.1935189 0.09573346 0.03194999 0.192504 0.09519678 0.03194999 0.193538 0.09569686 0.03024995 0.1914179 0.09482288 0.03194999 0.189204 0.09422987 0.03024995 0.190474 0.09449756 0.03194999 0.189197 0.09426885 0.03194999 0.184628 0.0942496 0.03194999 0.182485 0.09479528 0.03194999 0.182407 0.09482836 0.03194999 0.17839 0.09701776 0.03024995 0.176708 0.09857988 0.03024995 0.177074 0.09819358 0.03194999 0.1756899 0.09983438 0.03194999 0.1742219 0.102421 0.03194999 0.1734859 0.104596 0.03194999 0.173148 0.106865 0.03194999 0.173086 0.107393 0.03194999 0.173152 0.109157 0.03194999 0.173166 0.109539 0.03194999 0.173575 0.1116459 0.03194999 0.17427 0.113588 0.03024995 0.1742759 0.113586 0.03194999 0.176789 0.117408 0.03194999 0.177828 0.118416 0.03194999 0.179548 0.1197 0.03194999 0.180431 0.120167 0.03194999 0.181446 0.120703 0.03194999 0.184753 0.121631 0.03194999 0.1893219 0.12165 0.03194999 0.191542 0.121072 0.03194999 0.191545 0.121077 0.03024995 0.193437 0.120256 0.03194999 0.193643 0.120146 0.03024995 0.195255 0.119115 0.03194999 0.197218 0.1173 0.03194999 0.199728 0.113479 0.03024995 0.200464 0.111304 0.03194999 0.200801 0.109035 0.03194999 0.179275 0.11676 0.03194999 0.17631 0.112761 0.03194999 0.175371 0.115603 0.03194999 0.177447 0.112451 0.03344994 0.178398 0.112602 0.03214997 0.179221 0.113101 0.03214997 0.179121 0.113041 0.03344994 0.179794 0.113875 0.03344994 0.1794199 0.116595 0.03344994 0.1794199 0.116595 0.03214997 0.174304 0.113665 0.03194999 0.1756719 0.113048 0.03344994 0.1750209 0.111247 0.03344994 0.174809 0.105551 0.03344994 0.1735309 0.111417 0.03194999 0.175711 0.105729 0.03214997 0.175496 0.105687 0.03194999 0.175711 0.105729 0.03344994 0.177654 0.101247 0.03344994 0.178637 0.103811 0.03344994 0.1786569 0.102848 0.03214997 0.178254 0.104694 0.03344994 0.178637 0.103811 0.03214997 0.177565 0.105367 0.03214997 0.177368 0.105447 0.03214997 0.177368 0.105447 0.03344994 0.176674 0.1057299 0.03344994 0.194651 0.110842 0.03214997 0.193948 0.111728 0.03344994 0.193948 0.111728 0.03214997 0.193538 0.111667 0.03214997 0.1932139 0.11141 0.03214997 0.1932139 0.11141 0.03344994 0.1930609 0.111025 0.03344994 0.193122 0.110615 0.03344994 0.1930609 0.111025 0.03214997 0.193122 0.110615 0.03214997 0.1933799 0.110291 0.03344994 0.193765 0.1101379 0.03344994 0.194174 0.110199 0.03344994 0.194651 0.110842 0.03344994 0.187175 0.114985 0.03344994 0.187355 0.114758 0.03344994 0.187741 0.114606 0.03344994 0.1881499 0.1146669 0.03214997 0.1881499 0.1146669 0.03344994 0.188475 0.114924 0.03344994 0.188584 0.1155959 0.03214997 0.188584 0.1155959 0.03344994 0.188566 0.115719 0.03344994 0.188566 0.115719 0.03214997 0.188309 0.116043 0.03344994 0.187923 0.116196 0.03344994 0.187514 0.116135 0.03344994 0.187923 0.116196 0.03214997 0.187514 0.116135 0.03214997 0.187189 0.115877 0.03344994 0.187037 0.115492 0.03344994 0.187037 0.115492 0.03214997 0.187098 0.115083 0.03344994 0.187098 0.115083 0.03214997 0.179617 0.104324 0.03344994 0.179617 0.104324 0.03214997 0.180002 0.104172 0.03344994 0.180002 0.104172 0.03214997 0.1804119 0.104233 0.03344994 0.180736 0.10449 0.03344994 0.1808879 0.104875 0.03214997 0.180828 0.105285 0.03344994 0.18057 0.1056089 0.03344994 0.18057 0.1056089 0.03214997 0.1797749 0.105701 0.03344994 0.179451 0.105443 0.03344994 0.1792989 0.105058 0.03214997 0.186026 0.09970438 0.03344994 0.186334 0.09974998 0.03214997 0.1864359 0.09976506 0.03344994 0.18676 0.100023 0.03214997 0.18676 0.100023 0.03344994 0.186912 0.100408 0.03214997 0.186852 0.100817 0.03344994 0.186774 0.100915 0.03344994 0.186594 0.101142 0.03344994 0.186594 0.101142 0.03214997 0.1858 0.101233 0.03344994 0.1858 0.101233 0.03214997 0.185475 0.100976 0.03344994 0.185475 0.100976 0.03214997 0.1853229 0.100591 0.03214997 0.185365 0.100304 0.03214997 0.185384 0.100181 0.03344994 0.1922039 0.103574 0.03214997 0.181746 0.112326 0.03214997 0.181703 0.112613 0.03214997 0.179275 0.11676 0.03214997 0.190008 0.107175 0.03214997 0.191005 0.104877 0.03214997 0.190119 0.108139 0.03214997 0.1898649 0.109203 0.03214997 0.189262 0.110116 0.03214997 0.188847 0.110424 0.03214997 0.189994 0.107052 0.03214997 0.189505 0.106074 0.03214997 0.185566 0.105132 0.03214997 0.186615 0.104821 0.03214997 0.187707 0.104886 0.03214997 0.188711 0.105321 0.03214997 0.183831 0.107761 0.03214997 0.184688 0.1057839 0.03214997 0.1851029 0.105476 0.03214997 0.188383 0.110768 0.03214997 0.187335 0.111079 0.03214997 0.187487 0.112992 0.03214997 0.1862429 0.111014 0.03214997 0.185239 0.110579 0.03214997 0.184445 0.109826 0.03214997 0.183956 0.108848 0.03214997 0.183941 0.108725 0.03214997 0.1884829 0.110694 0.03214997 0.192638 0.112869 0.03214997 0.1910549 0.116519 0.03214997 0.190078 0.114381 0.03214997 0.1926749 0.116673 0.03214997 0.192541 0.117311 0.03214997 0.193405 0.117686 0.03214997 0.19539 0.116079 0.03214997 0.193391 0.11625 0.03214997 0.192867 0.11656 0.03214997 0.196296 0.114653 0.03214997 0.195637 0.113951 0.03214997 0.193857 0.113946 0.03214997 0.1933619 0.113278 0.03214997 0.195683 0.110063 0.03214997 0.1932809 0.105863 0.03214997 0.192128 0.1085219 0.03214997 0.19523 0.10897 0.03214997 0.193467 0.107414 0.03214997 0.1962479 0.108761 0.03214997 0.198476 0.105988 0.03214997 0.1972759 0.11017 0.03214997 0.198239 0.110171 0.03214997 0.196772 0.108452 0.03214997 0.197254 0.107774 0.03214997 0.197289 0.107601 0.03214997 0.197419 0.106959 0.03214997 0.196743 0.105479 0.03214997 0.194402 0.105256 0.03214997 0.194057 0.104072 0.03214997 0.195191 0.104992 0.03214997 0.192191 0.100947 0.03214997 0.191781 0.103085 0.03214997 0.18724 0.101117 0.03214997 0.188404 0.1005859 0.03214997 0.188395 0.09975469 0.03214997 0.193776 0.09848409 0.03214997 0.191679 0.09865188 0.03214997 0.192356 0.100132 0.03214997 0.178837 0.09960186 0.03214997 0.180305 0.102314 0.03214997 0.178313 0.101949 0.03214997 0.1785809 0.102649 0.03214997 0.181722 0.103114 0.03214997 0.177654 0.101247 0.03214997 0.182548 0.1030189 0.03214997 0.183264 0.102596 0.03214997 0.185467 0.105206 0.03214997 0.185202 0.102361 0.03214997 0.1857179 0.101169 0.03214997 0.183911 0.101103 0.03214997 0.183977 0.09970229 0.03214997 0.182511 0.09921467 0.03214997 0.179951 0.100726 0.03214997 0.180076 0.100327 0.03214997 0.180162 0.100176 0.03214997 0.1802819 0.09996306 0.03214997 0.1805509 0.09821677 0.03214997 0.181683 0.09913575 0.03214997 0.175496 0.105687 0.03214997 0.176674 0.1057299 0.03214997 0.175389 0.10632 0.03214997 0.176901 0.107762 0.03214997 0.176578 0.109356 0.03214997 0.175284 0.108415 0.03214997 0.175319 0.107717 0.03214997 0.178906 0.1114 0.03214997 0.178341 0.110912 0.03214997 0.177548 0.1106629 0.03214997 0.176924 0.110113 0.03214997 0.17913 0.107013 0.03214997 0.180835 0.1069509 0.03214997 0.180344 0.108083 0.03214997 0.18035 0.10809 0.03214997 0.181026 0.09787535 0.03214997 0.183266 0.09708458 0.03214997 0.184498 0.09850227 0.03214997 0.185641 0.09985655 0.03214997 0.184507 0.0985096 0.03214997 0.185384 0.100181 0.03214997 0.185434 0.09876906 0.03214997 0.186026 0.09970438 0.03214997 0.1864359 0.09976506 0.03214997 0.188717 0.0990076 0.03214997 0.188726 0.09899169 0.03214997 0.188243 0.09880208 0.03214997 0.189248 0.09648406 0.03214997 0.194048 0.100139 0.03214997 0.19453 0.09930527 0.03214997 0.192247 0.103287 0.03214997 0.192785 0.100771 0.03214997 0.192522 0.10284 0.03214997 0.193965 0.101283 0.03214997 0.1933169 0.102748 0.03214997 0.194155 0.102025 0.03214997 0.194729 0.1027989 0.03214997 0.197613 0.105613 0.03214997 0.196503 0.103449 0.03214997 0.198128 0.1044239 0.03214997 0.195369 0.113251 0.03214997 0.195313 0.112089 0.03214997 0.196385 0.1105329 0.03214997 0.190203 0.117981 0.03214997 0.192026 0.1184999 0.03214997 0.190684 0.118815 0.03214997 0.18839 0.117145 0.03214997 0.187189 0.115877 0.03214997 0.188309 0.116043 0.03214997 0.187559 0.117241 0.03214997 0.182577 0.114027 0.03214997 0.1817589 0.114953 0.03214997 0.185413 0.114917 0.03214997 0.185594 0.115729 0.03214997 0.18671 0.114783 0.03214997 0.183365 0.113762 0.03214997 0.184918 0.114249 0.03214997 0.183405 0.11774 0.03214997 0.182611 0.1174899 0.03214997 0.1818439 0.118465 0.03214997 0.182168 0.112815 0.03214997 0.18016 0.117447 0.03214997 0.181042 0.113213 0.03214997 0.181427 0.1130599 0.03214997 0.181685 0.112736 0.03214997 0.178386 0.1126 0.03214997 0.179794 0.113875 0.03214997 0.179949 0.114478 0.03214997 0.180552 0.1130869 0.03214997 0.180633 0.113152 0.03214997 0.180033 0.114807 0.03214997 0.179902 0.115761 0.03214997 0.180217 0.1121 0.03214997 0.1801559 0.112509 0.03214997 0.180308 0.1128939 0.03214997 0.17631 0.112761 0.03214997 0.177447 0.112451 0.03214997 0.175555 0.110495 0.03214997 0.176509 0.112671 0.03214997 0.17936 0.104649 0.03214997 0.178254 0.104694 0.03214997 0.179451 0.105443 0.03214997 0.1797749 0.105701 0.03214997 0.180185 0.105762 0.03214997 0.1804119 0.104233 0.03214997 0.182048 0.104152 0.03214997 0.180736 0.10449 0.03214997 0.187175 0.114985 0.03214997 0.187355 0.114758 0.03214997 0.187741 0.114606 0.03214997 0.188475 0.114924 0.03214997 0.189763 0.113979 0.03214997 0.188627 0.115309 0.03214997 0.188986 0.11577 0.03214997 0.180294 0.112002 0.03214997 0.179883 0.110395 0.03214997 0.180474 0.111775 0.03214997 0.180263 0.109861 0.03214997 0.180859 0.111623 0.03214997 0.181167 0.111669 0.03214997 0.18389 0.1082749 0.03214997 0.182945 0.111023 0.03214997 0.181683 0.110476 0.03214997 0.181269 0.111684 0.03214997 0.181593 0.111941 0.03214997 0.1864629 0.102908 0.03214997 0.186209 0.101294 0.03214997 0.193733 0.1037999 0.03214997 0.193656 0.103898 0.03214997 0.192681 0.104216 0.03214997 0.19006 0.107625 0.03214997 0.192356 0.103959 0.03214997 0.184085 0.106697 0.03214997 0.1828359 0.107818 0.03214997 0.184049 0.105019 0.03214997 0.180828 0.105285 0.03214997 0.190915 0.11132 0.03214997 0.1933799 0.110291 0.03214997 0.193765 0.1101379 0.03214997 0.194174 0.110199 0.03214997 0.194333 0.111576 0.03214997 0.19459 0.1112509 0.03214997 0.194499 0.110457 0.03214997 0.1944699 0.112862 0.03214997 0.186774 0.100915 0.03214997 0.186852 0.100817 0.03214997 0.193475 0.104125 0.03214997 0.19309 0.104277 0.03214997 0.192356 0.103959 0.03344994 0.1922039 0.103574 0.03344994 0.192265 0.103164 0.03214997 0.192265 0.103164 0.03344994 0.192908 0.102687 0.03214997 0.192908 0.102687 0.03344994 0.193641 0.103006 0.03344994 0.193641 0.103006 0.03214997 0.193794 0.103391 0.03344994 0.193794 0.103391 0.03214997 0.174697 0.109575 0.03344994 0.182621 0.09636467 0.03344994 0.176578 0.109356 0.03344994 0.176662 0.109538 0.03344994 0.187529 0.1128939 0.03344994 0.190783 0.111171 0.03344994 0.1915619 0.109939 0.03344994 0.1931149 0.108949 0.03344994 0.187119 0.1138409 0.03344994 0.1886529 0.11266 0.03344994 0.189229 0.114756 0.03344994 0.182995 0.110908 0.03344994 0.184678 0.112391 0.03344994 0.185961 0.112846 0.03344994 0.182161 0.109302 0.03344994 0.181975 0.107954 0.03344994 0.186413 0.103024 0.03344994 0.189855 0.103863 0.03344994 0.187313 0.102961 0.03344994 0.191929 0.108528 0.03344994 0.1934829 0.104943 0.03344994 0.191929 0.108435 0.03344994 0.194038 0.114758 0.03344994 0.1933619 0.113278 0.03344994 0.192638 0.112869 0.03344994 0.190432 0.115969 0.03344994 0.1926749 0.116673 0.03344994 0.193089 0.116429 0.03344994 0.194362 0.11791 0.03344994 0.195075 0.11729 0.03344994 0.193391 0.11625 0.03344994 0.196296 0.114653 0.03344994 0.1900849 0.115127 0.03344994 0.190086 0.115212 0.03344994 0.189972 0.116198 0.03344994 0.19181 0.11279 0.03344994 0.191901 0.111748 0.03344994 0.191021 0.113055 0.03344994 0.190749 0.111248 0.03344994 0.199365 0.108447 0.03344994 0.198239 0.110171 0.03344994 0.193628 0.107765 0.03344994 0.194436 0.10872 0.03344994 0.196582 0.110453 0.03344994 0.199329 0.107477 0.03344994 0.197254 0.107774 0.03344994 0.1972759 0.11017 0.03344994 0.196056 0.108875 0.03344994 0.193467 0.107414 0.03344994 0.191962 0.1084499 0.03344994 0.195044 0.1044999 0.03344994 0.194769 0.1051329 0.03344994 0.194402 0.105256 0.03344994 0.1960189 0.1050699 0.03344994 0.195191 0.104992 0.03344994 0.197419 0.106959 0.03344994 0.199294 0.106533 0.03344994 0.197238 0.106147 0.03344994 0.188404 0.1005859 0.03344994 0.191709 0.101624 0.03344994 0.1922709 0.100548 0.03344994 0.192785 0.100771 0.03344994 0.192175 0.09931987 0.03344994 0.191679 0.09865188 0.03344994 0.190955 0.09824317 0.03344994 0.191907 0.09657305 0.03344994 0.190096 0.09594929 0.03344994 0.1895239 0.09584689 0.03344994 0.188726 0.09899169 0.03344994 0.188719 0.09900838 0.03344994 0.180305 0.102314 0.03344994 0.181722 0.103114 0.03344994 0.183264 0.102596 0.03344994 0.184671 0.103512 0.03344994 0.183746 0.101918 0.03344994 0.180042 0.10174 0.03344994 0.178313 0.101949 0.03344994 0.1785809 0.102649 0.03344994 0.181084 0.09933686 0.03344994 0.181683 0.09913575 0.03344994 0.182511 0.09921467 0.03344994 0.183911 0.101103 0.03344994 0.183835 0.10076 0.03344994 0.184349 0.100983 0.03344994 0.18373 0.100291 0.03344994 0.183235 0.09962338 0.03344994 0.182041 0.107473 0.03344994 0.179854 0.107422 0.03344994 0.178266 0.105837 0.03344994 0.1816149 0.107289 0.03344994 0.18035 0.10809 0.03344994 0.176924 0.110113 0.03344994 0.177548 0.1106629 0.03344994 0.178341 0.110912 0.03344994 0.179686 0.111738 0.03344994 0.179167 0.110817 0.03344994 0.180095 0.110796 0.03344994 0.177703 0.107136 0.03344994 0.174656 0.109367 0.03344994 0.176578 0.109271 0.03344994 0.174621 0.108423 0.03344994 0.1765699 0.108525 0.03344994 0.174585 0.107453 0.03344994 0.177514 0.107199 0.03344994 0.183266 0.09708458 0.03344994 0.181408 0.09858858 0.03344994 0.1837469 0.0979188 0.03344994 0.1847569 0.10004 0.03344994 0.177565 0.105367 0.03344994 0.1786569 0.102848 0.03344994 0.176509 0.112671 0.03344994 0.1754299 0.112379 0.03344994 0.176337 0.110287 0.03344994 0.178398 0.112602 0.03344994 0.1801559 0.112509 0.03344994 0.179902 0.115761 0.03344994 0.181685 0.112736 0.03344994 0.181427 0.1130599 0.03344994 0.179884 0.118084 0.03344994 0.181042 0.113213 0.03344994 0.180633 0.113152 0.03344994 0.180033 0.114807 0.03344994 0.180308 0.1128939 0.03344994 0.179221 0.113101 0.03344994 0.185594 0.115729 0.03344994 0.1819649 0.114589 0.03344994 0.1816419 0.1161839 0.03344994 0.181988 0.11694 0.03344994 0.184426 0.120053 0.03344994 0.185413 0.114917 0.03344994 0.184918 0.114249 0.03344994 0.182168 0.112815 0.03344994 0.182577 0.114027 0.03344994 0.184947 0.117222 0.03344994 0.188183 0.117169 0.03344994 0.186715 0.117704 0.03344994 0.186109 0.118452 0.03344994 0.18882 0.115698 0.03344994 0.1894429 0.11739 0.03344994 0.188516 0.117131 0.03344994 0.1894519 0.117398 0.03344994 0.194182 0.118023 0.03344994 0.190684 0.118815 0.03344994 0.19459 0.1112509 0.03344994 0.194333 0.111576 0.03344994 0.193538 0.111667 0.03344994 0.194499 0.110457 0.03344994 0.199253 0.106325 0.03344994 0.195564 0.1033 0.03344994 0.196503 0.103449 0.03344994 0.197938 0.103005 0.03344994 0.19744 0.103229 0.03344994 0.193733 0.1037999 0.03344994 0.193892 0.104 0.03344994 0.1945289 0.102529 0.03344994 0.192522 0.10284 0.03344994 0.194155 0.102025 0.03344994 0.1933169 0.102748 0.03344994 0.193965 0.101283 0.03344994 0.193917 0.101093 0.03344994 0.1872349 0.09819579 0.03344994 0.188243 0.09880208 0.03344994 0.184507 0.0985096 0.03344994 0.185641 0.09985655 0.03344994 0.185322 0.09873777 0.03344994 0.187062 0.09829026 0.03344994 0.186912 0.100408 0.03344994 0.188627 0.115309 0.03344994 0.181746 0.112326 0.03344994 0.181593 0.111941 0.03344994 0.182577 0.111872 0.03344994 0.182705 0.1105509 0.03344994 0.181269 0.111684 0.03344994 0.180859 0.111623 0.03344994 0.180474 0.111775 0.03344994 0.180294 0.112002 0.03344994 0.180217 0.1121 0.03344994 0.186209 0.101294 0.03344994 0.185365 0.100304 0.03344994 0.1853229 0.100591 0.03344994 0.1868309 0.102059 0.03344994 0.19156 0.105955 0.03344994 0.192681 0.104216 0.03344994 0.19309 0.104277 0.03344994 0.193475 0.104125 0.03344994 0.193656 0.103898 0.03344994 0.181703 0.112613 0.03344994 0.18671 0.114783 0.03344994 0.17936 0.104649 0.03344994 0.179479 0.103038 0.03344994 0.1792989 0.105058 0.03344994 0.180185 0.105762 0.03344994 0.182828 0.10449 0.03344994 0.1808879 0.104875 0.03344994 0.18724 0.101117 0.03344994 0.191373 0.104028 0.03344994 0.191781 0.103085 0.03344994 0.192247 0.103287 0.03344994 0.176908 0.10071 0.03344994 0.176732 0.09859991 0.03194999 0.178143 0.09924638 0.03344994 0.178875 0.0986101 0.03344994 0.178406 0.09703618 0.03194999 0.179588 0.09799015 0.03344994 0.178695 0.09678536 0.03194999 0.179768 0.09787738 0.03344994 0.18121 0.09697157 0.03344994 0.180315 0.09576749 0.03194999 0.182316 0.09649586 0.03344994 0.180513 0.09564357 0.03194999 0.182969 0.09621477 0.03344994 0.1831949 0.09687727 0.03214997 0.18309 0.09656798 0.03344994 0.181809 0.118448 0.02574998 0.1818439 0.118465 0.02574998 0.196184 0.100734 0.02574998 0.198359 0.110651 0.02824997 0.198368 0.110612 0.02574998 0.196474 0.114781 0.03214997 0.191961 0.118534 0.02574998 0.175591 0.105249 0.02574998 0.175389 0.10632 0.02574998 0.177476 0.101119 0.03214997 0.177865 0.100608 0.03214997 0.177222 0.101487 0.02574998 0.177222 0.101487 0.02824997 0.176701 0.102353 0.03194999 0.176701 0.102353 0.02824997 0.175866 0.104277 0.02824997 0.175866 0.104277 0.03194999 0.177766 0.115166 0.02824997 0.177177 0.114345 0.02824997 0.177177 0.114345 0.03194999 0.178477 0.115992 0.02574998 0.178504 0.116021 0.02574998 0.178477 0.115992 0.03194999 0.178504 0.116021 0.02824997 0.177766 0.115166 0.02574998 0.1858659 0.119597 0.02824997 0.183804 0.119212 0.02824997 0.188003 0.119605 0.02574998 0.190029 0.119244 0.02824997 0.190029 0.119244 0.03194999 0.188003 0.119605 0.02824997 0.187964 0.119608 0.02574998 0.186875 0.11965 0.02824997 0.186875 0.11965 0.02574998 0.19539 0.116079 0.02824997 0.196728 0.114413 0.02574998 0.19771 0.112604 0.02824997 0.19771 0.112604 0.03194999 0.196728 0.114413 0.02824997 0.1967059 0.114446 0.02574998 0.1967059 0.114446 0.03194999 0.19606 0.115323 0.02824997 0.19606 0.115323 0.02574998 0.198566 0.1095409 0.02574998 0.198566 0.1095409 0.02824997 0.198368 0.110612 0.03194999 0.198454 0.110213 0.03194999 0.198454 0.110213 0.03214997 0.198121 0.104392 0.02574998 0.198109 0.104354 0.02574998 0.197306 0.102459 0.02824997 0.195446 0.09987926 0.02574998 0.195446 0.09987926 0.02824997 0.196184 0.100734 0.02824997 0.19616 0.100702 0.02574998 0.194718 0.09917879 0.02824997 0.188141 0.09630829 0.03214997 0.188141 0.09630829 0.03194999 0.185946 0.09629529 0.02574998 0.185946 0.09629529 0.02824997 0.1831949 0.09687727 0.03194999 0.184945 0.09642738 0.02824997 0.187075 0.09625035 0.02824997 0.187035 0.09625017 0.02574998 0.187075 0.09625035 0.02574998 0.195128 0.116305 0.03214997 0.1929579 0.118004 0.02574998 0.191997 0.118517 0.02574998 0.191961 0.118534 0.02824997 0.1907539 0.119023 0.03214997 0.193803 0.117451 0.03214997 0.193803 0.117451 0.02824997 0.1929579 0.118004 0.02824997 0.191997 0.118517 0.03214997 0.184715 0.119385 0.03214997 0.183804 0.119212 0.03214997 0.1828449 0.118897 0.02824997 0.180049 0.11738 0.03214997 0.180049 0.11738 0.02824997 0.181809 0.118448 0.02824997 0.1828449 0.118897 0.02574998 0.175555 0.110495 0.02574998 0.175841 0.111546 0.02574998 0.175841 0.111546 0.02824997 0.175546 0.110456 0.02824997 0.1761929 0.112493 0.02824997 0.1761929 0.112493 0.03214997 0.175546 0.110456 0.02574998 0.175384 0.106359 0.02574998 0.175591 0.105249 0.02824997 0.175384 0.106359 0.02824997 0.175284 0.108415 0.02824997 0.1754789 0.109915 0.03214997 0.17789 0.1005769 0.02824997 0.177865 0.100608 0.02574998 0.17789 0.1005769 0.02574998 0.180992 0.09789568 0.02574998 0.18292 0.09697508 0.03214997 0.18292 0.09697508 0.02824997 0.181989 0.09736567 0.02824997 0.179322 0.09909957 0.03214997 0.179322 0.09909957 0.02824997 0.180992 0.09789568 0.02824997 0.181026 0.09787535 0.02574998 0.181989 0.09736567 0.02574998 0.191142 0.09701728 0.02574998 0.191105 0.09700316 0.02574998 0.1921409 0.0974524 0.02824997 0.193027 0.0979371 0.02824997 0.191142 0.09701728 0.03214997 0.193027 0.0979371 0.03214997 0.189123 0.09644889 0.02824997 0.189123 0.09644889 0.03214997 0.191105 0.09700316 0.02824997 0.1921409 0.0974524 0.02574998 0.198403 0.105444 0.02824997 0.198577 0.106439 0.02824997 0.197306 0.102459 0.03194999 0.198121 0.104392 0.03214997 0.198109 0.104354 0.02824997 0.198403 0.105444 0.02574998 0.198577 0.106439 0.03214997 0.19866 0.108535 0.02824997 0.198647 0.10819 0.03214997 0.19866 0.108535 0.03214997 0.19929 0.111054 0.02574998 0.198359 0.110651 0.02574998 0.1994169 0.111109 0.02602344 0.1997539 0.111256 0.02674996 0.1997539 0.111256 0.02824997 0.1734859 0.104596 0.03024995 0.175306 0.100398 0.03024995 0.176708 0.09857988 0.02239996 0.17839 0.09701776 0.02239996 0.180307 0.0957539 0.02239996 0.1824049 0.0948227 0.02239996 0.184628 0.0942496 0.03024995 0.186915 0.0940501 0.03024995 0.186915 0.0940501 0.02239996 0.1914319 0.09478378 0.03024995 0.195465 0.09694427 0.02239996 0.197161 0.09849178 0.02239996 0.195465 0.09694427 0.03024995 0.198579 0.100297 0.03024995 0.200435 0.10448 0.02239996 0.2008219 0.106743 0.02239996 0.200832 0.109038 0.02239996 0.200832 0.109038 0.03024995 0.200464 0.111304 0.02239996 0.198644 0.1155019 0.02239996 0.19556 0.118882 0.02239996 0.197242 0.11732 0.03024995 0.187035 0.12185 0.03024995 0.184746 0.12167 0.03024995 0.182518 0.121116 0.02239996 0.1804119 0.120203 0.03024995 0.178485 0.118956 0.02239996 0.17427 0.113588 0.02239996 0.173515 0.11142 0.02239996 0.173515 0.11142 0.03024995 0.1731179 0.106862 0.03024995 0.1748639 0.1026999 0.02239996 0.174151 0.104822 0.02239996 0.1748639 0.1026999 0.03024995 0.174151 0.104822 0.03024995 0.173807 0.107034 0.03024995 0.1738409 0.109273 0.02239996 0.1738409 0.109273 0.03024995 0.174254 0.111473 0.02239996 0.174254 0.111473 0.03024995 0.175032 0.113573 0.03024995 0.176154 0.11551 0.02239996 0.176154 0.11551 0.03024995 0.177588 0.1172299 0.03024995 0.179291 0.118683 0.03024995 0.181215 0.119827 0.03024995 0.183305 0.12063 0.03024995 0.187739 0.121128 0.02239996 0.185501 0.121067 0.03024995 0.187739 0.121128 0.03024995 0.1899549 0.120809 0.03024995 0.192086 0.12012 0.03024995 0.194069 0.119082 0.03024995 0.195848 0.117723 0.02239996 0.197372 0.116083 0.02239996 0.195848 0.117723 0.03024995 0.197372 0.116083 0.03024995 0.198597 0.114208 0.02239996 0.198597 0.114208 0.03024995 0.199487 0.112154 0.03024995 0.199487 0.112154 0.02239996 0.200018 0.109979 0.03024995 0.200018 0.109979 0.02239996 0.200173 0.107746 0.03024995 0.199949 0.105518 0.02239996 0.199949 0.105518 0.03024995 0.199351 0.1033599 0.02239996 0.199351 0.1033599 0.03024995 0.1983979 0.101335 0.03024995 0.197115 0.09949946 0.03024995 0.195541 0.0979073 0.03024995 0.195541 0.0979073 0.02239996 0.1937209 0.09660398 0.02239996 0.1937209 0.09660398 0.03024995 0.191706 0.09562718 0.02239996 0.191706 0.09562718 0.03024995 0.187331 0.09475475 0.02239996 0.189556 0.09500479 0.03024995 0.187331 0.09475475 0.03024995 0.185096 0.09488439 0.02239996 0.185096 0.09488439 0.03024995 0.182915 0.0953899 0.02239996 0.182915 0.0953899 0.03024995 0.18085 0.09625679 0.02239996 0.18085 0.09625679 0.03024995 0.1789619 0.09745997 0.03024995 0.177305 0.09896498 0.02239996 0.177305 0.09896498 0.03024995 0.175925 0.100728 0.03024995 0.175925 0.100728 0.02239996 0.200173 0.107746 0.02239996 0.1983979 0.101335 0.02239996 0.19968 0.102312 0.02239996 0.197115 0.09949946 0.02239996 0.198579 0.100297 0.02239996 0.193538 0.09569686 0.02239996 0.1914319 0.09478378 0.02239996 0.189556 0.09500479 0.02239996 0.189204 0.09422987 0.02239996 0.184628 0.0942496 0.02239996 0.1789619 0.09745997 0.02239996 0.175306 0.100398 0.02239996 0.1742219 0.102421 0.02239996 0.1734859 0.104596 0.02239996 0.173807 0.107034 0.02239996 0.1731179 0.106862 0.02239996 0.1731269 0.109157 0.02239996 0.175032 0.113573 0.02239996 0.175371 0.115603 0.02239996 0.177588 0.1172299 0.02239996 0.176789 0.117408 0.02239996 0.179291 0.118683 0.02239996 0.181215 0.119827 0.02239996 0.1804119 0.120203 0.02239996 0.183305 0.12063 0.02239996 0.185501 0.121067 0.02239996 0.184746 0.12167 0.02239996 0.187035 0.12185 0.02239996 0.1899549 0.120809 0.02239996 0.1893219 0.12165 0.02239996 0.192086 0.12012 0.02239996 0.191545 0.121077 0.02239996 0.194069 0.119082 0.02239996 0.193643 0.120146 0.02239996 0.197242 0.11732 0.02239996 0.199728 0.113479 0.02239996 0.003092706 0.2120029 0.02039998 0.003420591 0.212288 0.02039998 -0.003092706 0.219797 0.02324998 -0.003092706 0.219797 0.02039998 -0.003896832 0.2128069 0.02039998 -0.002741336 0.220052 0.02324998 0.003612458 0.219321 0.02824997 0.002224683 0.22035 0.02324998 0.002224683 0.22035 0.02824997 0.001418173 0.220669 0.02324998 5.6858e-4 0.220842 0.02324998 5.6858e-4 0.220842 0.02824997 -2.98297e-4 0.220866 0.02324998 -2.98297e-4 0.220866 0.02824997 -0.001156091 0.220739 0.02324998 -0.001156091 0.220739 0.02824997 -0.001978754 0.220465 0.02324998 0.003896832 0.218993 0.02039998 0.003896832 0.218993 0.02324998 0.003092706 0.2120029 0.02324998 0.003420591 0.212288 0.02824997 -0.002224683 0.21145 0.02324998 -0.002224683 0.21145 0.02824997 -0.001418173 0.211131 0.02324998 -0.001418173 0.211131 0.02824997 -5.6858e-4 0.210958 0.02324998 2.98297e-4 0.210934 0.02324998 0.001156091 0.211061 0.02324998 0.001156091 0.211061 0.02824997 0.001978754 0.211335 0.02324998 0.002741336 0.211748 0.02324998 0.001978754 0.211335 0.02824997 0.002741336 0.211748 0.02824997 0.003995954 0.212936 0.02039998 0.004449844 0.213675 0.02039998 0.00476855 0.214482 0.02039998 0.00476855 0.214482 0.02824997 0.004942357 0.215331 0.02039998 0.00496602 0.216198 0.02039998 0.004838764 0.217056 0.02039998 0.004838764 0.217056 0.02824997 0.004564523 0.2178789 0.02039998 0.004151523 0.218641 0.02039998 0.003612458 0.219321 0.02324998 0.002963602 0.219896 0.02324998 -0.003420591 0.219512 0.02039998 -0.003995954 0.218864 0.02824997 -0.003995954 0.218864 0.02039998 -0.004449844 0.218125 0.02039998 -0.00476855 0.2173179 0.02039998 -0.004942357 0.216469 0.02039998 -0.00496602 0.215602 0.02039998 -0.004838764 0.214744 0.02824997 -0.004838764 0.214744 0.02039998 -0.004564523 0.213921 0.02039998 -0.004151523 0.213159 0.02039998 -0.003896832 0.2128069 0.02324998 -0.003612458 0.2124789 0.02324998 -0.002963602 0.211904 0.02324998 0.004942357 0.215331 0.02824997 0.004504323 0.214967 0.02824997 0.004598557 0.215786 0.02824997 0.004545032 0.216609 0.02824997 0.00496602 0.216198 0.02824997 0.004345357 0.217409 0.02824997 0.004564523 0.2178789 0.02824997 0.004006087 0.218161 0.02824997 0.004151523 0.218641 0.02824997 0.003538012 0.21884 0.02824997 0.002956271 0.219424 0.02824997 0.00227946 0.219895 0.02824997 0.002963602 0.219896 0.02824997 0.001529395 0.220238 0.02824997 7.30219e-4 0.2204419 0.02824997 0.001418173 0.220669 0.02824997 -9.24629e-5 0.220499 0.02824997 -9.12173e-4 0.220409 0.02824997 -0.001702547 0.220173 0.02824997 -0.001978754 0.220465 0.02824997 -0.002438187 0.219801 0.02824997 -0.002741336 0.220052 0.02824997 -0.003095507 0.219303 0.02824997 -0.003653347 0.218695 0.02824997 -0.003420591 0.219512 0.02824997 -0.004093706 0.217998 0.02824997 -0.004449844 0.218125 0.02824997 -0.004402518 0.217233 0.02824997 -0.00476855 0.2173179 0.02824997 -0.004569828 0.216426 0.02824997 -0.004590272 0.215601 0.02824997 -0.004942357 0.216469 0.02824997 -0.00496602 0.215602 0.02824997 -0.004463136 0.2147859 0.02824997 -0.00419259 0.214007 0.02824997 -0.004564523 0.213921 0.02824997 -0.003787279 0.213289 0.02824997 -0.003260254 0.212655 0.02824997 -0.004151523 0.213159 0.02824997 -0.003612458 0.2124789 0.02824997 -0.002963602 0.211904 0.02824997 -0.002628445 0.212125 0.02824997 -0.001912117 0.2117159 0.02824997 -0.001134335 0.2114419 0.02824997 -3.20167e-4 0.211311 0.02824997 -5.6858e-4 0.210958 0.02824997 5.04348e-4 0.211328 0.02824997 2.98297e-4 0.210934 0.02824997 0.001312613 0.211491 0.02824997 0.002078711 0.211796 0.02824997 0.002778053 0.212234 0.02824997 0.003388047 0.2127889 0.02824997 0.003889143 0.2134439 0.02824997 0.004265308 0.214177 0.02824997 0.003995954 0.212936 0.02824997 0.004449844 0.213675 0.02824997 0.00228554 0.2023749 0.02109998 0.003877401 0.2033129 0.02109998 0.00589621 0.204123 0.02109998 0.008309364 0.204986 0.02109998 0.007754206 0.205254 0.02109998 0.009400725 0.206676 0.02109998 0.009895026 0.2064 0.02109998 -0.01317477 0.212081 0.02109998 -0.01258367 0.212013 0.02109998 -0.01370924 0.2163659 0.02109998 -0.01265799 0.219538 0.02109998 -0.01285618 0.220683 0.02109998 -0.01188647 0.221572 0.02109998 -0.01196336 0.222611 0.02109998 -0.004758894 0.223838 0.01739996 -0.004901707 0.222597 0.01889997 -0.004758894 0.223838 0.01889997 -0.005408585 0.222194 0.01739996 -0.005548655 0.224498 0.01889997 -0.005762875 0.224583 0.01889997 -0.005762875 0.224583 0.01739996 -0.006402909 0.224488 0.01889997 -0.006402909 0.224488 0.01739996 -0.006909728 0.224086 0.01739996 -0.007113754 0.223256 0.01889997 -0.00714755 0.223484 0.01739996 -0.0070526 0.222844 0.01739996 -0.0070526 0.222844 0.01889997 0.01073318 0.213073 0.01739996 -0.00302577 0.2185159 0.01739996 -0.003662467 0.217508 0.01739996 0.006604909 0.215613 0.01739996 0.002826929 0.226633 0.01739996 0.01109474 0.216216 0.01739996 -3.1586e-4 0.226995 0.01739996 -6.08628e-4 0.226775 0.01739996 -0.002335488 0.226751 0.01739996 0.007048964 0.21644 0.01739996 0.007767081 0.217046 0.01739996 0.006763458 0.219726 0.01739996 0.008657872 0.217343 0.01739996 0.007270276 0.220129 0.01739996 0.006490707 0.224904 0.01739996 0.006409108 0.222115 0.01739996 0.007010877 0.221877 0.01739996 0.007413148 0.22137 0.01739996 0.00802499 0.223568 0.01739996 0.009289622 0.221974 0.01739996 0.007508099 0.22073 0.01739996 0.01024216 0.2201769 0.01739996 0.009595632 0.2172909 0.01739996 0.01085078 0.218236 0.01739996 0.01044809 0.216897 0.01739996 0.005119383 0.220376 0.01739996 0.003997504 0.21604 0.01739996 0.005262255 0.2216179 0.01739996 0.005769073 0.22202 0.01739996 0.00473845 0.225937 0.01739996 0.003423094 0.224153 0.01739996 0.003528118 0.225066 0.01739996 -0.001178383 0.226054 0.01739996 -0.001449286 0.225176 0.01739996 -9.93603e-4 0.223429 0.01739996 0.003778576 0.217212 0.01739996 0.003223896 0.218268 0.01739996 0.005024433 0.221016 0.01739996 0.002382755 0.2191129 0.01739996 0.001329898 0.219672 0.01739996 1.5891e-4 0.219897 0.01739996 -0.001026213 0.219766 0.01739996 -0.002120196 0.219292 0.01739996 -7.52833e-4 0.211971 0.01739996 4.38564e-4 0.211924 0.01739996 0.005521655 0.219869 0.01739996 0.003861248 0.214856 0.01739996 0.006123423 0.219631 0.01739996 0.006497561 0.21468 0.01739996 -0.003931939 0.215166 0.01739996 -0.004656255 0.2122049 0.01739996 -0.003540813 0.214039 0.01739996 -0.002834975 0.213078 0.01739996 -0.001877307 0.212368 0.01739996 0.00994873 0.212557 0.01739996 0.010037 0.211162 0.01739996 0.00902903 0.212366 0.01739996 0.008103966 0.212528 0.01739996 0.007304012 0.21302 0.01739996 0.001590967 0.21223 0.01739996 0.006742119 0.213773 0.01739996 0.00260204 0.212862 0.01739996 0.003381907 0.213764 0.01739996 -0.00900352 0.222391 0.01739996 -0.007667601 0.2239249 0.01739996 -0.006048619 0.222099 0.01739996 -0.008103966 0.219272 0.01739996 -0.003973782 0.2163569 0.01739996 -0.004663944 0.2231979 0.01739996 -0.004901707 0.222597 0.01739996 -0.005161106 0.224345 0.01739996 -0.00607419 0.22519 0.01739996 -0.004276633 0.226142 0.01739996 -0.003007054 0.22654 0.01739996 -0.006650388 0.222337 0.01739996 -0.010037 0.220638 0.01739996 -0.00902903 0.219434 0.01739996 -0.00994873 0.219243 0.01739996 -0.01073318 0.2187269 0.01739996 -0.01109474 0.215584 0.01739996 -0.006604909 0.216187 0.01739996 -0.01085078 0.213565 0.01739996 -0.008657872 0.214457 0.01739996 -0.007767081 0.214754 0.01739996 -0.007048964 0.21536 0.01739996 -0.006497561 0.2171199 0.01739996 -0.006742119 0.2180269 0.01739996 -0.007304012 0.21878 0.01739996 -0.005521655 0.211931 0.01739996 -0.0106402 0.212893 0.01739996 -0.009595632 0.214509 0.01739996 -0.01044809 0.2149029 0.01739996 -0.006123423 0.212169 0.01739996 -0.006763458 0.212074 0.01739996 -0.007270276 0.2116709 0.01739996 -0.007508099 0.21107 0.01739996 -0.01024216 0.211623 0.01739996 -0.009289622 0.2098259 0.01739996 -0.007413148 0.21043 0.01739996 -0.007010877 0.209923 0.01739996 -0.00802499 0.208232 0.01739996 -0.006409108 0.209685 0.01739996 -0.006490707 0.206896 0.01739996 -0.005769073 0.20978 0.01739996 -0.005262255 0.210182 0.01739996 -0.005344629 0.206221 0.01739996 -0.005024433 0.210784 0.01739996 -0.005119383 0.2114239 0.01739996 0.005762875 0.207217 0.01739996 0.00607419 0.20661 0.01739996 0.006048619 0.209701 0.01739996 0.005408585 0.209606 0.01739996 0.004663944 0.208602 0.01739996 0.006402909 0.207312 0.01739996 3.1586e-4 0.204805 0.01739996 0.002335488 0.205049 0.01739996 9.96971e-4 0.205452 0.01739996 0.004276633 0.205658 0.01739996 0.006909728 0.207714 0.01739996 0.00714755 0.208316 0.01739996 0.007667601 0.207875 0.01739996 0.00900352 0.2094089 0.01739996 0.009679377 0.210555 0.01739996 0.0070526 0.208956 0.01739996 0.006650388 0.209463 0.01739996 -0.002879559 0.208596 0.01739996 -0.003371715 0.207796 0.01739996 -0.003533959 0.206871 0.01739996 -0.003343403 0.205951 0.01739996 -0.00473845 0.2058629 0.01739996 -0.002826929 0.2051669 0.01739996 0.005161106 0.207455 0.01739996 0.001391351 0.206304 0.01739996 0.004758894 0.207962 0.01739996 0.001443445 0.207242 0.01739996 0.00114578 0.208133 0.01739996 0.004901707 0.209203 0.01739996 5.40463e-4 0.208851 0.01739996 -2.8714e-4 0.209295 0.01739996 -0.001220166 0.209402 0.01739996 -0.002126991 0.209158 0.01739996 0.002753376 0.226694 0.01741605 0.002758979 0.2267 0.01889997 0.001988768 0.227201 0.01754516 0.002398252 0.226986 0.0174939 0.001089632 0.2273899 0.01757097 0.001549243 0.227337 0.01757085 0.003296315 0.225955 0.01739996 0.002995491 0.22334 0.01739996 0.002303004 0.222737 0.01739996 0.002303004 0.222737 0.01889997 0.001439154 0.222424 0.01739996 5.20642e-4 0.2224439 0.01739996 5.20642e-4 0.2224439 0.01889997 -3.28508e-4 0.222795 0.01739996 -9.93603e-4 0.223429 0.01889997 -0.001384794 0.22426 0.01889997 -0.001384794 0.22426 0.01739996 -0.001449286 0.225176 0.01889997 -0.001178383 0.226054 0.01889997 -6.08628e-4 0.226775 0.01889997 1.83022e-4 0.227241 0.01749408 6.29886e-4 0.227358 0.01754516 8.01933e-5 0.203157 0.01889997 0.002029657 0.203326 0.01889997 -0.003209829 0.210317 0.01889997 -0.004047036 0.210938 0.01889997 0.005262255 0.2216179 0.01889997 -0.005498349 0.209995 0.01889997 -0.01030755 0.222421 0.01889997 -0.006650388 0.222337 0.01889997 -0.004340529 0.221369 0.01889997 -0.005820751 0.222133 0.01889997 -0.006048619 0.222099 0.01889997 -0.00714755 0.223484 0.01889997 -0.007181048 0.225759 0.01889997 -0.006909728 0.224086 0.01889997 -0.005460381 0.226806 0.01889997 -0.005274534 0.226881 0.01889997 -0.005161106 0.224345 0.01889997 -0.00416249 0.222917 0.01889997 -0.004663944 0.2231979 0.01889997 -0.004748582 0.222984 0.01889997 -0.005408585 0.222194 0.01889997 -0.01221799 0.212278 0.01889997 -0.007302403 0.209254 0.01889997 -0.006409108 0.209685 0.01889997 -0.007010877 0.209923 0.01889997 -0.007198274 0.210159 0.01889997 -0.004280745 0.2089059 0.01889997 -0.005754768 0.209076 0.01889997 -0.005664229 0.209863 0.01889997 -0.005769073 0.20978 0.01889997 -0.005262255 0.210182 0.01889997 -0.005024433 0.210784 0.01889997 -0.004410862 0.211208 0.01889997 -0.005119383 0.2114239 0.01889997 -0.005438387 0.211826 0.01889997 -0.006999552 0.211886 0.01889997 -0.005377233 0.2123579 0.01889997 -0.005374073 0.212351 0.01889997 -0.005521655 0.211931 0.01889997 0.007270276 0.220129 0.01889997 0.007165431 0.220045 0.01889997 0.008130729 0.221502 0.01889997 0.007413148 0.22137 0.01889997 0.007508099 0.22073 0.01889997 0.008390426 0.225492 0.01889997 0.005498349 0.221805 0.01889997 0.005769073 0.22202 0.01889997 0.004921197 0.2276549 0.01889997 0.006743133 0.226714 0.01889997 0.007700145 0.226004 0.01889997 0.006409108 0.222115 0.01889997 0.007010877 0.221877 0.01889997 0.007175683 0.213201 0.01889997 0.006962776 0.2134039 0.01889997 0.006571531 0.214235 0.01889997 0.006507039 0.215151 0.01889997 0.006847083 0.218589 0.01889997 0.006778001 0.216029 0.01889997 0.007347762 0.21675 0.01889997 0.007601141 0.216899 0.01889997 0.008139371 0.217216 0.01889997 0.009046018 0.217365 0.01889997 0.008477032 0.212419 0.01889997 0.007627844 0.21277 0.01889997 0.01198267 0.217998 0.01889997 0.01071536 0.216675 0.01889997 0.0112527 0.21593 0.01889997 0.0114845 0.215041 0.01889997 0.01119339 0.211136 0.01889997 0.01095187 0.213315 0.01889997 -0.00574398 0.2130849 0.01889997 -0.006763458 0.212074 0.01889997 -0.006123423 0.212169 0.01889997 -0.006055593 0.218092 0.01889997 -0.006397783 0.216636 0.01889997 -0.006395041 0.2151409 0.01889997 -0.006047606 0.213686 0.01889997 0.00256145 0.209991 0.01889997 0.001129806 0.20956 0.01889997 -3.62767e-4 0.20947 0.01889997 -0.004173099 0.209842 0.01889997 -0.001835763 0.209727 0.01889997 0.004940807 0.211769 0.01889997 0.006263673 0.217397 0.01889997 0.006439983 0.215912 0.01889997 0.006269097 0.214426 0.01889997 0.005760192 0.21302 0.01889997 0.0049932 0.211849 0.01889997 -3.86138e-4 0.222328 0.01889997 0.001106739 0.222244 0.01889997 0.002539992 0.221818 0.01889997 0.003836274 0.221073 0.01889997 -0.003496825 0.221272 0.01889997 -0.003230094 0.221471 0.01889997 -0.002814531 0.221652 0.01889997 -0.001858174 0.222066 0.01889997 -0.005386948 0.219429 0.01889997 -0.004954576 0.219946 0.01889997 -0.005888164 0.221547 0.01889997 -0.00443238 0.220571 0.01889997 -0.00442785 0.220576 0.01889997 0.003855049 0.210741 0.01889997 0.00281322 0.210137 0.01889997 0.004901707 0.209203 0.01889997 0.004748582 0.208816 0.01889997 0.004663944 0.208602 0.01889997 0.002580761 0.208117 0.01889997 0.004842102 0.207857 0.01889997 0.004758894 0.207962 0.01889997 0.01025938 0.212712 0.01889997 0.009395539 0.212399 0.01889997 0.00699377 0.211619 0.01889997 0.006733596 0.209358 0.01889997 0.006909728 0.207714 0.01889997 0.00714755 0.208316 0.01889997 0.007113754 0.208544 0.01889997 0.0070526 0.208956 0.01889997 0.009497106 0.20827 0.01889997 0.005408585 0.209606 0.01889997 0.005820751 0.209667 0.01889997 0.006048619 0.209701 0.01889997 0.006057739 0.211727 0.01889997 0.006650388 0.209463 0.01889997 -0.001547932 0.204463 0.01889997 2.34406e-4 0.204755 0.01889997 0.00204581 0.2034659 0.01889997 9.92902e-4 0.2082999 0.01889997 0.001227676 0.207974 0.01889997 0.001459479 0.207085 0.01889997 0.001354515 0.206172 0.01889997 9.26903e-4 0.205359 0.01889997 -0.00239706 0.204813 0.01889997 -0.003517866 0.207195 0.01889997 -0.003246963 0.208073 0.01889997 -0.002729296 0.208728 0.01889997 -0.002677202 0.2087939 0.01889997 -0.001885533 0.20926 0.01889997 -9.78961e-4 0.2094089 0.01889997 0.002688467 0.209053 0.01889997 -7.9815e-5 0.2092199 0.01889997 6.90422e-4 0.208719 0.01889997 -0.008036196 0.219245 0.01889997 -0.007029473 0.215384 0.01889997 -0.007265925 0.218744 0.01889997 -0.006728649 0.217999 0.01889997 -0.006496846 0.21711 0.01889997 -0.00660187 0.216197 0.01889997 -0.00772196 0.21478 0.01889997 -0.00858581 0.214467 0.01889997 -0.006847083 0.2132109 0.01889997 -0.01255315 0.213868 0.01889997 -0.009504318 0.214488 0.01889997 -0.01264089 0.214284 0.01889997 -0.01035344 0.214838 0.01889997 -0.01101857 0.215472 0.01889997 -0.01140975 0.216304 0.01889997 -0.01250195 0.21837 0.01889997 -0.01147425 0.21722 0.01889997 -0.01120334 0.218098 0.01889997 -0.01063358 0.218819 0.01889997 -0.01176375 0.22073 0.01889997 -0.009841978 0.219285 0.01889997 -0.01090764 0.22249 0.01889997 -0.01107627 0.222202 0.01889997 -0.01110208 0.222147 0.01889997 -0.006057739 0.220073 0.01889997 -0.008935332 0.219434 0.01889997 -0.003590762 0.227556 0.01889997 0.001988768 0.227201 0.01889997 0.002995491 0.22334 0.01889997 0.003296315 0.225955 0.01889997 0.002971827 0.228292 0.01889997 0.00483185 0.227684 0.01889997 0.003528118 0.225066 0.01889997 0.003423094 0.224153 0.01889997 0.004173099 0.221958 0.01889997 0.001439154 0.222424 0.01889997 -0.002688467 0.222747 0.01889997 -3.28508e-4 0.222795 0.01889997 1.83022e-4 0.227241 0.01889997 0.001089632 0.2273899 0.01889997 0.01080089 0.221566 0.01889997 0.007198274 0.221641 0.01889997 0.007225751 0.221607 0.01889997 0.008568584 0.225309 0.01889997 0.009820461 0.224022 0.01889997 0.01098167 0.221174 0.01889997 0.01191306 0.2185159 0.01889997 0.007783114 0.218481 0.01889997 0.009945154 0.217176 0.01889997 0.005024433 0.221016 0.01889997 0.005119383 0.220376 0.01889997 0.004048287 0.2208729 0.01889997 0.004617214 0.220339 0.01889997 0.005202651 0.220271 0.01889997 0.005521655 0.219869 0.01889997 0.004925787 0.220049 0.01889997 0.005749702 0.218801 0.01889997 0.006123423 0.219631 0.01889997 0.005782544 0.218711 0.01889997 0.006763458 0.219726 0.01889997 0.006999552 0.219914 0.01889997 0.00795269 0.219955 0.01889997 0.01137948 0.214128 0.01889997 0.01149529 0.211932 0.01889997 0.01172238 0.212531 0.01889997 0.01218116 0.2165189 0.01889997 0.002123355 0.203334 0.01889997 0.002457559 0.203419 0.01889997 0.005161106 0.207455 0.01889997 0.005204677 0.204312 0.01889997 0.005548655 0.207302 0.01889997 0.005993187 0.204653 0.01889997 0.005762875 0.207217 0.01889997 0.006402909 0.207312 0.01889997 0.00620824 0.204791 0.01889997 0.007719635 0.20576 0.01889997 0.006507813 0.207395 0.01889997 0.006804883 0.207631 0.01889997 0.00924617 0.20713 0.01889997 -0.002605795 0.204002 0.01889997 -2.53078e-4 0.203159 0.01889997 -4.93347e-4 0.2037129 0.01889997 -6.29438e-4 0.204442 0.01889997 -0.003062188 0.205447 0.01889997 -0.003453373 0.206279 0.01889997 -0.006143867 0.205363 0.01889997 -0.006179034 0.205388 0.01889997 -0.01151895 0.21189 0.01889997 -0.007270276 0.2116709 0.01889997 -0.007508099 0.21107 0.01889997 -0.007413148 0.21043 0.01889997 -0.007225751 0.210193 0.01889997 -0.01044726 0.209616 0.01889997 -0.01321607 0.21742 0.02139997 -0.01373815 0.214144 0.02139997 -0.0123468 0.210947 0.02139997 -0.0113486 0.207961 0.02139997 -0.009928047 0.206243 0.02139997 -0.006701111 0.204408 0.02139997 -0.008250415 0.204776 0.02139997 -0.0063591 0.2035959 0.02139997 -0.004303097 0.202735 0.02139997 0.001770436 0.202715 0.02139997 0.003916442 0.203186 0.02139997 0.004468381 0.202791 0.02139997 0.005955636 0.204004 0.02139997 0.006513416 0.2036769 0.02139997 0.007832407 0.205147 0.02139997 0.01144754 0.208104 0.02139997 0.01200628 0.210171 0.02139997 0.01375925 0.214317 0.02139997 0.01328605 0.216576 0.02139997 0.01299369 0.218753 0.02139997 0.0123468 0.220853 0.02139997 0.01195055 0.2229 0.02139997 0.01006954 0.2245939 0.02139997 0.01067286 0.224727 0.02139997 0.008501291 0.226132 0.02139997 0.009118795 0.226324 0.02139997 0.00732851 0.227652 0.02139997 0.004718184 0.228338 0.02139997 0.002606511 0.228945 0.02139997 0.005348443 0.228676 0.02139997 4.23825e-4 0.229196 0.02139997 0.003229796 0.229368 0.02139997 0.001027524 0.229712 0.02139997 -0.001770436 0.229085 0.02139997 -0.00550878 0.2286069 0.02139997 -0.007832407 0.226653 0.02139997 -0.007475852 0.227559 0.02139997 -0.0108996 0.223527 0.02139997 -0.01200628 0.221629 0.02139997 -0.01278555 0.219575 0.02139997 -0.01298058 0.22073 0.02139997 -0.01015955 0.222676 0.01893377 -0.009993135 0.2228929 0.01889997 -4.23825e-4 0.2026039 0.02139997 0.001752793 0.202847 0.02109998 0.009993135 0.208907 0.01889997 0.009232044 0.207929 0.01889997 0.0108996 0.2082729 0.02139997 0.01025974 0.208226 0.02029079 0.01016014 0.207746 0.02077686 0.009495437 0.206583 0.02139997 0.01143449 0.220812 0.01946008 0.01175975 0.221213 0.02049785 0.01169526 0.220935 0.02011168 0.01131105 0.22088 0.01926535 0.01132005 0.220441 0.01889997 0.01117897 0.221001 0.01910549 0.01104587 0.221166 0.01898986 0.01091855 0.221358 0.01892197 0.006701111 0.227392 0.02139997 0.009969055 0.224507 0.02109998 0.01124978 0.2227489 0.02109998 0.01136314 0.222818 0.02139997 0.01143938 0.222427 0.02109998 0.01163458 0.221996 0.02101916 0.01173979 0.221579 0.0208081 0.002925336 0.228741 0.02109998 0.002286911 0.227881 0.01889997 0.001869678 0.227986 0.01897448 0.001684963 0.228056 0.01907038 0.001530706 0.228136 0.01920437 0.001370191 0.2284899 0.01995557 0.001539826 0.228636 0.0203278 0.001817286 0.228742 0.02064615 0.002170801 0.228798 0.02089476 0.002576589 0.228796 0.02105468 -0.008705854 0.224442 0.01889997 -0.01002329 0.223453 0.01969885 -0.009466528 0.223527 0.01889997 -0.009963929 0.223277 0.01935315 -0.009981155 0.223128 0.01918637 -0.01004338 0.222928 0.01903849 -0.01063287 0.223341 0.02066439 -0.0108273 0.223195 0.02084028 -0.01315349 0.215231 0.02109998 -0.01328605 0.215224 0.02139997 -0.01308417 0.217405 0.02109998 -0.01137226 0.222543 0.02109998 -0.01120549 0.222793 0.02106696 -0.01102179 0.22301 0.02097755 -0.01247894 0.2117339 0.0210675 -0.01299369 0.213047 0.02139997 -0.01286399 0.213075 0.02109998 -0.01158875 0.210792 0.01995676 -0.01177448 0.210851 0.02028828 -0.01136314 0.208982 0.02139997 -0.01204466 0.211068 0.02066439 -0.01227647 0.211362 0.02091449 -0.01143264 0.2116079 0.01893389 -0.01132005 0.211359 0.01889997 -0.01137697 0.211336 0.01903849 -0.01095116 0.210622 0.01889997 -0.01136398 0.211077 0.01923495 -0.01141136 0.210892 0.01949834 -0.001407682 0.203161 0.02029955 -0.002606511 0.202855 0.02139997 -6.70663e-5 0.20273 0.02109998 -4.18958e-4 0.202756 0.02105468 -8.70144e-4 0.202864 0.02086186 -0.001232206 0.2030299 0.0205549 -0.001526534 0.203452 0.01967775 -0.001443266 0.203558 0.01941758 -0.001245796 0.203649 0.0191648 -9.22253e-4 0.203705 0.018974 -0.002389788 0.203939 0.01889997 0.0110079 0.210647 0.01889997 0.01278555 0.212225 0.02139997 -0.00153017 0.203348 0.01991248 -0.00476408 0.2047049 0.01889997 -0.004718184 0.203462 0.02139997 -0.004325866 0.204496 0.01889997 -0.01147425 0.210822 0.01969259 -0.01041829 0.209558 0.01889997 -0.009232223 0.207929 0.01889997 -0.01006954 0.207206 0.02139997 -0.00779438 0.2065179 0.01889997 -0.008501291 0.205668 0.02139997 -0.007630288 0.206404 0.01889997 -0.0103603 0.223478 0.02034449 -0.01013165 0.223507 0.01996839 -0.009495437 0.225217 0.02139997 -0.005955636 0.227796 0.02139997 -0.003630578 0.22754 0.01889997 0.001418471 0.228224 0.01937019 0.001354515 0.2283149 0.01955807 3.88581e-4 0.228091 0.01889997 -0.001623213 0.227988 0.01889997 -0.002097487 0.2278839 0.01889997 -0.003916442 0.228614 0.02139997 0.01159906 0.2195349 0.01889997 0.01163005 0.2208459 0.01989668 0.01154255 0.220802 0.01967567 0.01209604 0.217154 0.01889997 0.01321607 0.21438 0.02139997 0.01211708 0.214506 0.01889997 0.003279745 0.229219 0.02109998 0.004671096 0.228214 0.02109998 0.006634294 0.2272779 0.02109998 0.007258296 0.22754 0.02109998 0.009031414 0.226225 0.02109998 0.008416473 0.2260299 0.02109998 -0.01273638 0.216333 0.01889997 -0.01218318 0.214343 0.01785719 -4.87411e-4 0.2031559 0.01892137 -7.12269e-4 0.203137 0.01898735 -9.15465e-4 0.203101 0.01909875 -0.001083672 0.203046 0.01925247 -0.001204609 0.202973 0.01944005 -0.002135574 0.202216 0.02139997 -0.001284122 0.202794 0.0198611 -0.001249015 0.202697 0.02007198 -0.001063764 0.202511 0.02045458 -7.59651e-4 0.20235 0.02076917 -3.66639e-4 0.202235 0.02099364 8.71547e-5 0.20205 0.02139997 7.72897e-5 0.203618 0.01785719 0.003962635 0.2042739 0.01785719 0.002046465 0.2037889 0.01785719 0.004111468 0.203838 0.01889997 0.009429872 0.207329 0.01889997 0.007440149 0.206128 0.01785719 0.005776166 0.205061 0.01785719 0.01012855 0.206682 0.02105039 0.01027357 0.206909 0.02095258 0.01048398 0.207436 0.02054995 0.01050865 0.207652 0.02029055 0.01026427 0.207943 0.01944994 0.01015186 0.2089869 0.01785719 0.009683072 0.2075909 0.01893597 0.00947237 0.207375 0.01889997 0.008911371 0.207448 0.01785719 0.00645101 0.203794 0.02109998 0.00838977 0.2048799 0.02139997 0.01004874 0.206369 0.02139997 8.6312e-5 0.202184 0.02109736 1.69584e-4 0.202184 0.02109998 0.002307653 0.202244 0.02139997 0.004425585 0.202916 0.02109998 -0.01079237 0.2226949 0.01892155 -0.01067519 0.221974 0.01785719 -0.01069635 0.222899 0.01898759 -0.01062625 0.223093 0.01909917 -0.01059007 0.223266 0.01925337 -0.01059269 0.223407 0.01944094 -0.01070857 0.223565 0.01986187 -0.01080995 0.223583 0.0200721 -0.01078319 0.224592 0.02139997 -0.01106417 0.223516 0.02045518 -0.0113554 0.223332 0.02077007 -0.01165205 0.223049 0.02099418 -0.01151138 0.220183 0.01785719 -0.01194375 0.220344 0.01889997 -0.01204925 0.218281 0.01785719 -0.01220178 0.217304 0.01785719 -0.01227515 0.2163169 0.01785719 -0.01177567 0.212409 0.01785719 -0.01212918 0.210878 0.0197677 -0.01248216 0.210979 0.02042227 -0.01327866 0.2119629 0.02139997 -0.01305305 0.21175 0.02105396 -0.01293754 0.2115229 0.02096569 -0.01267027 0.211151 0.02067887 -0.01203155 0.210972 0.01948314 -0.01198148 0.211184 0.01919907 -0.01200884 0.211529 0.01898127 -0.01205396 0.211736 0.01892119 -0.01211905 0.211959 0.01889997 -0.01314598 0.212002 0.02108907 -0.01384198 0.2163709 0.02139997 -0.01360654 0.214161 0.02109998 -0.013457 0.218559 0.02109998 -0.01375925 0.217483 0.02139997 -0.01358729 0.218585 0.02139997 -0.01203775 0.2227489 0.02139997 -0.01192134 0.222683 0.02109736 0.01128 0.22185 0.01892125 0.01116079 0.222051 0.01889997 0.01140826 0.221665 0.01898699 0.01154106 0.221508 0.01909786 0.01167285 0.2213889 0.01925116 0.01179605 0.221321 0.01943814 0.01190316 0.221305 0.01964396 0.01199138 0.22134 0.01985806 0.01205807 0.221418 0.02006858 0.01212716 0.22167 0.02045065 0.01211434 0.222015 0.02076786 0.01201808 0.222414 0.02099329 0.0109961 0.222341 0.01889997 0.010598 0.222108 0.01785719 0.009464859 0.223728 0.01785719 0.008086621 0.225145 0.01785719 0.006498992 0.2263219 0.01785719 0.002864241 0.2278439 0.01785719 0.004743039 0.22723 0.01785719 0.001715481 0.228915 0.01976728 0.001747965 0.228784 0.01948255 0.001978933 0.229171 0.02042216 0.002222359 0.229247 0.02067846 0.002677619 0.229293 0.02096539 9.11258e-4 0.228148 0.01785719 0.001907587 0.2286339 0.01919829 0.002220153 0.228485 0.0189808 0.002421736 0.228421 0.01892089 0.002646744 0.228366 0.01889997 0.00319761 0.229234 0.02108919 0.002934217 0.229279 0.0210545 0.005297183 0.2285529 0.02109998 0.01183509 0.222833 0.02109736 0.01179379 0.222905 0.02109998 0.01057058 0.224642 0.02109998 -0.01224458 0.210867 0.02001869 -0.01247519 0.209884 0.02139997 -0.01106309 0.210565 0.01785719 -0.01006406 0.208859 0.01785719 -0.008804321 0.207336 0.01785719 -0.007316529 0.206035 0.01785719 -0.005639314 0.204989 0.01785719 -0.003816008 0.204226 0.01785719 -0.001271009 0.202888 0.01964676 -0.001893877 0.203765 0.01785719 0.001763045 0.229021 0.02001816 -0.001065313 0.228136 0.01785719 -0.001201272 0.229698 0.02139997 -0.003014326 0.227807 0.01785719 -0.003399074 0.229326 0.02139997 -0.004885256 0.227169 0.01785719 -0.009249269 0.226209 0.02139997 -0.006629645 0.226239 0.01785719 -0.008202373 0.225042 0.01785719 -0.01063358 0.223507 0.01964718 -0.009562611 0.223608 0.01785719 0.01039707 0.207918 0.01972258 0.01254987 0.210041 0.02139997 0.01112937 0.210705 0.01785719 0.01332718 0.21213 0.02139997 0.01181864 0.212557 0.01785719 0.01220178 0.214496 0.01785719 0.01383495 0.216545 0.02139997 0.01226896 0.216472 0.01785719 0.01355236 0.218756 0.02139997 0.01291877 0.220893 0.02139997 0.01201838 0.218432 0.01785719 0.01145648 0.220328 0.01785719 0.009948194 0.2064639 0.02108865 0.009658336 0.206946 0.02109998 0.00986582 0.207201 0.02106046 0.01003175 0.207467 0.02095258 0.01040434 0.207181 0.0207774 0.01023697 0.208006 0.02054995 0.01047766 0.207821 0.01999998 0.01022756 0.208398 0.01999998 0.01014667 0.208496 0.01972275 0.01009535 0.207892 0.0192216 0.01001447 0.208519 0.01944994 0.009847223 0.208464 0.0192216 0.009899675 0.207772 0.01904737 0.009653747 0.208339 0.01904737 0.009439766 0.208151 0.01893585 -0.004969596 0.215668 0.02884995 -0.004974961 0.215901 0.02974998 -0.004961729 0.215669 0.02974998 -0.004942715 0.2153339 0.02974998 -0.004863381 0.214875 0.02974998 -0.00486809 0.214874 0.02884995 -0.00464046 0.214107 0.02884995 -0.004292726 0.213385 0.02884995 -0.004465162 0.213706 0.02974998 -0.004635155 0.214109 0.02974998 -0.003852248 0.212752 0.02974998 -0.004186034 0.213212 0.02974998 -0.00383377 0.212729 0.02884995 -0.003275513 0.212155 0.02884995 -0.002632439 0.211679 0.02884995 -0.002630352 0.211682 0.02974998 -0.002570331 0.21164 0.02974998 -0.002067983 0.2113749 0.02974998 -0.001921176 0.211311 0.02884995 -3.69108e-4 0.210939 0.02884995 -9.8944e-4 0.211024 0.02974998 -0.001160144 0.211062 0.02884995 -0.001158416 0.211069 0.02974998 1.40585e-4 0.210927 0.02974998 4.31518e-4 0.2109439 0.02884995 4.30827e-4 0.210952 0.02974998 0.001220941 0.211077 0.02884995 0.001220464 0.211079 0.02974998 0.00126326 0.211088 0.02974998 0.001978754 0.211335 0.02884995 0.001803576 0.211263 0.02974998 0.003256797 0.212139 0.02974998 0.002806842 0.2117919 0.02974998 0.002685368 0.211712 0.02884995 0.002320349 0.211499 0.02974998 0.003319442 0.2122 0.02974998 0.003322362 0.212197 0.02884995 0.003664255 0.212535 0.02974998 0.004023969 0.212975 0.02974998 0.003873348 0.212778 0.02884995 0.004323303 0.21344 0.02974998 0.004324018 0.21344 0.02884995 0.004331171 0.213452 0.02974998 0.004662692 0.214165 0.02884995 0.004966795 0.215614 0.02974998 0.0049721 0.215731 0.02884995 0.004875421 0.214937 0.02974998 0.004880607 0.214936 0.02884995 0.004966914 0.216183 0.02974998 0.004934847 0.216531 0.02884995 0.004927217 0.21653 0.02974998 0.004773855 0.2172999 0.02974998 0.004769742 0.217314 0.02884995 0.004768967 0.217314 0.02974998 0.004076421 0.218752 0.02884995 0.004332661 0.218345 0.02974998 0.004481136 0.218061 0.02884995 0.003666281 0.219263 0.02974998 0.004025697 0.218823 0.02974998 0.003561854 0.219364 0.02974998 0.003566205 0.2193689 0.02884995 0.002963602 0.219896 0.02884995 0.003259003 0.219659 0.02974998 0.002959191 0.2198899 0.02974998 0.002284228 0.22032 0.02884995 0.001545667 0.220629 0.02884995 0.001806318 0.220535 0.02974998 -3.13064e-5 0.220875 0.02884995 7.09484e-4 0.220824 0.02974998 7.67129e-4 0.220815 0.02884995 -8.28931e-4 0.220805 0.02884995 -8.27998e-4 0.220799 0.02974998 -0.001605033 0.220609 0.02884995 -0.001603722 0.220606 0.02974998 -0.002339661 0.220291 0.02884995 -0.003604054 0.219319 0.02974998 -0.003466188 0.219469 0.02974998 -0.003609597 0.2193239 0.02884995 -0.00301361 0.219858 0.02884995 -0.004112005 0.2186999 0.02884995 -0.004463851 0.218096 0.02974998 -0.004184424 0.218591 0.02974998 -0.004107356 0.218697 0.02974998 -0.004787147 0.217254 0.02884995 -0.004507958 0.218004 0.02884995 -0.004942357 0.216469 0.02884995 -0.004845321 0.217028 0.02974998 -0.004779636 0.217252 0.02974998 -0.004944503 0.215901 0.02990305 -0.004846036 0.214775 0.02974998 -0.004657447 0.21424 0.02990305 -0.004686117 0.21423 0.02974998 -0.004437863 0.21372 0.02990305 -0.004286229 0.213389 0.02974998 -0.003828704 0.2127709 0.02990305 -0.003832578 0.2127299 0.02974998 -0.003468275 0.212333 0.02974998 -0.003270208 0.212162 0.02974998 -0.003039121 0.211961 0.02974998 -0.003020524 0.2119849 0.02990305 -0.001918792 0.211317 0.02974998 -0.001538753 0.211169 0.02974998 -4.27213e-4 0.210943 0.02974998 1.39724e-4 0.210957 0.02990305 -3.69022e-4 0.210942 0.02974998 7.06549e-4 0.210975 0.02974998 0.00179255 0.211292 0.02990305 0.002306103 0.211526 0.02990305 0.001975774 0.211342 0.02974998 0.002682149 0.211717 0.02974998 0.00323683 0.212162 0.02990305 0.003641843 0.212556 0.02990305 0.003867208 0.212783 0.02974998 0.004581987 0.213962 0.02974998 0.00465548 0.214168 0.02974998 0.00477302 0.214497 0.02974998 0.004871845 0.215055 0.02990305 0.004901826 0.21505 0.02974998 0.004936516 0.216181 0.02990305 0.004966795 0.215731 0.02974998 0.004872322 0.216742 0.02990305 0.004902362 0.216747 0.02974998 0.004744648 0.217292 0.02990305 0.00458312 0.217835 0.02974998 0.004555106 0.217823 0.02990305 0.004473984 0.218057 0.02974998 0.004306137 0.21833 0.02990305 0.004072904 0.21875 0.02974998 0.002809286 0.220006 0.02974998 0.002792119 0.219981 0.02990305 0.002308726 0.220272 0.02990305 0.002322971 0.220299 0.02974998 0.002283215 0.220318 0.02974998 0.001543164 0.220621 0.02974998 0.001266121 0.2207109 0.02974998 7.66535e-4 0.220813 0.02974998 7.05141e-4 0.220794 0.02990305 1.43548e-4 0.2208729 0.02974998 1.4267e-4 0.220842 0.02990305 -3.11111e-5 0.220868 0.02974998 -4.21662e-4 0.220827 0.02990305 -4.24259e-4 0.220857 0.02974998 -9.86535e-4 0.220776 0.02974998 -0.001535892 0.220632 0.02974998 -0.001526534 0.220603 0.02990305 -0.0020653 0.220426 0.02974998 -0.002552032 0.220135 0.02990305 -0.002335906 0.220283 0.02974998 -0.002567768 0.220161 0.02974998 -0.003012716 0.219857 0.02974998 -0.003036797 0.219841 0.02974998 -0.003826797 0.219031 0.02990305 -0.0038504 0.2190499 0.02974998 -0.004158794 0.218574 0.02990305 -0.004436552 0.218083 0.02990305 -0.004503548 0.218003 0.02974998 -0.004656493 0.217563 0.02990305 -0.004815697 0.217021 0.02990305 -0.004685163 0.217573 0.02974998 -0.004912137 0.2164649 0.02990305 -0.004942357 0.216469 0.02974998 -0.004358768 0.2180449 0.03003275 -0.003759682 0.218976 0.03003275 -0.00338453 0.219385 0.03003275 -0.003444969 0.219447 0.02990305 -0.002965271 0.219748 0.03003275 -0.0030182 0.219817 0.02990305 -0.002052664 0.220398 0.02990305 -0.002507328 0.220061 0.03003275 -0.002016663 0.220319 0.03003275 -0.001499772 0.220521 0.03003275 -9.80497e-4 0.220746 0.02990305 1.40168e-4 0.2207559 0.03003275 6.92776e-4 0.220708 0.03003275 0.001258373 0.220682 0.02990305 0.001795232 0.220507 0.02990305 0.001236319 0.220598 0.03003275 0.002743124 0.219909 0.03003275 0.003239095 0.219636 0.02990305 0.003182291 0.21957 0.03003275 0.00364381 0.219242 0.02990305 0.003579914 0.219184 0.03003275 0.00400108 0.218805 0.02990305 0.004786908 0.216727 0.03003275 0.00484997 0.216176 0.03003275 0.004936397 0.215616 0.02990305 0.004743814 0.214506 0.02990305 0.004553914 0.2139739 0.02990305 0.004474103 0.214008 0.03003275 0.004304707 0.213467 0.02990305 0.003999352 0.212992 0.02990305 0.004229187 0.21351 0.03003275 0.003929197 0.213043 0.03003275 0.003577947 0.2126139 0.03003275 0.003180086 0.212228 0.03003275 0.002789676 0.211818 0.02990305 0.001761078 0.211373 0.03003275 0.001255512 0.211118 0.02990305 7.02225e-4 0.211006 0.02990305 6.8991e-4 0.211091 0.03003275 1.37274e-4 0.211044 0.03003275 -4.24598e-4 0.210974 0.02990305 -9.6614e-4 0.211139 0.03003275 -9.83385e-4 0.211054 0.02990305 -0.001529335 0.211198 0.02990305 -0.002055346 0.211403 0.02990305 -0.001502513 0.2112799 0.03003275 -0.002554595 0.211666 0.02990305 -0.002967536 0.212054 0.03003275 -0.003447055 0.212355 0.02990305 -0.003761529 0.212826 0.03003275 -0.004160404 0.213228 0.02990305 -0.004087448 0.213275 0.03003275 -0.00436002 0.213758 0.03003275 -0.004575788 0.214269 0.03003275 -0.004731893 0.214801 0.03003275 -0.004816353 0.2147819 0.02990305 -0.004912436 0.215338 0.02990305 -0.004857838 0.215901 0.03003275 -0.004826009 0.216455 0.03003275 -0.004731237 0.217002 0.03003275 -0.004452586 0.21749 0.03011959 -0.004574835 0.217534 0.03003275 -0.004085838 0.218528 0.03003275 -0.002440333 0.21995 0.03011959 -0.001459717 0.2203969 0.03011959 -9.63303e-4 0.220661 0.03003275 -9.3757e-4 0.220534 0.03011959 -4.14268e-4 0.22074 0.03003275 -4.03201e-4 0.220611 0.03011959 0.001763761 0.220426 0.03003275 0.001203298 0.220472 0.03011959 0.002268254 0.220196 0.03003275 0.00266987 0.219802 0.03011959 0.003097236 0.219472 0.03011959 0.003930926 0.2187539 0.03003275 0.003484308 0.219096 0.03011959 0.003825902 0.2186779 0.03011959 0.004230618 0.218287 0.03003275 0.004117608 0.218224 0.03011959 0.004475235 0.21779 0.03003275 0.004536926 0.217231 0.03011959 0.00466144 0.217267 0.03003275 0.004659056 0.216705 0.03011959 0.004720389 0.2161689 0.03011959 0.004849791 0.2156209 0.03003275 0.004786431 0.21507 0.03003275 0.004658579 0.215092 0.03011959 0.004660606 0.2145299 0.03003275 0.004116237 0.2135739 0.03011959 0.003824234 0.21312 0.03011959 0.003482401 0.212702 0.03011959 0.00274074 0.211889 0.03003275 0.003095149 0.212326 0.03011959 0.002265691 0.211603 0.03003275 0.001233518 0.211201 0.03003275 -4.17152e-4 0.2110599 0.03003275 -0.00146234 0.211404 0.03011959 -0.002019286 0.211482 0.03003275 -0.002509772 0.211741 0.03003275 -0.002888262 0.212157 0.03011959 -0.003386616 0.212417 0.03003275 -0.003661036 0.212908 0.03011959 -0.004243552 0.213815 0.03011959 -0.004453539 0.214312 0.03011959 -0.004826307 0.215348 0.03003275 -0.004605472 0.21483 0.03011959 -0.004697382 0.215362 0.03011959 -0.004604876 0.2169719 0.03011959 -0.004455745 0.216938 0.03014999 -0.004308462 0.2174389 0.03014999 -0.0042423 0.217987 0.03011959 -0.004104971 0.21792 0.03014999 -0.003976702 0.218457 0.03011959 -0.003847956 0.218375 0.03014999 -0.003659307 0.218894 0.03011959 -0.00329411 0.219292 0.03011959 -0.003540813 0.218797 0.03014999 -0.002886056 0.219645 0.03011959 -0.003187477 0.219182 0.03014999 -0.002792596 0.219524 0.03014999 -0.00196278 0.220201 0.03011959 -0.002361297 0.219819 0.03014999 -0.001899242 0.220062 0.03014999 -0.001412451 0.220252 0.03014999 -9.07215e-4 0.220384 0.03014999 -3.90147e-4 0.220458 0.03014999 1.36423e-4 0.2206259 0.03011959 6.74269e-4 0.22058 0.03011959 1.32007e-4 0.220473 0.03014999 6.5244e-4 0.220428 0.03014999 0.001716673 0.220305 0.03011959 0.001164317 0.220324 0.03014999 0.001661062 0.220163 0.03014999 0.002207636 0.220081 0.03011959 0.00213617 0.219946 0.03014999 0.002583444 0.219676 0.03014999 0.002996981 0.219357 0.03014999 0.003371477 0.218993 0.03014999 0.003702044 0.2185879 0.03014999 0.004355669 0.217739 0.03011959 0.003984272 0.2181479 0.03014999 0.004214644 0.21768 0.03014999 0.004390001 0.217188 0.03014999 0.004508197 0.216679 0.03014999 0.004567563 0.2161599 0.03014999 0.00472027 0.215629 0.03011959 0.004567444 0.215637 0.03014999 0.00450772 0.215119 0.03014999 0.004536151 0.214567 0.03011959 0.004389286 0.21461 0.03014999 0.004354536 0.214058 0.03011959 0.004213571 0.214118 0.03014999 0.003982961 0.213649 0.03014999 0.003700435 0.21321 0.03014999 0.003369629 0.212805 0.03014999 0.002667546 0.211996 0.03011959 0.002994954 0.212442 0.03014999 0.002581179 0.212123 0.03014999 0.002133786 0.211853 0.03014999 0.002205133 0.211718 0.03011959 0.001658558 0.211636 0.03014999 0.00171405 0.211494 0.03011959 0.001200556 0.211327 0.03011959 6.71481e-4 0.21122 0.03011959 0.001161694 0.211475 0.03014999 1.33607e-4 0.211174 0.03011959 6.49741e-4 0.211371 0.03014999 -4.06008e-4 0.211189 0.03011959 1.29281e-4 0.211327 0.03014999 -3.92864e-4 0.211342 0.03014999 -9.40331e-4 0.211266 0.03011959 -9.09887e-4 0.211416 0.03014999 -0.001415014 0.211549 0.03014999 -0.001965343 0.2116 0.03011959 -0.001901745 0.211739 0.03014999 -0.002442717 0.211852 0.03011959 -0.002363681 0.211983 0.03014999 -0.002794742 0.212278 0.03014999 -0.003189444 0.21262 0.03014999 -0.003296136 0.2125099 0.03011959 -0.003542542 0.213005 0.03014999 -0.003978252 0.213345 0.03011959 -0.003849446 0.213428 0.03014999 -0.004106163 0.213883 0.03014999 -0.004309356 0.2143639 0.03014999 -0.0044564 0.214865 0.03014999 -0.004545271 0.21538 0.03014999 -0.004574954 0.215901 0.03014999 -0.004728019 0.215901 0.03011959 -0.004697084 0.21644 0.03011959 -0.004544973 0.216423 0.03014999 -0.003885149 0.2127529 0.03444999 0.003885149 0.219047 0.03744995 0.003095865 0.219166 0.03794997 0.002161443 0.219847 0.03794997 0.001084327 0.2202669 0.03794997 -6.4317e-5 0.2204 0.03794997 5.66701e-4 0.220826 0.03744995 -7.14634e-5 0.220899 0.03744995 -0.001208722 0.220235 0.03794997 -0.001343011 0.2207159 0.03744995 -0.0020774 0.220405 0.03744995 -0.002525985 0.220215 0.03744995 0.003068923 0.211953 0.03444999 0.003728508 0.2125689 0.03444999 0.003068923 0.211953 0.03744995 0.003885149 0.219047 0.03444999 0.0031538 0.2126899 0.03794997 -0.003095865 0.212634 0.03794997 -0.003571391 0.212414 0.03744995 -0.00124073 0.211061 0.03744995 -0.001084327 0.211533 0.03794997 6.43171e-5 0.2114 0.03794997 -0.001204848 0.2110469 0.03744995 7.14634e-5 0.210901 0.03744995 0.001343011 0.211084 0.03744995 0.001208722 0.211565 0.03794997 0.00227338 0.212016 0.03794997 0.00268644 0.211694 0.03744995 -0.003068923 0.219847 0.03444999 -5.23071e-4 0.214494 0.03794997 -0.002161443 0.211953 0.03794997 -0.001116454 0.214898 0.03794997 -0.003800272 0.21349 0.03794997 -0.001454114 0.215532 0.03794997 8.59849e-4 0.214671 0.03794997 0.001332521 0.215211 0.03794997 0.003800272 0.2183099 0.03794997 8.44312e-4 0.21714 0.03794997 1.71431e-4 0.21739 0.03794997 -0.0031538 0.21911 0.03794997 -5.40723e-4 0.217299 0.03794997 -0.00227338 0.219783 0.03794997 7.71393e-4 0.217177 0.03677266 0.001044511 0.216977 0.03484797 0.001323759 0.216605 0.03014999 0.001194059 0.216808 0.03507494 0.001274645 0.216691 0.03612387 0.001323759 0.216605 0.03794997 0.001323759 0.216605 0.03589636 -4.65064e-4 0.217326 0.0367825 -5.37889e-4 0.217293 0.03672796 -0.001147031 0.216867 0.03569996 -0.001128971 0.216888 0.03794997 -0.001061975 0.2169589 0.03612339 -9.56771e-4 0.217055 0.03632497 -0.001128971 0.216888 0.03550356 -0.001458585 0.21625 0.03014999 -5.40723e-4 0.217299 0.03466236 -0.001128971 0.216888 0.03014999 -7.72952e-4 0.217186 0.03484815 7.76746e-4 0.2171829 0.03461748 8.44312e-4 0.21714 0.03014999 1.71431e-4 0.21739 0.03014999 -5.40723e-4 0.217299 0.03014999 -1.59998e-4 0.217391 0.03449416 -0.001458585 0.21625 0.03794997 -0.001454114 0.215532 0.03014999 -0.001116454 0.214898 0.03014999 -5.23071e-4 0.214494 0.03014999 1.90172e-4 0.214412 0.03794997 -1.71431e-4 0.21441 0.03014999 1.90172e-4 0.214412 0.03014999 8.59849e-4 0.214671 0.03014999 0.001332521 0.215211 0.03014999 0.00149995 0.215909 0.03794997 0.001323759 0.216605 0.03550356 0.00149995 0.215909 0.03014999 0.001274824 0.21669 0.03527665 -4.61359e-4 0.2173179 0.03462725 -5.39496e-5 0.2208999 0.03461748 1.71431e-4 0.21739 0.03444999 -0.001061797 0.2169589 0.03527617 -6.44742e-4 0.220858 0.03537559 -9.56771e-4 0.217055 0.03507494 -5.17555e-4 0.2208729 0.03507494 -6.88518e-4 0.220852 0.03569996 -6.44827e-4 0.220858 0.03602397 -0.001128971 0.216888 0.03589636 -7.72851e-4 0.217186 0.03655189 -5.39496e-5 0.2208999 0.0367825 -1.60004e-4 0.217391 0.03690576 0.001187801 0.220757 0.0367825 4.94626e-4 0.217316 0.03690576 1.71431e-4 0.21739 0.03694999 2.4813e-4 0.220894 0.03690719 0.001194059 0.216808 0.03632497 0.001044631 0.216976 0.03655177 8.44312e-4 0.21714 0.03673756 0.001336514 0.216581 0.03569996 0.001795053 0.220567 0.03569996 4.95316e-4 0.217316 0.0344944 0.001440525 0.220688 0.03481608 8.4012e-4 0.2171339 0.03467196 0.003728508 0.2125689 0.03344994 0.003985404 0.2129499 0.03344994 0.003439843 0.219529 0.03744995 0.004489064 0.213698 0.03344994 0.004489064 0.213698 0.03444999 0.004916608 0.214991 0.03444999 0.00497961 0.216351 0.03444999 0.004673182 0.217678 0.03344994 0.004673182 0.217678 0.03444999 0.004020214 0.218873 0.03444999 0.004020214 0.218873 0.03344994 0.003046154 0.219816 0.03744995 -0.003068923 0.219847 0.03744995 -0.003240168 0.219708 0.03444999 -0.00414741 0.218693 0.03444999 -0.00414741 0.218693 0.03344994 -0.004747033 0.2174699 0.03444999 -0.00499463 0.216131 0.03444999 -0.004871785 0.214775 0.03444999 -0.004387617 0.213502 0.03444999 -0.004387617 0.213502 0.03344994 -0.003578007 0.2124069 0.03344994 -3.15422e-4 0.22089 0.03658407 -5.17555e-4 0.2208729 0.03632497 -7.89898e-4 0.2208369 0.03344994 -3.15777e-4 0.22089 0.0348162 5.71437e-4 0.220867 0.03344994 2.4865e-4 0.220894 0.03449255 5.71437e-4 0.220867 0.03444999 0.001890361 0.220529 0.03344994 8.9271e-4 0.22082 0.03449285 0.001187801 0.220757 0.03461748 0.001633286 0.2206259 0.03507494 0.001753926 0.220582 0.03537625 0.001753926 0.220582 0.03602379 0.001633286 0.2206259 0.03632497 0.001440346 0.220688 0.03658396 0.001204848 0.220753 0.03744995 8.92354e-4 0.22082 0.03690719 5.71437e-4 0.220867 0.03694999 -7.84074e-4 0.220797 0.03744995 0.002401649 0.2202849 0.03744995 0.001875519 0.2204909 0.03744995 1.09568e-4 0.210906 0.03744995 0.001449465 0.211129 0.03744995 0.002691447 0.211686 0.03344994 0.002525985 0.211585 0.03744995 1.10258e-4 0.210901 0.03344994 -0.001242458 0.211057 0.03344994 -0.002054035 0.211388 0.03344994 -0.002401649 0.211515 0.03744995 -0.00249505 0.211583 0.03744995 -0.002503037 0.211572 0.03344994 -0.003439843 0.212271 0.03744995 -0.003885149 0.2127529 0.03744995 -9.73499e-4 0.220781 0.03344994 -8.84962e-4 0.220808 0.03344994 -0.009080946 0.2149749 0.03214997 -0.009797036 0.215398 0.03344994 -0.01027929 0.216076 0.03344994 -0.01027929 0.216076 0.03214997 -0.01026326 0.217703 0.03214997 -0.009767889 0.218371 0.03214997 -0.009043633 0.21878 0.03344994 -0.008215725 0.218858 0.03344994 -0.007427334 0.218594 0.03344994 -0.006814777 0.218031 0.03214997 -0.006814777 0.218031 0.03344994 -0.006483972 0.217268 0.03214997 -0.006492137 0.216436 0.03214997 -0.006837844 0.21568 0.03344994 -0.008254766 0.2148799 0.03214997 -0.008672833 0.2148849 0.03214997 -0.003980159 0.225607 0.03214997 -0.004285991 0.225434 0.03344994 -0.004704415 0.225198 0.03344994 -0.004704415 0.225198 0.03214997 -0.005199849 0.22453 0.03214997 -0.005199849 0.22453 0.03344994 -0.004957854 0.222541 0.03344994 -0.004017531 0.221803 0.03214997 -0.004017531 0.221803 0.03344994 -0.003609418 0.2217119 0.03214997 -0.003191292 0.2217079 0.03344994 -0.002397894 0.221957 0.03214997 -0.00177443 0.2225069 0.03344994 -0.00177443 0.2225069 0.03214997 -0.001428723 0.223264 0.03214997 -0.003152251 0.225686 0.03214997 -0.003152251 0.225686 0.03344994 -0.001751303 0.224858 0.03344994 0.003739833 0.224227 0.03214997 0.0032444 0.223559 0.03344994 0.0032444 0.223559 0.03214997 0.003063499 0.222747 0.03344994 0.003486394 0.221569 0.03344994 0.003710627 0.221254 0.03214997 0.004426717 0.220831 0.03344994 0.00483483 0.22074 0.03214997 0.005252957 0.220736 0.03344994 0.006336331 0.2212409 0.03344994 0.006046354 0.2209849 0.03214997 0.006669819 0.221536 0.03344994 0.007015526 0.222292 0.03344994 0.007023692 0.223124 0.03344994 0.004464089 0.224635 0.03214997 0.004464089 0.224635 0.03344994 0.005291998 0.224714 0.03214997 0.005291998 0.224714 0.03344994 0.005459249 0.224658 0.03214997 0.006080389 0.224449 0.03214997 0.006528615 0.224038 0.03214997 0.006692886 0.223887 0.03214997 0.007023692 0.223124 0.03214997 0.007120668 0.216428 0.03344994 0.006625235 0.2157599 0.03214997 0.006625235 0.2157599 0.03344994 0.006444394 0.2149479 0.03214997 0.00660932 0.214133 0.03214997 0.007091462 0.213455 0.03344994 0.008615672 0.21294 0.03344994 0.008615493 0.212938 0.03214997 0.007807612 0.213033 0.03214997 0.008633792 0.212938 0.03344994 0.009427249 0.213187 0.03344994 0.01039636 0.214494 0.03344994 0.01040458 0.2153249 0.03214997 0.01007378 0.2160879 0.03344994 0.009461224 0.216651 0.03344994 0.009058177 0.216786 0.03344994 0.008672833 0.216915 0.03344994 0.002744138 0.206205 0.03344994 0.00156182 0.2089329 0.03344994 0.00138092 0.208121 0.03344994 0.00138092 0.208121 0.03214997 0.001912057 0.206791 0.03344994 0.003152251 0.2061139 0.03214997 0.003570377 0.20611 0.03344994 0.003325819 0.206113 0.03214997 0.004282355 0.2063339 0.03344994 0.004363775 0.20636 0.03344994 0.00451374 0.206492 0.03344994 0.004987239 0.20691 0.03214997 0.005332946 0.207666 0.03344994 0.002057194 0.209601 0.03344994 0.00278151 0.210009 0.03214997 0.004656434 0.209586 0.03344994 0.005013823 0.209253 0.03214997 0.005341112 0.208498 0.03344994 0.005341112 0.208498 0.03214997 0.005332946 0.207666 0.03214997 -0.005662739 0.210981 0.03214997 -0.005662739 0.210981 0.03344994 -0.00596863 0.210808 0.03344994 -0.006386995 0.210572 0.03214997 -0.006386995 0.210572 0.03344994 -0.006882429 0.209904 0.03344994 -0.006882429 0.209904 0.03214997 -0.007063329 0.209092 0.03344994 -0.007063329 0.209092 0.03214997 -0.006532192 0.207763 0.03344994 -0.006416201 0.2075999 0.03344994 -0.006342709 0.207556 0.03344994 -0.005700111 0.207177 0.03214997 -0.005461394 0.2071239 0.03214997 -0.004873871 0.207082 0.03344994 -0.004873871 0.207082 0.03214997 -0.004080474 0.207331 0.03344994 -0.004080474 0.207331 0.03214997 -0.003457009 0.207881 0.03344994 -0.003111302 0.208638 0.03344994 -0.003111302 0.208638 0.03214997 -0.00483483 0.2110599 0.03214997 -0.00404644 0.210795 0.03214997 -0.003433942 0.210232 0.03214997 -0.003433942 0.210232 0.03344994 -0.008338272 0.2117609 0.03214997 -0.008662104 0.209899 0.03344994 -0.00831753 0.210798 0.03214997 -0.008721172 0.212644 0.03214997 -0.009409606 0.213317 0.03344994 -0.009409606 0.213317 0.03214997 -0.01030129 0.21368 0.03344994 -0.01126408 0.213679 0.03344994 0.008662104 0.2219009 0.03344994 0.009320914 0.222603 0.03214997 0.008662104 0.2219009 0.03214997 0.00831753 0.221002 0.03214997 0.009269177 0.21862 0.03344994 0.009409606 0.218483 0.03214997 0.01030129 0.21812 0.03344994 0.01030129 0.21812 0.03214997 0.009147167 0.205434 0.03194999 0.01069146 0.207017 0.03194999 0.008963882 0.2083809 0.03194999 0.01046556 0.211179 0.03214997 0.007753968 0.210749 0.03214997 0.008286237 0.211071 0.03214997 0.008577227 0.211248 0.03344994 0.008577227 0.211248 0.03214997 0.007151603 0.2098619 0.03344994 0.007180452 0.209975 0.03214997 0.006941676 0.209043 0.03344994 0.007073104 0.2080889 0.03344994 0.007073104 0.2080889 0.03214997 0.01130336 0.210802 0.03344994 0.0117563 0.212056 0.03344994 0.01295906 0.210984 0.03194999 0.01195359 0.212603 0.03344994 0.0133996 0.212204 0.03194999 0.01358997 0.2131839 0.03194999 0.01216578 0.218299 0.03344994 0.0137369 0.217745 0.03194999 0.01239007 0.216397 0.03344994 0.01380884 0.214311 0.03194999 0.01147896 0.218163 0.03214997 0.01363748 0.218589 0.03194999 0.01328396 0.219992 0.03194999 0.00377959 0.2269729 0.03194999 0.004490256 0.229055 0.03194999 0.00383979 0.229259 0.03194999 0.003391087 0.227098 0.03194999 0.00133711 0.227523 0.03194999 -7.59753e-4 0.227575 0.03194999 -7.05945e-4 0.229782 0.03194999 0.00400573 0.227635 0.03344994 0.005973994 0.228416 0.03194999 0.006462275 0.228206 0.03194999 0.007956504 0.227268 0.03194999 0.009724676 0.225809 0.03194999 0.008832156 0.224604 0.03344994 0.009900569 0.225656 0.03194999 0.009822487 0.22343 0.03344994 0.01123064 0.22408 0.03194999 0.01128488 0.224016 0.03194999 0.003708839 0.226765 0.03214997 -8.65998e-4 0.226402 0.03214997 -8.65998e-4 0.226402 0.03344994 -3.93879e-4 0.22582 0.03214997 -2.59715e-4 0.225654 0.03214997 5.8426e-4 0.2251909 0.03214997 0.00154072 0.225081 0.03344994 0.00246787 0.22534 0.03214997 0.00246787 0.22534 0.03344994 0.002636134 0.225471 0.03214997 0.002636134 0.225471 0.03344994 0.003228127 0.225931 0.03214997 0.003708839 0.226765 0.03344994 -0.001236259 0.228238 0.03344994 -0.001144647 0.227324 0.03214997 -0.002975761 0.2294459 0.03194999 -0.004038631 0.227585 0.03344994 -0.005167245 0.228778 0.03194999 -0.004932045 0.227277 0.03344994 -0.005528688 0.228653 0.03194999 -0.009079873 0.226416 0.03194999 -0.006625056 0.226382 0.03344994 -0.01069146 0.224783 0.03194999 -0.01200765 0.2229019 0.03194999 -0.01064115 0.220764 0.03194999 -0.007555246 0.224545 0.03214997 -0.007073104 0.223711 0.03214997 -0.01046556 0.220621 0.03344994 -0.008577227 0.220552 0.03214997 -0.007753968 0.221051 0.03214997 -0.007180452 0.221825 0.03214997 -0.007073104 0.223711 0.03344994 -0.01267069 0.221615 0.03194999 -0.01066529 0.2207109 0.03214997 -0.01046556 0.220621 0.03214997 -0.01130336 0.220998 0.03344994 -0.01295906 0.220816 0.03194999 -0.01195359 0.219197 0.03344994 -0.01231878 0.217317 0.03344994 -0.0138517 0.216341 0.03194999 -0.01388877 0.2153429 0.03194999 -0.0137369 0.214055 0.03194999 -0.01216578 0.213501 0.03344994 -0.01363748 0.2132109 0.03194999 -0.01121348 0.212561 0.03194999 -0.01242917 0.209677 0.03194999 7.05945e-4 0.202018 0.03194999 -0.00377959 0.204827 0.03194999 -0.002373635 0.204443 0.03194999 -0.00383979 0.2025409 0.03194999 -2.89872e-4 0.204204 0.03194999 0.008280217 0.227065 0.03194999 0.009735226 0.225821 0.03024995 0.01123547 0.224084 0.03024995 0.01242917 0.222123 0.03194999 0.01328396 0.219992 0.03024995 0.01389288 0.215457 0.03024995 0.01388877 0.216457 0.03194999 0.0138517 0.215459 0.03194999 0.01363056 0.213177 0.03024995 0.01299637 0.21097 0.03024995 0.01267069 0.210185 0.03194999 0.01200765 0.208898 0.03194999 0.01200765 0.208898 0.03024995 0.009079873 0.205384 0.03194999 0.0074265 0.20415 0.03194999 0.007220447 0.204041 0.03194999 0.005528688 0.2031469 0.03194999 0.005167245 0.203022 0.03194999 0.001385807 0.202069 0.03194999 7.05945e-4 0.202018 0.03024995 -0.001588582 0.202091 0.03194999 -0.004490256 0.202745 0.03194999 -0.006462275 0.203594 0.03194999 -0.009735226 0.205979 0.03024995 -0.009900569 0.206144 0.03194999 -0.01123547 0.207716 0.03024995 -0.01242917 0.209677 0.03024995 -0.01328396 0.211808 0.03194999 -0.01328396 0.211808 0.03024995 -0.01377636 0.2140499 0.03024995 -0.01389288 0.216343 0.03024995 -0.01380884 0.217489 0.03194999 -0.01358997 0.218616 0.03194999 -0.01363056 0.2186239 0.03024995 -0.0133996 0.219596 0.03194999 -0.01299637 0.22083 0.03024995 -0.01200765 0.2229019 0.03024995 -0.009147167 0.226366 0.03194999 -0.0074265 0.22765 0.03194999 -0.007220447 0.227759 0.03194999 -0.007227957 0.227773 0.03024995 -0.005175173 0.228801 0.03024995 -0.003498971 0.2293519 0.03194999 -0.001385807 0.229731 0.03194999 -7.05945e-4 0.229782 0.03024995 0.001588582 0.229709 0.03194999 0.001588582 0.229709 0.03024995 0.00383979 0.229259 0.03024995 -0.01128488 0.2077839 0.03194999 -0.009608328 0.208117 0.03344994 -0.01123064 0.20772 0.03194999 -0.008832156 0.2071959 0.03344994 -0.009724676 0.205991 0.03194999 -0.007546782 0.206079 0.03344994 -0.007386624 0.20594 0.03344994 -0.008280217 0.204735 0.03194999 -0.006586432 0.205438 0.03344994 -0.005973994 0.203384 0.03194999 -0.00400573 0.204165 0.03344994 -0.005764901 0.204922 0.03344994 -0.007956504 0.204532 0.03194999 -0.009498715 0.209069 0.03194999 -0.009498715 0.209069 0.03214997 -0.01006704 0.20866 0.03344994 -0.003708839 0.205035 0.03214997 0.001144647 0.2044759 0.03214997 8.65998e-4 0.205398 0.03344994 0.001144647 0.2044759 0.03344994 3.93879e-4 0.20598 0.03344994 2.59715e-4 0.206146 0.03344994 -0.00154072 0.206719 0.03214997 -0.00246787 0.2064599 0.03344994 -0.003228127 0.205869 0.03344994 9.48586e-4 0.224146 0.03344994 6.23975e-5 0.223442 0.03214997 3.80596e-4 0.222708 0.03214997 0.001499712 0.222874 0.03214997 0.001591145 0.2236689 0.03214997 0.001333713 0.223993 0.03214997 -0.005381464 0.219891 0.03214997 -0.005229294 0.2202759 0.03344994 -0.005229294 0.2202759 0.03214997 -0.005290031 0.220686 0.03344994 -0.005547463 0.22101 0.03214997 -0.005816876 0.221117 0.03214997 -0.006342232 0.2211019 0.03214997 -0.0066666 0.220844 0.03214997 -0.006818771 0.220459 0.03214997 -0.006500601 0.219725 0.03344994 -0.006115436 0.219573 0.03344994 -0.006115436 0.219573 0.03214997 -9.48586e-4 0.2076539 0.03214997 -5.38957e-4 0.207715 0.03214997 -1.2316e-4 0.2087669 0.03344994 -3.80596e-4 0.209092 0.03344994 -7.65726e-4 0.209244 0.03214997 -0.001175343 0.209183 0.03344994 -0.001175343 0.209183 0.03214997 -0.001499712 0.208926 0.03344994 -0.001651883 0.208541 0.03344994 -0.001499712 0.208926 0.03214997 -0.001651883 0.208541 0.03214997 -0.001591145 0.208131 0.03344994 0.006500601 0.2120749 0.03214997 0.005705833 0.212166 0.03344994 0.005705833 0.212166 0.03214997 0.005381464 0.2119089 0.03344994 0.005229294 0.211524 0.03214997 0.005244433 0.211421 0.03214997 0.005229294 0.211524 0.03344994 0.005290031 0.211114 0.03214997 0.005547463 0.21079 0.03214997 0.005816876 0.210683 0.03214997 0.005547463 0.21079 0.03344994 0.005816876 0.210683 0.03344994 0.005932569 0.210637 0.03214997 0.006404638 0.218241 0.03214997 -0.01126408 0.213679 0.03214997 -0.00521636 0.226337 0.03214997 -0.006611287 0.225549 0.03214997 0.008338272 0.220039 0.03214997 0.008388638 0.219923 0.03214997 3.60005e-4 0.219029 0.03214997 -7.3201e-4 0.218964 0.03214997 0.001408576 0.2187179 0.03214997 0.002081334 0.220649 0.03214997 0.002287268 0.218066 0.03214997 0.003019273 0.215002 0.03214997 0.004676461 0.217853 0.03214997 0.003144323 0.216089 0.03214997 0.00289011 0.217153 0.03214997 -3.60005e-4 0.2127709 0.03214997 7.3201e-4 0.212836 0.03214997 0.001206219 0.213042 0.03214997 0.001622021 0.213222 0.03214997 -0.003144323 0.2157109 0.03214997 -0.004676461 0.2139469 0.03214997 -0.003019273 0.216798 0.03214997 -0.002530097 0.217776 0.03214997 -0.001735687 0.218529 0.03214997 -0.00289011 0.2146469 0.03214997 -0.002287268 0.213734 0.03214997 -0.001622021 0.218578 0.03214997 -0.001206219 0.218758 0.03214997 -0.001420557 0.224095 0.03214997 -0.003778815 0.22175 0.03214997 -0.003191292 0.2217079 0.03214997 -0.005380749 0.223718 0.03214997 -0.005766868 0.221552 0.03214997 -0.005215823 0.222903 0.03214997 -0.004733622 0.222226 0.03214997 -0.003827214 0.221329 0.03214997 -0.005323946 0.225401 0.03214997 -0.004510164 0.225308 0.03214997 -0.003327906 0.225669 0.03214997 -0.00236386 0.225421 0.03214997 -0.001915633 0.225009 0.03214997 -0.001751303 0.224858 0.03214997 0.003934085 0.224336 0.03214997 0.003063499 0.222747 0.03214997 0.004426717 0.220831 0.03214997 0.003228425 0.2219319 0.03214997 0.00377959 0.2269729 0.03214997 0.005628347 0.226128 0.03214997 0.007109463 0.225192 0.03214997 0.007015526 0.222292 0.03214997 0.007342457 0.223944 0.03214997 0.006669819 0.221536 0.03214997 0.005008399 0.220739 0.03214997 0.005252957 0.220736 0.03214997 0.007844924 0.216837 0.03214997 0.008672833 0.216915 0.03214997 0.007120668 0.216428 0.03214997 0.007091462 0.213455 0.03214997 0.008556425 0.212424 0.03214997 0.008215725 0.212942 0.03214997 0.009058177 0.216786 0.03214997 0.009122133 0.217342 0.03214997 0.009461224 0.216651 0.03214997 0.01106625 0.212136 0.03214997 0.009427249 0.213187 0.03214997 0.01005065 0.213737 0.03214997 0.01039636 0.214494 0.03214997 0.01169759 0.216135 0.03214997 0.01159828 0.217057 0.03214997 0.01007378 0.2160879 0.03214997 0.001545846 0.207306 0.03214997 0.00156182 0.2089329 0.03214997 0.002744138 0.206205 0.03214997 0.002028048 0.206628 0.03214997 8.65998e-4 0.205398 0.03214997 0.001166462 0.204258 0.03214997 0.001735687 0.213271 0.03214997 0.002530097 0.214024 0.03214997 0.003609418 0.210088 0.03214997 0.001074969 0.211901 0.03214997 0.002057194 0.209601 0.03214997 8.25785e-4 0.209735 0.03214997 0.002051949 0.209594 0.03214997 0.003776669 0.210032 0.03214997 0.004397809 0.209823 0.03214997 0.005217134 0.20547 0.03214997 0.003838419 0.204848 0.03214997 0.003570377 0.20611 0.03214997 0.004363775 0.20636 0.03214997 -0.00562638 0.205689 0.03214997 -0.004381179 0.205051 0.03214997 -0.003228127 0.205869 0.03214997 -0.003457009 0.207881 0.03214997 -0.00702244 0.210637 0.03214997 -0.006898403 0.208277 0.03214997 -0.006416201 0.2075999 0.03214997 -0.007449269 0.206927 0.03214997 -0.005291998 0.207086 0.03214997 -0.002204179 0.210083 0.03214997 -0.003103137 0.209469 0.03214997 -0.003430426 0.210224 0.03214997 -0.001954972 0.2122499 0.03214997 0.007699429 0.20709 0.03214997 0.006943285 0.209031 0.03214997 0.006941676 0.209043 0.03214997 0.005643963 0.2091799 0.03214997 0.005010306 0.209261 0.03214997 0.006342232 0.210698 0.03214997 0.0066666 0.210956 0.03214997 0.006780743 0.211245 0.03214997 0.006758034 0.21175 0.03214997 0.006050348 0.212713 0.03214997 0.0095281 0.211399 0.03214997 0.006818771 0.211341 0.03214997 0.008409321 0.2111459 0.03214997 0.008633792 0.212938 0.03214997 0.01103436 0.21201 0.03214997 0.01066529 0.211089 0.03214997 0.01126408 0.2181209 0.03214997 0.006616055 0.21763 0.03214997 0.007357716 0.2195259 0.03214997 0.006899535 0.220095 0.03214997 0.007523775 0.218407 0.03214997 0.009269177 0.21862 0.03214997 0.007675945 0.218792 0.03214997 0.008721172 0.219156 0.03214997 0.00154072 0.225081 0.03214997 -0.006941676 0.222757 0.03214997 -0.007699429 0.2247099 0.03214997 -0.007255911 0.221723 0.03214997 -0.006500601 0.219725 0.03214997 -0.0095281 0.220401 0.03214997 -0.005932569 0.221163 0.03214997 -0.007427334 0.218594 0.03214997 -0.008215725 0.218858 0.03214997 -0.01103246 0.2196609 0.03214997 -0.006758034 0.22005 0.03214997 -0.009043633 0.21878 0.03214997 -0.01044416 0.216891 0.03214997 -0.006050348 0.219087 0.03214997 -0.007461309 0.21513 0.03214997 -0.006837844 0.21568 0.03214997 -0.009797036 0.215398 0.03214997 -0.006674051 0.213666 0.03214997 -0.006789743 0.213712 0.03214997 -0.007523775 0.213393 0.03214997 -0.007199406 0.213651 0.03214997 -0.007660746 0.212906 0.03214997 -0.007615208 0.212599 0.03214997 -0.008321762 0.2107869 0.03214997 -0.0091663 0.213079 0.03214997 -0.007675945 0.213008 0.03214997 -0.01162946 0.214617 0.03214997 -0.01030129 0.21368 0.03214997 -0.006849527 0.21214 0.03214997 -0.00697261 0.212122 0.03214997 -0.007357716 0.212274 0.03214997 -0.009325325 0.2088339 0.03214997 -0.009320914 0.209197 0.03214997 -0.008662104 0.209899 0.03214997 -0.007913768 0.207282 0.03214997 -0.001333713 0.207807 0.03214997 -5.8426e-4 0.206609 0.03214997 -0.001591145 0.208131 0.03214997 -0.002636134 0.206329 0.03214997 -0.00246787 0.2064599 0.03214997 -2.1459e-4 0.207973 0.03214997 2.59715e-4 0.206146 0.03214997 3.93879e-4 0.20598 0.03214997 -6.23974e-5 0.208358 0.03214997 -1.2316e-4 0.2087669 0.03214997 -0.004110753 0.218864 0.03214997 -0.005705833 0.2196339 0.03214997 -0.005290031 0.220686 0.03214997 -0.0063923 0.210565 0.03214997 -0.006563007 0.2121829 0.03214997 -0.006238639 0.21244 0.03214997 -0.005010485 0.211043 0.03214997 -0.006124496 0.212729 0.03214997 -0.001823723 0.2133899 0.03214997 -0.002187728 0.21366 0.03214997 -0.004833579 0.212581 0.03214997 -0.006086409 0.212825 0.03214997 -0.006147205 0.213235 0.03214997 0.005992352 0.212209 0.03214997 0.005381464 0.2119089 0.03214997 0.003953576 0.21157 0.03214997 0.00495994 0.220318 0.03214997 0.001823723 0.21841 0.03214997 0.002187728 0.21814 0.03214997 0.006086409 0.218975 0.03214997 -0.005992352 0.219591 0.03214997 -0.006616055 0.21417 0.03214997 -0.006404638 0.213559 0.03214997 -0.001408576 0.213082 0.03214997 -3.80596e-4 0.209092 0.03214997 -5.0578e-4 0.224847 0.03214997 1.2316e-4 0.223033 0.03214997 -9.48644e-4 0.220997 0.03214997 7.65726e-4 0.2225559 0.03214997 9.48586e-4 0.224146 0.03214997 5.38957e-4 0.224085 0.03214997 2.1459e-4 0.223827 0.03214997 0.001175343 0.222617 0.03214997 0.001651883 0.223259 0.03214997 0.002524197 0.224498 0.03214997 0.006147205 0.218565 0.03214997 0.004110753 0.212936 0.03214997 0.006115436 0.212227 0.03214997 0.006563007 0.219617 0.03214997 0.006238639 0.2193599 0.03344994 0.006238639 0.2193599 0.03214997 0.006674051 0.218134 0.03214997 0.006789743 0.218088 0.03344994 0.006789743 0.218088 0.03214997 0.007199406 0.218149 0.03344994 0.007199406 0.218149 0.03214997 0.007675945 0.218792 0.03344994 0.007615208 0.219201 0.03214997 0.007357716 0.2195259 0.03344994 0.00697261 0.219678 0.03214997 0.006849527 0.21966 0.03214997 0.005992352 0.212209 0.03344994 0.006050348 0.212713 0.03344994 0.009764075 0.222922 0.03344994 0.01006704 0.22314 0.03344994 -0.002107083 0.210928 0.03344994 -0.004004955 0.218852 0.03344994 -0.003240168 0.219708 0.03344994 -0.002092599 0.220441 0.03344994 -0.004551172 0.213932 0.03344994 -0.004871785 0.214775 0.03344994 -0.00499463 0.216131 0.03344994 -0.004747033 0.2174699 0.03344994 -0.005904614 0.211364 0.03344994 9.75925e-4 0.21104 0.03344994 0.004720449 0.210142 0.03344994 0.004570662 0.217865 0.03344994 0.00497961 0.216351 0.03344994 0.004916608 0.214991 0.03344994 0.00197637 0.220479 0.03344994 0.002056479 0.2204329 0.03344994 -0.001420557 0.224095 0.03344994 -0.001428723 0.223264 0.03344994 -3.93879e-4 0.22582 0.03344994 -0.00236386 0.225421 0.03344994 -0.001144647 0.227324 0.03344994 -0.003121376 0.227901 0.03344994 -0.003980159 0.225607 0.03344994 -0.005119621 0.227178 0.03344994 -0.005380749 0.223718 0.03344994 -0.004766821 0.221255 0.03344994 -0.004660129 0.222182 0.03344994 -0.004733622 0.222226 0.03344994 -0.005215823 0.222903 0.03344994 -8.25785e-4 0.222065 0.03344994 -9.69285e-4 0.220818 0.03344994 -0.002107918 0.222213 0.03344994 -0.002397894 0.221957 0.03344994 0.003228425 0.2219319 0.03344994 0.005764901 0.226878 0.03344994 0.003739833 0.224227 0.03344994 0.003228127 0.225931 0.03344994 0.003710627 0.221254 0.03344994 0.002204179 0.221717 0.03344994 0.002060711 0.2204689 0.03344994 0.006878912 0.219915 0.03344994 0.005858242 0.220033 0.03344994 0.006046354 0.2209849 0.03344994 0.005964934 0.22096 0.03344994 0.006586432 0.226362 0.03344994 0.006080389 0.224449 0.03344994 0.006339013 0.224212 0.03344994 0.007386624 0.2258599 0.03344994 0.006692886 0.223887 0.03344994 0.007807612 0.213033 0.03344994 0.00660932 0.214133 0.03344994 0.006444394 0.2149479 0.03344994 0.006616055 0.21763 0.03344994 0.007844924 0.216837 0.03344994 0.01040458 0.2153249 0.03344994 0.01231878 0.214483 0.03344994 0.01005065 0.213737 0.03344994 0.00145477 0.211116 0.03344994 9.22929e-4 0.210579 0.03344994 0.00278151 0.210009 0.03344994 0.001545846 0.207306 0.03344994 0.002028048 0.206628 0.03344994 0.003609418 0.210088 0.03344994 0.004397809 0.209823 0.03344994 0.005010306 0.209261 0.03344994 0.001236259 0.203562 0.03344994 0.004932045 0.204523 0.03344994 0.005119621 0.204622 0.03344994 0.004987239 0.20691 0.03344994 -0.00483483 0.2110599 0.03344994 -0.00404644 0.210795 0.03344994 -0.003103137 0.209469 0.03344994 -0.003930509 0.207463 0.03344994 0.00785607 0.206337 0.03344994 0.007555246 0.207255 0.03344994 0.007589876 0.206138 0.03344994 0.005323946 0.206399 0.03344994 0.006625056 0.205418 0.03344994 -0.002636134 0.206329 0.03344994 -5.8426e-4 0.206609 0.03344994 -0.005700111 0.207177 0.03344994 -0.003708839 0.205035 0.03344994 -0.00831753 0.210798 0.03344994 -0.007342457 0.2078559 0.03344994 -0.006898403 0.208277 0.03344994 -0.009320914 0.209197 0.03344994 -0.006789743 0.213712 0.03344994 -0.007199406 0.213651 0.03344994 -0.01232194 0.214826 0.03344994 -0.007523775 0.213393 0.03344994 -0.007675945 0.213008 0.03344994 -0.008721172 0.212644 0.03344994 -0.007615208 0.212599 0.03344994 -0.008338272 0.2117609 0.03344994 -0.007357716 0.212274 0.03344994 -0.008335769 0.2116439 0.03344994 -0.00697261 0.212122 0.03344994 -0.006849527 0.21214 0.03344994 -0.006483972 0.217268 0.03344994 -0.006492137 0.216436 0.03344994 -0.006616055 0.21417 0.03344994 -0.007461309 0.21513 0.03344994 -0.008254766 0.2148799 0.03344994 -0.009080946 0.2149749 0.03344994 -0.01239007 0.215403 0.03344994 -0.01044416 0.216891 0.03344994 -0.01026326 0.217703 0.03344994 -0.009767889 0.218371 0.03344994 -0.006758034 0.22005 0.03344994 -0.005705833 0.2196339 0.03344994 -0.005992352 0.219591 0.03344994 -0.006050348 0.219087 0.03344994 -0.0117563 0.219744 0.03344994 -0.006342232 0.2211019 0.03344994 -0.007380127 0.221556 0.03344994 -0.0066666 0.220844 0.03344994 -0.007753968 0.221051 0.03344994 -0.008577227 0.220552 0.03344994 -0.006818771 0.220459 0.03344994 -0.0095281 0.220401 0.03344994 -0.005643963 0.22262 0.03344994 -0.006941676 0.222757 0.03344994 -0.005787491 0.221372 0.03344994 -0.007180452 0.221825 0.03344994 -0.006943285 0.222769 0.03344994 -0.007555246 0.224545 0.03344994 -0.008160054 0.225237 0.03344994 7.65726e-4 0.2225559 0.03344994 3.80596e-4 0.222708 0.03344994 1.2316e-4 0.223033 0.03344994 6.23975e-5 0.223442 0.03344994 2.1459e-4 0.223827 0.03344994 -2.59715e-4 0.225654 0.03344994 5.38957e-4 0.224085 0.03344994 5.8426e-4 0.2251909 0.03344994 0.001333713 0.223993 0.03344994 0.001591145 0.2236689 0.03344994 0.001651883 0.223259 0.03344994 0.001499712 0.222874 0.03344994 0.001175343 0.222617 0.03344994 0.007546782 0.225721 0.03344994 0.009320914 0.222603 0.03344994 0.008338272 0.220039 0.03344994 0.00702244 0.221163 0.03344994 0.00831753 0.221002 0.03344994 0.008321762 0.221013 0.03344994 0.007523775 0.218407 0.03344994 0.00697261 0.219678 0.03344994 0.008471548 0.219732 0.03344994 0.008721172 0.219156 0.03344994 0.007615208 0.219201 0.03344994 0.009409606 0.218483 0.03344994 0.009122133 0.217342 0.03344994 0.01232194 0.216974 0.03344994 0.01126408 0.2181209 0.03344994 0.0095281 0.211399 0.03344994 0.01046556 0.211179 0.03344994 0.006115436 0.212227 0.03344994 0.006500601 0.2120749 0.03344994 0.008556425 0.212424 0.03344994 0.006758034 0.21175 0.03344994 0.008409321 0.2111459 0.03344994 0.007753968 0.210749 0.03344994 0.006818771 0.211341 0.03344994 0.0066666 0.210956 0.03344994 0.007180452 0.209975 0.03344994 0.005741119 0.210025 0.03344994 -0.005932569 0.221163 0.03344994 -0.005816876 0.221117 0.03344994 -0.005381464 0.219891 0.03344994 -0.005029678 0.21897 0.03344994 -0.005547463 0.22101 0.03344994 -0.006925284 0.211482 0.03344994 -0.006404638 0.213559 0.03344994 -0.006147205 0.213235 0.03344994 -0.006086409 0.212825 0.03344994 -0.006238639 0.21244 0.03344994 -0.006563007 0.2121829 0.03344994 0.006342232 0.210698 0.03344994 0.005932569 0.210637 0.03344994 0.005290031 0.211114 0.03344994 0.006404638 0.218241 0.03344994 0.006147205 0.218565 0.03344994 0.003069102 0.219847 0.03344994 0.005595386 0.217748 0.03344994 0.006086409 0.218975 0.03344994 0.006563007 0.219617 0.03344994 0.006849527 0.21966 0.03344994 -0.006674051 0.213666 0.03344994 -0.005595386 0.214052 0.03344994 -7.65726e-4 0.209244 0.03344994 5.0578e-4 0.206953 0.03344994 -5.38957e-4 0.207715 0.03344994 -0.00154072 0.206719 0.03344994 -0.002524197 0.207302 0.03344994 -9.48586e-4 0.2076539 0.03344994 -6.23974e-5 0.208358 0.03344994 -2.1459e-4 0.207973 0.03344994 -0.001333713 0.207807 0.03344994 0.005029678 0.21283 0.03344994 0.006674051 0.218134 0.03344994 0.004038631 0.204215 0.03344994 0.003498971 0.202448 0.03194999 0.003121376 0.203899 0.03344994 0.002975761 0.202354 0.03194999 0.007699429 0.20709 0.03194999 0.008160054 0.2065629 0.03344994 0.007555246 0.207255 0.03214997 0.007914483 0.206844 0.03344994 -0.01167428 0.216675 0.02574998 -0.0116716 0.216714 0.02574998 0.01066529 0.211089 0.03194999 0.0108543 0.2202669 0.02824997 0.0108543 0.2202669 0.02574998 0.01086908 0.22023 0.02574998 0.009498715 0.2227309 0.03214997 0.003352999 0.227109 0.02574998 7.2009e-4 0.204222 0.02574998 7.2009e-4 0.204222 0.02824997 -2.89872e-4 0.204204 0.02824997 -0.00377959 0.204827 0.03214997 -0.002373635 0.204443 0.02824997 -0.01043719 0.210613 0.03194999 -0.01043719 0.210613 0.02824997 -0.01122474 0.212599 0.02574998 -0.01147896 0.2136369 0.03194999 -0.01122474 0.212599 0.02824997 -0.01121348 0.212561 0.02574998 -0.0108543 0.211533 0.02824997 -0.0108543 0.211533 0.02574998 -0.009601771 0.222585 0.03194999 -0.01064115 0.220764 0.02824997 -0.01066529 0.2207109 0.03194999 -0.009579002 0.222618 0.02574998 -0.006673097 0.22551 0.02574998 -0.006640434 0.225533 0.02574998 -0.006640434 0.225533 0.03214997 -0.001166462 0.227542 0.03214997 -7.2009e-4 0.227578 0.02574998 0.00133711 0.227523 0.02824997 -7.2009e-4 0.227578 0.02824997 -7.59753e-4 0.227575 0.02574998 -0.001842498 0.227454 0.02824997 -0.001842498 0.227454 0.02574998 0.004418015 0.226734 0.02574998 0.004418015 0.226734 0.02824997 0.003352999 0.227109 0.02824997 0.003391087 0.227098 0.02574998 0.005336046 0.226312 0.02824997 0.008654415 0.223773 0.02574998 0.008681118 0.223744 0.02574998 0.01086908 0.22023 0.03194999 0.009921193 0.222102 0.03194999 0.009921193 0.222102 0.02824997 0.008681118 0.223744 0.02824997 0.01122474 0.219201 0.02574998 0.01146769 0.2182199 0.03194999 0.01122474 0.219201 0.02824997 0.01146769 0.2182199 0.02824997 0.01147896 0.218163 0.03194999 0.01103436 0.21201 0.02824997 0.009579002 0.209182 0.02574998 0.007477223 0.206901 0.02824997 0.008963882 0.2083809 0.02824997 0.009579002 0.209182 0.02824997 0.01016235 0.210102 0.03194999 0.01018208 0.210137 0.02824997 0.01016235 0.210102 0.02574998 0.01018208 0.210137 0.02574998 -0.001166462 0.227542 0.03194999 -0.002832233 0.227252 0.02824997 -0.002832233 0.227252 0.03214997 -0.003158807 0.2271389 0.03214997 -0.004813671 0.226564 0.02824997 -0.005715548 0.226109 0.02574998 -0.006673097 0.22551 0.02824997 -0.008253753 0.224192 0.02824997 -0.007699429 0.2247099 0.03194999 -0.009579002 0.222618 0.02824997 -0.008253753 0.224192 0.03194999 -0.01018208 0.2216629 0.02824997 -0.009601771 0.222585 0.02574998 -0.01018208 0.2216629 0.02574998 -0.004813671 0.226564 0.03214997 -0.005715548 0.226109 0.02824997 -0.01133865 0.218785 0.02824997 -0.01133865 0.218785 0.03214997 -0.0116716 0.216714 0.03214997 -0.01147896 0.2136369 0.03214997 -0.01162946 0.214617 0.02824997 -0.01163208 0.214747 0.03214997 -0.01167428 0.216675 0.02824997 -0.0115453 0.217797 0.02824997 -0.0115453 0.217797 0.02574998 -0.008681118 0.208056 0.02574998 -0.009325325 0.2088339 0.02824997 -0.008681118 0.208056 0.02824997 -0.007913768 0.207282 0.02574998 -0.007884442 0.207256 0.02824997 -0.007884442 0.207256 0.02574998 -0.004381179 0.205051 0.02574998 -0.004418015 0.205066 0.02574998 -0.006247878 0.206008 0.03214997 -0.006247878 0.206008 0.02824997 -0.004418015 0.205066 0.02824997 -0.003352999 0.2046909 0.02824997 -0.003352999 0.2046909 0.02574998 0.001842498 0.204346 0.02824997 0.001166462 0.204258 0.03194999 0.001803219 0.20434 0.02574998 0.001803219 0.20434 0.03214997 0.001842498 0.204346 0.02574998 0.005715548 0.205691 0.02574998 0.007477223 0.206901 0.03214997 0.003160774 0.204679 0.03214997 0.003838419 0.204848 0.02824997 0.005715548 0.205691 0.02824997 0.005750238 0.205711 0.03214997 0.005750238 0.205711 0.02574998 0.006673097 0.20629 0.02824997 0.006673097 0.20629 0.02574998 0.0115453 0.214003 0.02574998 0.01169759 0.216135 0.02824997 0.0115453 0.214003 0.02824997 0.01155155 0.214043 0.03214997 0.01155155 0.214043 0.02574998 0.01167428 0.215125 0.02824997 0.01167428 0.215125 0.02574998 0.007884442 0.224544 0.02824997 0.008629739 0.223796 0.03214997 0.009498715 0.2227309 0.03194999 0.008654415 0.223773 0.03214997 0.007884442 0.224544 0.02574998 0.007450044 0.224879 0.03214997 0.007109463 0.225192 0.02824997 0.005336046 0.226312 0.03214997 -0.005230128 0.2037799 0.02824997 -0.005230128 0.2037799 0.02674996 -0.004959702 0.204209 0.02574998 -0.001588582 0.202091 0.03024995 0.002981185 0.202323 0.03024995 0.007227957 0.2040269 0.02239996 0.005175173 0.2029989 0.03024995 0.007227957 0.2040269 0.03024995 0.009083628 0.205379 0.03024995 0.009083628 0.205379 0.02239996 0.01069146 0.207017 0.03024995 0.01363056 0.213177 0.02239996 0.01389288 0.215457 0.02239996 0.01377636 0.21775 0.02239996 0.01377636 0.21775 0.03024995 0.01328396 0.219992 0.02239996 0.01242917 0.222123 0.02239996 0.01242917 0.222123 0.03024995 0.009735226 0.225821 0.02239996 0.005986213 0.2284449 0.02239996 0.007969439 0.227288 0.03024995 0.005986213 0.2284449 0.03024995 0.00383979 0.229259 0.02239996 0.001588582 0.229709 0.02239996 -7.05945e-4 0.229782 0.02239996 -0.002981185 0.229477 0.03024995 -0.009083628 0.2264209 0.02239996 -0.009083628 0.2264209 0.03024995 -0.01069146 0.224783 0.03024995 -0.01363056 0.2186239 0.02239996 -0.01377636 0.2140499 0.02239996 -0.01328396 0.211808 0.02239996 -0.009735226 0.205979 0.02239996 -0.007969439 0.204512 0.02239996 -0.007969439 0.204512 0.03024995 -0.005986213 0.203355 0.03024995 -0.005986213 0.203355 0.02239996 -0.00383979 0.2025409 0.03024995 -0.00383979 0.2025409 0.02239996 7.293e-4 0.20272 0.03024995 -0.001508533 0.202786 0.03024995 -0.003703057 0.20323 0.03024995 -0.005791008 0.204038 0.03024995 -0.005791008 0.204038 0.02239996 -0.009411871 0.206645 0.02239996 -0.007712364 0.205187 0.03024995 -0.01084059 0.208369 0.02239996 -0.009411871 0.206645 0.03024995 -0.01084059 0.208369 0.03024995 -0.01273036 0.21241 0.02239996 -0.01195746 0.210309 0.03024995 -0.01273036 0.21241 0.03024995 -0.01313698 0.214612 0.03024995 -0.01316565 0.2168509 0.03024995 -0.01316565 0.2168509 0.02239996 -0.01281565 0.219062 0.03024995 -0.012097 0.221182 0.03024995 -0.01103019 0.223151 0.02239996 -0.01103019 0.223151 0.03024995 -0.009646117 0.224911 0.03024995 -0.007984578 0.226411 0.02239996 -0.007984578 0.226411 0.03024995 -0.006093323 0.227609 0.02239996 -0.006093323 0.227609 0.03024995 -0.00402677 0.228471 0.03024995 -0.001844346 0.228971 0.03024995 3.91056e-4 0.229094 0.03024995 0.002615213 0.228838 0.03024995 0.004764199 0.22821 0.03024995 0.006776094 0.227228 0.02239996 0.006776094 0.227228 0.03024995 0.008593082 0.22592 0.03024995 0.01016288 0.224324 0.02239996 0.01016288 0.224324 0.03024995 0.01144027 0.222485 0.03024995 0.01238858 0.220457 0.02239996 0.01238858 0.220457 0.03024995 0.01298046 0.218297 0.02239996 0.01298046 0.218297 0.03024995 0.01319885 0.216069 0.03024995 0.01303768 0.213836 0.03024995 0.01250135 0.211663 0.03024995 0.01160538 0.2096109 0.03024995 0.01037555 0.20774 0.02239996 0.01037555 0.20774 0.03024995 0.008847236 0.206104 0.03024995 0.007064402 0.204749 0.02239996 0.007064402 0.204749 0.03024995 0.005078315 0.203716 0.02239996 0.005078315 0.203716 0.03024995 0.002946197 0.203033 0.03024995 0.002946197 0.203033 0.02239996 -0.002981185 0.229477 0.02239996 3.91056e-4 0.229094 0.02239996 0.002615213 0.228838 0.02239996 0.004764199 0.22821 0.02239996 0.008593082 0.22592 0.02239996 0.007969439 0.227288 0.02239996 0.01123547 0.224084 0.02239996 0.01144027 0.222485 0.02239996 0.01319885 0.216069 0.02239996 0.01303768 0.213836 0.02239996 0.01250135 0.211663 0.02239996 0.01299637 0.21097 0.02239996 0.01160538 0.2096109 0.02239996 0.01200765 0.208898 0.02239996 0.01069146 0.207017 0.02239996 0.008847236 0.206104 0.02239996 0.005175173 0.2029989 0.02239996 0.002981185 0.202323 0.02239996 7.293e-4 0.20272 0.02239996 -0.001508533 0.202786 0.02239996 7.05945e-4 0.202018 0.02239996 -0.001588582 0.202091 0.02239996 -0.003703057 0.20323 0.02239996 -0.007712364 0.205187 0.02239996 -0.01195746 0.210309 0.02239996 -0.01123547 0.207716 0.02239996 -0.01242917 0.209677 0.02239996 -0.01313698 0.214612 0.02239996 -0.01389288 0.216343 0.02239996 -0.01281565 0.219062 0.02239996 -0.012097 0.221182 0.02239996 -0.01299637 0.22083 0.02239996 -0.01200765 0.2229019 0.02239996 -0.01069146 0.224783 0.02239996 -0.009646117 0.224911 0.02239996 -0.007227957 0.227773 0.02239996 -0.005175173 0.228801 0.02239996 -0.00402677 0.228471 0.02239996 -0.001844346 0.228971 0.02239996 -0.188944 0.103415 0.02990305 -0.188956 0.1033869 0.02974998 -0.188414 0.10322 0.02990305 -0.188519 0.103226 0.02974998 -0.188423 0.103191 0.02974998 -0.187871 0.103056 0.02974998 -0.187741 0.10304 0.02974998 -0.187866 0.103086 0.02990305 -0.187306 0.103017 0.02990305 -0.1867409 0.103011 0.02990305 -0.18674 0.102981 0.02974998 -0.1861799 0.10307 0.02990305 -0.186175 0.10304 0.02974998 -0.186146 0.103046 0.02974998 -0.18562 0.103163 0.02974998 -0.1853719 0.103249 0.02974998 -0.185095 0.103377 0.02990305 -0.184637 0.103563 0.02974998 -0.184586 0.103621 0.02990305 -0.184571 0.103594 0.02974998 -0.184108 0.1039209 0.02990305 -0.18327 0.104675 0.02990305 -0.183647 0.104252 0.02974998 -0.1833699 0.104531 0.02974998 -0.182896 0.105102 0.02974998 -0.1829209 0.105119 0.02990305 -0.182474 0.105849 0.02974998 -0.18219 0.106597 0.02974998 -0.182205 0.106646 0.02990305 -0.182088 0.1071979 0.02990305 -0.1821759 0.106638 0.02974998 -0.18204 0.1073819 0.02974998 -0.182045 0.108325 0.02990305 -0.182011 0.1081809 0.02974998 -0.182111 0.108975 0.02974998 -0.182258 0.109432 0.02990305 -0.182229 0.109441 0.02974998 -0.182457 0.10996 0.02990305 -0.1823419 0.109741 0.02974998 -0.182429 0.109972 0.02974998 -0.182716 0.110462 0.02990305 -0.183147 0.111116 0.02974998 -0.183373 0.111382 0.02974998 -0.183703 0.1116909 0.02974998 -0.184261 0.112083 0.02990305 -0.184244 0.112109 0.02974998 -0.184345 0.112167 0.02974998 -0.185257 0.112619 0.02974998 -0.185808 0.112755 0.02990305 -0.186363 0.112857 0.02990305 -0.186359 0.112887 0.02974998 -0.186606 0.1129029 0.02974998 -0.187406 0.112902 0.02974998 -0.187493 0.112898 0.02974998 -0.18749 0.112868 0.02990305 -0.188054 0.112807 0.02974998 -0.188194 0.112767 0.02974998 -0.188047 0.112777 0.02990305 -0.188601 0.112652 0.02974998 -0.189126 0.1124359 0.02974998 -0.1896589 0.112136 0.02974998 -0.1900669 0.111808 0.02990305 -0.190487 0.111431 0.02990305 -0.190292 0.111647 0.02974998 -0.190861 0.111008 0.02990305 -0.191184 0.110545 0.02990305 -0.19121 0.110561 0.02974998 -0.191631 0.109682 0.02974998 -0.191691 0.109534 0.02974998 -0.191841 0.108986 0.02974998 -0.191897 0.108421 0.02990305 -0.191927 0.108424 0.02974998 -0.1919389 0.108119 0.02974998 -0.191949 0.107857 0.02974998 -0.191908 0.1073189 0.02974998 -0.191906 0.10729 0.02974998 -0.1916 0.106201 0.02990305 -0.19137 0.105686 0.02990305 -0.191084 0.105199 0.02990305 -0.191048 0.105101 0.02974998 -0.190743 0.104749 0.02990305 -0.190767 0.1047289 0.02974998 -0.190535 0.104487 0.02974998 -0.190354 0.10434 0.02990305 -0.190375 0.104318 0.02974998 -0.18992 0.103978 0.02990305 -0.1894479 0.103669 0.02990305 -0.189464 0.103642 0.02974998 -0.190295 0.104403 0.03003275 -0.191012 0.105248 0.03003275 -0.191293 0.105725 0.03003275 -0.191769 0.1067399 0.02990305 -0.1918759 0.107294 0.02990305 -0.191685 0.106761 0.03003275 -0.191919 0.107857 0.02990305 -0.191811 0.108979 0.02990305 -0.191662 0.109524 0.02990305 -0.191452 0.1100479 0.02990305 -0.19111 0.110499 0.03003275 -0.190793 0.110954 0.03003275 -0.189607 0.112136 0.02990305 -0.189113 0.112408 0.02990305 -0.188591 0.112623 0.02990305 -0.1890749 0.11233 0.03003275 -0.186926 0.1128939 0.02990305 -0.186927 0.112808 0.03003275 -0.186374 0.112771 0.03003275 -0.185268 0.11259 0.02990305 -0.18475 0.112366 0.02990305 -0.183807 0.111747 0.02990305 -0.183395 0.111361 0.02990305 -0.18303 0.110931 0.02990305 -0.183099 0.110879 0.03003275 -0.182536 0.109925 0.03003275 -0.18234 0.109406 0.03003275 -0.182119 0.108884 0.02990305 -0.182034 0.10776 0.02990305 -0.1821309 0.108318 0.03003275 -0.182385 0.106111 0.02990305 -0.182289 0.106669 0.03003275 -0.182466 0.1061429 0.03003275 -0.1826249 0.1055999 0.02990305 -0.183335 0.104733 0.03003275 -0.183667 0.104274 0.02990305 -0.1837249 0.104339 0.03003275 -0.185128 0.103457 0.03003275 -0.1856279 0.103192 0.02990305 -0.186194 0.103155 0.03003275 -0.186745 0.103098 0.03003275 -0.1873 0.103103 0.03003275 -0.1878499 0.103172 0.03003275 -0.188389 0.103303 0.03003275 -0.18891 0.103494 0.03003275 -0.190206 0.104498 0.03011959 -0.190677 0.104805 0.03003275 -0.191178 0.105785 0.03011959 -0.191519 0.106232 0.03003275 -0.19179 0.107306 0.03003275 -0.191832 0.107859 0.03003275 -0.191811 0.108413 0.03003275 -0.191726 0.108961 0.03003275 -0.191599 0.108934 0.03011959 -0.1915799 0.1094959 0.03003275 -0.191457 0.109455 0.03011959 -0.191374 0.110011 0.03003275 -0.191256 0.109956 0.03011959 -0.191 0.110431 0.03011959 -0.190425 0.11137 0.03003275 -0.1906909 0.1108739 0.03011959 -0.190333 0.1112779 0.03011959 -0.190013 0.111741 0.03003275 -0.189932 0.111639 0.03011959 -0.189561 0.112062 0.03003275 -0.189492 0.111952 0.03011959 -0.188562 0.112541 0.03003275 -0.189019 0.112213 0.03011959 -0.18852 0.112418 0.03011959 -0.188029 0.1126919 0.03003275 -0.187481 0.112781 0.03003275 -0.188001 0.112565 0.03011959 -0.185828 0.112671 0.03003275 -0.185859 0.112544 0.03011959 -0.185298 0.112509 0.03003275 -0.184789 0.1122879 0.03003275 -0.185342 0.112387 0.03011959 -0.1848469 0.112172 0.03011959 -0.184309 0.112011 0.03003275 -0.183863 0.11168 0.03003275 -0.183946 0.111581 0.03011959 -0.183458 0.111301 0.03003275 -0.183552 0.111212 0.03011959 -0.18279 0.110418 0.03003275 -0.182205 0.108868 0.03003275 -0.182332 0.108843 0.03011959 -0.182121 0.107764 0.03003275 -0.182174 0.107211 0.03003275 -0.182701 0.105641 0.03003275 -0.182992 0.1051689 0.03003275 -0.183098 0.105243 0.03011959 -0.183432 0.1048189 0.03011959 -0.183812 0.104435 0.03011959 -0.184158 0.103992 0.03003275 -0.184628 0.103697 0.03003275 -0.185652 0.103276 0.03003275 -0.1893399 0.103856 0.03011959 -0.189405 0.103744 0.03003275 -0.189869 0.104048 0.03003275 -0.190101 0.10461 0.03014999 -0.190578 0.104889 0.03011959 -0.1904619 0.104988 0.03014999 -0.190904 0.10532 0.03011959 -0.190777 0.105405 0.03014999 -0.191042 0.105855 0.03014999 -0.191397 0.106278 0.03011959 -0.191254 0.106332 0.03014999 -0.191559 0.106793 0.03011959 -0.191411 0.10683 0.03014999 -0.191509 0.107343 0.03014999 -0.191661 0.107323 0.03011959 -0.191702 0.107861 0.03011959 -0.191549 0.107864 0.03014999 -0.191529 0.108386 0.03014999 -0.191681 0.108401 0.03011959 -0.1914499 0.108903 0.03014999 -0.191312 0.109406 0.03014999 -0.191118 0.1098909 0.03014999 -0.190869 0.110351 0.03014999 -0.1905699 0.110779 0.03014999 -0.190224 0.111171 0.03014999 -0.189836 0.11152 0.03014999 -0.18941 0.111823 0.03014999 -0.188953 0.112075 0.03014999 -0.18847 0.112274 0.03014999 -0.187967 0.112416 0.03014999 -0.1874679 0.112652 0.03011959 -0.187452 0.1125 0.03014999 -0.186928 0.112678 0.03011959 -0.18693 0.112525 0.03014999 -0.18639 0.112642 0.03011959 -0.1864089 0.1124899 0.03014999 -0.185895 0.112396 0.03014999 -0.185395 0.112244 0.03014999 -0.184916 0.112036 0.03014999 -0.1843799 0.1119019 0.03011959 -0.184464 0.111774 0.03014999 -0.184044 0.111463 0.03014999 -0.183663 0.111106 0.03014999 -0.183203 0.1108 0.03011959 -0.1833249 0.1107079 0.03014999 -0.182902 0.110352 0.03011959 -0.183034 0.110274 0.03014999 -0.182655 0.109872 0.03011959 -0.182795 0.1098099 0.03014999 -0.18261 0.1093209 0.03014999 -0.182464 0.109367 0.03011959 -0.18226 0.108308 0.03011959 -0.182482 0.108814 0.03014999 -0.182413 0.108297 0.03014999 -0.18225 0.107769 0.03011959 -0.182403 0.107774 0.03014999 -0.1823019 0.107231 0.03011959 -0.182453 0.107254 0.03014999 -0.1825619 0.106744 0.03014999 -0.1824139 0.106703 0.03011959 -0.1827279 0.106248 0.03014999 -0.182586 0.106191 0.03011959 -0.18295 0.1057749 0.03014999 -0.182815 0.1057029 0.03011959 -0.183224 0.105331 0.03014999 -0.183547 0.10492 0.03014999 -0.183915 0.104549 0.03014999 -0.184233 0.104098 0.03011959 -0.1846899 0.10381 0.03011959 -0.1843219 0.104223 0.03014999 -0.184764 0.103944 0.03014999 -0.185177 0.103577 0.03011959 -0.185235 0.1037189 0.03014999 -0.185687 0.103401 0.03011959 -0.185729 0.103548 0.03014999 -0.186214 0.103283 0.03011959 -0.186239 0.103435 0.03014999 -0.186751 0.103227 0.03011959 -0.1867589 0.10338 0.03014999 -0.187291 0.103233 0.03011959 -0.187827 0.103299 0.03011959 -0.187281 0.103385 0.03014999 -0.188351 0.103427 0.03011959 -0.187799 0.10345 0.03014999 -0.188858 0.103613 0.03011959 -0.188307 0.103573 0.03014999 -0.1887969 0.103754 0.03014999 -0.1892639 0.103989 0.03014999 -0.1897 0.104275 0.03014999 -0.189791 0.104152 0.03011959 -0.189256 0.103537 0.02974998 -0.1892589 0.10353 0.02884995 -0.188521 0.1032209 0.02884995 -0.1877419 0.103035 0.02884995 -0.187308 0.102986 0.02974998 -0.186146 0.103045 0.02884995 -0.186944 0.102975 0.02884995 -0.186944 0.1029829 0.02974998 -0.18537 0.103241 0.02884995 -0.185083 0.103349 0.02974998 -0.184635 0.103559 0.02884995 -0.18409 0.103897 0.02974998 -0.183365 0.104526 0.02884995 -0.183965 0.103997 0.02974998 -0.183247 0.104655 0.02974998 -0.1828629 0.10515 0.02884995 -0.182865 0.1051509 0.02974998 -0.1825979 0.105585 0.02974998 -0.182357 0.1061 0.02974998 -0.182188 0.106596 0.02884995 -0.182004 0.1077589 0.02974998 -0.182058 0.107194 0.02974998 -0.18209 0.1088899 0.02974998 -0.182107 0.108976 0.02884995 -0.182014 0.108327 0.02974998 -0.182683 0.110464 0.02974998 -0.182682 0.110465 0.02884995 -0.18269 0.110477 0.02974998 -0.1831409 0.1111209 0.02884995 -0.183006 0.110949 0.02974998 -0.183788 0.11177 0.02974998 -0.184342 0.112171 0.02884995 -0.184736 0.112393 0.02974998 -0.185057 0.112532 0.02974998 -0.185801 0.112784 0.02974998 -0.185815 0.112788 0.02884995 -0.185815 0.112787 0.02974998 -0.187406 0.112906 0.02884995 -0.186926 0.112925 0.02974998 -0.188951 0.1125079 0.02974998 -0.1896229 0.112161 0.02974998 -0.190846 0.11107 0.02974998 -0.1908479 0.111072 0.02884995 -0.190508 0.111452 0.02974998 -0.190086 0.111832 0.02974998 -0.190885 0.111027 0.02974998 -0.191293 0.110407 0.02974998 -0.19148 0.110061 0.02974998 -0.191856 0.108914 0.02884995 -0.191852 0.108914 0.02974998 -0.191799 0.106733 0.02974998 -0.191738 0.1065379 0.02974998 -0.191628 0.106191 0.02974998 -0.191451 0.105791 0.02974998 -0.191398 0.105672 0.02974998 -0.191051 0.105098 0.02884995 -0.191109 0.105182 0.02974998 -0.189938 0.103954 0.02974998 -0.189938 0.103954 0.02884995 -0.190541 0.104481 0.02884995 -0.1839399 0.104493 0.02884995 -0.183961 0.103992 0.02884995 -0.184568 0.10403 0.02884995 -0.185265 0.103679 0.02884995 -0.186012 0.103452 0.02884995 -0.1867859 0.103354 0.02884995 -0.187565 0.103388 0.02884995 -0.188328 0.1035529 0.02884995 -0.189051 0.103845 0.02884995 -0.189715 0.104255 0.02884995 -0.1902999 0.104771 0.02884995 -0.190789 0.105379 0.02884995 -0.191169 0.106061 0.02884995 -0.191428 0.106797 0.02884995 -0.191456 0.105789 0.02884995 -0.191745 0.106536 0.02884995 -0.191559 0.1075659 0.02884995 -0.191558 0.108346 0.02884995 -0.19191 0.1073189 0.02884995 -0.191425 0.109115 0.02884995 -0.191947 0.108119 0.02884995 -0.191164 0.10985 0.02884995 -0.1916379 0.109685 0.02884995 -0.191299 0.11041 0.02884995 -0.190783 0.110531 0.02884995 -0.190292 0.111137 0.02884995 -0.190297 0.111653 0.02884995 -0.189705 0.111652 0.02884995 -0.18904 0.11206 0.02884995 -0.18966 0.112138 0.02884995 -0.1889539 0.112515 0.02884995 -0.188316 0.11235 0.02884995 -0.188196 0.112773 0.02884995 -0.187553 0.112514 0.02884995 -0.186774 0.112546 0.02884995 -0.186606 0.112911 0.02884995 -0.186 0.1124449 0.02884995 -0.185254 0.112216 0.02884995 -0.185054 0.112539 0.02884995 -0.184558 0.111864 0.02884995 -0.1839309 0.111399 0.02884995 -0.183699 0.111695 0.02884995 -0.183392 0.110835 0.02884995 -0.182956 0.110188 0.02884995 -0.182636 0.109477 0.02884995 -0.182334 0.1097429 0.02884995 -0.18244 0.108721 0.02884995 -0.182375 0.107944 0.02884995 -0.182005 0.108182 0.02884995 -0.182442 0.107167 0.02884995 -0.182032 0.107381 0.02884995 -0.18264 0.106412 0.02884995 -0.182962 0.105701 0.02884995 -0.182467 0.105846 0.02884995 -0.1834 0.105055 0.02884995 -0.188352 0.105285 0.02614998 -0.188762 0.10554 0.02614998 -0.189125 0.105858 0.02494996 -0.189125 0.105858 0.02614998 -0.189433 0.10623 0.02494996 -0.189433 0.10623 0.02614998 -0.189677 0.106647 0.02494996 -0.189677 0.106647 0.02614998 -0.189851 0.107097 0.02494996 -0.189851 0.107097 0.02614998 -0.189951 0.10757 0.02494996 -0.189951 0.10757 0.02614998 -0.1899729 0.108052 0.02614998 -0.1899729 0.108052 0.02494996 -0.189918 0.108532 0.02614998 -0.189918 0.108532 0.02494996 -0.189787 0.108996 0.02494996 -0.189582 0.109434 0.02494996 -0.189787 0.108996 0.02614998 -0.189582 0.109434 0.02614998 -0.189311 0.109833 0.02494996 -0.189311 0.109833 0.02614998 -0.188978 0.110183 0.02614998 -0.188978 0.110183 0.02494996 -0.188594 0.110475 0.02614998 -0.188594 0.110475 0.02494996 -0.188168 0.110702 0.02494996 -0.188168 0.110702 0.02614998 -0.187711 0.110858 0.02494996 -0.187711 0.110858 0.02614998 -0.1872349 0.110939 0.02614998 -0.1872349 0.110939 0.02494996 -0.186752 0.110942 0.02494996 -0.186752 0.110942 0.02614998 -0.186275 0.110867 0.02494996 -0.186275 0.110867 0.02614998 -0.185816 0.1107169 0.02614998 -0.185816 0.1107169 0.02494996 -0.185387 0.110496 0.02614998 -0.185387 0.110496 0.02494996 -0.185 0.110208 0.02494996 -0.1846629 0.109862 0.02494996 -0.185 0.110208 0.02614998 -0.1846629 0.109862 0.02614998 -0.184386 0.109466 0.02494996 -0.184386 0.109466 0.02614998 -0.184177 0.109031 0.02494996 -0.184177 0.109031 0.02614998 -0.1840389 0.108569 0.02494996 -0.1840389 0.108569 0.02614998 -0.183978 0.10809 0.02494996 -0.183978 0.10809 0.02614998 -0.183995 0.107607 0.02494996 -0.183995 0.107607 0.02614998 -0.184088 0.107134 0.02614998 -0.184088 0.107134 0.02494996 -0.184256 0.106681 0.02494996 -0.184256 0.106681 0.02614998 -0.184495 0.106261 0.02494996 -0.184495 0.106261 0.02614998 -0.184798 0.105885 0.02494996 -0.184798 0.105885 0.02614998 -0.185158 0.105563 0.02494996 -0.185158 0.105563 0.02614998 -0.185564 0.105302 0.02494996 -0.185564 0.105302 0.02614998 -0.186007 0.10511 0.02494996 -0.186007 0.10511 0.02614998 -0.186475 0.104992 0.02494996 -0.186475 0.104992 0.02614998 -0.186956 0.10495 0.02494996 -0.186956 0.10495 0.02614998 -0.1874369 0.104986 0.02494996 -0.1874369 0.104986 0.02614998 -0.187907 0.105098 0.02494996 -0.188352 0.105285 0.02494996 -0.187907 0.105098 0.02614998 -0.188762 0.10554 0.02494996 -0.17882 0.1094869 0.01739996 -0.178725 0.108847 0.01739996 -0.1786659 0.109874 0.01889997 -0.17882 0.1094869 0.01889997 -0.178725 0.108847 0.01889997 -0.177942 0.11051 0.01889997 -0.176833 0.110348 0.01739996 -0.177047 0.110433 0.01889997 -0.177435 0.110586 0.01739996 -0.176336 0.109201 0.01739996 -0.176431 0.109841 0.01739996 -0.176833 0.110348 0.01889997 -0.178466 0.10852 0.01889997 -0.178322 0.10834 0.01739996 -0.1767539 0.108456 0.01889997 -0.194415 0.117722 0.01785719 -0.1762779 0.100952 0.01898735 -0.176182 0.1011559 0.01892137 -0.176348 0.100758 0.01909875 -0.176385 0.100584 0.01925247 -0.176267 0.100285 0.0198611 -0.176165 0.100267 0.02007198 -0.175911 0.100334 0.02045458 -0.17562 0.100517 0.02076917 -0.176192 0.0992583 0.02139997 -0.175324 0.1008 0.02099364 -0.1762999 0.101876 0.01785719 -0.175464 0.103667 0.01785719 -0.1747 0.107533 0.01785719 -0.174337 0.106663 0.01889997 -0.174926 0.105569 0.01785719 -0.174792 0.109507 0.01785719 -0.174493 0.112871 0.02042227 -0.174305 0.112699 0.0206784 -0.1744999 0.113966 0.02139997 -0.173921 0.112099 0.02105426 -0.1740379 0.112328 0.02096515 -0.174943 0.112878 0.01948308 -0.174993 0.1126649 0.01919859 -0.174966 0.11232 0.01898097 -0.174921 0.112115 0.01892119 -0.174856 0.111891 0.01889997 -0.175199 0.111441 0.01785719 -0.1737999 0.111769 0.02109998 -0.173829 0.1118479 0.02108919 -0.173994 0.10312 0.02139997 -0.173518 0.105291 0.02109998 -0.1732659 0.107484 0.02109998 -0.173368 0.1096889 0.02109998 -0.175053 0.101167 0.02109736 -0.1750119 0.101239 0.02109998 -0.1741189 0.1031669 0.02109998 -0.198431 0.103522 0.01785719 -0.198256 0.102001 0.01892155 -0.197573 0.101742 0.01785719 -0.198384 0.102186 0.01898759 -0.198517 0.102344 0.01909917 -0.198649 0.102462 0.01925337 -0.198773 0.10253 0.01944094 -0.19888 0.102545 0.01964718 -0.1989679 0.102509 0.01986187 -0.199034 0.10243 0.0200721 -0.199102 0.102176 0.02045518 -0.199894 0.102957 0.02139997 -0.199089 0.101832 0.02077007 -0.198992 0.101434 0.02099418 -0.1934739 0.09752798 0.01785719 -0.1942909 0.09808468 0.01785719 -0.195365 0.09835815 0.01889997 -0.195062 0.09870547 0.01785719 -0.19644 0.100122 0.01785719 -0.191492 0.0960626 0.01889997 -0.189839 0.09600627 0.01785719 -0.191718 0.09662038 0.01785719 -0.1889539 0.09467935 0.02042227 -0.188738 0.0948292 0.02001869 -0.189198 0.09460288 0.02067887 -0.189907 0.09457069 0.02105396 -0.189653 0.0945574 0.02096569 -0.188723 0.09506618 0.01948314 -0.1888819 0.09521585 0.01919907 -0.1878859 0.09570145 0.01785719 -0.189194 0.09536439 0.01898127 -0.189395 0.0954287 0.01892119 -0.189622 0.09548407 0.01889997 -0.190255 0.09463059 0.02109998 -0.190205 0.09448188 0.02139997 -0.190173 0.09461635 0.02108907 -0.192272 0.0952968 0.02109998 -0.194233 0.09631037 0.02109998 -0.194303 0.09619778 0.02139997 -0.196006 0.09762549 0.02109998 -0.195225 0.09682559 0.02139997 -0.196094 0.09752547 0.02139997 -0.198926 0.10095 0.02139997 -0.19881 0.1010169 0.02109736 -0.198769 0.100945 0.02109998 -0.197546 0.09920787 0.02109998 -0.186264 0.120712 0.01898699 -0.186488 0.120694 0.01892125 -0.187052 0.120232 0.01785719 -0.186061 0.1207489 0.01909786 -0.185892 0.120804 0.01925116 -0.185081 0.120085 0.01785719 -0.1856909 0.121055 0.01985806 -0.184839 0.121634 0.02139997 -0.185725 0.121152 0.02006858 -0.185908 0.121338 0.02045065 -0.186214 0.121499 0.02076786 -0.187062 0.1218 0.02139997 -0.186722 0.120691 0.01889997 -0.189021 0.120061 0.01785719 -0.189098 0.120516 0.01889997 -0.1908389 0.120075 0.01889997 -0.192751 0.118789 0.01785719 -0.192968 0.119197 0.01889997 -0.1909379 0.119576 0.01785719 -0.196447 0.116475 0.01889997 -0.1946949 0.11809 0.01889997 -0.1972579 0.115906 0.01948255 -0.197127 0.114863 0.01785719 -0.1974779 0.116299 0.02042216 -0.197423 0.116548 0.02067846 -0.197094 0.117181 0.0210545 -0.198422 0.115746 0.02139997 -0.197234 0.116965 0.02096539 -0.197049 0.115969 0.01919829 -0.1967639 0.116165 0.0189808 -0.195886 0.116402 0.01785719 -0.1966069 0.116308 0.01892089 -0.19687 0.1174499 0.02109998 -0.196923 0.117386 0.02108919 -0.191443 0.121059 0.02139997 -0.1913999 0.120934 0.02109998 -0.193426 0.120056 0.02109998 -0.193488 0.120173 0.02139997 -0.195365 0.11897 0.02139997 -0.195284 0.1188639 0.02109998 -0.186607 0.121615 0.02099329 -0.187061 0.121666 0.02109736 -0.187144 0.121666 0.02109998 -0.18926 0.121476 0.02109998 -0.18869 0.09493488 0.0197677 -0.188002 0.0941382 0.02139997 -0.183576 0.0945236 0.02139997 -0.18591 0.09571397 0.01785719 -0.181466 0.09524267 0.02139997 -0.183961 0.09604328 0.01785719 -0.18209 0.09668099 0.01785719 -0.177726 0.09764111 0.02139997 -0.1803449 0.09761059 0.01785719 -0.178773 0.09880799 0.01785719 -0.177412 0.100242 0.01785719 -0.1763409 0.100343 0.01964676 -0.176382 0.100443 0.01944005 -0.197456 0.116037 0.02001816 -0.1973879 0.115943 0.01976728 -0.1995249 0.113809 0.02139997 -0.198104 0.113145 0.01785719 -0.200302 0.11172 0.02139997 -0.198794 0.111293 0.01785719 -0.200734 0.109533 0.02139997 -0.20081 0.107305 0.02139997 -0.199177 0.109354 0.01785719 -0.199244 0.107378 0.01785719 -0.198993 0.105418 0.01785719 -0.174731 0.112983 0.02001816 -0.1748459 0.112972 0.0197677 -0.175912 0.113285 0.01785719 -0.177047 0.1176069 0.02139997 -0.1769109 0.114991 0.01785719 -0.178171 0.116514 0.01785719 -0.1796579 0.117815 0.01785719 -0.181336 0.118861 0.01785719 -0.182672 0.121115 0.02139997 -0.1831589 0.119624 0.01785719 -0.1857039 0.120961 0.01964396 -0.185771 0.120876 0.01943814 -0.193033 0.09610611 0.02139997 -0.192323 0.09517437 0.02139997 -0.188859 0.0947808 0.02139997 -0.185774 0.09415221 0.02139997 -0.180373 0.09640049 0.02139997 -0.179499 0.09629088 0.02139997 -0.176981 0.09916996 0.02139997 -0.174937 0.101101 0.02139997 -0.1746709 0.102891 0.02139997 -0.173388 0.105265 0.02139997 -0.173133 0.107479 0.02139997 -0.173695 0.10716 0.02139997 -0.173237 0.109706 0.02139997 -0.173696 0.111887 0.02139997 -0.17601 0.115483 0.02139997 -0.175626 0.115889 0.02139997 -0.1773999 0.1171849 0.02139997 -0.178724 0.119074 0.02139997 -0.180616 0.120254 0.02139997 -0.189283 0.121606 0.02139997 -0.191586 0.120429 0.02139997 -0.193577 0.119499 0.02139997 -0.196969 0.11673 0.02139997 -0.197024 0.117481 0.02139997 -0.200255 0.10874 0.02139997 -0.200204 0.106543 0.02139997 -0.200527 0.105094 0.02139997 -0.19903 0.102324 0.02139997 -0.1979399 0.100417 0.02139997 -0.19655 0.09871476 0.02139997 -0.197648 0.09912329 0.02139997 -0.1949 0.0972647 0.02139997 -0.197776 0.102284 0.01889997 -0.1756719 0.100935 0.02139997 -0.174006 0.1049849 0.02139997 -0.174136 0.105015 0.02109998 -0.173828 0.107168 0.02109998 -0.173746 0.1093569 0.02139997 -0.173878 0.109342 0.02109998 -0.175058 0.112901 0.02049809 -0.175581 0.112415 0.01899075 -0.175528 0.11219 0.01892215 -0.1756179 0.11236 0.01889997 -0.175305 0.113044 0.02011227 -0.17492 0.113576 0.02139997 -0.17561 0.112624 0.01910698 -0.175608 0.112804 0.01926767 -0.175573 0.11294 0.01946336 -0.1755059 0.1130239 0.01967775 -0.174805 0.112637 0.0208075 -0.174572 0.112274 0.02101939 -0.174158 0.111515 0.02139997 -0.174391 0.111837 0.02109998 -0.174286 0.111479 0.02109998 -0.185449 0.120397 0.01967567 -0.1860229 0.120957 0.0208081 -0.185696 0.120791 0.02049785 -0.185091 0.121119 0.02139997 -0.185488 0.120596 0.02011168 -0.185443 0.120495 0.01989668 -0.1855109 0.120308 0.01946008 -0.185632 0.120235 0.01926535 -0.1858029 0.120182 0.01910549 -0.186012 0.120149 0.01898986 -0.186242 0.120135 0.01892197 -0.19154 0.120304 0.02109998 -0.189444 0.120887 0.02109998 -0.187281 0.121117 0.02109998 -0.189469 0.121017 0.02139997 -0.1872839 0.12125 0.02139997 -0.186908 0.12112 0.02109998 -0.186437 0.121074 0.02101916 -0.195388 0.118255 0.02139997 -0.195304 0.118152 0.02109998 -0.193511 0.119384 0.02109998 -0.196507 0.115612 0.01897448 -0.19666 0.115487 0.01907038 -0.196806 0.1153939 0.01920437 -0.196938 0.1153399 0.01937019 -0.197193 0.115432 0.01995557 -0.198278 0.114965 0.02139997 -0.197235 0.115652 0.0203278 -0.197188 0.115945 0.02064615 -0.1970599 0.116279 0.02089476 -0.1968539 0.116629 0.02105468 -0.196633 0.116904 0.02109998 -0.198528 0.103046 0.01969885 -0.1983129 0.103565 0.01889997 -0.198345 0.103009 0.01935315 -0.198225 0.1029199 0.01918637 -0.198028 0.102792 0.01889997 -0.198083 0.102766 0.01903849 -0.197923 0.102539 0.01893377 -0.199792 0.104385 0.02139997 -0.1987349 0.102462 0.02066439 -0.198706 0.102221 0.02084028 -0.198644 0.10196 0.02097755 -0.1910009 0.09527045 0.02139997 -0.192972 0.0962243 0.02109998 -0.194821 0.09737139 0.02109998 -0.196455 0.09880697 0.02109998 -0.19783 0.100492 0.02109998 -0.198414 0.101423 0.02109998 -0.198547 0.101692 0.02106696 -0.189606 0.09505969 0.0210675 -0.1899 0.0951085 0.02109998 -0.190961 0.09539705 0.02109998 -0.188314 0.095474 0.01969259 -0.186666 0.09465038 0.02139997 -0.188345 0.09535968 0.01995676 -0.18849 0.09522849 0.02028828 -0.188813 0.09510308 0.02066439 -0.1891829 0.0950492 0.02091449 -0.188974 0.09590268 0.01893389 -0.188711 0.0958153 0.01903849 -0.188702 0.09587585 0.01889997 -0.18788 0.09582698 0.01889997 -0.18848 0.0956968 0.01923495 -0.188344 0.0955637 0.01949834 -0.186691 0.09575629 0.01889997 -0.1768699 0.100349 0.01991248 -0.176647 0.100361 0.02029955 -0.174794 0.102941 0.02109998 -0.175603 0.101307 0.02109998 -0.1758019 0.101015 0.02105468 -0.17612 0.100678 0.02086186 -0.176445 0.100448 0.0205549 -0.176958 0.100404 0.01967775 -0.177008 0.100529 0.01941758 -0.176988 0.100746 0.0191648 -0.1768749 0.101054 0.018974 -0.175414 0.113057 0.01989769 -0.175922 0.113108 0.01889997 -0.176922 0.114857 0.01889997 -0.177812 0.09990006 0.01889997 -0.178562 0.09764468 0.02139997 -0.179662 0.09822666 0.01889997 -0.177973 0.09974408 0.01889997 -0.184688 0.09596925 0.01889997 -0.184481 0.09488266 0.02139997 -0.182747 0.09650909 0.01889997 -0.182566 0.09659379 0.01889997 -0.182364 0.09547138 0.02139997 -0.198718 0.102767 0.02034449 -0.198629 0.102979 0.01996839 -0.1987259 0.104682 0.01889997 -0.199122 0.108873 0.01889997 -0.199104 0.10666 0.01889997 -0.197049 0.11533 0.01955807 -0.198255 0.112588 0.01889997 -0.199279 0.113009 0.02139997 -0.199943 0.110915 0.02139997 -0.1988649 0.110668 0.01889997 -0.182949 0.120629 0.02139997 -0.183284 0.119575 0.01889997 -0.1827999 0.119376 0.01889997 -0.180917 0.119794 0.02139997 -0.181421 0.118809 0.01889997 -0.17905 0.1186349 0.02139997 -0.1777909 0.115921 0.01889997 -0.180961 0.09734278 0.01889997 -0.183942 0.09955406 0.01889997 -0.175071 0.103421 0.01889997 -0.182013 0.119052 0.01889997 -0.189866 0.100703 0.01889997 -0.189536 0.1138589 0.01889997 -0.1910859 0.120012 0.01889997 -0.189296 0.115366 0.01889997 -0.1893399 0.115664 0.01889997 -0.195875 0.105409 0.01889997 -0.1951299 0.106413 0.01889997 -0.1952829 0.106026 0.01889997 -0.195368 0.1058109 0.01889997 -0.196515 0.105314 0.01889997 -0.196902 0.105467 0.01889997 -0.197117 0.105552 0.01889997 -0.197519 0.106059 0.01889997 -0.19915 0.108674 0.01889997 -0.197614 0.106699 0.01889997 -0.197376 0.1073009 0.01889997 -0.198871 0.110626 0.01889997 -0.197196 0.107444 0.01889997 -0.195627 0.10756 0.01889997 -0.195484 0.10738 0.01889997 -0.195133 0.107853 0.01889997 -0.195225 0.107053 0.01889997 -0.189947 0.09555757 0.01889997 -0.184579 0.100026 0.01889997 -0.184559 0.09989368 0.01889997 -0.184797 0.09929198 0.01889997 -0.18487 0.09830278 0.01889997 -0.185304 0.0988897 0.01889997 -0.185602 0.09884548 0.01889997 -0.183745 0.102379 0.01889997 -0.184701 0.1019639 0.01889997 -0.185658 0.101278 0.01889997 -0.187043 0.100179 0.01889997 -0.185117 0.101784 0.01889997 -0.186166 0.101203 0.01889997 -0.186589 0.101522 0.01889997 -0.186596 0.101522 0.01889997 -0.186298 0.1011829 0.01889997 -0.186805 0.100781 0.01889997 -0.187404 0.116867 0.01889997 -0.187002 0.116361 0.01889997 -0.186982 0.116228 0.01889997 -0.186951 0.116019 0.01889997 -0.188006 0.117105 0.01889997 -0.188304 0.117061 0.01889997 -0.189153 0.116608 0.01889997 -0.191875 0.11967 0.01889997 -0.188646 0.1170099 0.01889997 -0.183073 0.113211 0.01889997 -0.18588 0.115224 0.01889997 -0.1792449 0.114336 0.01889997 -0.179722 0.113551 0.01889997 -0.18045 0.112991 0.01889997 -0.181049 0.112815 0.01889997 -0.1813319 0.112732 0.01889997 -0.182247 0.112809 0.01889997 -0.184045 0.115657 0.01889997 -0.1853179 0.115981 0.01889997 -0.183108 0.117201 0.01889997 -0.177253 0.115262 0.01889997 -0.179261 0.116142 0.01889997 -0.179751 0.116919 0.01889997 -0.1836979 0.113885 0.01889997 -0.184037 0.114738 0.01889997 -0.18404 0.115032 0.01889997 -0.182289 0.117618 0.01889997 -0.181375 0.1177099 0.01889997 -0.180489 0.117467 0.01889997 -0.1880699 0.100676 0.01889997 -0.187409 0.101568 0.01889997 -0.191901 0.103801 0.01889997 -0.190811 0.102777 0.01889997 -0.1895149 0.102032 0.01889997 -0.188082 0.101606 0.01889997 -0.180577 0.107214 0.01889997 -0.180919 0.105758 0.01889997 -0.1815879 0.104421 0.01889997 -0.182547 0.103274 0.01889997 -0.18097 0.110249 0.01889997 -0.185139 0.114123 0.01889997 -0.1837649 0.113533 0.01889997 -0.182564 0.112642 0.01889997 -0.180332 0.11111 0.01889997 -0.181601 0.111499 0.01889997 -0.193244 0.109424 0.01889997 -0.192735 0.11083 0.01889997 -0.190135 0.114593 0.01889997 -0.191916 0.112081 0.01889997 -0.1908299 0.113109 0.01889997 -0.193376 0.107608 0.01889997 -0.193415 0.107938 0.01889997 -0.194249 0.109045 0.01889997 -0.193363 0.108388 0.01889997 -0.192725 0.105049 0.01889997 -0.192956 0.105682 0.01889997 -0.1932359 0.106447 0.01889997 -0.193239 0.106453 0.01889997 -0.193882 0.106925 0.01889997 -0.18058 0.108709 0.01889997 -0.1805779 0.107505 0.01889997 -0.178322 0.10834 0.01889997 -0.179701 0.106855 0.01889997 -0.177721 0.108102 0.01889997 -0.177588 0.108122 0.01889997 -0.176431 0.109841 0.01889997 -0.176411 0.109709 0.01889997 -0.1748369 0.111831 0.01889997 -0.179084 0.115241 0.01889997 -0.179771 0.1118659 0.01889997 -0.175456 0.1119599 0.01889997 -0.177435 0.110586 0.01889997 -0.180927 0.110164 0.01889997 -0.178582 0.110089 0.01889997 -0.178075 0.110491 0.01889997 -0.177873 0.104259 0.01889997 -0.178611 0.104806 0.01889997 -0.179497 0.10505 0.01889997 -0.1798959 0.10501 0.01889997 -0.181195 0.100551 0.01889997 -0.180369 0.100149 0.01889997 -0.179454 0.100072 0.01889997 -0.179262 0.09850156 0.01889997 -0.1785719 0.100331 0.01889997 -0.177844 0.100891 0.01889997 -0.177383 0.103482 0.01889997 -0.177206 0.102581 0.01889997 -0.178944 0.106293 0.01889997 -0.180411 0.104957 0.01889997 -0.18182 0.101224 0.01889997 -0.182128 0.102 0.01889997 -0.182159 0.102078 0.01889997 -0.1821669 0.102997 0.01889997 -0.181843 0.103857 0.01889997 -0.18123 0.104541 0.01889997 -0.190504 0.09901279 0.01889997 -0.191896 0.0961948 0.01889997 -0.193718 0.09713649 0.01889997 -0.193029 0.09827059 0.01889997 -0.193855 0.09867298 0.01889997 -0.196795 0.0998283 0.01889997 -0.194827 0.101119 0.01889997 -0.197039 0.100177 0.01889997 -0.193071 0.10308 0.01889997 -0.192157 0.103172 0.01889997 -0.191271 0.102928 0.01889997 -0.1936179 0.10479 0.01889997 -0.198136 0.101799 0.01889997 -0.197971 0.101509 0.01889997 -0.1979359 0.101459 0.01889997 -0.19481 0.105674 0.01889997 -0.19389 0.102663 0.01889997 -0.196869 0.107703 0.01889997 -0.196229 0.107798 0.01889997 -0.189391 0.116006 0.01889997 -0.193149 0.115589 0.01889997 -0.192411 0.115041 0.01889997 -0.1919209 0.114264 0.01889997 -0.1962209 0.11672 0.01889997 -0.194765 0.118027 0.01889997 -0.194949 0.11574 0.01889997 -0.1940349 0.115832 0.01889997 -0.191744 0.113363 0.01889997 -0.191905 0.112458 0.01889997 -0.192382 0.1116729 0.01889997 -0.1931099 0.111113 0.01889997 -0.193992 0.110854 0.01889997 -0.197338 0.114382 0.01889997 -0.1957679 0.115323 0.01889997 -0.196207 0.115921 0.01889997 -0.194907 0.110931 0.01889997 -0.195733 0.111333 0.01889997 -0.196358 0.112007 0.01889997 -0.198402 0.112126 0.01889997 -0.1966969 0.11286 0.01889997 -0.196705 0.113779 0.01889997 -0.196381 0.114639 0.01889997 -0.186052 0.120098 0.01889997 -0.187761 0.117793 0.01889997 -0.186482 0.120137 0.01889997 -0.187055 0.120693 0.01889997 -0.1883479 0.1170549 0.01889997 -0.185248 0.120024 0.01889997 -0.184324 0.119813 0.01889997 -0.183721 0.116517 0.01889997 -0.188893 0.114859 0.01889997 -0.189258 0.113943 0.01889997 -0.188292 0.1146219 0.01889997 -0.18851 0.114168 0.01889997 -0.188105 0.1142899 0.01889997 -0.188159 0.114641 0.01889997 -0.186612 0.11438 0.01889997 -0.187652 0.114717 0.01889997 -0.1871449 0.115119 0.01889997 -0.1869069 0.115721 0.01889997 -0.186518 0.114363 0.01889997 -0.18651 0.116865 0.01889997 -0.178196 0.116417 0.01889997 -0.179709 0.117747 0.01889997 -0.175184 0.103505 0.01889997 -0.175031 0.103506 0.01889997 -0.174937 0.103838 0.01889997 -0.174473 0.10548 0.01889997 -0.177081 0.108197 0.01889997 -0.176574 0.108599 0.01889997 -0.176336 0.109201 0.01889997 -0.174238 0.107517 0.01889997 -0.17425 0.107772 0.01889997 -0.176356 0.109334 0.01889997 -0.174334 0.109566 0.01889997 -0.174757 0.111572 0.01889997 -0.176667 0.101429 0.01889997 -0.1760669 0.10136 0.01889997 -0.175899 0.101648 0.01889997 -0.177367 0.101676 0.01889997 -0.180922 0.0973609 0.01889997 -0.18461 0.1002359 0.01889997 -0.183058 0.100746 0.01889997 -0.1846539 0.100534 0.01889997 -0.183815 0.101307 0.01889997 -0.185056 0.101041 0.01889997 -0.186999 0.09988129 0.01889997 -0.186948 0.09953939 0.01889997 -0.186546 0.09903258 0.01889997 -0.189262 0.09596925 0.01889997 -0.185944 0.09879475 0.01889997 -0.1856459 0.09883898 0.01889997 -0.186756 0.09576016 0.01889997 -0.19448 0.09934645 0.01752275 -0.194819 0.1001999 0.01889997 -0.194663 0.09969478 0.01747018 -0.19346 0.09843307 0.01756119 -0.19448 0.09934645 0.01889997 -0.193855 0.09867298 0.01757419 -0.194199 0.09898036 0.01756125 -0.193029 0.09827059 0.01752275 -0.194827 0.101119 0.01739996 -0.194503 0.101979 0.01889997 -0.193071 0.10308 0.01739996 -0.192157 0.103172 0.01739996 -0.190533 0.102381 0.01889997 -0.190043 0.101604 0.01739996 -0.190043 0.101604 0.01889997 -0.189866 0.100703 0.01739996 -0.1900269 0.09979808 0.01889997 -0.191232 0.0984528 0.01889997 -0.192249 0.09818369 0.01739996 -0.1921139 0.0981937 0.01889997 -0.192641 0.0981962 0.01747 -0.197376 0.1073009 0.01739996 -0.197614 0.106699 0.01739996 -0.1980569 0.107334 0.01739996 -0.193298 0.117072 0.01739996 -0.193027 0.115525 0.01739996 -0.193919 0.11582 0.01739996 -0.194857 0.115765 0.01739996 -0.19754 0.111353 0.01739996 -0.196741 0.113224 0.01739996 -0.1965219 0.112311 0.01739996 -0.194274 0.110841 0.01739996 -0.1791599 0.115832 0.01739996 -0.191992 0.112256 0.01739996 -0.188893 0.114859 0.01739996 -0.189296 0.115366 0.01739996 -0.1917499 0.113163 0.01739996 -0.191861 0.114096 0.01739996 -0.1923069 0.114922 0.01739996 -0.189391 0.116006 0.01739996 -0.189153 0.116608 0.01739996 -0.188646 0.1170099 0.01739996 -0.191527 0.118073 0.01739996 -0.189603 0.118734 0.01739996 -0.188006 0.117105 0.01739996 -0.18759 0.119032 0.01739996 -0.187404 0.116867 0.01739996 -0.185557 0.1189579 0.01739996 -0.1835719 0.118515 0.01739996 -0.197693 0.110666 0.01739996 -0.195981 0.1115429 0.01739996 -0.195195 0.111029 0.01739996 -0.187652 0.114717 0.01739996 -0.181701 0.117716 0.01739996 -0.182614 0.117497 0.01739996 -0.183382 0.116956 0.01739996 -0.187002 0.116361 0.01739996 -0.183896 0.11617 0.01739996 -0.1869069 0.115721 0.01739996 -0.1840839 0.115249 0.01739996 -0.1839179 0.114325 0.01739996 -0.1834239 0.113526 0.01739996 -0.186222 0.111879 0.01739996 -0.188292 0.1146219 0.01739996 -0.192551 0.111501 0.01739996 -0.189577 0.110988 0.01739996 -0.190357 0.110086 0.01739996 -0.19335 0.111006 0.01739996 -0.190836 0.108994 0.01739996 -0.1833119 0.106342 0.01739996 -0.18414 0.110772 0.01739996 -0.1871449 0.115119 0.01739996 -0.182669 0.112967 0.01739996 -0.183434 0.109811 0.01739996 -0.179105 0.114894 0.01739996 -0.1794 0.114002 0.01739996 -0.177853 0.114273 0.01739996 -0.177507 0.11366 0.01739996 -0.180003 0.113282 0.01739996 -0.180829 0.112836 0.01739996 -0.181762 0.112725 0.01739996 -0.183043 0.108684 0.01739996 -0.187134 0.103953 0.01739996 -0.194819 0.1001999 0.01739996 -0.19479 0.100068 0.01739996 -0.197759 0.105322 0.01739996 -0.195627 0.10756 0.01739996 -0.196229 0.107798 0.01739996 -0.196869 0.107703 0.01739996 -0.197519 0.106059 0.01739996 -0.197117 0.105552 0.01739996 -0.195875 0.105409 0.01739996 -0.19389 0.102663 0.01739996 -0.190533 0.102381 0.01739996 -0.1921139 0.0981937 0.01739996 -0.191232 0.0984528 0.01739996 -0.190378 0.09738516 0.01739996 -0.190504 0.09901279 0.01739996 -0.1900269 0.09979808 0.01739996 -0.195225 0.107053 0.01739996 -0.1951299 0.106413 0.01739996 -0.191271 0.102928 0.01739996 -0.195368 0.1058109 0.01739996 -0.197983 0.109367 0.01739996 -0.196515 0.105314 0.01739996 -0.194503 0.101979 0.01739996 -0.197098 0.103398 0.01739996 -0.196097 0.101627 0.01739996 -0.184559 0.09989368 0.01739996 -0.184797 0.09929198 0.01739996 -0.185304 0.0988897 0.01739996 -0.1824229 0.09782707 0.01739996 -0.185944 0.09879475 0.01739996 -0.184347 0.09716629 0.01739996 -0.186359 0.09686779 0.01739996 -0.186546 0.09903258 0.01739996 -0.186948 0.09953939 0.01739996 -0.188392 0.09694159 0.01739996 -0.1846539 0.100534 0.01739996 -0.1812649 0.09848165 0.01739996 -0.185056 0.101041 0.01739996 -0.185658 0.101278 0.01739996 -0.186298 0.1011829 0.01739996 -0.189691 0.09723168 0.01739996 -0.186805 0.100781 0.01739996 -0.187043 0.100179 0.01739996 -0.175893 0.108566 0.01739996 -0.176574 0.108599 0.01739996 -0.186103 0.10207 0.01739996 -0.178582 0.110089 0.01739996 -0.178755 0.104871 0.01739996 -0.177209 0.102676 0.01739996 -0.177428 0.1035889 0.01739996 -0.17641 0.104547 0.01739996 -0.177969 0.104357 0.01739996 -0.1822 0.102737 0.01739996 -0.182089 0.101804 0.01739996 -0.181643 0.100978 0.01739996 -0.180922 0.1003749 0.01739996 -0.180652 0.09882789 0.01739996 -0.180031 0.10008 0.01739996 -0.179093 0.100135 0.01739996 -0.177081 0.108197 0.01739996 -0.177721 0.108102 0.01739996 -0.175967 0.106533 0.01739996 -0.176191 0.110578 0.01739996 -0.176852 0.112502 0.01739996 -0.178075 0.110491 0.01739996 -0.179675 0.105059 0.01739996 -0.1806 0.104894 0.01739996 -0.181398 0.104399 0.01739996 -0.181958 0.103644 0.01739996 -0.1893579 0.104737 0.01739996 -0.1893579 0.104737 0.02139997 -0.190199 0.1055819 0.02139997 -0.190199 0.1055819 0.01739996 -0.190753 0.106638 0.01739996 -0.190753 0.106638 0.02139997 -0.190972 0.10781 0.02139997 -0.190972 0.10781 0.01739996 -0.190836 0.108994 0.02139997 -0.190357 0.110086 0.02139997 -0.189577 0.110988 0.02139997 -0.188566 0.11162 0.02139997 -0.188566 0.11162 0.01739996 -0.187413 0.111926 0.01739996 -0.187413 0.111926 0.02139997 -0.186222 0.111879 0.02139997 -0.1850979 0.111482 0.01739996 -0.1850979 0.111482 0.02139997 -0.18414 0.110772 0.02139997 -0.183434 0.109811 0.02139997 -0.183043 0.108684 0.02139997 -0.183001 0.107493 0.01739996 -0.183001 0.107493 0.02139997 -0.1833119 0.106342 0.02139997 -0.1839489 0.105334 0.01739996 -0.1839489 0.105334 0.02139997 -0.184855 0.104558 0.02139997 -0.184855 0.104558 0.01739996 -0.185949 0.104084 0.01739996 -0.185949 0.104084 0.02139997 -0.187134 0.103953 0.02139997 -0.188305 0.104178 0.01739996 -0.188305 0.104178 0.02139997 -0.182054 0.10868 0.02039998 -0.1821359 0.109106 0.02039998 -0.191896 0.1072199 0.02324998 -0.191896 0.1072199 0.02039998 -0.191814 0.1067939 0.02039998 -0.186677 0.102984 0.02039998 -0.186245 0.103029 0.02039998 -0.188131 0.112789 0.02824997 -0.1889539 0.112515 0.02824997 -0.189716 0.112102 0.02824997 -0.189716 0.112102 0.02324998 -0.190396 0.111562 0.02824997 -0.190396 0.111562 0.02324998 -0.190971 0.110914 0.02324998 -0.190971 0.110914 0.02824997 -0.191425 0.110175 0.02324998 -0.191743 0.109368 0.02324998 -0.191425 0.110175 0.02824997 -0.191743 0.109368 0.02824997 -0.191917 0.108519 0.02324998 -0.191917 0.108519 0.02824997 -0.191941 0.107652 0.02824997 -0.191941 0.107652 0.02324998 -0.191814 0.1067939 0.02824997 -0.187705 0.112871 0.02039998 -0.184996 0.103385 0.02324998 -0.184996 0.103385 0.02824997 -0.184234 0.103798 0.02324998 -0.184234 0.103798 0.02824997 -0.1835539 0.104338 0.02324998 -0.1835539 0.104338 0.02824997 -0.182979 0.104986 0.02324998 -0.182525 0.105725 0.02324998 -0.182979 0.104986 0.02824997 -0.182525 0.105725 0.02824997 -0.182206 0.106532 0.02824997 -0.182206 0.106532 0.02324998 -0.182032 0.107381 0.02824997 -0.182032 0.107381 0.02324998 -0.182009 0.108248 0.02324998 -0.182009 0.108248 0.02824997 -0.182054 0.10868 0.02324998 -0.1821359 0.109106 0.02824997 -0.18241 0.109929 0.02824997 -0.18241 0.109929 0.02039998 -0.182823 0.110691 0.02039998 -0.182823 0.110691 0.02824997 -0.183362 0.111371 0.02824997 -0.183362 0.111371 0.02039998 -0.184011 0.111946 0.02039998 -0.184011 0.111946 0.02824997 -0.18475 0.1123999 0.02824997 -0.18475 0.1123999 0.02039998 -0.185557 0.1127189 0.02039998 -0.185557 0.1127189 0.02824997 -0.186406 0.112892 0.02824997 -0.186406 0.112892 0.02039998 -0.187273 0.112916 0.02039998 -0.187273 0.112916 0.02824997 -0.187705 0.112871 0.02324998 -0.188131 0.112789 0.02324998 -0.1889539 0.112515 0.02324998 -0.191539 0.105971 0.02039998 -0.191539 0.105971 0.02824997 -0.191126 0.105209 0.02039998 -0.190587 0.104529 0.02039998 -0.191126 0.105209 0.02824997 -0.190587 0.104529 0.02824997 -0.189938 0.103954 0.02039998 -0.189938 0.103954 0.02824997 -0.1892 0.1035 0.02824997 -0.1892 0.1035 0.02039998 -0.1883929 0.103181 0.02039998 -0.1883929 0.103181 0.02824997 -0.187543 0.103008 0.02039998 -0.187543 0.103008 0.02824997 -0.186677 0.102984 0.02824997 -0.186245 0.103029 0.02324998 -0.185819 0.103111 0.02824997 -0.185819 0.103111 0.02324998 -0.191467 0.105755 0.03444999 -0.191928 0.107266 0.03744995 -0.188397 0.112743 0.03744995 -0.188843 0.112546 0.03744995 -0.189312 0.111795 0.03794997 -0.190013 0.11187 0.03744995 -0.190215 0.111073 0.03794997 -0.190575 0.11142 0.03744995 -0.190958 0.110904 0.03744995 -0.19134 0.110388 0.03744995 -0.1913329 0.10907 0.03794997 -0.182823 0.110737 0.03444999 -0.182022 0.108634 0.03744995 -0.187162 0.112446 0.03794997 -0.187758 0.112888 0.03744995 -0.181989 0.108173 0.03744995 -0.182475 0.107977 0.03794997 -0.185552 0.103157 0.03744995 -0.184483 0.103631 0.03744995 -0.184378 0.103677 0.03744995 -0.183405 0.104456 0.03744995 -0.183375 0.10448 0.03744995 -0.183046 0.105756 0.03794997 -0.182132 0.106705 0.03744995 -0.181975 0.10798 0.03744995 -0.191332 0.106824 0.03794997 -0.191928 0.107266 0.03444999 -0.186788 0.103454 0.03794997 -0.186192 0.103012 0.03444999 -0.183735 0.104827 0.03794997 -0.184638 0.104105 0.03794997 -0.185591 0.107371 0.03794997 -0.185481 0.10808 0.03794997 -0.182617 0.10683 0.03794997 -0.185712 0.1087599 0.03794997 -0.182618 0.109076 0.03794997 -0.188255 0.112264 0.03794997 -0.190904 0.110144 0.03794997 -0.1856949 0.103636 0.03794997 -0.186666 0.106482 0.03794997 -0.1880069 0.106862 0.03794997 -0.191475 0.107923 0.03794997 -0.188457 0.1081809 0.03794997 -0.188457 0.1081809 0.03014999 -0.187624 0.109295 0.03467196 -0.187626 0.109301 0.03014999 -0.186924 0.109449 0.03794997 -0.186924 0.109449 0.03589636 -0.186896 0.109448 0.03569996 -0.187626 0.109301 0.03794997 -0.18818 0.108844 0.03794997 -0.18818 0.108844 0.03694999 -0.188395 0.107466 0.03794997 -0.188385 0.1074399 0.03569996 -0.188395 0.107466 0.03589636 -0.188454 0.107699 0.03507494 -0.188395 0.107466 0.03014999 -0.188475 0.107923 0.03484815 -0.187698 0.109264 0.03461748 -0.18818 0.108844 0.03014999 -0.188395 0.107466 0.03550356 -0.1880069 0.106862 0.03014999 -0.1873829 0.106507 0.03794997 -0.1873829 0.106507 0.03014999 -0.186666 0.106482 0.03014999 -0.186019 0.1067939 0.03794997 -0.186019 0.1067939 0.03014999 -0.18577 0.107056 0.03014999 -0.185591 0.107371 0.03014999 -0.185481 0.10808 0.03014999 -0.185712 0.1087599 0.03014999 -0.186233 0.109254 0.03014999 -0.186233 0.109254 0.03794997 -0.186924 0.109449 0.03550356 -0.186924 0.109449 0.03014999 -0.191591 0.109871 0.03602397 -0.188457 0.1081809 0.03466236 -0.1914539 0.110172 0.0348162 -0.188434 0.10826 0.03462725 -0.191332 0.110403 0.03461748 -0.188347 0.108557 0.03449416 -0.190991 0.1109279 0.03444999 -0.191541 0.109988 0.03507494 -0.191608 0.10983 0.03569996 -0.188423 0.10756 0.03527617 -0.188454 0.107699 0.03632497 -0.188423 0.10756 0.03612339 -0.188475 0.107923 0.03655189 -0.191541 0.109988 0.03632497 -0.18845 0.1081809 0.03672796 -0.1914539 0.110172 0.03658407 -0.188442 0.10826 0.0367825 -0.188347 0.108557 0.03690576 -0.187626 0.109301 0.03673756 -0.190401 0.111591 0.03658396 -0.187695 0.109256 0.03677266 -0.187954 0.109086 0.03690576 -0.190789 0.111183 0.03690719 -0.187022 0.109449 0.03612387 -0.190153 0.11181 0.03602379 -0.187164 0.109438 0.03632497 -0.1902509 0.1117269 0.03632497 -0.187385 0.109393 0.03655177 -0.190119 0.111838 0.03569996 -0.187022 0.109449 0.03527665 -0.18818 0.108844 0.03444999 -0.1879529 0.109087 0.0344944 -0.190789 0.111183 0.03449285 -0.190587 0.111407 0.03461748 -0.187385 0.109393 0.03484797 -0.187164 0.109438 0.03507494 -0.18198 0.108174 0.03344994 -0.182226 0.109513 0.03444999 -0.182226 0.109513 0.03344994 -0.182428 0.1099269 0.03344994 -0.182823 0.110737 0.03344994 -0.1837289 0.111753 0.03344994 -0.1837289 0.111753 0.03444999 -0.186178 0.112886 0.03344994 -0.184876 0.112488 0.03444999 -0.186178 0.112886 0.03444999 -0.186392 0.112891 0.03344994 -0.187539 0.112918 0.03444999 -0.187758 0.112888 0.03444999 -0.1919749 0.10792 0.03744995 -0.191534 0.105958 0.03344994 -0.191893 0.107048 0.03444999 -0.190708 0.104624 0.03344994 -0.190708 0.104624 0.03444999 -0.1896719 0.10374 0.03444999 -0.1896719 0.10374 0.03344994 -0.188437 0.103168 0.03344994 -0.188437 0.103168 0.03444999 -0.187546 0.103025 0.03344994 -0.187092 0.102951 0.03444999 -0.186192 0.103012 0.03744995 -0.191608 0.109719 0.03744995 -0.191591 0.109871 0.03537559 -0.191646 0.109735 0.03344994 -0.190401 0.111592 0.03481608 -0.1902509 0.1117269 0.03507494 -0.190038 0.1119019 0.03344994 -0.191175 0.110662 0.03449255 -0.190153 0.11181 0.03537625 -0.190587 0.111407 0.0367825 -0.190991 0.1109279 0.03694999 -0.1911759 0.110662 0.03690719 -0.191332 0.110403 0.0367825 -0.189572 0.112223 0.03744995 -0.189952 0.111951 0.03344994 -0.182022 0.108634 0.03444999 -0.1821179 0.10682 0.03744995 -0.182105 0.106818 0.03344994 -0.182278 0.106365 0.03344994 -0.182595 0.105548 0.03744995 -0.182591 0.1055459 0.03344994 -0.182609 0.105512 0.03744995 -0.183402 0.104452 0.03344994 -0.184095 0.103915 0.03344994 -0.184478 0.103618 0.03344994 -0.185739 0.103105 0.03344994 -0.185741 0.103114 0.03744995 -0.191817 0.109195 0.03744995 -0.191915 0.108403 0.03744995 -0.190715 0.09962338 0.03214997 -0.190715 0.09962338 0.03344994 -0.191439 0.09921467 0.03344994 -0.192267 0.09913575 0.03214997 -0.192267 0.09913575 0.03344994 -0.193055 0.09940057 0.03344994 -0.1939899 0.101558 0.03214997 -0.1939989 0.100726 0.03344994 -0.193645 0.102314 0.03344994 -0.1930209 0.102865 0.03214997 -0.1930209 0.102865 0.03344994 -0.192228 0.103114 0.03214997 -0.192228 0.103114 0.03344994 -0.191402 0.1030189 0.03344994 -0.190686 0.102596 0.03214997 -0.190686 0.102596 0.03344994 -0.190038 0.101103 0.03344994 -0.190219 0.100291 0.03214997 -0.190432 0.09993129 0.03214997 -0.190219 0.100291 0.03344994 -0.197026 0.110113 0.03344994 -0.197371 0.109356 0.03214997 -0.197049 0.107762 0.03344994 -0.197049 0.107762 0.03214997 -0.196436 0.107199 0.03344994 -0.196436 0.107199 0.03214997 -0.195205 0.106977 0.03344994 -0.194746 0.107055 0.03344994 -0.194096 0.107422 0.03214997 -0.194096 0.107422 0.03344994 -0.19393 0.107602 0.03214997 -0.193419 0.108902 0.03214997 -0.193419 0.108902 0.03344994 -0.194783 0.110817 0.03344994 -0.197026 0.110113 0.03214997 -0.195822 0.110846 0.03214997 -0.196402 0.1106629 0.03344994 -0.195609 0.110912 0.03214997 -0.192308 0.1161839 0.03344994 -0.192314 0.115575 0.03214997 -0.191985 0.114589 0.03344994 -0.191373 0.114027 0.03344994 -0.191985 0.114589 0.03214997 -0.190584 0.113762 0.03214997 -0.190141 0.113804 0.03344994 -0.189032 0.114249 0.03344994 -0.188537 0.114917 0.03344994 -0.188374 0.115646 0.03344994 -0.188356 0.115729 0.03214997 -0.188356 0.115729 0.03344994 -0.188521 0.116544 0.03214997 -0.188521 0.116544 0.03344994 -0.189003 0.117222 0.03344994 -0.191962 0.11694 0.03344994 -0.191339 0.1174899 0.03344994 -0.190545 0.11774 0.03344994 -0.189719 0.117645 0.03214997 -0.181312 0.112869 0.03214997 -0.1821399 0.11279 0.03214997 -0.182928 0.113055 0.03214997 -0.1835409 0.113618 0.03344994 -0.183872 0.114381 0.03214997 -0.1838639 0.115212 0.03344994 -0.1835179 0.115969 0.03214997 -0.180092 0.113946 0.03214997 -0.179912 0.114758 0.03344994 -0.180076 0.115573 0.03344994 -0.180076 0.115573 0.03214997 -0.180559 0.11625 0.03344994 -0.180559 0.11625 0.03214997 -0.181275 0.116673 0.03344994 -0.1832129 0.1162379 0.03344994 -0.1832129 0.1162379 0.03214997 -0.182894 0.116519 0.03344994 -0.182894 0.116519 0.03214997 -0.182101 0.116768 0.03214997 -0.180487 0.1065739 0.03214997 -0.18016 0.105819 0.03344994 -0.18016 0.105819 0.03214997 -0.178759 0.104992 0.03214997 -0.178759 0.104992 0.03344994 -0.17813 0.105052 0.03344994 -0.177931 0.1050699 0.03214997 -0.177931 0.1050699 0.03344994 -0.176924 0.105787 0.03214997 -0.176712 0.106147 0.03214997 -0.176531 0.106959 0.03344994 -0.176696 0.107774 0.03344994 -0.177178 0.108452 0.03344994 -0.176696 0.107774 0.03214997 -0.177178 0.108452 0.03214997 -0.180483 0.107414 0.03344994 -0.180137 0.10817 0.03214997 -0.1791779 0.108826 0.03344994 -0.1787199 0.10897 0.03344994 -0.1778939 0.108875 0.03214997 -0.185546 0.1005859 0.03214997 -0.185551 0.09974658 0.03214997 -0.1852239 0.09899169 0.03214997 -0.184611 0.09842908 0.03214997 -0.183823 0.09816437 0.03344994 -0.183823 0.09816437 0.03214997 -0.182995 0.09824317 0.03344994 -0.181988 0.09895986 0.03214997 -0.181594 0.100132 0.03344994 -0.1817589 0.100947 0.03214997 -0.182241 0.101624 0.03344994 -0.182241 0.101624 0.03214997 -0.1829569 0.102047 0.03344994 -0.183784 0.102142 0.03344994 -0.183775 0.102141 0.03214997 -0.178653 0.112856 0.03344994 -0.178637 0.112089 0.03344994 -0.178637 0.112089 0.03214997 -0.178254 0.111206 0.03214997 -0.178254 0.111206 0.03344994 -0.177565 0.1105329 0.03214997 -0.177565 0.1105329 0.03344994 -0.176674 0.11017 0.03344994 -0.176674 0.11017 0.03214997 -0.175711 0.110171 0.03214997 -0.175981 0.111953 0.03194999 -0.1878409 0.118452 0.03344994 -0.1878409 0.118452 0.03214997 -0.1872349 0.117704 0.03344994 -0.1872349 0.117704 0.03214997 -0.1863909 0.117241 0.03214997 -0.186265 0.117226 0.03214997 -0.185434 0.117131 0.03214997 -0.185434 0.117131 0.03344994 -0.184696 0.117338 0.03344994 -0.184507 0.11739 0.03344994 -0.1837469 0.117981 0.03344994 -0.1837469 0.117981 0.03214997 -0.183266 0.118815 0.03344994 -0.176908 0.11519 0.03344994 -0.1756899 0.116066 0.03194999 -0.178143 0.116654 0.03344994 -0.176238 0.116715 0.03194999 -0.177074 0.117706 0.03194999 -0.181744 0.119158 0.03344994 -0.180513 0.120256 0.03194999 -0.18121 0.118928 0.03344994 -0.1796669 0.119725 0.03194999 -0.182969 0.119685 0.03344994 -0.1831949 0.119023 0.03214997 -0.183877 0.1215 0.03194999 -0.1852909 0.119528 0.03194999 -0.200013 0.103132 0.03194999 -0.199042 0.101052 0.03194999 -0.196507 0.101166 0.03194999 -0.196122 0.118416 0.03194999 -0.196372 0.11492 0.03194999 -0.196624 0.117955 0.03194999 -0.1993499 0.11428 0.03194999 -0.1996459 0.113665 0.03194999 -0.194827 0.119382 0.03194999 -0.1951349 0.117287 0.03344994 -0.1935999 0.118432 0.03344994 -0.191907 0.119327 0.03344994 -0.192504 0.120703 0.03194999 -0.190474 0.121402 0.03194999 -0.188443 0.121766 0.03194999 -0.188211 0.120288 0.03344994 -0.188361 0.121781 0.03194999 -0.19453 0.116595 0.03214997 -0.19453 0.116595 0.03344994 -0.194674 0.11676 0.03214997 -0.19744 0.112671 0.03214997 -0.196503 0.112451 0.03344994 -0.195763 0.112569 0.03214997 -0.195552 0.112602 0.03214997 -0.195552 0.112602 0.03344994 -0.194729 0.113101 0.03344994 -0.194729 0.113101 0.03214997 -0.194155 0.113875 0.03214997 -0.193946 0.115019 0.03214997 -0.194048 0.115761 0.03214997 -0.19764 0.112761 0.03194999 -0.19764 0.112761 0.03214997 -0.19744 0.112671 0.03344994 -0.200194 0.112146 0.03194999 -0.199113 0.1102949 0.03344994 -0.200711 0.109914 0.03194999 -0.200784 0.109539 0.03194999 -0.199141 0.105551 0.03344994 -0.199365 0.107453 0.03344994 -0.200864 0.107393 0.03194999 -0.200855 0.107626 0.03194999 -0.198239 0.105729 0.03214997 -0.198239 0.105729 0.03344994 -0.198454 0.105687 0.03214997 -0.195313 0.103811 0.03344994 -0.1952919 0.102848 0.03214997 -0.195646 0.104578 0.03214997 -0.1956959 0.104694 0.03214997 -0.196385 0.105367 0.03344994 -0.196385 0.105367 0.03214997 -0.1972759 0.1057299 0.03214997 -0.196395 0.1053709 0.03344994 -0.196474 0.101119 0.03194999 -0.196474 0.101119 0.03214997 -0.196296 0.101247 0.03214997 -0.196296 0.101247 0.03344994 -0.196182 0.09969067 0.03344994 -0.197712 0.09918528 0.03194999 -0.194362 0.09799015 0.03344994 -0.195255 0.09678536 0.03194999 -0.19274 0.09697157 0.03344994 -0.193437 0.09564357 0.03194999 -0.190981 0.09621477 0.03344994 -0.190073 0.09439957 0.03194999 -0.188516 0.09876906 0.03344994 -0.188516 0.09876906 0.03214997 -0.187559 0.09865909 0.03214997 -0.1858299 0.0965262 0.03214997 -0.1858299 0.0965262 0.03344994 -0.186708 0.09818661 0.03214997 -0.186715 0.09819579 0.03214997 -0.187457 0.09860306 0.03344994 -0.189115 0.09860128 0.03214997 -0.1894429 0.0985096 0.03344994 -0.190684 0.09708458 0.03344994 -0.190203 0.0979188 0.03214997 -0.190684 0.09708458 0.03214997 -0.183256 0.09457349 0.03194999 -0.183853 0.09594929 0.03344994 -0.185038 0.09573715 0.03344994 -0.185739 0.09561181 0.03344994 -0.182043 0.09657305 0.03344994 -0.18035 0.09746819 0.03344994 -0.1811079 0.09537547 0.03194999 -0.192842 0.120524 0.03194999 -0.190694 0.121326 0.03194999 -0.186149 0.121825 0.03194999 -0.183877 0.1215 0.03024995 -0.182485 0.121105 0.03194999 -0.181704 0.120769 0.03194999 -0.179645 0.11976 0.03024995 -0.178695 0.119115 0.03194999 -0.177801 0.118393 0.03024995 -0.177828 0.1183609 0.03194999 -0.174907 0.114848 0.03024995 -0.174907 0.114848 0.03194999 -0.173937 0.112768 0.03194999 -0.173937 0.112768 0.03024995 -0.173337 0.110639 0.03194999 -0.173321 0.110556 0.03024995 -0.173095 0.108274 0.03194999 -0.173079 0.108273 0.03024995 -0.173756 0.103754 0.03194999 -0.173727 0.103744 0.03024995 -0.1746 0.10162 0.03024995 -0.177325 0.09794509 0.03024995 -0.177325 0.09794509 0.03194999 -0.179122 0.09651809 0.03194999 -0.179104 0.0964933 0.03024995 -0.179548 0.09620016 0.03194999 -0.181446 0.09519678 0.03194999 -0.183476 0.09449756 0.03194999 -0.18325 0.09455829 0.03024995 -0.185506 0.09413409 0.03194999 -0.185589 0.09411931 0.03194999 -0.1877999 0.09407448 0.03024995 -0.1877999 0.09407448 0.03194999 -0.191465 0.09479528 0.03194999 -0.192261 0.09509438 0.03024995 -0.192245 0.0951308 0.03194999 -0.194305 0.09613978 0.03024995 -0.194283 0.09617477 0.03194999 -0.196122 0.09753847 0.03194999 -0.196875 0.09819358 0.03194999 -0.19826 0.09983438 0.03194999 -0.199042 0.101052 0.03024995 -0.200612 0.105261 0.03194999 -0.200622 0.105345 0.03194999 -0.200374 0.1116459 0.03194999 -0.200223 0.112156 0.03024995 -0.1993499 0.11428 0.03024995 -0.198139 0.11623 0.03194999 -0.198139 0.11623 0.03024995 -0.196624 0.117955 0.03024995 -0.194846 0.1194069 0.03024995 -0.194401 0.1197 0.03194999 -0.1746 0.10162 0.03194999 -0.17581 0.09966975 0.03194999 -0.17699 0.101851 0.03194999 -0.177828 0.09748387 0.03194999 -0.176509 0.103229 0.03214997 -0.178398 0.103298 0.03214997 -0.179221 0.1027989 0.03344994 -0.179794 0.102025 0.03214997 -0.180033 0.101093 0.03214997 -0.17631 0.103139 0.03214997 -0.176509 0.103229 0.03344994 -0.1930609 0.104875 0.03214997 -0.193168 0.104606 0.03214997 -0.1933799 0.1056089 0.03344994 -0.1933799 0.1056089 0.03214997 -0.193765 0.105762 0.03214997 -0.194401 0.105521 0.03344994 -0.194499 0.105443 0.03214997 -0.194499 0.105443 0.03344994 -0.194651 0.105058 0.03214997 -0.194333 0.104324 0.03214997 -0.193948 0.104172 0.03344994 -0.193948 0.104172 0.03214997 -0.1932139 0.10449 0.03344994 -0.179553 0.111495 0.03214997 -0.179617 0.111576 0.03214997 -0.180002 0.111728 0.03214997 -0.180736 0.11141 0.03344994 -0.180736 0.11141 0.03214997 -0.180782 0.111294 0.03344994 -0.1808879 0.111025 0.03344994 -0.1808879 0.111025 0.03214997 -0.180828 0.110615 0.03344994 -0.18057 0.110291 0.03214997 -0.180185 0.1101379 0.03344994 -0.180474 0.110252 0.03214997 -0.180185 0.1101379 0.03214997 -0.1797749 0.110199 0.03344994 -0.179549 0.110379 0.03344994 -0.179451 0.110457 0.03344994 -0.179451 0.110457 0.03214997 -0.1858 0.1146669 0.03214997 -0.188377 0.1010529 0.03214997 -0.181593 0.103959 0.03214997 -0.1907539 0.09687727 0.03214997 -0.198621 0.108651 0.03214997 -0.191026 0.118892 0.03214997 -0.1862429 0.104886 0.03214997 -0.186129 0.104936 0.03214997 -0.187707 0.111014 0.03214997 -0.187821 0.110964 0.03214997 -0.189505 0.109826 0.03214997 -0.190047 0.112127 0.03214997 -0.188711 0.110579 0.03214997 -0.1882359 0.110784 0.03214997 -0.186615 0.111079 0.03214997 -0.182352 0.110028 0.03214997 -0.184085 0.109203 0.03214997 -0.1863279 0.112977 0.03214997 -0.184688 0.110116 0.03214997 -0.185566 0.110768 0.03214997 -0.183956 0.107052 0.03214997 -0.183897 0.1075659 0.03214997 -0.1857129 0.105116 0.03214997 -0.190119 0.107761 0.03214997 -0.1898649 0.106697 0.03214997 -0.189262 0.1057839 0.03214997 -0.188383 0.105132 0.03214997 -0.187335 0.104821 0.03214997 -0.19359 0.10735 0.03214997 -0.190105 0.107884 0.03214997 -0.191864 0.109677 0.03214997 -0.190053 0.108334 0.03214997 -0.189994 0.108848 0.03214997 -0.194066 0.110395 0.03214997 -0.193813 0.10773 0.03214997 -0.1935999 0.10809 0.03214997 -0.193584 0.109717 0.03214997 -0.1973789 0.108525 0.03214997 -0.194753 0.105782 0.03214997 -0.195648 0.106935 0.03214997 -0.19482 0.107013 0.03214997 -0.197377 0.108748 0.03214997 -0.196503 0.112451 0.03214997 -0.196402 0.1106629 0.03214997 -0.197099 0.109952 0.03214997 -0.194783 0.110817 0.03214997 -0.1923159 0.115352 0.03214997 -0.191373 0.114027 0.03214997 -0.189756 0.1138409 0.03214997 -0.189032 0.114249 0.03214997 -0.188749 0.114557 0.03214997 -0.192308 0.1161839 0.03214997 -0.193324 0.117777 0.03214997 -0.191962 0.11694 0.03214997 -0.19183 0.117057 0.03214997 -0.191339 0.1174899 0.03214997 -0.193018 0.117938 0.03214997 -0.190758 0.117673 0.03214997 -0.190545 0.11774 0.03214997 -0.189003 0.117222 0.03214997 -0.19027 0.118331 0.03214997 -0.185165 0.114545 0.03214997 -0.1838639 0.115212 0.03214997 -0.1835409 0.113618 0.03214997 -0.181189 0.111596 0.03214997 -0.180588 0.113278 0.03214997 -0.180305 0.113586 0.03214997 -0.179912 0.114758 0.03214997 -0.178182 0.115652 0.03214997 -0.179591 0.117025 0.03214997 -0.181275 0.116673 0.03214997 -0.183663 0.116571 0.03214997 -0.181223 0.1055819 0.03214997 -0.179548 0.105256 0.03214997 -0.178187 0.103331 0.03214997 -0.175676 0.105077 0.03214997 -0.177447 0.103449 0.03214997 -0.1772069 0.105479 0.03214997 -0.176062 0.103732 0.03214997 -0.180491 0.106582 0.03214997 -0.181248 0.109209 0.03214997 -0.183831 0.108139 0.03214997 -0.183845 0.108016 0.03214997 -0.182974 0.106881 0.03214997 -0.180483 0.107414 0.03214997 -0.176836 0.105937 0.03214997 -0.175484 0.1057479 0.03214997 -0.176531 0.106959 0.03214997 -0.1794199 0.09930527 0.03214997 -0.179275 0.0991404 0.03214997 -0.1797699 0.09873139 0.03214997 -0.181775 0.09931987 0.03214997 -0.179902 0.100139 0.03214997 -0.181594 0.100132 0.03214997 -0.1822699 0.09865188 0.03214997 -0.182105 0.09883207 0.03214997 -0.182995 0.09824317 0.03214997 -0.1829569 0.102047 0.03214997 -0.184791 0.104432 0.03214997 -0.183784 0.102142 0.03214997 -0.184577 0.101893 0.03214997 -0.186517 0.102104 0.03214997 -0.1852 0.101343 0.03214997 -0.185274 0.101182 0.03214997 -0.1754429 0.109926 0.03214997 -0.175275 0.107835 0.03214997 -0.177554 0.110529 0.03214997 -0.1792989 0.110842 0.03214997 -0.17936 0.1112509 0.03214997 -0.17865 0.112712 0.03214997 -0.178653 0.112856 0.03214997 -0.1804119 0.111667 0.03214997 -0.178313 0.113951 0.03214997 -0.179687 0.113622 0.03214997 -0.1786569 0.113052 0.03214997 -0.180102 0.11393 0.03214997 -0.178089 0.115561 0.03214997 -0.177654 0.114653 0.03214997 -0.184507 0.11739 0.03214997 -0.183266 0.118815 0.03214997 -0.1864359 0.116135 0.03214997 -0.18676 0.115877 0.03214997 -0.185475 0.114924 0.03214997 -0.186026 0.116196 0.03214997 -0.185641 0.116043 0.03214997 -0.184696 0.117338 0.03214997 -0.188141 0.119592 0.03214997 -0.187158 0.116022 0.03214997 -0.18812 0.119374 0.03214997 -0.189498 0.119372 0.03214997 -0.1894659 0.119382 0.03214997 -0.193159 0.114435 0.03214997 -0.193917 0.114807 0.03214997 -0.197865 0.10809 0.03214997 -0.198637 0.107049 0.03214997 -0.198638 0.107016 0.03214997 -0.193538 0.104233 0.03214997 -0.1927599 0.104304 0.03214997 -0.195637 0.101949 0.03214997 -0.195313 0.103811 0.03214997 -0.19459 0.104649 0.03214997 -0.191402 0.1030189 0.03214997 -0.1939989 0.100726 0.03214997 -0.195143 0.09957307 0.03214997 -0.193668 0.09996306 0.03214997 -0.193516 0.09824919 0.03214997 -0.193645 0.102314 0.03214997 -0.190038 0.101103 0.03214997 -0.190203 0.101918 0.03214997 -0.193055 0.09940057 0.03214997 -0.191439 0.09921467 0.03214997 -0.188475 0.100976 0.03214997 -0.188627 0.100591 0.03214997 -0.191679 0.09723716 0.03214997 -0.188566 0.100181 0.03214997 -0.187923 0.09970438 0.03214997 -0.188212 0.09981846 0.03214997 -0.188309 0.09985655 0.03214997 -0.1894429 0.0985096 0.03214997 -0.185929 0.09923708 0.03214997 -0.187189 0.100023 0.03214997 -0.187514 0.09976506 0.03214997 -0.186109 0.09744775 0.03214997 -0.182929 0.09701228 0.03214997 -0.185518 0.09634095 0.03214997 -0.180308 0.103006 0.03214997 -0.179221 0.1027989 0.03214997 -0.181746 0.103574 0.03214997 -0.181685 0.103164 0.03214997 -0.181427 0.10284 0.03214997 -0.18304 0.103133 0.03214997 -0.180004 0.100881 0.03214997 -0.181042 0.102687 0.03214997 -0.180633 0.102748 0.03214997 -0.1801559 0.103391 0.03214997 -0.180217 0.1037999 0.03214997 -0.180474 0.104125 0.03214997 -0.180859 0.104277 0.03214997 -0.194401 0.105521 0.03214997 -0.194174 0.105701 0.03214997 -0.193122 0.105285 0.03214997 -0.191597 0.105872 0.03214997 -0.185554 0.09975469 0.03214997 -0.187144 0.100138 0.03214997 -0.187037 0.100408 0.03214997 -0.187098 0.100817 0.03214997 -0.187291 0.101061 0.03214997 -0.187355 0.101142 0.03214997 -0.187741 0.101294 0.03214997 -0.180782 0.111294 0.03214997 -0.1787109 0.108969 0.03214997 -0.178333 0.1094779 0.03214997 -0.179549 0.110379 0.03214997 -0.1787199 0.10897 0.03214997 -0.1797749 0.110199 0.03214997 -0.179514 0.10872 0.03214997 -0.180005 0.108287 0.03214997 -0.180828 0.110615 0.03214997 -0.1883209 0.114454 0.03214997 -0.188537 0.114917 0.03214997 -0.188661 0.114707 0.03214997 -0.186912 0.115492 0.03214997 -0.186852 0.115083 0.03214997 -0.1932139 0.10449 0.03214997 -0.188785 0.101355 0.03214997 -0.1881499 0.101233 0.03214997 -0.1876209 0.102923 0.03214997 -0.185239 0.105321 0.03214997 -0.184445 0.106074 0.03214997 -0.181269 0.104216 0.03214997 -0.193475 0.111775 0.03214997 -0.193733 0.1121 0.03214997 -0.194976 0.111985 0.03214997 -0.193794 0.112509 0.03214997 -0.193641 0.1128939 0.03214997 -0.1933169 0.113152 0.03214997 -0.19309 0.111623 0.03214997 -0.192681 0.111684 0.03214997 -0.192356 0.111941 0.03214997 -0.1922039 0.112326 0.03214997 -0.192265 0.112736 0.03214997 -0.192522 0.1130599 0.03214997 -0.192908 0.113213 0.03214997 -0.186806 0.115762 0.03344994 -0.186594 0.114758 0.03344994 -0.186594 0.114758 0.03214997 -0.186209 0.114606 0.03344994 -0.186209 0.114606 0.03214997 -0.185573 0.114847 0.03214997 -0.185573 0.114847 0.03344994 -0.1853229 0.115309 0.03214997 -0.1853229 0.115309 0.03344994 -0.185384 0.115719 0.03344994 -0.185641 0.116043 0.03344994 -0.185384 0.115719 0.03214997 -0.186806 0.115762 0.03214997 -0.181189 0.111596 0.03344994 -0.188585 0.120221 0.03344994 -0.188174 0.119917 0.03344994 -0.175175 0.110276 0.03344994 -0.18555 0.100235 0.03344994 -0.191668 0.109638 0.03344994 -0.191689 0.109548 0.03344994 -0.191467 0.105755 0.03344994 -0.193996 0.106499 0.03344994 -0.191893 0.107048 0.03344994 -0.191954 0.108408 0.03344994 -0.185999 0.100569 0.03344994 -0.187092 0.102951 0.03344994 -0.183722 0.103639 0.03344994 -0.184876 0.112488 0.03344994 -0.189872 0.111997 0.03344994 -0.188859 0.112582 0.03344994 -0.187539 0.112918 0.03344994 -0.198278 0.113048 0.03344994 -0.195763 0.112569 0.03344994 -0.195609 0.110912 0.03344994 -0.194066 0.110395 0.03344994 -0.199302 0.1091549 0.03344994 -0.1973789 0.108525 0.03344994 -0.1973749 0.109005 0.03344994 -0.199294 0.109367 0.03344994 -0.197371 0.109356 0.03344994 -0.198929 0.111247 0.03344994 -0.194608 0.105674 0.03344994 -0.19482 0.107013 0.03344994 -0.195648 0.106935 0.03344994 -0.193584 0.109717 0.03344994 -0.193496 0.109281 0.03344994 -0.192727 0.110318 0.03344994 -0.1917189 0.10957 0.03344994 -0.1935999 0.10809 0.03344994 -0.194048 0.115761 0.03344994 -0.1923159 0.115352 0.03344994 -0.189902 0.112019 0.03344994 -0.189756 0.1138409 0.03344994 -0.190584 0.113762 0.03344994 -0.187013 0.115915 0.03344994 -0.188433 0.116108 0.03344994 -0.192742 0.118885 0.03344994 -0.191004 0.117596 0.03344994 -0.189719 0.117645 0.03344994 -0.181312 0.112869 0.03344994 -0.182928 0.113055 0.03344994 -0.1821399 0.11279 0.03344994 -0.183872 0.114381 0.03344994 -0.185165 0.114545 0.03344994 -0.1835179 0.115969 0.03344994 -0.182101 0.116768 0.03344994 -0.179588 0.11791 0.03344994 -0.177768 0.116209 0.03344994 -0.180092 0.113946 0.03344994 -0.180491 0.106582 0.03344994 -0.179628 0.109159 0.03344994 -0.181905 0.106089 0.03344994 -0.179548 0.105256 0.03344994 -0.177447 0.103449 0.03344994 -0.178187 0.103331 0.03344994 -0.178974 0.103914 0.03344994 -0.178398 0.103298 0.03344994 -0.1772069 0.105479 0.03344994 -0.176712 0.106147 0.03344994 -0.1750209 0.104653 0.03344994 -0.174656 0.106533 0.03344994 -0.176549 0.106876 0.03344994 -0.1765699 0.107155 0.03344994 -0.176084 0.10781 0.03344994 -0.180137 0.10817 0.03344994 -0.179514 0.10872 0.03344994 -0.1790159 0.109984 0.03344994 -0.1778939 0.108875 0.03344994 -0.185546 0.1005859 0.03344994 -0.1852 0.101343 0.03344994 -0.184577 0.101893 0.03344994 -0.183194 0.09822428 0.03344994 -0.1852239 0.09899169 0.03344994 -0.185554 0.09975469 0.03344994 -0.1866109 0.09974348 0.03344994 -0.1817589 0.100947 0.03344994 -0.181634 0.100328 0.03344994 -0.180004 0.100881 0.03344994 -0.1794199 0.09930527 0.03344994 -0.179902 0.100139 0.03344994 -0.175711 0.110171 0.03344994 -0.174648 0.106745 0.03344994 -0.180033 0.101093 0.03344994 -0.179794 0.102025 0.03344994 -0.182243 0.09650397 0.03344994 -0.18292 0.09828519 0.03344994 -0.181207 0.09701478 0.03344994 -0.1822699 0.09865188 0.03344994 -0.181775 0.09931987 0.03344994 -0.178815 0.09861338 0.03344994 -0.186715 0.09819579 0.03344994 -0.184611 0.09842908 0.03344994 -0.1836799 0.09756916 0.03344994 -0.186109 0.09744775 0.03344994 -0.188475 0.100976 0.03344994 -0.188627 0.100591 0.03344994 -0.192206 0.09674185 0.03344994 -0.188566 0.100181 0.03344994 -0.190203 0.0979188 0.03344994 -0.188309 0.09985655 0.03344994 -0.187559 0.09865909 0.03344994 -0.187923 0.09970438 0.03344994 -0.187514 0.09976506 0.03344994 -0.187189 0.100023 0.03344994 -0.190203 0.101918 0.03344994 -0.193668 0.09996306 0.03344994 -0.195807 0.09924638 0.03344994 -0.1939899 0.101558 0.03344994 -0.1927599 0.104304 0.03344994 -0.195563 0.104386 0.03344994 -0.193168 0.104606 0.03344994 -0.193538 0.104233 0.03344994 -0.194333 0.104324 0.03344994 -0.19459 0.104649 0.03344994 -0.194651 0.105058 0.03344994 -0.1952919 0.102848 0.03344994 -0.195637 0.101949 0.03344994 -0.197042 0.10071 0.03344994 -0.1956959 0.104694 0.03344994 -0.195616 0.106422 0.03344994 -0.1972759 0.1057299 0.03344994 -0.192522 0.1130599 0.03344994 -0.192265 0.112736 0.03344994 -0.192356 0.111941 0.03344994 -0.190991 0.1109279 0.03344994 -0.19091 0.112767 0.03344994 -0.1922039 0.112326 0.03344994 -0.194155 0.113875 0.03344994 -0.193946 0.115019 0.03344994 -0.192908 0.113213 0.03344994 -0.193917 0.114807 0.03344994 -0.1933169 0.113152 0.03344994 -0.193641 0.1128939 0.03344994 -0.193794 0.112509 0.03344994 -0.193733 0.1121 0.03344994 -0.193475 0.111775 0.03344994 -0.19309 0.111623 0.03344994 -0.192681 0.111684 0.03344994 -0.191706 0.119396 0.03344994 -0.18812 0.119374 0.03344994 -0.190096 0.119951 0.03344994 -0.1863909 0.117241 0.03344994 -0.188021 0.116663 0.03344994 -0.187242 0.117713 0.03344994 -0.18676 0.115877 0.03344994 -0.1864359 0.116135 0.03344994 -0.186058 0.1172029 0.03344994 -0.186026 0.116196 0.03344994 -0.183663 0.116571 0.03344994 -0.179687 0.113622 0.03344994 -0.1786569 0.113052 0.03344994 -0.178313 0.113951 0.03344994 -0.177654 0.114653 0.03344994 -0.180588 0.113278 0.03344994 -0.180103 0.113931 0.03344994 -0.1804119 0.111667 0.03344994 -0.180002 0.111728 0.03344994 -0.179617 0.111576 0.03344994 -0.17936 0.1112509 0.03344994 -0.1792989 0.110842 0.03344994 -0.17817 0.111125 0.03344994 -0.193122 0.105285 0.03344994 -0.193765 0.105762 0.03344994 -0.194174 0.105701 0.03344994 -0.187037 0.100408 0.03344994 -0.187144 0.100138 0.03344994 -0.1881499 0.101233 0.03344994 -0.187741 0.101294 0.03344994 -0.1881729 0.10218 0.03344994 -0.187355 0.101142 0.03344994 -0.187098 0.100817 0.03344994 -0.18057 0.110291 0.03344994 -0.181801 0.110771 0.03344994 -0.187625 0.11509 0.03344994 -0.1858 0.1146669 0.03344994 -0.186852 0.115083 0.03344994 -0.186912 0.115492 0.03344994 -0.188377 0.1010529 0.03344994 -0.188785 0.101355 0.03344994 -0.1930609 0.104875 0.03344994 -0.192148 0.105129 0.03344994 -0.180308 0.103006 0.03344994 -0.180791 0.101465 0.03344994 -0.180633 0.102748 0.03344994 -0.181042 0.102687 0.03344994 -0.181427 0.10284 0.03344994 -0.181685 0.103164 0.03344994 -0.181746 0.103574 0.03344994 -0.181593 0.103959 0.03344994 -0.181269 0.104216 0.03344994 -0.180859 0.104277 0.03344994 -0.180474 0.104125 0.03344994 -0.180217 0.1037999 0.03344994 -0.1801559 0.103391 0.03344994 -0.185777 0.1137199 0.03344994 -0.185475 0.114924 0.03344994 -0.174765 0.109972 0.03344994 -0.173328 0.110555 0.03194999 -0.173086 0.108507 0.03194999 -0.174726 0.109642 0.03344994 -0.174585 0.108447 0.03344994 -0.173166 0.106361 0.03194999 -0.1732389 0.1059859 0.03194999 -0.174836 0.105605 0.03344994 -0.173575 0.104254 0.03194999 -0.1756719 0.102852 0.03344994 -0.174304 0.102235 0.03194999 -0.175496 0.110213 0.03194999 -0.174809 0.1103489 0.03344994 -0.1934829 0.09822708 0.02574998 -0.177476 0.114781 0.03214997 -0.18533 0.119534 0.02574998 -0.1852909 0.119528 0.02574998 -0.195006 0.1164579 0.02824997 -0.195006 0.1164579 0.02574998 -0.194977 0.116486 0.02574998 -0.185808 0.09630829 0.03194999 -0.185808 0.09630829 0.03214997 -0.17631 0.103139 0.03194999 -0.176502 0.102735 0.02574998 -0.17699 0.101851 0.02824997 -0.17824 0.100166 0.02824997 -0.17824 0.100166 0.03194999 -0.179275 0.0991404 0.03194999 -0.187615 0.09626746 0.02824997 -0.187615 0.09626746 0.03194999 -0.189729 0.09657865 0.02574998 -0.1907539 0.09687727 0.03194999 -0.189729 0.09657865 0.02824997 -0.1896899 0.09656947 0.03194999 -0.1896899 0.09656947 0.02574998 -0.18862 0.09636616 0.02824997 -0.18862 0.09636616 0.02574998 -0.197057 0.102014 0.02824997 -0.197566 0.102977 0.03194999 -0.196507 0.101166 0.02824997 -0.197582 0.103013 0.02574998 -0.197582 0.103013 0.02824997 -0.198634 0.106976 0.02824997 -0.198454 0.105687 0.03194999 -0.197466 0.11313 0.02574998 -0.197448 0.113165 0.02574998 -0.196372 0.11492 0.02824997 -0.197448 0.113165 0.02824997 -0.197466 0.11313 0.03194999 -0.197902 0.1121309 0.02824997 -0.197902 0.1121309 0.02574998 -0.194148 0.117193 0.02574998 -0.194977 0.116486 0.03194999 -0.194674 0.11676 0.03194999 -0.194148 0.117193 0.02824997 -0.189427 0.11939 0.02574998 -0.188141 0.119592 0.03194999 -0.187385 0.119643 0.03194999 -0.187385 0.119643 0.02824997 -0.184221 0.119321 0.02574998 -0.182178 0.118573 0.03214997 -0.18533 0.119534 0.02824997 -0.184221 0.119321 0.02824997 -0.18325 0.119041 0.03194999 -0.18325 0.119041 0.02824997 -0.1831949 0.119023 0.03194999 -0.178089 0.115561 0.02824997 -0.176367 0.112887 0.02574998 -0.175981 0.111953 0.02824997 -0.176367 0.112887 0.02824997 -0.176873 0.113852 0.03194999 -0.176873 0.113852 0.02574998 -0.1768929 0.1138859 0.02824997 -0.1768929 0.1138859 0.02574998 -0.198222 0.111173 0.03214997 -0.198222 0.111173 0.02824997 -0.198674 0.108105 0.02574998 -0.198638 0.107016 0.02574998 -0.198283 0.104948 0.02824997 -0.198283 0.104948 0.03194999 -0.197566 0.102977 0.02574998 -0.197057 0.102014 0.02574998 -0.198287 0.110834 0.03214997 -0.198617 0.109113 0.02824997 -0.198617 0.109113 0.03214997 -0.198674 0.108105 0.02824997 -0.195748 0.100276 0.03214997 -0.195143 0.09957307 0.02824997 -0.1943899 0.09889978 0.02824997 -0.191679 0.09723716 0.02824997 -0.191792 0.09729975 0.03214997 -0.1934829 0.09822708 0.02824997 -0.193516 0.09824919 0.02574998 -0.1943899 0.09889978 0.02574998 -0.1834689 0.09678769 0.02574998 -0.184522 0.09650987 0.02574998 -0.183431 0.09679961 0.02824997 -0.1834689 0.09678769 0.03214997 -0.185518 0.09634095 0.02824997 -0.184522 0.09650987 0.02824997 -0.183431 0.09679961 0.02574998 -0.179802 0.09870696 0.02574998 -0.181532 0.09759306 0.03214997 -0.180945 0.09797209 0.03214997 -0.181532 0.09759306 0.02824997 -0.179802 0.09870696 0.02824997 -0.178944 0.09944158 0.02824997 -0.1797699 0.09873139 0.02574998 -0.178944 0.09944158 0.02574998 -0.176048 0.103769 0.02824997 -0.176502 0.102735 0.02824997 -0.176062 0.103732 0.02574998 -0.176048 0.103769 0.02574998 -0.175276 0.107795 0.02574998 -0.175496 0.110213 0.03214997 -0.1754429 0.109926 0.02824997 -0.175484 0.1057479 0.02824997 -0.175334 0.107253 0.03214997 -0.175276 0.107795 0.02824997 -0.175275 0.107835 0.02574998 -0.175315 0.108924 0.02824997 -0.175315 0.108924 0.02574998 -0.17956 0.117 0.02574998 -0.180467 0.117673 0.02824997 -0.18133 0.118198 0.03214997 -0.18133 0.118198 0.02824997 -0.177476 0.114781 0.03194999 -0.17956 0.117 0.02824997 -0.179591 0.117025 0.02574998 -0.180467 0.117673 0.02574998 -0.189427 0.11939 0.02824997 -0.1894659 0.119382 0.02574998 -0.190519 0.1191 0.02824997 -0.190519 0.1191 0.02574998 -0.191467 0.118753 0.03214997 -0.191467 0.118753 0.02824997 -0.193324 0.117777 0.02824997 -0.199615 0.106716 0.02574998 -0.198634 0.106976 0.02574998 -0.2001039 0.106586 0.02674996 -0.2001039 0.106586 0.02824997 -0.17581 0.09966975 0.03024995 -0.17581 0.09966975 0.02239996 -0.173215 0.105982 0.03024995 -0.173079 0.108273 0.02239996 -0.173321 0.110556 0.02239996 -0.176207 0.11674 0.02239996 -0.176207 0.11674 0.03024995 -0.179645 0.11976 0.02239996 -0.181689 0.120806 0.02239996 -0.181689 0.120806 0.03024995 -0.183877 0.1215 0.02239996 -0.186149 0.121825 0.02239996 -0.186149 0.121825 0.03024995 -0.188444 0.121772 0.02239996 -0.190699 0.121342 0.02239996 -0.188444 0.121772 0.03024995 -0.190699 0.121342 0.03024995 -0.192853 0.120546 0.02239996 -0.194846 0.1194069 0.02239996 -0.192853 0.120546 0.03024995 -0.200223 0.112156 0.02239996 -0.200735 0.1099179 0.02239996 -0.200735 0.1099179 0.03024995 -0.200871 0.107627 0.03024995 -0.200628 0.1053439 0.03024995 -0.200013 0.103132 0.02239996 -0.200013 0.103132 0.03024995 -0.197742 0.09915965 0.03024995 -0.196149 0.09750729 0.03024995 -0.196149 0.09750729 0.02239996 -0.190073 0.09439957 0.02239996 -0.190073 0.09439957 0.03024995 -0.185505 0.09412789 0.03024995 -0.181097 0.09535396 0.03024995 -0.181097 0.09535396 0.02239996 -0.176373 0.100087 0.03024995 -0.177854 0.0984081 0.02239996 -0.177854 0.0984081 0.03024995 -0.179598 0.09700387 0.03024995 -0.181554 0.0959146 0.03024995 -0.183666 0.09517151 0.02239996 -0.183666 0.09517151 0.03024995 -0.188112 0.09479898 0.02239996 -0.185873 0.09479606 0.03024995 -0.188112 0.09479898 0.03024995 -0.190318 0.09518027 0.03024995 -0.190318 0.09518027 0.02239996 -0.1924279 0.09592896 0.03024995 -0.196121 0.0984323 0.02239996 -0.1943809 0.09702348 0.03024995 -0.196121 0.0984323 0.03024995 -0.197598 0.100115 0.02239996 -0.197598 0.100115 0.03024995 -0.198769 0.102023 0.03024995 -0.1996009 0.104101 0.03024995 -0.20007 0.1062909 0.02239996 -0.20007 0.1062909 0.03024995 -0.2001619 0.108528 0.03024995 -0.1998749 0.110748 0.03024995 -0.199216 0.112888 0.03024995 -0.198206 0.114886 0.03024995 -0.1968719 0.116684 0.02239996 -0.1968719 0.116684 0.03024995 -0.195254 0.1182309 0.03024995 -0.193397 0.119482 0.03024995 -0.191356 0.120402 0.03024995 -0.186957 0.12115 0.02239996 -0.189188 0.120963 0.03024995 -0.186957 0.12115 0.03024995 -0.184727 0.120957 0.03024995 -0.182561 0.1203899 0.03024995 -0.180522 0.119465 0.02239996 -0.180522 0.119465 0.03024995 -0.178669 0.118209 0.03024995 -0.177054 0.116658 0.02239996 -0.177054 0.116658 0.03024995 -0.1757259 0.114856 0.02239996 -0.1757259 0.114856 0.03024995 -0.1747199 0.112855 0.03024995 -0.174067 0.110714 0.02239996 -0.173786 0.108493 0.02239996 -0.174067 0.110714 0.03024995 -0.173786 0.108493 0.03024995 -0.174359 0.104068 0.02239996 -0.173884 0.106256 0.03024995 -0.174359 0.104068 0.03024995 -0.175196 0.101992 0.02239996 -0.175196 0.101992 0.03024995 -0.176373 0.100087 0.02239996 -0.1993499 0.11428 0.02239996 -0.198139 0.11623 0.02239996 -0.196624 0.117955 0.02239996 -0.195254 0.1182309 0.02239996 -0.193397 0.119482 0.02239996 -0.191356 0.120402 0.02239996 -0.189188 0.120963 0.02239996 -0.184727 0.120957 0.02239996 -0.182561 0.1203899 0.02239996 -0.178669 0.118209 0.02239996 -0.177801 0.118393 0.02239996 -0.174907 0.114848 0.02239996 -0.1747199 0.112855 0.02239996 -0.173937 0.112768 0.02239996 -0.173884 0.106256 0.02239996 -0.173215 0.105982 0.02239996 -0.173727 0.103744 0.02239996 -0.1746 0.10162 0.02239996 -0.177325 0.09794509 0.02239996 -0.179598 0.09700387 0.02239996 -0.179104 0.0964933 0.02239996 -0.181554 0.0959146 0.02239996 -0.18325 0.09455829 0.02239996 -0.185873 0.09479606 0.02239996 -0.185505 0.09412789 0.02239996 -0.1877999 0.09407448 0.02239996 -0.1924279 0.09592896 0.02239996 -0.192261 0.09509438 0.02239996 -0.194305 0.09613978 0.02239996 -0.1943809 0.09702348 0.02239996 -0.197742 0.09915965 0.02239996 -0.199042 0.101052 0.02239996 -0.198769 0.102023 0.02239996 -0.1996009 0.104101 0.02239996 -0.2001619 0.108528 0.02239996 -0.200628 0.1053439 0.02239996 -0.200871 0.107627 0.02239996 -0.1998749 0.110748 0.02239996 -0.199216 0.112888 0.02239996 -0.198206 0.114886 0.02239996 -0.185846 -0.112409 0.02884995 -0.185145 -0.11217 0.02884995 -0.184492 -0.111822 0.02824997 -0.183903 -0.111374 0.02824997 -0.184492 -0.111822 0.02884995 -0.183903 -0.111374 0.02884995 -0.183393 -0.110837 0.02824997 -0.182977 -0.110225 0.02824997 -0.183393 -0.110837 0.02884995 -0.182977 -0.110225 0.02884995 -0.182664 -0.109554 0.02884995 -0.182664 -0.109554 0.02824997 -0.182462 -0.108842 0.02824997 -0.182462 -0.108842 0.02884995 -0.1823779 -0.108106 0.02824997 -0.1823779 -0.108106 0.02884995 -0.182412 -0.107367 0.02824997 -0.182412 -0.107367 0.02884995 -0.182565 -0.106642 0.02824997 -0.182565 -0.106642 0.02884995 -0.182832 -0.105952 0.02824997 -0.183206 -0.105313 0.02824997 -0.182832 -0.105952 0.02884995 -0.183206 -0.105313 0.02884995 -0.183677 -0.104743 0.02824997 -0.184235 -0.104255 0.02824997 -0.183677 -0.104743 0.02884995 -0.184235 -0.104255 0.02884995 -0.184863 -0.103864 0.02824997 -0.184863 -0.103864 0.02884995 -0.185546 -0.103578 0.02824997 -0.185546 -0.103578 0.02884995 -0.186266 -0.1034049 0.02824997 -0.186266 -0.1034049 0.02884995 -0.187004 -0.10335 0.02824997 -0.187004 -0.10335 0.02884995 -0.187741 -0.1034139 0.02884995 -0.187741 -0.1034139 0.02824997 -0.188459 -0.103596 0.02824997 -0.188459 -0.103596 0.02884995 -0.1891379 -0.10389 0.02824997 -0.189761 -0.10429 0.02824997 -0.1891379 -0.10389 0.02884995 -0.189761 -0.10429 0.02884995 -0.190312 -0.104784 0.02884995 -0.190312 -0.104784 0.02824997 -0.190777 -0.105361 0.02824997 -0.191143 -0.1060039 0.02824997 -0.190777 -0.105361 0.02884995 -0.191401 -0.106698 0.02824997 -0.191143 -0.1060039 0.02884995 -0.191401 -0.106698 0.02884995 -0.191545 -0.107424 0.02824997 -0.191545 -0.107424 0.02884995 -0.19157 -0.108164 0.02824997 -0.19157 -0.108164 0.02884995 -0.191476 -0.108898 0.02824997 -0.191266 -0.109608 0.02824997 -0.191476 -0.108898 0.02884995 -0.191266 -0.109608 0.02884995 -0.190944 -0.110275 0.02884995 -0.190944 -0.110275 0.02824997 -0.1905199 -0.110882 0.02824997 -0.1905199 -0.110882 0.02884995 -0.190004 -0.111412 0.02884995 -0.190004 -0.111412 0.02824997 -0.189409 -0.111853 0.02824997 -0.189409 -0.111853 0.02884995 -0.188751 -0.112193 0.02884995 -0.188751 -0.112193 0.02824997 -0.188048 -0.112423 0.02884995 -0.188048 -0.112423 0.02824997 -0.187316 -0.112537 0.02824997 -0.187316 -0.112537 0.02884995 -0.186576 -0.112533 0.02884995 -0.186576 -0.112533 0.02824997 -0.185846 -0.112409 0.02824997 -0.185145 -0.11217 0.02824997 -0.190963 -0.115638 0.01739996 -0.19147 -0.116041 0.01739996 -0.191708 -0.1166419 0.01739996 -0.1903229 -0.115543 0.01889997 -0.1903229 -0.115543 0.01739996 -0.1907359 -0.115604 0.01889997 -0.19147 -0.116041 0.01889997 -0.189224 -0.116928 0.01889997 -0.189224 -0.116928 0.01739996 -0.189319 -0.116288 0.01739996 -0.189722 -0.115781 0.01739996 -0.189722 -0.115781 0.01889997 -0.1916469 -0.117054 0.01889997 -0.191211 -0.117789 0.01889997 -0.190609 -0.118027 0.01739996 -0.190609 -0.118027 0.01889997 -0.189462 -0.11753 0.01739996 -0.178097 -0.117678 0.02109998 -0.17708 -0.1174499 0.02109998 -0.180524 -0.120056 0.02109998 -0.1825489 -0.120934 0.02109998 -0.185944 -0.12108 0.02109998 -0.184689 -0.121476 0.02109998 -0.198406 -0.112251 0.01893585 -0.1990129 -0.112181 0.01893585 -0.1990939 -0.111891 0.01889997 -0.20015 -0.111769 0.02109998 -0.199559 -0.111837 0.02109998 -0.200022 -0.112112 0.02105045 -0.199898 -0.112352 0.02095258 -0.199294 -0.112421 0.02095258 -0.1997269 -0.112601 0.02077716 -0.19893 -0.112869 0.02054995 -0.1995469 -0.112798 0.02054995 -0.198751 -0.112998 0.02029109 -0.1992099 -0.112985 0.01999998 -0.198585 -0.113057 0.01999998 -0.198998 -0.112861 0.01944994 -0.198958 -0.112689 0.01922148 -0.1989639 -0.112459 0.01904737 -0.199975 -0.110062 0.02109998 -0.200581 -0.1096889 0.02109998 -0.200432 -0.105291 0.02109998 -0.199831 -0.1031669 0.02109998 -0.198051 -0.101648 0.01889997 -0.1809819 -0.119197 0.01889997 -0.181199 -0.118789 0.01785719 -0.175695 -0.102 0.01892137 -0.175814 -0.101799 0.01889997 -0.175566 -0.102186 0.01898735 -0.175518 -0.103522 0.01785719 -0.175433 -0.102343 0.01909875 -0.175301 -0.102461 0.01925247 -0.175178 -0.10253 0.01944005 -0.17507 -0.102545 0.01964676 -0.174982 -0.102509 0.0198611 -0.174916 -0.10243 0.02007198 -0.174847 -0.102177 0.02045458 -0.174861 -0.101833 0.02076917 -0.1740559 -0.102957 0.02139997 -0.174957 -0.101435 0.02099364 -0.177101 -0.09990531 0.01889997 -0.1763769 -0.101742 0.01785719 -0.178888 -0.09870547 0.01785719 -0.177154 -0.0998283 0.01889997 -0.17751 -0.100122 0.01785719 -0.178584 -0.09835815 0.01889997 -0.177395 -0.09958118 0.01889997 -0.182232 -0.09662038 0.01785719 -0.180459 -0.09701919 0.01889997 -0.180232 -0.09713649 0.01889997 -0.180476 -0.09752798 0.01785719 -0.179541 -0.09764838 0.01889997 -0.185259 -0.09493488 0.0197677 -0.185227 -0.0950663 0.01948308 -0.185212 -0.09482938 0.02001816 -0.184996 -0.09467935 0.02042227 -0.185947 -0.0941382 0.02139997 -0.184298 -0.0945574 0.02096515 -0.184753 -0.094603 0.0206784 -0.185068 -0.09521615 0.01919859 -0.184755 -0.09536468 0.01898097 -0.1845549 -0.09542858 0.01892119 -0.1841109 -0.09600627 0.01785719 -0.1840029 -0.09555757 0.01889997 -0.182054 -0.0961948 0.01889997 -0.1816779 -0.0952968 0.02109998 -0.183695 -0.09463059 0.02109998 -0.183777 -0.09461635 0.02108919 -0.184041 -0.09457075 0.02105426 -0.177943 -0.09762549 0.02109998 -0.179717 -0.09631037 0.02109998 -0.179646 -0.09619778 0.02139997 -0.183745 -0.09448188 0.02139997 -0.17514 -0.1010169 0.02109736 -0.175024 -0.10095 0.02139997 -0.175181 -0.100945 0.02109998 -0.1764039 -0.09920787 0.02109998 -0.187463 -0.120694 0.01892155 -0.1868979 -0.120232 0.01785719 -0.187228 -0.120691 0.01889997 -0.1876879 -0.120713 0.01898759 -0.187891 -0.1207489 0.01909917 -0.188059 -0.120804 0.01925337 -0.18818 -0.120877 0.01944094 -0.188246 -0.120962 0.01964718 -0.188259 -0.121057 0.01986187 -0.188224 -0.1211529 0.0200721 -0.188038 -0.12134 0.02045518 -0.1877329 -0.1215 0.02077007 -0.186888 -0.1218 0.02139997 -0.18209 -0.119219 0.01785719 -0.1828629 -0.120012 0.01889997 -0.183012 -0.119576 0.01785719 -0.184852 -0.120516 0.01889997 -0.1849279 -0.120061 0.01785719 -0.177729 -0.11672 0.01889997 -0.178063 -0.116402 0.01785719 -0.179255 -0.11809 0.01889997 -0.179535 -0.117722 0.01785719 -0.176472 -0.116299 0.02042227 -0.176527 -0.116549 0.02067887 -0.176716 -0.116966 0.02096569 -0.175527 -0.115746 0.02139997 -0.1766909 -0.115906 0.01948314 -0.1769 -0.115969 0.01919907 -0.176823 -0.114863 0.01785719 -0.1771849 -0.116164 0.01898127 -0.177341 -0.116307 0.01892119 -0.177503 -0.116475 0.01889997 -0.176926 -0.117481 0.02139997 -0.177026 -0.117386 0.02108907 -0.176854 -0.117179 0.02105396 -0.1785849 -0.11897 0.02139997 -0.1786659 -0.1188639 0.02109998 -0.180461 -0.120173 0.02139997 -0.181466 -0.120657 0.02139997 -0.182506 -0.121059 0.02139997 -0.18734 -0.121616 0.02099418 -0.1868889 -0.121666 0.02109736 -0.186805 -0.121666 0.02109998 -0.197768 -0.1011559 0.01892125 -0.19765 -0.101876 0.01785719 -0.197883 -0.10136 0.01889997 -0.197672 -0.100953 0.01898699 -0.197602 -0.100759 0.01909786 -0.196538 -0.100242 0.01785719 -0.197565 -0.1005859 0.01925116 -0.197567 -0.100445 0.01943814 -0.1976079 -0.100344 0.01964396 -0.197682 -0.100285 0.01985806 -0.1977829 -0.100267 0.02006858 -0.198036 -0.100333 0.02045065 -0.198328 -0.100516 0.02076786 -0.198625 -0.100799 0.02099329 -0.1989189 -0.103506 0.01889997 -0.198486 -0.103667 0.01785719 -0.199024 -0.105569 0.01785719 -0.19925 -0.107533 0.01785719 -0.199616 -0.109566 0.01889997 -0.199158 -0.109507 0.01785719 -0.19945 -0.113966 0.02139997 -0.1993719 -0.112927 0.02029055 -0.198751 -0.111441 0.01785719 -0.200121 -0.111847 0.02108865 -0.200562 -0.105265 0.02139997 -0.200684 -0.107484 0.02109998 -0.198896 -0.101167 0.02109736 -0.198938 -0.101239 0.02109998 -0.176494 -0.116037 0.02001869 -0.1765609 -0.115943 0.0197677 -0.174425 -0.113809 0.02139997 -0.175846 -0.113145 0.01785719 -0.173216 -0.109533 0.02139997 -0.1751559 -0.111293 0.01785719 -0.174773 -0.109354 0.01785719 -0.174706 -0.107378 0.01785719 -0.174956 -0.105418 0.01785719 -0.199086 -0.112963 0.01972246 -0.198038 -0.113285 0.01785719 -0.196903 -0.1176069 0.02139997 -0.197039 -0.114991 0.01785719 -0.195779 -0.116514 0.01785719 -0.195225 -0.119074 0.02139997 -0.1942909 -0.117815 0.01785719 -0.193334 -0.120254 0.02139997 -0.192614 -0.118861 0.01785719 -0.190791 -0.119624 0.01785719 -0.1888689 -0.120085 0.01785719 -0.186064 -0.09570145 0.01785719 -0.18804 -0.09571397 0.01785719 -0.189989 -0.09604328 0.01785719 -0.19186 -0.09668099 0.01785719 -0.192484 -0.09524267 0.02139997 -0.194451 -0.09629088 0.02139997 -0.193605 -0.09761059 0.01785719 -0.196224 -0.09764111 0.02139997 -0.195177 -0.09880799 0.01785719 -0.178007 -0.117776 0.02139997 -0.1736479 -0.11172 0.02139997 -0.1738629 -0.110196 0.02139997 -0.1731399 -0.107305 0.02139997 -0.173422 -0.105094 0.02139997 -0.175248 -0.101669 0.02139997 -0.176442 -0.0998243 0.02139997 -0.176302 -0.09912329 0.02139997 -0.177856 -0.09752547 0.02139997 -0.1815789 -0.09579038 0.02139997 -0.181626 -0.09517437 0.02139997 -0.188176 -0.09415221 0.02139997 -0.190185 -0.0950399 0.02139997 -0.192266 -0.09574431 0.02139997 -0.190374 -0.0945236 0.02139997 -0.194203 -0.09678167 0.02139997 -0.1959429 -0.09812378 0.02139997 -0.197758 -0.0992583 0.02139997 -0.1990129 -0.101101 0.02139997 -0.1999559 -0.10312 0.02139997 -0.200278 -0.107893 0.02139997 -0.200817 -0.107479 0.02139997 -0.200106 -0.110083 0.02139997 -0.200713 -0.109706 0.02139997 -0.199576 -0.112215 0.02139997 -0.200254 -0.111887 0.02139997 -0.198323 -0.115889 0.02139997 -0.191278 -0.121115 0.02139997 -0.188131 -0.121203 0.02139997 -0.1859329 -0.121212 0.02139997 -0.1891109 -0.121634 0.02139997 -0.184667 -0.121606 0.02139997 -0.187763 -0.120136 0.01893377 -0.1880339 -0.120101 0.01889997 -0.176547 -0.09990531 0.02109998 -0.177923 -0.09820139 0.02139997 -0.178013 -0.09829866 0.02109998 -0.179651 -0.09684437 0.02139997 -0.179724 -0.09695518 0.02109998 -0.181632 -0.09591168 0.02109998 -0.183654 -0.09506797 0.02139997 -0.183687 -0.0951966 0.02109998 -0.185551 -0.09529638 0.02011227 -0.1853049 -0.0951544 0.02049809 -0.185145 -0.09585046 0.01899075 -0.1849229 -0.09591686 0.01892215 -0.184688 -0.09596925 0.01889997 -0.185618 -0.09538459 0.01989769 -0.18534 -0.09577059 0.01910698 -0.185495 -0.09567916 0.01926767 -0.185595 -0.09558039 0.01946336 -0.185635 -0.09548056 0.01967775 -0.184949 -0.09506726 0.0208075 -0.184518 -0.09504687 0.02101939 -0.18405 -0.0951085 0.02109998 -0.196946 -0.100503 0.01946008 -0.196991 -0.100405 0.01967567 -0.197763 -0.100623 0.0208081 -0.197456 -0.100422 0.02049785 -0.197183 -0.100339 0.02011168 -0.196943 -0.100644 0.01926535 -0.196982 -0.100819 0.01910549 -0.197058 -0.1010169 0.01898986 -0.197034 -0.101077 0.01889997 -0.197161 -0.101223 0.01892197 -0.1999559 -0.105726 0.02109998 -0.199413 -0.10362 0.02109998 -0.200087 -0.105704 0.02139997 -0.199539 -0.103576 0.02139997 -0.198531 -0.1016319 0.02109998 -0.198647 -0.101568 0.02139997 -0.198347 -0.101307 0.02109998 -0.198071 -0.100922 0.02101916 -0.200145 -0.107893 0.02109998 -0.198374 -0.112933 0.01944994 -0.19835 -0.11253 0.01904737 -0.198338 -0.11276 0.01922166 -0.199116 -0.112672 0.02077645 -0.199431 -0.112166 0.02105468 -0.188497 -0.120528 0.01996839 -0.188504 -0.120407 0.01969885 -0.19002 -0.119761 0.01889997 -0.188381 -0.120267 0.01935315 -0.188244 -0.120208 0.01918637 -0.18804 -0.120162 0.01903849 -0.1902959 -0.120832 0.02139997 -0.188102 -0.120879 0.02066439 -0.187879 -0.120974 0.02084028 -0.187622 -0.12105 0.02097755 -0.179747 -0.119118 0.02139997 -0.181684 -0.120156 0.02139997 -0.1817359 -0.120034 0.02109998 -0.183797 -0.1207309 0.02109998 -0.1837649 -0.12086 0.02139997 -0.1870419 -0.12112 0.02109998 -0.187342 -0.121101 0.02106696 -0.176907 -0.116313 0.02091449 -0.177127 -0.116674 0.0210675 -0.176512 -0.116166 0.02139997 -0.177317 -0.116904 0.02109998 -0.179819 -0.119007 0.02109998 -0.176757 -0.115432 0.01995676 -0.175302 -0.114332 0.02139997 -0.176715 -0.1156229 0.02028828 -0.176768 -0.115965 0.02066439 -0.177541 -0.115705 0.01893389 -0.177334 -0.115521 0.01903849 -0.176928 -0.114795 0.01889997 -0.177116 -0.11538 0.01923495 -0.176309 -0.113855 0.01889997 -0.175431 -0.103048 0.01967775 -0.175239 -0.1028 0.02029955 -0.175213 -0.102582 0.0205549 -0.175536 -0.101423 0.02109998 -0.175383 -0.101741 0.02105468 -0.1752499 -0.102186 0.02086186 -0.175339 -0.102999 0.01991248 -0.175565 -0.103029 0.01941758 -0.175742 -0.102903 0.0191648 -0.175953 -0.102651 0.018974 -0.185819 -0.09469705 0.02139997 -0.1859149 -0.09579908 0.01889997 -0.1880159 -0.09468758 0.02139997 -0.174374 -0.103685 0.02139997 -0.175368 -0.104257 0.01889997 -0.173844 -0.105817 0.02139997 -0.1749359 -0.105994 0.01889997 -0.176932 -0.115329 0.01949834 -0.17684 -0.115348 0.01969259 -0.175456 -0.1119599 0.01889997 -0.1744109 -0.1123239 0.02139997 -0.1749359 -0.1098099 0.01889997 -0.173672 -0.108007 0.02139997 -0.191922 -0.119098 0.01889997 -0.192371 -0.12011 0.02139997 -0.188358 -0.120711 0.02034449 -0.19369 -0.118132 0.01889997 -0.193847 -0.118008 0.01889997 -0.194299 -0.119056 0.02139997 -0.1984609 -0.113035 0.01972246 -0.198702 -0.114231 0.02139997 -0.196632 -0.1154 0.01889997 -0.197508 -0.116076 0.02139997 -0.196305 -0.115759 0.01889997 -0.196027 -0.117699 0.02139997 -0.197073 -0.100351 0.01989668 -0.196568 -0.100417 0.01889997 -0.197438 -0.09973388 0.02139997 -0.195923 -0.09972256 0.01889997 -0.194783 -0.09862148 0.01889997 -0.193602 -0.09771049 0.01889997 -0.174782 -0.108045 0.01889997 -0.174898 -0.106478 0.01889997 -0.1787779 -0.10816 0.01889997 -0.175979 -0.101509 0.01889997 -0.193373 -0.107214 0.01889997 -0.178915 -0.109837 0.01889997 -0.178188 -0.109522 0.01889997 -0.1874679 -0.120137 0.01889997 -0.188921 -0.115873 0.01889997 -0.189319 -0.116288 0.01889997 -0.189463 -0.116108 0.01889997 -0.190963 -0.115638 0.01889997 -0.189462 -0.11753 0.01889997 -0.188847 -0.119962 0.01889997 -0.1897889 -0.117789 0.01889997 -0.189969 -0.117932 0.01889997 -0.191613 -0.117282 0.01889997 -0.195241 -0.116914 0.01889997 -0.178938 -0.117805 0.01889997 -0.17842 -0.111354 0.01889997 -0.178531 -0.111635 0.01889997 -0.17879 -0.109886 0.01889997 -0.177568 -0.110951 0.01889997 -0.1783879 -0.110393 0.01889997 -0.178293 -0.111033 0.01889997 -0.180654 -0.108974 0.01889997 -0.180706 -0.109424 0.01889997 -0.180539 -0.110146 0.01889997 -0.181215 -0.11083 0.01889997 -0.181218 -0.110836 0.01889997 -0.1773819 -0.115483 0.01889997 -0.177743 -0.115921 0.01889997 -0.179038 -0.112037 0.01889997 -0.179678 -0.112132 0.01889997 -0.1799989 -0.112005 0.01889997 -0.180279 -0.111894 0.01889997 -0.181665 -0.111517 0.01889997 -0.180682 -0.111387 0.01889997 -0.180777 -0.110747 0.01889997 -0.180727 -0.110623 0.01889997 -0.194272 -0.103768 0.01889997 -0.194148 -0.103817 0.01889997 -0.193951 -0.103895 0.01889997 -0.194463 -0.10309 0.01889997 -0.195419 -0.104265 0.01889997 -0.194912 -0.103863 0.01889997 -0.199477 -0.10548 0.01889997 -0.199575 -0.106333 0.01889997 -0.195657 -0.104867 0.01889997 -0.199711 -0.107517 0.01889997 -0.195562 -0.105507 0.01889997 -0.19516 -0.106014 0.01889997 -0.194838 -0.106141 0.01889997 -0.18639 -0.100617 0.01889997 -0.18958 -0.10194 0.01889997 -0.190476 -0.102145 0.01889997 -0.191385 -0.102012 0.01889997 -0.193053 -0.0999754 0.01889997 -0.193004 -0.09905785 0.01889997 -0.188199 -0.09886819 0.01889997 -0.186765 -0.09975278 0.01889997 -0.193102 -0.1025 0.01889997 -0.191641 -0.101867 0.01889997 -0.192185 -0.101559 0.01889997 -0.192767 -0.100848 0.01889997 -0.192627 -0.09821999 0.01889997 -0.194109 -0.09810149 0.01889997 -0.191973 -0.09757471 0.01889997 -0.189343 -0.09747087 0.01889997 -0.190212 -0.09717297 0.01889997 -0.188446 -0.0958743 0.01889997 -0.188078 -0.099779 0.01889997 -0.188225 -0.100386 0.01889997 -0.1882939 -0.100672 0.01889997 -0.188819 -0.101426 0.01889997 -0.182034 -0.112081 0.01889997 -0.181223 -0.112536 0.01889997 -0.185845 -0.1142899 0.01889997 -0.184413 -0.1138589 0.01889997 -0.18756 -0.115283 0.01889997 -0.18312 -0.113109 0.01889997 -0.183139 -0.102777 0.01889997 -0.181225 -0.105049 0.01889997 -0.180711 -0.106453 0.01889997 -0.180535 -0.107938 0.01889997 -0.185964 -0.1016 0.01889997 -0.185868 -0.101606 0.01889997 -0.183214 -0.100296 0.01889997 -0.1836259 -0.1003569 0.01889997 -0.183391 -0.102632 0.01889997 -0.184435 -0.102032 0.01889997 -0.192727 -0.103364 0.01889997 -0.191403 -0.103274 0.01889997 -0.190205 -0.102379 0.01889997 -0.1888329 -0.101784 0.01889997 -0.187361 -0.101522 0.01889997 -0.192349 -0.111499 0.01889997 -0.193022 -0.110164 0.01889997 -0.19337 -0.108709 0.01889997 -0.19097 -0.115063 0.01889997 -0.190185 -0.113533 0.01889997 -0.190549 -0.113263 0.01889997 -0.191386 -0.112642 0.01889997 -0.1873379 -0.11438 0.01889997 -0.188002 -0.114264 0.01889997 -0.188804 -0.114124 0.01889997 -0.189541 -0.114444 0.01889997 -0.188811 -0.114123 0.01889997 -0.189879 -0.113664 0.01889997 -0.181525 -0.101823 0.01889997 -0.182479 -0.09985947 0.01889997 -0.182986 -0.100262 0.01889997 -0.182389 -0.102198 0.01889997 -0.18243 -0.0997349 0.01889997 -0.183341 -0.09787297 0.01889997 -0.184328 -0.09548407 0.01889997 -0.1886399 -0.09806257 0.01889997 -0.1879299 -0.09579038 0.01889997 -0.184676 -0.0988475 0.01889997 -0.183981 -0.09796798 0.01889997 -0.185115 -0.09591007 0.01889997 -0.184161 -0.09811121 0.01889997 -0.184487 -0.09837019 0.01889997 -0.184228 -0.100119 0.01889997 -0.184487 -0.09979248 0.01889997 -0.18463 -0.09961199 0.01889997 -0.184725 -0.09897196 0.01889997 -0.17744 -0.1021749 0.01889997 -0.18007 -0.102278 0.01889997 -0.17723 -0.09996145 0.01889997 -0.179228 -0.101913 0.01889997 -0.178309 -0.101877 0.01889997 -0.177677 -0.106644 0.01889997 -0.176916 -0.10613 0.01889997 -0.176391 -0.105376 0.01889997 -0.1761749 -0.104483 0.01889997 -0.178573 -0.106848 0.01889997 -0.179399 -0.106728 0.01889997 -0.179482 -0.106715 0.01889997 -0.1802819 -0.106263 0.01889997 -0.179642 -0.108535 0.01889997 -0.182049 -0.103801 0.01889997 -0.180864 -0.105552 0.01889997 -0.18115 -0.104679 0.01889997 -0.181101 -0.103762 0.01889997 -0.180889 -0.10329 0.01889997 -0.180724 -0.102924 0.01889997 -0.183013 -0.11378 0.01889997 -0.182144 -0.114078 0.01889997 -0.185854 -0.116582 0.01889997 -0.185805 -0.115665 0.01889997 -0.185428 -0.114827 0.01889997 -0.184774 -0.114181 0.01889997 -0.1839309 -0.113816 0.01889997 -0.183277 -0.118751 0.01889997 -0.184186 -0.118618 0.01889997 -0.184985 -0.118166 0.01889997 -0.181441 -0.114669 0.01889997 -0.181 -0.1154749 0.01889997 -0.1808789 -0.1163859 0.01889997 -0.181095 -0.117279 0.01889997 -0.181619 -0.118033 0.01889997 -0.182381 -0.118547 0.01889997 -0.186895 -0.120693 0.01889997 -0.186834 -0.120688 0.01889997 -0.185275 -0.120553 0.01889997 -0.185567 -0.117455 0.01889997 -0.191708 -0.1166419 0.01889997 -0.1952739 -0.116888 0.01889997 -0.197727 -0.113709 0.01889997 -0.19747 -0.112751 0.01889997 -0.194308 -0.107365 0.01889997 -0.192903 -0.110771 0.01889997 -0.19156 -0.1137019 0.01889997 -0.199193 -0.111572 0.01889997 -0.198494 -0.1119599 0.01889997 -0.197708 -0.110961 0.01889997 -0.199596 -0.109658 0.01889997 -0.195834 -0.109112 0.01889997 -0.194916 -0.109076 0.01889997 -0.193522 -0.113329 0.01889997 -0.194284 -0.113843 0.01889997 -0.1951799 -0.114048 0.01889997 -0.197282 -0.101429 0.01889997 -0.195546 -0.104587 0.01889997 -0.1955299 -0.104546 0.01889997 -0.195892 -0.1037099 0.01889997 -0.199407 -0.105234 0.01889997 -0.195197 -0.0989409 0.01889997 -0.194558 -0.106252 0.01889997 -0.193918 -0.106157 0.01889997 -0.193306 -0.106931 0.01889997 -0.1934109 -0.105754 0.01889997 -0.193127 -0.106171 0.01889997 -0.1933619 -0.10563 0.01889997 -0.1930299 -0.105758 0.01889997 -0.193173 -0.105153 0.01889997 -0.192362 -0.104421 0.01889997 -0.193268 -0.104513 0.01889997 -0.192301 -0.104348 0.01889997 -0.19367 -0.104006 0.01889997 -0.191826 -0.09675925 0.01889997 -0.189918 -0.0961135 0.01889997 -0.1892859 -0.0960108 0.01889997 -0.19113 -0.09720927 0.01889997 -0.182242 -0.0992577 0.01889997 -0.182303 -0.09884548 0.01889997 -0.182337 -0.09861767 0.01889997 -0.182739 -0.09811079 0.01889997 -0.1828629 -0.09806156 0.01889997 -0.183216 -0.0979222 0.01889997 -0.184267 -0.0954979 0.01889997 -0.175422 -0.104039 0.01889997 -0.176174 -0.102284 0.01889997 -0.176738 -0.102766 0.01889997 -0.1762959 -0.103572 0.01889997 -0.174778 -0.108003 0.01889997 -0.179112 -0.109759 0.01889997 -0.179392 -0.109648 0.01889997 -0.180032 -0.1097429 0.01889997 -0.174953 -0.110009 0.01889997 -0.178404 -0.111313 0.01889997 -0.176273 -0.113801 0.01889997 -0.197699 -0.110962 0.01741605 -0.197684 -0.110868 0.01739996 -0.197775 -0.111416 0.0174939 -0.196888 -0.113462 0.01889997 -0.1972129 -0.113133 0.01754516 -0.19747 -0.112751 0.01757097 -0.197757 -0.111878 0.01889997 -0.197654 -0.112327 0.01757085 -0.197757 -0.111878 0.01754516 -0.197331 -0.110123 0.01889997 -0.195834 -0.109112 0.01739996 -0.196677 -0.1094779 0.01889997 -0.194916 -0.109076 0.01739996 -0.194047 -0.109374 0.01889997 -0.1933439 -0.109965 0.01889997 -0.192903 -0.110771 0.01739996 -0.192782 -0.1116819 0.01889997 -0.192998 -0.112575 0.01889997 -0.194284 -0.113843 0.01739996 -0.196089 -0.113915 0.01889997 -0.196888 -0.113462 0.01749408 -0.195657 -0.104867 0.01739996 -0.19688 -0.102942 0.01739996 -0.197628 -0.104834 0.01739996 -0.195562 -0.105507 0.01739996 -0.189893 -0.09724128 0.01739996 -0.1958 -0.101218 0.01739996 -0.194272 -0.103768 0.01739996 -0.194912 -0.103863 0.01739996 -0.195419 -0.104265 0.01739996 -0.193918 -0.106157 0.01739996 -0.1934109 -0.105754 0.01739996 -0.1906369 -0.106342 0.01739996 -0.193173 -0.105153 0.01739996 -0.192796 -0.09849959 0.01739996 -0.194423 -0.09972065 0.01739996 -0.193062 -0.09940016 0.01739996 -0.192978 -0.100336 0.01739996 -0.1925539 -0.1011739 0.01739996 -0.19367 -0.104006 0.01739996 -0.191851 -0.101796 0.01739996 -0.190967 -0.102116 0.01739996 -0.188504 -0.101048 0.01739996 -0.189167 -0.101713 0.01739996 -0.190029 -0.102086 0.01739996 -0.193268 -0.104513 0.01739996 -0.189095 -0.104558 0.01739996 -0.196425 -0.113771 0.01739996 -0.196089 -0.113915 0.01739996 -0.195204 -0.115398 0.01739996 -0.187728 -0.111879 0.01739996 -0.188852 -0.111482 0.01739996 -0.194558 -0.106252 0.01739996 -0.19516 -0.106014 0.01739996 -0.194047 -0.109374 0.01739996 -0.190949 -0.107493 0.01739996 -0.1933439 -0.109965 0.01739996 -0.192782 -0.1116819 0.01739996 -0.18981 -0.110772 0.01739996 -0.196677 -0.1094779 0.01739996 -0.198018 -0.106831 0.01739996 -0.197331 -0.110123 0.01739996 -0.198036 -0.108865 0.01739996 -0.185384 -0.11162 0.01739996 -0.183196 -0.106638 0.01739996 -0.182977 -0.10781 0.01739996 -0.189054 -0.09766238 0.01739996 -0.1884289 -0.09836357 0.01739996 -0.1878899 -0.09688848 0.01739996 -0.188107 -0.0992459 0.01739996 -0.188133 -0.100185 0.01739996 -0.184592 -0.104737 0.01739996 -0.185645 -0.104178 0.01739996 -0.186816 -0.103953 0.01739996 -0.1951799 -0.114048 0.01739996 -0.193522 -0.113329 0.01739996 -0.1946859 -0.115874 0.01739996 -0.192998 -0.112575 0.01739996 -0.191613 -0.117282 0.01739996 -0.191983 -0.117855 0.01739996 -0.191211 -0.117789 0.01739996 -0.190091 -0.118603 0.01739996 -0.189969 -0.117932 0.01739996 -0.188094 -0.118993 0.01739996 -0.193707 -0.116775 0.01739996 -0.180972 -0.115564 0.01739996 -0.181396 -0.114726 0.01739996 -0.183921 -0.1138139 0.01739996 -0.184783 -0.114187 0.01739996 -0.185521 -0.117536 0.01739996 -0.1848959 -0.118238 0.01739996 -0.18606 -0.119011 0.01739996 -0.1840569 -0.118659 0.01739996 -0.185817 -0.115715 0.01739996 -0.185843 -0.116654 0.01739996 -0.185446 -0.114852 0.01739996 -0.181154 -0.1174 0.01739996 -0.182099 -0.114104 0.01739996 -0.182982 -0.113784 0.01739996 -0.179527 -0.116179 0.01739996 -0.180539 -0.110146 0.01739996 -0.180032 -0.1097429 0.01739996 -0.179392 -0.109648 0.01739996 -0.180777 -0.110747 0.01739996 -0.181446 -0.110135 0.01739996 -0.180887 -0.1165 0.01739996 -0.180682 -0.111387 0.01739996 -0.180279 -0.111894 0.01739996 -0.179051 -0.115661 0.01739996 -0.179678 -0.112132 0.01739996 -0.1781499 -0.114682 0.01739996 -0.17707 -0.112958 0.01739996 -0.179038 -0.112037 0.01739996 -0.178531 -0.111635 0.01739996 -0.176322 -0.111066 0.01739996 -0.178293 -0.111033 0.01739996 -0.175932 -0.109069 0.01739996 -0.1783879 -0.110393 0.01739996 -0.17879 -0.109886 0.01739996 -0.182739 -0.09811079 0.01739996 -0.181967 -0.09804475 0.01739996 -0.185856 -0.09690725 0.01739996 -0.183859 -0.09729707 0.01739996 -0.183341 -0.09787297 0.01739996 -0.183981 -0.09796798 0.01739996 -0.184487 -0.09837019 0.01739996 -0.184725 -0.09897196 0.01739996 -0.187186 -0.09689497 0.01739996 -0.18463 -0.09961199 0.01739996 -0.184228 -0.100119 0.01739996 -0.177524 -0.102129 0.01739996 -0.178425 -0.101863 0.01739996 -0.178746 -0.100502 0.01739996 -0.182337 -0.09861767 0.01739996 -0.182242 -0.0992577 0.01739996 -0.180243 -0.0991252 0.01739996 -0.182479 -0.09985947 0.01739996 -0.17936 -0.101947 0.01739996 -0.180199 -0.102371 0.01739996 -0.180821 -0.103074 0.01739996 -0.182986 -0.100262 0.01739996 -0.17921 -0.106792 0.01739996 -0.1782709 -0.106818 0.01739996 -0.17592 -0.107739 0.01739996 -0.177388 -0.106496 0.01739996 -0.175913 -0.107035 0.01739996 -0.176687 -0.105871 0.01739996 -0.176266 -0.105032 0.01739996 -0.18114 -0.1039569 0.01739996 -0.1836259 -0.1003569 0.01739996 -0.181111 -0.104896 0.01739996 -0.180738 -0.105758 0.01739996 -0.180073 -0.106421 0.01739996 -0.185384 -0.11162 0.02139997 -0.186536 -0.111926 0.02139997 -0.186536 -0.111926 0.01739996 -0.187728 -0.111879 0.02139997 -0.188852 -0.111482 0.02139997 -0.18981 -0.110772 0.02139997 -0.1905159 -0.109811 0.01739996 -0.1905159 -0.109811 0.02139997 -0.190907 -0.108684 0.01739996 -0.190907 -0.108684 0.02139997 -0.190949 -0.107493 0.02139997 -0.1906369 -0.106342 0.02139997 -0.190001 -0.105334 0.02139997 -0.190001 -0.105334 0.01739996 -0.189095 -0.104558 0.02139997 -0.188001 -0.104084 0.01739996 -0.188001 -0.104084 0.02139997 -0.186816 -0.103953 0.02139997 -0.185645 -0.104178 0.02139997 -0.184592 -0.104737 0.02139997 -0.183751 -0.1055819 0.01739996 -0.183751 -0.1055819 0.02139997 -0.183196 -0.106638 0.02139997 -0.182977 -0.10781 0.02139997 -0.1831139 -0.108994 0.01739996 -0.1831139 -0.108994 0.02139997 -0.183593 -0.110086 0.01739996 -0.183593 -0.110086 0.02139997 -0.184373 -0.110988 0.02139997 -0.184373 -0.110988 0.01739996 -0.184489 -0.112259 0.02974998 -0.1842899 -0.112138 0.02884995 -0.183652 -0.111653 0.02884995 -0.183185 -0.111173 0.02974998 -0.183102 -0.111072 0.02884995 -0.182312 -0.109685 0.02884995 -0.182322 -0.109712 0.02974998 -0.182554 -0.110231 0.02974998 -0.182651 -0.11041 0.02884995 -0.182842 -0.11072 0.02974998 -0.182094 -0.108914 0.02884995 -0.182152 -0.10917 0.02974998 -0.182102 -0.108913 0.02974998 -0.182044 -0.108613 0.02974998 -0.182003 -0.108119 0.02884995 -0.1820009 -0.108046 0.02974998 -0.18204 -0.1073189 0.02884995 -0.182205 -0.106536 0.02884995 -0.182047 -0.10732 0.02974998 -0.182022 -0.107479 0.02974998 -0.182469 -0.105842 0.02974998 -0.182494 -0.105789 0.02884995 -0.182496 -0.10579 0.02974998 -0.182738 -0.105342 0.02974998 -0.182898 -0.105098 0.02884995 -0.183063 -0.104876 0.02974998 -0.183409 -0.104481 0.02884995 -0.184011 -0.103954 0.02884995 -0.1854299 -0.103225 0.02974998 -0.185429 -0.1032209 0.02884995 -0.185346 -0.103249 0.02974998 -0.184691 -0.10353 0.02884995 -0.184821 -0.103465 0.02974998 -0.1846939 -0.103536 0.02974998 -0.186209 -0.103042 0.02974998 -0.186208 -0.103035 0.02884995 -0.186453 -0.103002 0.02974998 -0.1870059 -0.102976 0.02974998 -0.187804 -0.103045 0.02884995 -0.187588 -0.103013 0.02974998 -0.1870059 -0.102975 0.02884995 -0.18858 -0.103241 0.02884995 -0.1881459 -0.103115 0.02974998 -0.187802 -0.103052 0.02974998 -0.189211 -0.103506 0.02974998 -0.189315 -0.103559 0.02884995 -0.18869 -0.10328 0.02974998 -0.188578 -0.103246 0.02974998 -0.189703 -0.10379 0.02974998 -0.189989 -0.103992 0.02884995 -0.189984 -0.103998 0.02974998 -0.190942 -0.104948 0.02974998 -0.190584 -0.104526 0.02884995 -0.190584 -0.1045269 0.02974998 -0.190574 -0.104516 0.02974998 -0.191479 -0.105848 0.02974998 -0.191087 -0.10515 0.02884995 -0.19172 -0.106456 0.02974998 -0.191483 -0.105846 0.02884995 -0.191756 -0.106597 0.02974998 -0.191762 -0.106596 0.02884995 -0.191917 -0.107381 0.02884995 -0.19191 -0.1073819 0.02974998 -0.191935 -0.10757 0.02974998 -0.191944 -0.108182 0.02884995 -0.191843 -0.108976 0.02884995 -0.191835 -0.108974 0.02974998 -0.191353 -0.110312 0.02974998 -0.191268 -0.110465 0.02884995 -0.191615 -0.1097429 0.02884995 -0.191775 -0.109259 0.02974998 -0.190705 -0.1112419 0.02974998 -0.190809 -0.1111209 0.02884995 -0.189607 -0.112171 0.02884995 -0.19025 -0.111695 0.02884995 -0.189381 -0.112304 0.02974998 -0.189603 -0.112165 0.02974998 -0.188135 -0.112788 0.02884995 -0.188896 -0.112539 0.02884995 -0.188895 -0.112538 0.02974998 -0.187344 -0.112911 0.02884995 -0.187213 -0.112919 0.02974998 -0.186543 -0.112906 0.02884995 -0.186645 -0.112914 0.02974998 -0.185754 -0.112773 0.02884995 -0.1860809 -0.112844 0.02974998 -0.184996 -0.112515 0.02884995 -0.184996 -0.112515 0.02974998 -0.1881909 -0.111761 0.03014999 -0.188223 -0.112351 0.03014999 -0.183751 -0.1055819 0.03014999 -0.183378 -0.105123 0.03014999 -0.183125 -0.106866 0.03014999 -0.1825 -0.107 0.03014999 -0.18338 -0.106196 0.03014999 -0.182831 -0.106011 0.03014999 -0.184689 -0.111913 0.03014999 -0.184754 -0.111277 0.03014999 -0.1841959 -0.110827 0.03014999 -0.186065 -0.111845 0.03014999 -0.185384 -0.11162 0.03014999 -0.187713 -0.112465 0.03014999 -0.1874909 -0.111917 0.03014999 -0.186775 -0.111945 0.03014999 -0.1861529 -0.112451 0.03014999 -0.182401 -0.108038 0.03014999 -0.1829929 -0.107571 0.03014999 -0.18242 -0.107516 0.03014999 -0.184252 -0.111626 0.03014999 -0.18349 -0.110914 0.03014999 -0.183727 -0.110284 0.03014999 -0.189974 -0.110597 0.03014999 -0.189453 -0.11109 0.03014999 -0.190037 -0.111349 0.03014999 -0.18963 -0.111676 0.03014999 -0.188852 -0.111482 0.03014999 -0.189188 -0.111954 0.03014999 -0.187017 -0.103375 0.03014999 -0.186816 -0.103953 0.03014999 -0.187532 -0.103989 0.03014999 -0.183724 -0.104731 0.03014999 -0.184226 -0.105045 0.03014999 -0.184112 -0.104382 0.03014999 -0.184788 -0.1046 0.03014999 -0.183362 -0.109667 0.03014999 -0.182909 -0.1100479 0.03014999 -0.1831139 -0.108994 0.03014999 -0.182696 -0.10957 0.03014999 -0.182989 -0.108288 0.03014999 -0.190398 -0.110019 0.03014999 -0.190405 -0.110978 0.03014999 -0.190975 -0.107971 0.03014999 -0.191537 -0.107601 0.03014999 -0.1845369 -0.104079 0.03014999 -0.185422 -0.104264 0.03014999 -0.184994 -0.103826 0.03014999 -0.185477 -0.103627 0.03014999 -0.186105 -0.104046 0.03014999 -0.18598 -0.103485 0.03014999 -0.190907 -0.108684 0.03014999 -0.191389 -0.109154 0.03014999 -0.190713 -0.109375 0.03014999 -0.191223 -0.109649 0.03014999 -0.191154 -0.106088 0.03014999 -0.1907269 -0.106564 0.03014999 -0.191339 -0.106576 0.03014999 -0.190914 -0.107256 0.03014999 -0.190001 -0.105334 0.03014999 -0.190419 -0.105916 0.03014999 -0.189485 -0.104836 0.03014999 -0.187538 -0.10341 0.03014999 -0.18823 -0.104152 0.03014999 -0.188552 -0.103655 0.03014999 -0.188888 -0.104437 0.03014999 -0.189484 -0.104124 0.03014999 -0.184294 -0.1121309 0.02974998 -0.184032 -0.111923 0.02990305 -0.184014 -0.111948 0.02974998 -0.183656 -0.111649 0.02974998 -0.183577 -0.111584 0.02974998 -0.183106 -0.111069 0.02974998 -0.182657 -0.110407 0.02974998 -0.1823509 -0.109701 0.02990305 -0.182181 -0.109163 0.02990305 -0.182314 -0.109684 0.02974998 -0.182074 -0.108609 0.02990305 -0.182006 -0.108119 0.02974998 -0.182031 -0.108046 0.02990305 -0.182053 -0.107481 0.02990305 -0.182108 -0.106917 0.02974998 -0.1822119 -0.1065379 0.02974998 -0.182258 -0.106369 0.02974998 -0.182905 -0.105103 0.02974998 -0.1834099 -0.104483 0.02974998 -0.183439 -0.10445 0.02974998 -0.183861 -0.10407 0.02974998 -0.18388 -0.104094 0.02990305 -0.184015 -0.10396 0.02974998 -0.184324 -0.10374 0.02974998 -0.184834 -0.103493 0.02990305 -0.185356 -0.103278 0.02990305 -0.1858929 -0.103094 0.02974998 -0.18702 -0.103006 0.02990305 -0.187021 -0.102975 0.02974998 -0.187584 -0.103043 0.02990305 -0.188679 -0.103309 0.02990305 -0.189197 -0.103533 0.02990305 -0.189312 -0.103564 0.02974998 -0.189686 -0.103815 0.02990305 -0.190159 -0.104128 0.02974998 -0.1905519 -0.104537 0.02990305 -0.19108 -0.105154 0.02974998 -0.191259 -0.10542 0.02974998 -0.191233 -0.105436 0.02990305 -0.191519 -0.105925 0.02974998 -0.191691 -0.106465 0.02990305 -0.19186 -0.107007 0.02974998 -0.19183 -0.107013 0.02990305 -0.191905 -0.107572 0.02990305 -0.191916 -0.108137 0.02990305 -0.191946 -0.108138 0.02974998 -0.191942 -0.1081809 0.02974998 -0.191862 -0.108699 0.02990305 -0.191893 -0.108703 0.02974998 -0.191613 -0.109742 0.02974998 -0.191594 -0.109798 0.02974998 -0.191262 -0.1104609 0.02974998 -0.191031 -0.110778 0.02990305 -0.1906819 -0.111222 0.02990305 -0.191056 -0.110796 0.02974998 -0.190803 -0.111117 0.02974998 -0.1903049 -0.1116459 0.02974998 -0.190248 -0.111692 0.02974998 -0.189844 -0.111977 0.02990305 -0.189862 -0.112002 0.02974998 -0.188858 -0.112522 0.02990305 -0.1888689 -0.11255 0.02974998 -0.188332 -0.112736 0.02974998 -0.188133 -0.112781 0.02974998 -0.1877779 -0.11286 0.02974998 -0.187343 -0.112906 0.02974998 -0.1866469 -0.112884 0.02990305 -0.186544 -0.112902 0.02974998 -0.186087 -0.112814 0.02990305 -0.185756 -0.112765 0.02974998 -0.1855289 -0.1127099 0.02974998 -0.186102 -0.112729 0.03003275 -0.187212 -0.112889 0.02990305 -0.187773 -0.11283 0.02990305 -0.188324 -0.112707 0.02990305 -0.189366 -0.112278 0.02990305 -0.189325 -0.112202 0.03003275 -0.190285 -0.111624 0.02990305 -0.190617 -0.111165 0.03003275 -0.191327 -0.110298 0.02990305 -0.191566 -0.109786 0.02990305 -0.191745 -0.109251 0.02990305 -0.191662 -0.109228 0.03003275 -0.191829 -0.108133 0.03003275 -0.191819 -0.107579 0.03003275 -0.191491 -0.105938 0.02990305 -0.190918 -0.1049669 0.02990305 -0.19049 -0.104597 0.03003275 -0.19014 -0.104151 0.02990305 -0.1900849 -0.104218 0.03003275 -0.189639 -0.103888 0.03003275 -0.189158 -0.103611 0.03003275 -0.188139 -0.103144 0.02990305 -0.1886489 -0.10339 0.03003275 -0.187573 -0.103129 0.03003275 -0.18702 -0.103092 0.03003275 -0.186457 -0.103033 0.02990305 -0.185899 -0.103124 0.02990305 -0.186466 -0.103119 0.03003275 -0.185385 -0.1033599 0.03003275 -0.18434 -0.103766 0.02990305 -0.184386 -0.103839 0.03003275 -0.183935 -0.104161 0.03003275 -0.183461 -0.104471 0.02990305 -0.183087 -0.104895 0.02990305 -0.1827639 -0.105358 0.02990305 -0.182838 -0.105403 0.03003275 -0.182496 -0.105855 0.02990305 -0.182575 -0.105891 0.03003275 -0.182287 -0.106379 0.02990305 -0.1823689 -0.106406 0.03003275 -0.182223 -0.106941 0.03003275 -0.182138 -0.106923 0.02990305 -0.1821179 -0.108044 0.03003275 -0.18216 -0.108597 0.03003275 -0.182265 -0.109142 0.03003275 -0.182581 -0.110217 0.02990305 -0.182868 -0.110703 0.02990305 -0.183208 -0.111153 0.02990305 -0.18294 -0.110655 0.03003275 -0.183598 -0.111562 0.02990305 -0.184504 -0.112233 0.02990305 -0.184083 -0.111854 0.03003275 -0.184547 -0.112158 0.03003275 -0.185008 -0.112487 0.02990305 -0.185043 -0.112407 0.03003275 -0.1855379 -0.112681 0.02990305 -0.185563 -0.112598 0.03003275 -0.1861259 -0.112601 0.03011959 -0.186653 -0.112797 0.03003275 -0.186661 -0.112668 0.03011959 -0.187207 -0.112802 0.03003275 -0.187759 -0.112744 0.03003275 -0.1883 -0.112623 0.03003275 -0.188825 -0.112442 0.03003275 -0.188775 -0.112322 0.03011959 -0.189794 -0.111906 0.03003275 -0.189719 -0.111801 0.03011959 -0.190226 -0.111559 0.03003275 -0.19014 -0.111463 0.03011959 -0.190959 -0.110729 0.03003275 -0.1908529 -0.110655 0.03011959 -0.19125 -0.110257 0.03003275 -0.191485 -0.109754 0.03003275 -0.191365 -0.109706 0.03011959 -0.191648 -0.108666 0.03011959 -0.191777 -0.108686 0.03003275 -0.1917 -0.108129 0.03011959 -0.191689 -0.107589 0.03011959 -0.191745 -0.107029 0.03003275 -0.191609 -0.106492 0.03003275 -0.191412 -0.105973 0.03003275 -0.191294 -0.106026 0.03011959 -0.1911579 -0.10548 0.03003275 -0.1910459 -0.1055459 0.03011959 -0.190746 -0.105097 0.03011959 -0.190849 -0.105019 0.03003275 -0.190396 -0.104686 0.03011959 -0.189568 -0.103996 0.03011959 -0.1881189 -0.103229 0.03003275 -0.187557 -0.103258 0.03011959 -0.187018 -0.103222 0.03011959 -0.186479 -0.103248 0.03011959 -0.185947 -0.103335 0.03011959 -0.185918 -0.103208 0.03003275 -0.184872 -0.1035709 0.03003275 -0.1849279 -0.103688 0.03011959 -0.1835229 -0.104532 0.03003275 -0.183155 -0.104948 0.03003275 -0.183257 -0.105028 0.03011959 -0.182949 -0.105471 0.03011959 -0.182139 -0.10749 0.03003275 -0.18235 -0.106968 0.03011959 -0.182268 -0.107502 0.03011959 -0.182289 -0.10858 0.03011959 -0.1824319 -0.1096709 0.03003275 -0.182658 -0.110177 0.03003275 -0.1827729 -0.110118 0.03011959 -0.183048 -0.110583 0.03011959 -0.183274 -0.111097 0.03003275 -0.183657 -0.111499 0.03003275 -0.183746 -0.111404 0.03011959 -0.1850939 -0.1122879 0.03011959 -0.1856009 -0.112474 0.03011959 -0.1856459 -0.112328 0.03014999 -0.186672 -0.112515 0.03014999 -0.187201 -0.112673 0.03011959 -0.187194 -0.11252 0.03014999 -0.187738 -0.112616 0.03011959 -0.188265 -0.1124989 0.03011959 -0.188717 -0.1121799 0.03014999 -0.189262 -0.112088 0.03011959 -0.190519 -0.111079 0.03011959 -0.1907269 -0.110567 0.03014999 -0.191136 -0.110195 0.03011959 -0.1910009 -0.110122 0.03014999 -0.191536 -0.109194 0.03011959 -0.191497 -0.108643 0.03014999 -0.191547 -0.108123 0.03014999 -0.191467 -0.107083 0.03014999 -0.191617 -0.107054 0.03011959 -0.191485 -0.10653 0.03011959 -0.190914 -0.105624 0.03014999 -0.190623 -0.10519 0.03014999 -0.190285 -0.1047919 0.03014999 -0.189903 -0.104435 0.03014999 -0.190001 -0.104318 0.03011959 -0.1891 -0.103726 0.03011959 -0.189031 -0.103863 0.03014999 -0.188605 -0.103512 0.03011959 -0.1880879 -0.103355 0.03011959 -0.1880519 -0.103504 0.03014999 -0.186495 -0.1034 0.03014999 -0.185427 -0.103482 0.03011959 -0.184455 -0.103949 0.03011959 -0.184016 -0.104262 0.03011959 -0.183615 -0.104624 0.03011959 -0.182692 -0.105946 0.03011959 -0.183079 -0.105551 0.03014999 -0.182492 -0.106448 0.03011959 -0.182637 -0.106496 0.03014999 -0.1822479 -0.108041 0.03011959 -0.1824409 -0.108559 0.03014999 -0.1825399 -0.109072 0.03014999 -0.182391 -0.1091099 0.03011959 -0.1825529 -0.109625 0.03011959 -0.183175 -0.1104969 0.03014999 -0.183373 -0.111013 0.03011959 -0.1838499 -0.111292 0.03014999 -0.184161 -0.111749 0.03011959 -0.184612 -0.112045 0.03011959 -0.185155 -0.112148 0.03014999 -0.185146 -0.103323 0.02039998 -0.188803 -0.112577 0.02324998 -0.188803 -0.112577 0.02039998 -0.182348 -0.109778 0.02039998 -0.191743 -0.106532 0.02824997 -0.191941 -0.108248 0.02324998 -0.191917 -0.107381 0.02824997 -0.191941 -0.108248 0.02824997 -0.191814 -0.109106 0.02824997 -0.191814 -0.109106 0.02324998 -0.191539 -0.109929 0.02324998 -0.191126 -0.110691 0.02324998 -0.191539 -0.109929 0.02824997 -0.191126 -0.110691 0.02824997 -0.190587 -0.111371 0.02324998 -0.190587 -0.111371 0.02824997 -0.189938 -0.111946 0.02324998 -0.189938 -0.111946 0.02824997 -0.1892 -0.1123999 0.02324998 -0.1892 -0.1123999 0.02824997 -0.191602 -0.106122 0.02039998 -0.18475 -0.1035 0.02324998 -0.185146 -0.103323 0.02324998 -0.182206 -0.109368 0.02824997 -0.182032 -0.108519 0.02324998 -0.182032 -0.108519 0.02824997 -0.182009 -0.107652 0.02324998 -0.182009 -0.107652 0.02824997 -0.1821359 -0.1067939 0.02324998 -0.1821359 -0.1067939 0.02824997 -0.18241 -0.105971 0.02324998 -0.182823 -0.105209 0.02324998 -0.18241 -0.105971 0.02824997 -0.182823 -0.105209 0.02824997 -0.183362 -0.104529 0.02324998 -0.183362 -0.104529 0.02824997 -0.184011 -0.103954 0.02324998 -0.184011 -0.103954 0.02824997 -0.18475 -0.1035 0.02824997 -0.185557 -0.103181 0.02824997 -0.185557 -0.103181 0.02039998 -0.186406 -0.103008 0.02824997 -0.186406 -0.103008 0.02039998 -0.187273 -0.102984 0.02039998 -0.187273 -0.102984 0.02824997 -0.188131 -0.103111 0.02824997 -0.188131 -0.103111 0.02039998 -0.1889539 -0.103385 0.02039998 -0.1889539 -0.103385 0.02824997 -0.189716 -0.103798 0.02824997 -0.189716 -0.103798 0.02039998 -0.190396 -0.104338 0.02039998 -0.190396 -0.104338 0.02824997 -0.190971 -0.104986 0.02824997 -0.190971 -0.104986 0.02039998 -0.191425 -0.105725 0.02039998 -0.191425 -0.105725 0.02824997 -0.191602 -0.106122 0.02324998 -0.191743 -0.106532 0.02324998 -0.191917 -0.107381 0.02324998 -0.1883929 -0.1127189 0.02039998 -0.1883929 -0.1127189 0.02824997 -0.187543 -0.112892 0.02039998 -0.186677 -0.112916 0.02039998 -0.187543 -0.112892 0.02824997 -0.185819 -0.112789 0.02039998 -0.186677 -0.112916 0.02824997 -0.185819 -0.112789 0.02824997 -0.184996 -0.112515 0.02039998 -0.184996 -0.112515 0.02824997 -0.184234 -0.112102 0.02039998 -0.184234 -0.112102 0.02824997 -0.1835539 -0.111562 0.02824997 -0.1835539 -0.111562 0.02039998 -0.182979 -0.110914 0.02039998 -0.182979 -0.110914 0.02824997 -0.182525 -0.110175 0.02039998 -0.182525 -0.110175 0.02824997 -0.182348 -0.109778 0.02324998 -0.182206 -0.109368 0.02324998 -0.181634 -0.115352 0.03344994 -0.181634 -0.115352 0.03214997 -0.1816419 -0.1161839 0.03214997 -0.181988 -0.11694 0.03214997 -0.1816419 -0.1161839 0.03344994 -0.181988 -0.11694 0.03344994 -0.182611 -0.1174899 0.03214997 -0.182611 -0.1174899 0.03344994 -0.183405 -0.11774 0.03344994 -0.184947 -0.117222 0.03344994 -0.185429 -0.116544 0.03214997 -0.185594 -0.115729 0.03214997 -0.185413 -0.114917 0.03344994 -0.184918 -0.114249 0.03344994 -0.184918 -0.114249 0.03214997 -0.184193 -0.1138409 0.03214997 -0.1819649 -0.114589 0.03214997 -0.193771 -0.115717 0.03214997 -0.193391 -0.11625 0.03214997 -0.193391 -0.11625 0.03344994 -0.192867 -0.11656 0.03214997 -0.193089 -0.116429 0.03344994 -0.1918489 -0.116768 0.03214997 -0.1910549 -0.116519 0.03344994 -0.1910549 -0.116519 0.03214997 -0.190432 -0.115969 0.03214997 -0.190086 -0.115212 0.03214997 -0.190078 -0.114381 0.03214997 -0.1900849 -0.115127 0.03344994 -0.190078 -0.114381 0.03344994 -0.190409 -0.113618 0.03344994 -0.191021 -0.113055 0.03214997 -0.191388 -0.112932 0.03344994 -0.19181 -0.11279 0.03344994 -0.1933619 -0.113278 0.03344994 -0.194038 -0.114758 0.03214997 -0.193906 -0.114164 0.03214997 -0.193857 -0.113946 0.03344994 -0.193857 -0.113946 0.03214997 -0.1933619 -0.113278 0.03214997 -0.196772 -0.108452 0.03344994 -0.196056 -0.108875 0.03344994 -0.19523 -0.10897 0.03344994 -0.196056 -0.108875 0.03214997 -0.193628 -0.107765 0.03344994 -0.193467 -0.107414 0.03214997 -0.193467 -0.107414 0.03344994 -0.193584 -0.106183 0.03214997 -0.19379 -0.105819 0.03344994 -0.19379 -0.105819 0.03214997 -0.194339 -0.105314 0.03344994 -0.194402 -0.105256 0.03344994 -0.194402 -0.105256 0.03214997 -0.195191 -0.104992 0.03344994 -0.1960189 -0.1050699 0.03344994 -0.197419 -0.106959 0.03344994 -0.197419 -0.106959 0.03214997 -0.197287 -0.106365 0.03214997 -0.197238 -0.106147 0.03214997 -0.188404 -0.1005859 0.03214997 -0.188404 -0.1005859 0.03344994 -0.189373 -0.101893 0.03214997 -0.188726 -0.09899169 0.03214997 -0.188717 -0.0990076 0.03214997 -0.188521 -0.09935575 0.03214997 -0.188395 -0.09975469 0.03214997 -0.188726 -0.09899169 0.03344994 -0.189339 -0.09842908 0.03214997 -0.190127 -0.09816437 0.03344994 -0.190955 -0.09824317 0.03344994 -0.190955 -0.09824317 0.03214997 -0.191679 -0.09865188 0.03214997 -0.1922709 -0.100548 0.03214997 -0.192356 -0.100132 0.03344994 -0.181722 -0.103114 0.03214997 -0.180305 -0.102314 0.03214997 -0.180042 -0.10174 0.03344994 -0.1802819 -0.09996306 0.03344994 -0.180894 -0.09940057 0.03344994 -0.181084 -0.09933686 0.03344994 -0.181683 -0.09913575 0.03214997 -0.182548 -0.1030189 0.03344994 -0.183264 -0.102596 0.03344994 -0.183746 -0.101918 0.03344994 -0.183835 -0.10076 0.03344994 -0.18373 -0.100291 0.03214997 -0.1837249 -0.100284 0.03214997 -0.183235 -0.09962338 0.03214997 -0.180263 -0.109861 0.03214997 -0.179883 -0.110395 0.03344994 -0.179581 -0.110573 0.03344994 -0.179883 -0.110395 0.03214997 -0.179167 -0.110817 0.03344994 -0.179158 -0.110818 0.03214997 -0.177548 -0.1106629 0.03344994 -0.177548 -0.1106629 0.03214997 -0.176924 -0.110113 0.03344994 -0.176924 -0.110113 0.03214997 -0.176578 -0.109356 0.03214997 -0.1765699 -0.108525 0.03214997 -0.1765699 -0.108525 0.03344994 -0.177514 -0.107199 0.03344994 -0.178302 -0.106935 0.03214997 -0.18053 -0.108902 0.03214997 -0.179854 -0.107422 0.03214997 -0.17913 -0.107013 0.03214997 -0.1878409 -0.09744775 0.03344994 -0.1878409 -0.09744775 0.03214997 -0.1872349 -0.09819579 0.03344994 -0.1872349 -0.09819579 0.03214997 -0.186936 -0.09835946 0.03214997 -0.1863909 -0.09865909 0.03214997 -0.1863909 -0.09865909 0.03344994 -0.185434 -0.09876906 0.03344994 -0.185434 -0.09876906 0.03214997 -0.185322 -0.09873777 0.03344994 -0.1837469 -0.0979188 0.03344994 -0.184498 -0.09850227 0.03214997 -0.1837469 -0.0979188 0.03214997 -0.188141 -0.09630829 0.03194999 -0.188361 -0.09411931 0.03194999 -0.1895239 -0.09584689 0.03344994 -0.189197 -0.09426885 0.03194999 -0.190096 -0.09594929 0.03344994 -0.196122 -0.09748387 0.03194999 -0.194401 -0.09620016 0.03194999 -0.1935189 -0.09573346 0.03194999 -0.191907 -0.09657305 0.03344994 -0.192504 -0.09519678 0.03194999 -0.194718 -0.09917879 0.03194999 -0.198579 -0.100297 0.03194999 -0.196503 -0.103449 0.03344994 -0.195552 -0.103298 0.03214997 -0.195552 -0.103298 0.03344994 -0.194729 -0.1027989 0.03344994 -0.193965 -0.101283 0.03214997 -0.193965 -0.101283 0.03344994 -0.194048 -0.100139 0.03214997 -0.19744 -0.103229 0.03214997 -0.197938 -0.103005 0.03344994 -0.19764 -0.103139 0.03214997 -0.1996459 -0.102235 0.03194999 -0.198278 -0.102852 0.03344994 -0.199674 -0.102314 0.03194999 -0.198929 -0.104653 0.03344994 -0.200374 -0.104254 0.03194999 -0.200419 -0.104483 0.03194999 -0.199253 -0.106325 0.03344994 -0.199294 -0.106533 0.03344994 -0.200784 -0.106361 0.03194999 -0.199365 -0.108447 0.03344994 -0.199141 -0.1103489 0.03344994 -0.200864 -0.108507 0.03194999 -0.1858299 -0.119374 0.03344994 -0.1858299 -0.119374 0.03214997 -0.186715 -0.117704 0.03214997 -0.190203 -0.117981 0.03344994 -0.200464 -0.111304 0.03194999 -0.1967059 -0.114446 0.03194999 -0.1972759 -0.11017 0.03214997 -0.195637 -0.113951 0.03344994 -0.1952919 -0.113052 0.03344994 -0.1952919 -0.113052 0.03214997 -0.1956959 -0.111206 0.03344994 -0.195313 -0.112089 0.03214997 -0.196385 -0.1105329 0.03344994 -0.1956959 -0.111206 0.03214997 -0.196385 -0.1105329 0.03214997 -0.196582 -0.110453 0.03214997 -0.198239 -0.110171 0.03344994 -0.196474 -0.114781 0.03194999 -0.196296 -0.114653 0.03214997 -0.196296 -0.114653 0.03344994 -0.197042 -0.11519 0.03344994 -0.196875 -0.117706 0.03194999 -0.195544 -0.1188639 0.03194999 -0.194182 -0.118023 0.03344994 -0.193635 -0.120132 0.03194999 -0.19274 -0.118928 0.03344994 -0.190684 -0.118815 0.03214997 -0.1907539 -0.119023 0.03214997 -0.190981 -0.119685 0.03344994 -0.1907539 -0.119023 0.03194999 -0.1893219 -0.12165 0.03194999 -0.187964 -0.119608 0.03194999 -0.187035 -0.12185 0.03194999 -0.185589 -0.121781 0.03194999 -0.184753 -0.121631 0.03194999 -0.183476 -0.121402 0.03194999 -0.177828 -0.118416 0.03194999 -0.178815 -0.117287 0.03344994 -0.179884 -0.118084 0.03344994 -0.18035 -0.118432 0.03344994 -0.180431 -0.120167 0.03194999 -0.182532 -0.121077 0.03194999 -0.179275 -0.11676 0.03194999 -0.176789 -0.117408 0.03194999 -0.177177 -0.114345 0.03194999 -0.175371 -0.115603 0.03194999 -0.175866 -0.104277 0.03194999 -0.176701 -0.102353 0.03194999 -0.1734859 -0.104596 0.03194999 -0.1742219 -0.102421 0.03194999 -0.175306 -0.100398 0.03194999 -0.200798 -0.106743 0.03194999 -0.2008219 -0.106743 0.03024995 -0.19968 -0.102312 0.03024995 -0.198579 -0.100297 0.03024995 -0.197161 -0.09849178 0.03194999 -0.195441 -0.0969761 0.03194999 -0.1914179 -0.09482288 0.03194999 -0.1914319 -0.09478378 0.03024995 -0.190474 -0.09449756 0.03194999 -0.186915 -0.0940501 0.03024995 -0.184628 -0.0942496 0.03024995 -0.180513 -0.09564357 0.03194999 -0.180315 -0.09576749 0.03194999 -0.180307 -0.0957539 0.03024995 -0.178695 -0.09678536 0.03194999 -0.178406 -0.09703618 0.03194999 -0.176708 -0.09857988 0.03024995 -0.176732 -0.09859991 0.03194999 -0.175306 -0.100398 0.03024995 -0.173148 -0.106865 0.03194999 -0.1731269 -0.109157 0.03024995 -0.173166 -0.109539 0.03194999 -0.173575 -0.1116459 0.03194999 -0.1742759 -0.113586 0.03194999 -0.176789 -0.117408 0.03024995 -0.178485 -0.118956 0.03024995 -0.178508 -0.118924 0.03194999 -0.179548 -0.1197 0.03194999 -0.181446 -0.120703 0.03194999 -0.1804119 -0.120203 0.03024995 -0.184746 -0.12167 0.03024995 -0.191465 -0.121105 0.03194999 -0.191542 -0.121072 0.03194999 -0.193437 -0.120256 0.03194999 -0.193643 -0.120146 0.03024995 -0.195255 -0.119115 0.03194999 -0.197242 -0.11732 0.03024995 -0.197218 -0.1173 0.03194999 -0.19826 -0.116066 0.03194999 -0.198644 -0.1155019 0.03024995 -0.198644 -0.1155019 0.03194999 -0.199728 -0.113479 0.03194999 -0.200612 -0.110639 0.03194999 -0.200801 -0.109035 0.03194999 -0.1831949 -0.09687727 0.03194999 -0.184628 -0.0942496 0.03194999 -0.187035 -0.09625017 0.03194999 -0.186915 -0.0940501 0.03194999 -0.181809 -0.118448 0.02824997 -0.181809 -0.118448 0.02574998 -0.1818439 -0.118465 0.02574998 -0.196184 -0.100734 0.02824997 -0.196184 -0.100734 0.02574998 -0.191961 -0.118534 0.02574998 -0.177222 -0.101487 0.02574998 -0.176701 -0.102353 0.02824997 -0.175866 -0.104277 0.02824997 -0.175389 -0.10632 0.03214997 -0.175591 -0.105249 0.02824997 -0.178477 -0.115992 0.03194999 -0.177177 -0.114345 0.02824997 -0.178477 -0.115992 0.02574998 -0.178504 -0.116021 0.02574998 -0.180049 -0.11738 0.02824997 -0.178504 -0.116021 0.02824997 -0.177766 -0.115166 0.02824997 -0.177766 -0.115166 0.02574998 -0.186875 -0.11965 0.02824997 -0.1858659 -0.119597 0.02824997 -0.1858659 -0.119597 0.03194999 -0.185808 -0.119592 0.03194999 -0.188003 -0.119605 0.02574998 -0.190029 -0.119244 0.02824997 -0.188003 -0.119605 0.02824997 -0.190029 -0.119244 0.03194999 -0.187964 -0.119608 0.02574998 -0.186875 -0.11965 0.02574998 -0.19539 -0.116079 0.02824997 -0.196728 -0.114413 0.02574998 -0.19771 -0.112604 0.02824997 -0.19771 -0.112604 0.03194999 -0.196728 -0.114413 0.02824997 -0.1967059 -0.114446 0.02574998 -0.19606 -0.115323 0.02824997 -0.19606 -0.115323 0.02574998 -0.198566 -0.1095409 0.02574998 -0.198566 -0.1095409 0.02824997 -0.198454 -0.110213 0.03194999 -0.198368 -0.110612 0.02574998 -0.198368 -0.110612 0.03194999 -0.198359 -0.110651 0.02824997 -0.198359 -0.110651 0.02574998 -0.198109 -0.104354 0.02574998 -0.19764 -0.103139 0.03194999 -0.197306 -0.102459 0.02824997 -0.197306 -0.102459 0.03194999 -0.19616 -0.100702 0.03194999 -0.195446 -0.09987926 0.02574998 -0.194674 -0.0991404 0.03214997 -0.19616 -0.100702 0.02574998 -0.195446 -0.09987926 0.02824997 -0.194718 -0.09917879 0.02824997 -0.194674 -0.0991404 0.03194999 -0.188141 -0.09630829 0.03214997 -0.189123 -0.09644889 0.03214997 -0.187075 -0.09625035 0.02824997 -0.185946 -0.09629529 0.02574998 -0.185946 -0.09629529 0.02824997 -0.184945 -0.09642738 0.02824997 -0.184945 -0.09642738 0.03194999 -0.187035 -0.09625017 0.02574998 -0.187075 -0.09625035 0.02574998 -0.19539 -0.116079 0.03214997 -0.193803 -0.117451 0.02824997 -0.1929579 -0.118004 0.02574998 -0.191997 -0.118517 0.02574998 -0.191961 -0.118534 0.02824997 -0.1929579 -0.118004 0.02824997 -0.191997 -0.118517 0.03214997 -0.183804 -0.119212 0.02824997 -0.1828449 -0.118897 0.02824997 -0.1818439 -0.118465 0.03214997 -0.1828449 -0.118897 0.02574998 -0.175841 -0.111546 0.02574998 -0.175841 -0.111546 0.02824997 -0.175546 -0.110456 0.02824997 -0.175555 -0.110495 0.03214997 -0.175284 -0.108415 0.02824997 -0.1761929 -0.112493 0.02824997 -0.1761929 -0.112493 0.03214997 -0.175555 -0.110495 0.02574998 -0.175546 -0.110456 0.02574998 -0.175384 -0.106359 0.02574998 -0.175384 -0.106359 0.02824997 -0.175284 -0.108415 0.03214997 -0.175389 -0.10632 0.02574998 -0.175591 -0.105249 0.02574998 -0.17789 -0.1005769 0.02824997 -0.178837 -0.09960186 0.03214997 -0.179322 -0.09909957 0.02824997 -0.177222 -0.101487 0.02824997 -0.177865 -0.100608 0.02574998 -0.17789 -0.1005769 0.02574998 -0.181026 -0.09787535 0.02574998 -0.180992 -0.09789568 0.02574998 -0.1831949 -0.09687727 0.03214997 -0.18292 -0.09697508 0.03214997 -0.18292 -0.09697508 0.02824997 -0.181989 -0.09736567 0.02824997 -0.180992 -0.09789568 0.02824997 -0.181989 -0.09736567 0.02574998 -0.191105 -0.09700316 0.02574998 -0.193027 -0.0979371 0.02824997 -0.193027 -0.0979371 0.03214997 -0.189123 -0.09644889 0.02824997 -0.191105 -0.09700316 0.02824997 -0.191142 -0.09701728 0.02574998 -0.1921409 -0.0974524 0.02824997 -0.1921409 -0.0974524 0.02574998 -0.198128 -0.1044239 0.03214997 -0.198109 -0.104354 0.02824997 -0.198121 -0.104392 0.03214997 -0.198121 -0.104392 0.02574998 -0.198403 -0.105444 0.02824997 -0.198403 -0.105444 0.02574998 -0.198577 -0.106439 0.02824997 -0.19866 -0.108535 0.02824997 -0.17631 -0.112761 0.03194999 -0.17631 -0.112761 0.03214997 -0.176509 -0.112671 0.03344994 -0.173086 -0.107393 0.03194999 -0.173152 -0.109157 0.03194999 -0.174656 -0.109367 0.03344994 -0.1735309 -0.111417 0.03194999 -0.1754299 -0.112379 0.03344994 -0.1756719 -0.113048 0.03344994 -0.174304 -0.113665 0.03194999 -0.175711 -0.105729 0.03214997 -0.174809 -0.105551 0.03344994 -0.175496 -0.105687 0.03194999 -0.173337 -0.105261 0.03194999 -0.178313 -0.101949 0.03344994 -0.177654 -0.101247 0.03214997 -0.178313 -0.101949 0.03214997 -0.1785809 -0.102649 0.03214997 -0.1786569 -0.102848 0.03344994 -0.178254 -0.104694 0.03344994 -0.177565 -0.105367 0.03344994 -0.177368 -0.105447 0.03344994 -0.177476 -0.101119 0.03194999 -0.1756899 -0.09983438 0.03194999 -0.177476 -0.101119 0.03214997 -0.176908 -0.10071 0.03344994 -0.177654 -0.101247 0.03344994 -0.182407 -0.09482836 0.03194999 -0.182485 -0.09479528 0.03194999 -0.177074 -0.09819358 0.03194999 -0.178143 -0.09924638 0.03344994 -0.182969 -0.09621477 0.03344994 -0.18309 -0.09656798 0.03344994 -0.17936 -0.104649 0.03344994 -0.17936 -0.104649 0.03214997 -0.1804119 -0.104233 0.03344994 -0.1804119 -0.104233 0.03214997 -0.180736 -0.10449 0.03344994 -0.1808879 -0.104875 0.03344994 -0.180736 -0.10449 0.03214997 -0.1808879 -0.104875 0.03214997 -0.180828 -0.105285 0.03344994 -0.18057 -0.1056089 0.03344994 -0.180185 -0.105762 0.03344994 -0.1797749 -0.105701 0.03344994 -0.180185 -0.105762 0.03214997 -0.179451 -0.105443 0.03344994 -0.1792989 -0.105058 0.03344994 -0.1864359 -0.09976506 0.03344994 -0.18676 -0.100023 0.03344994 -0.18676 -0.100023 0.03214997 -0.186912 -0.100408 0.03344994 -0.186774 -0.100915 0.03214997 -0.186594 -0.101142 0.03214997 -0.186594 -0.101142 0.03344994 -0.186209 -0.101294 0.03214997 -0.185475 -0.100976 0.03344994 -0.1853229 -0.100591 0.03344994 -0.185365 -0.100304 0.03344994 -0.185384 -0.100181 0.03214997 -0.185641 -0.09985655 0.03344994 -0.185641 -0.09985655 0.03214997 -0.186026 -0.09970438 0.03344994 -0.186026 -0.09970438 0.03214997 -0.192247 -0.103287 0.03214997 -0.179275 -0.11676 0.03214997 -0.192026 -0.1184999 0.03214997 -0.198476 -0.105988 0.03214997 -0.194057 -0.104072 0.03214997 -0.183956 -0.108848 0.03214997 -0.192128 -0.1085219 0.03214997 -0.190119 -0.108139 0.03214997 -0.1898649 -0.109203 0.03214997 -0.189262 -0.110116 0.03214997 -0.189994 -0.107052 0.03214997 -0.187707 -0.104886 0.03214997 -0.188711 -0.105321 0.03214997 -0.191005 -0.104877 0.03214997 -0.189505 -0.106074 0.03214997 -0.18389 -0.1082749 0.03214997 -0.184688 -0.1057839 0.03214997 -0.1851029 -0.105476 0.03214997 -0.185467 -0.105206 0.03214997 -0.184445 -0.109826 0.03214997 -0.1884829 -0.110694 0.03214997 -0.188383 -0.110768 0.03214997 -0.187335 -0.111079 0.03214997 -0.1862429 -0.111014 0.03214997 -0.187487 -0.112992 0.03214997 -0.185239 -0.110579 0.03214997 -0.190915 -0.11132 0.03214997 -0.188847 -0.110424 0.03214997 -0.192638 -0.112869 0.03214997 -0.190151 -0.114147 0.03214997 -0.190203 -0.113982 0.03214997 -0.190409 -0.113618 0.03214997 -0.189763 -0.113979 0.03214997 -0.188986 -0.11577 0.03214997 -0.1926749 -0.116673 0.03214997 -0.192541 -0.117311 0.03214997 -0.193405 -0.117686 0.03214997 -0.196474 -0.114781 0.03214997 -0.193873 -0.115573 0.03214997 -0.195128 -0.116305 0.03214997 -0.193803 -0.117451 0.03214997 -0.195637 -0.113951 0.03214997 -0.19523 -0.10897 0.03214997 -0.194436 -0.10872 0.03214997 -0.193813 -0.10817 0.03214997 -0.193459 -0.106582 0.03214997 -0.198577 -0.106439 0.03214997 -0.197254 -0.107774 0.03214997 -0.19866 -0.108535 0.03214997 -0.197289 -0.107601 0.03214997 -0.198647 -0.10819 0.03214997 -0.193669 -0.106032 0.03214997 -0.195191 -0.104992 0.03214997 -0.1960189 -0.1050699 0.03214997 -0.196743 -0.105479 0.03214997 -0.197613 -0.105613 0.03214997 -0.191709 -0.101624 0.03214997 -0.1909919 -0.102047 0.03214997 -0.1901659 -0.102142 0.03214997 -0.188749 -0.101343 0.03214997 -0.192356 -0.100132 0.03214997 -0.190127 -0.09816437 0.03214997 -0.191142 -0.09701728 0.03214997 -0.192175 -0.09931987 0.03214997 -0.180928 -0.102865 0.03214997 -0.1799589 -0.101558 0.03214997 -0.177865 -0.100608 0.03214997 -0.183746 -0.101918 0.03214997 -0.185566 -0.105132 0.03214997 -0.1864629 -0.102908 0.03214997 -0.186615 -0.104821 0.03214997 -0.183264 -0.102596 0.03214997 -0.182548 -0.1030189 0.03214997 -0.182048 -0.104152 0.03214997 -0.182539 -0.10302 0.03214997 -0.1857179 -0.101169 0.03214997 -0.183781 -0.101745 0.03214997 -0.185475 -0.100976 0.03214997 -0.183911 -0.101103 0.03214997 -0.1853229 -0.100591 0.03214997 -0.1802819 -0.09996306 0.03214997 -0.180162 -0.100176 0.03214997 -0.179322 -0.09909957 0.03214997 -0.180076 -0.100327 0.03214997 -0.179951 -0.100726 0.03214997 -0.180894 -0.09940057 0.03214997 -0.182511 -0.09921467 0.03214997 -0.183977 -0.09970229 0.03214997 -0.175496 -0.105687 0.03214997 -0.176901 -0.107762 0.03214997 -0.176674 -0.1057299 0.03214997 -0.177514 -0.107199 0.03214997 -0.178341 -0.110912 0.03214997 -0.1754789 -0.109915 0.03214997 -0.176644 -0.108292 0.03214997 -0.175319 -0.107717 0.03214997 -0.176696 -0.108126 0.03214997 -0.180835 -0.1069509 0.03214997 -0.180344 -0.108083 0.03214997 -0.18035 -0.10809 0.03214997 -0.180366 -0.109717 0.03214997 -0.183266 -0.09708458 0.03214997 -0.181026 -0.09787535 0.03214997 -0.1805509 -0.09821677 0.03214997 -0.184507 -0.0985096 0.03214997 -0.185365 -0.100304 0.03214997 -0.18724 -0.101117 0.03214997 -0.186852 -0.100817 0.03214997 -0.186334 -0.09974998 0.03214997 -0.187062 -0.09829026 0.03214997 -0.1864359 -0.09976506 0.03214997 -0.188243 -0.09880208 0.03214997 -0.186912 -0.100408 0.03214997 -0.189248 -0.09648406 0.03214997 -0.18812 -0.0965262 0.03214997 -0.193917 -0.101093 0.03214997 -0.192785 -0.100771 0.03214997 -0.19453 -0.09930527 0.03214997 -0.193776 -0.09848409 0.03214997 -0.191781 -0.103085 0.03214997 -0.192191 -0.100947 0.03214997 -0.1933169 -0.102748 0.03214997 -0.193641 -0.103006 0.03214997 -0.192522 -0.10284 0.03214997 -0.194155 -0.102025 0.03214997 -0.194653 -0.102697 0.03214997 -0.196503 -0.103449 0.03214997 -0.194729 -0.1027989 0.03214997 -0.195369 -0.113251 0.03214997 -0.1944699 -0.112862 0.03214997 -0.1962479 -0.108761 0.03214997 -0.196772 -0.108452 0.03214997 -0.198239 -0.110171 0.03214997 -0.198454 -0.110213 0.03214997 -0.1894429 -0.11739 0.03214997 -0.190203 -0.117981 0.03214997 -0.188566 -0.115719 0.03214997 -0.18839 -0.117145 0.03214997 -0.188516 -0.117131 0.03214997 -0.188309 -0.116043 0.03214997 -0.187923 -0.116196 0.03214997 -0.187559 -0.117241 0.03214997 -0.187514 -0.116135 0.03214997 -0.186109 -0.118452 0.03214997 -0.187189 -0.115877 0.03214997 -0.184715 -0.119385 0.03214997 -0.185808 -0.119592 0.03214997 -0.182168 -0.112815 0.03214997 -0.183365 -0.113762 0.03214997 -0.185413 -0.114917 0.03214997 -0.18671 -0.114783 0.03214997 -0.187037 -0.115492 0.03214997 -0.184947 -0.117222 0.03214997 -0.184231 -0.117645 0.03214997 -0.183804 -0.119212 0.03214997 -0.183405 -0.11774 0.03214997 -0.18016 -0.117447 0.03214997 -0.1817589 -0.114953 0.03214997 -0.182577 -0.114027 0.03214997 -0.180049 -0.11738 0.03214997 -0.181042 -0.113213 0.03214997 -0.180633 -0.113152 0.03214997 -0.181703 -0.112613 0.03214997 -0.181685 -0.112736 0.03214997 -0.181427 -0.1130599 0.03214997 -0.180552 -0.1130869 0.03214997 -0.179221 -0.113101 0.03214997 -0.180308 -0.1128939 0.03214997 -0.178386 -0.1126 0.03214997 -0.179794 -0.113875 0.03214997 -0.179949 -0.114478 0.03214997 -0.180033 -0.114807 0.03214997 -0.179902 -0.115761 0.03214997 -0.1794199 -0.116595 0.03214997 -0.180217 -0.1121 0.03214997 -0.178906 -0.1114 0.03214997 -0.178398 -0.112602 0.03214997 -0.1801559 -0.112509 0.03214997 -0.177447 -0.112451 0.03214997 -0.176509 -0.112671 0.03214997 -0.180828 -0.105285 0.03214997 -0.1792989 -0.105058 0.03214997 -0.1786569 -0.102848 0.03214997 -0.179617 -0.104324 0.03214997 -0.180002 -0.104172 0.03214997 -0.18057 -0.1056089 0.03214997 -0.177368 -0.105447 0.03214997 -0.1797749 -0.105701 0.03214997 -0.179451 -0.105443 0.03214997 -0.177565 -0.105367 0.03214997 -0.178254 -0.104694 0.03214997 -0.178637 -0.103811 0.03214997 -0.187355 -0.114758 0.03214997 -0.187741 -0.114606 0.03214997 -0.1881499 -0.1146669 0.03214997 -0.188475 -0.114924 0.03214997 -0.188627 -0.115309 0.03214997 -0.188584 -0.1155959 0.03214997 -0.179167 -0.110817 0.03214997 -0.180294 -0.112002 0.03214997 -0.180474 -0.111775 0.03214997 -0.180859 -0.111623 0.03214997 -0.181167 -0.111669 0.03214997 -0.181269 -0.111684 0.03214997 -0.183941 -0.108725 0.03214997 -0.181683 -0.110476 0.03214997 -0.181593 -0.111941 0.03214997 -0.185202 -0.102361 0.03214997 -0.1858 -0.101233 0.03214997 -0.19309 -0.104277 0.03214997 -0.19006 -0.107625 0.03214997 -0.190008 -0.107175 0.03214997 -0.193733 -0.1037999 0.03214997 -0.1932809 -0.105863 0.03214997 -0.187098 -0.115083 0.03214997 -0.187175 -0.114985 0.03214997 -0.182945 -0.111023 0.03214997 -0.181746 -0.112326 0.03214997 -0.183831 -0.107761 0.03214997 -0.1828359 -0.107818 0.03214997 -0.184085 -0.106697 0.03214997 -0.184049 -0.105019 0.03214997 -0.195683 -0.110063 0.03214997 -0.194651 -0.110842 0.03214997 -0.19459 -0.1112509 0.03214997 -0.194333 -0.111576 0.03214997 -0.193765 -0.1101379 0.03214997 -0.194174 -0.110199 0.03214997 -0.194499 -0.110457 0.03214997 -0.193948 -0.111728 0.03214997 -0.193538 -0.111667 0.03214997 -0.19181 -0.11279 0.03214997 -0.1932139 -0.11141 0.03214997 -0.1930609 -0.111025 0.03214997 -0.193122 -0.110615 0.03214997 -0.1933799 -0.110291 0.03214997 -0.193733 -0.1037999 0.03344994 -0.193656 -0.103898 0.03214997 -0.193656 -0.103898 0.03344994 -0.193475 -0.104125 0.03214997 -0.19309 -0.104277 0.03344994 -0.192681 -0.104216 0.03214997 -0.192681 -0.104216 0.03344994 -0.192356 -0.103959 0.03214997 -0.1922039 -0.103574 0.03214997 -0.192265 -0.103164 0.03214997 -0.192908 -0.102687 0.03214997 -0.1933169 -0.102748 0.03344994 -0.193794 -0.103391 0.03214997 -0.186774 -0.100915 0.03344994 -0.1984069 -0.103208 0.03344994 -0.1750209 -0.111247 0.03344994 -0.174697 -0.109575 0.03344994 -0.182621 -0.09636467 0.03344994 -0.182995 -0.110908 0.03344994 -0.187119 -0.1138409 0.03344994 -0.189229 -0.114756 0.03344994 -0.187529 -0.1128939 0.03344994 -0.183565 -0.111607 0.03344994 -0.182577 -0.111872 0.03344994 -0.1816149 -0.107289 0.03344994 -0.180095 -0.110796 0.03344994 -0.182701 -0.105355 0.03344994 -0.182159 -0.106604 0.03344994 -0.189855 -0.103863 0.03344994 -0.191929 -0.108528 0.03344994 -0.191962 -0.1084499 0.03344994 -0.191929 -0.108435 0.03344994 -0.190962 -0.104974 0.03344994 -0.194038 -0.114758 0.03344994 -0.192638 -0.112869 0.03344994 -0.189972 -0.116198 0.03344994 -0.190432 -0.115969 0.03344994 -0.1918489 -0.116768 0.03344994 -0.1926749 -0.116673 0.03344994 -0.194362 -0.11791 0.03344994 -0.195075 -0.11729 0.03344994 -0.195807 -0.116654 0.03344994 -0.193873 -0.115573 0.03344994 -0.195369 -0.113251 0.03344994 -0.190086 -0.115212 0.03344994 -0.1902469 -0.115564 0.03344994 -0.191901 -0.111748 0.03344994 -0.190783 -0.111171 0.03344994 -0.191021 -0.113055 0.03344994 -0.190749 -0.111248 0.03344994 -0.193813 -0.10817 0.03344994 -0.194436 -0.10872 0.03344994 -0.1931149 -0.108949 0.03344994 -0.196582 -0.110453 0.03344994 -0.1972759 -0.11017 0.03344994 -0.197254 -0.107774 0.03344994 -0.193459 -0.106582 0.03344994 -0.194769 -0.1051329 0.03344994 -0.195044 -0.1044999 0.03344994 -0.199329 -0.107477 0.03344994 -0.197343 -0.106616 0.03344994 -0.197238 -0.106147 0.03344994 -0.196743 -0.105479 0.03344994 -0.1909919 -0.102047 0.03344994 -0.191709 -0.101624 0.03344994 -0.188395 -0.09975469 0.03344994 -0.188749 -0.101343 0.03344994 -0.189373 -0.101893 0.03344994 -0.1901659 -0.102142 0.03344994 -0.192191 -0.100947 0.03344994 -0.192785 -0.100771 0.03344994 -0.1922709 -0.100548 0.03344994 -0.1935999 -0.09746819 0.03344994 -0.192175 -0.09931987 0.03344994 -0.191679 -0.09865188 0.03344994 -0.189339 -0.09842908 0.03344994 -0.180928 -0.102865 0.03344994 -0.182828 -0.10449 0.03344994 -0.181722 -0.103114 0.03344994 -0.180305 -0.102314 0.03344994 -0.1799589 -0.101558 0.03344994 -0.1785809 -0.102649 0.03344994 -0.183911 -0.101103 0.03344994 -0.18373 -0.100291 0.03344994 -0.179951 -0.100726 0.03344994 -0.180832 -0.09945827 0.03344994 -0.178875 -0.0986101 0.03344994 -0.179588 -0.09799015 0.03344994 -0.179768 -0.09787738 0.03344994 -0.181408 -0.09858858 0.03344994 -0.181683 -0.09913575 0.03344994 -0.182511 -0.09921467 0.03344994 -0.18053 -0.108902 0.03344994 -0.18035 -0.10809 0.03344994 -0.180366 -0.109717 0.03344994 -0.179854 -0.107422 0.03344994 -0.17913 -0.107013 0.03344994 -0.178266 -0.105837 0.03344994 -0.176662 -0.109538 0.03344994 -0.179686 -0.111738 0.03344994 -0.178341 -0.110912 0.03344994 -0.176578 -0.109356 0.03344994 -0.176578 -0.109271 0.03344994 -0.174621 -0.108423 0.03344994 -0.178302 -0.106935 0.03344994 -0.177703 -0.107136 0.03344994 -0.174585 -0.107453 0.03344994 -0.176901 -0.107762 0.03344994 -0.175711 -0.105729 0.03344994 -0.176674 -0.1057299 0.03344994 -0.182316 -0.09649586 0.03344994 -0.1847569 -0.10004 0.03344994 -0.183235 -0.09962338 0.03344994 -0.183266 -0.09708458 0.03344994 -0.18121 -0.09697157 0.03344994 -0.178637 -0.103811 0.03344994 -0.176337 -0.110287 0.03344994 -0.177447 -0.112451 0.03344994 -0.178398 -0.112602 0.03344994 -0.179902 -0.115761 0.03344994 -0.1794199 -0.116595 0.03344994 -0.181427 -0.1130599 0.03344994 -0.181042 -0.113213 0.03344994 -0.180633 -0.113152 0.03344994 -0.180308 -0.1128939 0.03344994 -0.180033 -0.114807 0.03344994 -0.1801559 -0.112509 0.03344994 -0.179794 -0.113875 0.03344994 -0.179221 -0.113101 0.03344994 -0.179121 -0.113041 0.03344994 -0.185594 -0.115729 0.03344994 -0.18671 -0.114783 0.03344994 -0.185429 -0.116544 0.03344994 -0.182577 -0.114027 0.03344994 -0.1819649 -0.114589 0.03344994 -0.182043 -0.119327 0.03344994 -0.183853 -0.119951 0.03344994 -0.184426 -0.120053 0.03344994 -0.184231 -0.117645 0.03344994 -0.184193 -0.1138409 0.03344994 -0.183365 -0.113762 0.03344994 -0.182168 -0.112815 0.03344994 -0.187189 -0.115877 0.03344994 -0.187355 -0.114758 0.03344994 -0.187175 -0.114985 0.03344994 -0.187098 -0.115083 0.03344994 -0.187037 -0.115492 0.03344994 -0.188183 -0.117169 0.03344994 -0.187923 -0.116196 0.03344994 -0.188309 -0.116043 0.03344994 -0.187559 -0.117241 0.03344994 -0.186715 -0.117704 0.03344994 -0.187514 -0.116135 0.03344994 -0.186109 -0.118452 0.03344994 -0.185739 -0.120288 0.03344994 -0.188516 -0.117131 0.03344994 -0.1894429 -0.11739 0.03344994 -0.1894519 -0.117398 0.03344994 -0.190684 -0.118815 0.03344994 -0.194499 -0.110457 0.03344994 -0.193122 -0.110615 0.03344994 -0.1930609 -0.111025 0.03344994 -0.194174 -0.110199 0.03344994 -0.193765 -0.1101379 0.03344994 -0.1933799 -0.110291 0.03344994 -0.194651 -0.110842 0.03344994 -0.19459 -0.1112509 0.03344994 -0.194333 -0.111576 0.03344994 -0.1932139 -0.11141 0.03344994 -0.193538 -0.111667 0.03344994 -0.193948 -0.111728 0.03344994 -0.195313 -0.112089 0.03344994 -0.195564 -0.1033 0.03344994 -0.19744 -0.103229 0.03344994 -0.1945289 -0.102529 0.03344994 -0.193892 -0.104 0.03344994 -0.192265 -0.103164 0.03344994 -0.191781 -0.103085 0.03344994 -0.192522 -0.10284 0.03344994 -0.192908 -0.102687 0.03344994 -0.193794 -0.103391 0.03344994 -0.194155 -0.102025 0.03344994 -0.193641 -0.103006 0.03344994 -0.193917 -0.101093 0.03344994 -0.194048 -0.100139 0.03344994 -0.19453 -0.09930527 0.03344994 -0.194066 -0.09781569 0.03344994 -0.1951349 -0.09861338 0.03344994 -0.187062 -0.09829026 0.03344994 -0.18812 -0.0965262 0.03344994 -0.188211 -0.09561181 0.03344994 -0.186852 -0.100817 0.03344994 -0.188243 -0.09880208 0.03344994 -0.188719 -0.09900838 0.03344994 -0.184507 -0.0985096 0.03344994 -0.18882 -0.115698 0.03344994 -0.188566 -0.115719 0.03344994 -0.188584 -0.1155959 0.03344994 -0.187741 -0.114606 0.03344994 -0.1881499 -0.1146669 0.03344994 -0.188475 -0.114924 0.03344994 -0.188627 -0.115309 0.03344994 -0.181746 -0.112326 0.03344994 -0.181593 -0.111941 0.03344994 -0.181269 -0.111684 0.03344994 -0.182161 -0.109302 0.03344994 -0.180859 -0.111623 0.03344994 -0.180474 -0.111775 0.03344994 -0.180294 -0.112002 0.03344994 -0.180217 -0.1121 0.03344994 -0.1858 -0.101233 0.03344994 -0.185384 -0.100181 0.03344994 -0.184349 -0.100983 0.03344994 -0.1868309 -0.102059 0.03344994 -0.192247 -0.103287 0.03344994 -0.1922039 -0.103574 0.03344994 -0.1934829 -0.104943 0.03344994 -0.193475 -0.104125 0.03344994 -0.192356 -0.103959 0.03344994 -0.181685 -0.112736 0.03344994 -0.181703 -0.112613 0.03344994 -0.179617 -0.104324 0.03344994 -0.179479 -0.103038 0.03344994 -0.180002 -0.104172 0.03344994 -0.186209 -0.101294 0.03344994 -0.18724 -0.101117 0.03344994 -0.191373 -0.104028 0.03344994 -0.188646 -0.103238 0.03444999 -0.185954 -0.103055 0.03444999 -0.190851 -0.1047919 0.03444999 -0.189855 -0.103863 0.03444999 -0.1886529 -0.11266 0.03444999 -0.182307 -0.109741 0.03444999 -0.182705 -0.1105509 0.03444999 -0.183565 -0.111607 0.03444999 -0.184678 -0.112391 0.03444999 -0.189449 -0.112295 0.03744995 -0.1916429 -0.106159 0.03744995 -0.191837 -0.1067849 0.03744995 -0.191889 -0.10727 0.03744995 -0.19178 -0.109333 0.03744995 -0.191299 -0.109195 0.03794997 -0.1892009 -0.111861 0.03794997 -0.185772 -0.103614 0.03794997 -0.1847479 -0.104039 0.03794997 -0.182599 -0.108998 0.03794997 -0.181976 -0.107837 0.03744995 -0.183475 -0.1043789 0.03744995 -0.183568 -0.104309 0.03744995 -0.1845009 -0.103605 0.03744995 -0.188178 -0.112286 0.03794997 -0.182307 -0.109741 0.03744995 -0.182988 -0.110036 0.03794997 -0.182476 -0.107848 0.03794997 -0.18265 -0.106705 0.03794997 -0.190124 -0.111164 0.03794997 -0.1831099 -0.105645 0.03794997 -0.185781 -0.107041 0.03794997 -0.183825 -0.104736 0.03794997 -0.18634 -0.106591 0.03794997 -0.190962 -0.105864 0.03794997 -0.1877329 -0.106656 0.03794997 -0.1913509 -0.106902 0.03794997 -0.191474 -0.108052 0.03794997 -0.188351 -0.108547 0.03794997 -0.1908389 -0.110255 0.03794997 -0.1916429 -0.106159 0.03444999 -0.191928 -0.107266 0.03344994 -0.185091 -0.103319 0.03444999 -0.185091 -0.103319 0.03744995 -0.184671 -0.103512 0.03344994 -0.185954 -0.103055 0.03344994 -0.186413 -0.103024 0.03344994 -0.187313 -0.102961 0.03344994 -0.187313 -0.102961 0.03444999 -0.188646 -0.103238 0.03344994 -0.190851 -0.1047919 0.03344994 -0.19156 -0.105955 0.03444999 -0.19156 -0.105955 0.03344994 -0.188859 -0.112581 0.03444999 -0.1898609 -0.112033 0.03344994 -0.1886529 -0.11266 0.03344994 -0.1873199 -0.112938 0.03344994 -0.185961 -0.112846 0.03344994 -0.1873199 -0.112938 0.03444999 -0.185961 -0.112846 0.03444999 -0.184678 -0.112391 0.03344994 -0.182705 -0.1105509 0.03344994 -0.190856 -0.1111029 0.03344994 -0.191138 -0.110718 0.0348162 -0.191775 -0.10935 0.03461748 -0.191884 -0.108898 0.03507494 -0.1915619 -0.109939 0.03444999 -0.1915619 -0.109939 0.03344994 -0.191907 -0.108772 0.03602379 -0.191888 -0.108621 0.03744995 -0.191524 -0.109922 0.03744995 -0.1915619 -0.109939 0.03694999 -0.191269 -0.110512 0.03744995 -0.191424 -0.110232 0.03690719 -0.191278 -0.1104969 0.0367825 -0.191929 -0.108627 0.03344994 -0.191974 -0.108063 0.03744995 -0.184675 -0.10352 0.03744995 -0.18356 -0.104298 0.03344994 -0.183254 -0.104675 0.03344994 -0.182705 -0.105358 0.03744995 -0.182681 -0.105388 0.03744995 -0.18217 -0.106567 0.03744995 -0.182164 -0.106605 0.03744995 -0.182041 -0.107473 0.03344994 -0.181988 -0.1079519 0.03744995 -0.181975 -0.107954 0.03344994 -0.182112 -0.109115 0.03744995 -0.18217 -0.1093 0.03744995 -0.188859 -0.112581 0.03744995 -0.1898379 -0.112002 0.03744995 -0.190716 -0.111234 0.03344994 -0.190474 -0.111521 0.03744995 -0.190824 -0.111077 0.03744995 -0.191907 -0.108772 0.03537625 -0.187497 -0.109356 0.03632497 -0.191278 -0.1104969 0.03461748 -0.187973 -0.109059 0.03462725 -0.188187 -0.108834 0.03449416 -0.191424 -0.110232 0.03449255 -0.188351 -0.108547 0.03444999 -0.187362 -0.109399 0.03527617 -0.190946 -0.110987 0.03537559 -0.1910229 -0.110885 0.03507494 -0.187497 -0.109356 0.03507494 -0.187238 -0.109427 0.03569996 -0.190946 -0.110988 0.03602397 -0.1909199 -0.111022 0.03569996 -0.1910229 -0.110885 0.03632497 -0.187912 -0.109112 0.03672796 -0.191139 -0.110718 0.03658407 -0.187977 -0.109066 0.0367825 -0.188187 -0.108834 0.03690576 -0.188471 -0.107839 0.03673756 -0.188466 -0.10792 0.03677266 -0.191842 -0.109097 0.03658396 -0.191775 -0.10935 0.0367825 -0.191682 -0.109637 0.03690719 -0.188351 -0.108547 0.03694999 -0.188297 -0.107241 0.03612387 -0.188358 -0.10737 0.03632497 -0.191884 -0.108898 0.03632497 -0.1884289 -0.107583 0.03655177 -0.191914 -0.108729 0.03569996 -0.191682 -0.109637 0.03449285 -0.188449 -0.108229 0.0344944 -0.191842 -0.109096 0.03481608 -0.188475 -0.107919 0.03461748 -0.188464 -0.10784 0.03467196 -0.1884289 -0.1075839 0.03484797 -0.188358 -0.10737 0.03507494 -0.188248 -0.107156 0.03794997 -0.188248 -0.107156 0.03589636 -0.188233 -0.107133 0.03569996 -0.187916 -0.109118 0.03794997 -0.188471 -0.107839 0.03794997 -0.188449 -0.1082299 0.03690576 -0.187702 -0.109262 0.03655189 -0.186549 -0.109388 0.03794997 -0.1872659 -0.109422 0.03794997 -0.1872659 -0.109422 0.03589636 -0.187361 -0.109399 0.03612339 -0.1872659 -0.109422 0.03550356 -0.187916 -0.109118 0.03466236 -0.1872659 -0.109422 0.03014999 -0.187702 -0.109262 0.03484815 -0.188471 -0.107839 0.03014999 -0.188351 -0.108547 0.03014999 -0.187916 -0.109118 0.03014999 -0.186549 -0.109388 0.03014999 -0.185929 -0.109025 0.03794997 -0.185929 -0.109025 0.03014999 -0.185549 -0.108416 0.03794997 -0.185549 -0.108416 0.03014999 -0.185496 -0.1077 0.03014999 -0.185496 -0.1077 0.03794997 -0.185599 -0.107353 0.03014999 -0.185781 -0.107041 0.03014999 -0.18634 -0.106591 0.03014999 -0.187045 -0.106452 0.03794997 -0.187045 -0.106452 0.03014999 -0.1877329 -0.106656 0.03014999 -0.188248 -0.107156 0.03550356 -0.188248 -0.107156 0.03014999 -0.188297 -0.107241 0.03527665 -0.175306 -0.100398 0.02239996 -0.1742219 -0.102421 0.03024995 -0.176708 -0.09857988 0.02239996 -0.17839 -0.09701776 0.02239996 -0.17839 -0.09701776 0.03024995 -0.180307 -0.0957539 0.02239996 -0.1824049 -0.0948227 0.02239996 -0.1824049 -0.0948227 0.03024995 -0.186915 -0.0940501 0.02239996 -0.189204 -0.09422987 0.03024995 -0.193538 -0.09569686 0.03024995 -0.197161 -0.09849178 0.02239996 -0.195465 -0.09694427 0.03024995 -0.197161 -0.09849178 0.03024995 -0.198579 -0.100297 0.02239996 -0.19968 -0.102312 0.02239996 -0.200435 -0.10448 0.02239996 -0.200435 -0.10448 0.03024995 -0.2008219 -0.106743 0.02239996 -0.200832 -0.109038 0.03024995 -0.200464 -0.111304 0.03024995 -0.199728 -0.113479 0.02239996 -0.199728 -0.113479 0.03024995 -0.19556 -0.118882 0.02239996 -0.19556 -0.118882 0.03024995 -0.191545 -0.121077 0.02239996 -0.1893219 -0.12165 0.02239996 -0.191545 -0.121077 0.03024995 -0.187035 -0.12185 0.02239996 -0.1893219 -0.12165 0.03024995 -0.187035 -0.12185 0.03024995 -0.184746 -0.12167 0.02239996 -0.182518 -0.121116 0.02239996 -0.182518 -0.121116 0.03024995 -0.176789 -0.117408 0.02239996 -0.175371 -0.115603 0.03024995 -0.17427 -0.113588 0.03024995 -0.173515 -0.11142 0.03024995 -0.1731269 -0.109157 0.02239996 -0.1731179 -0.106862 0.03024995 -0.1734859 -0.104596 0.02239996 -0.1734859 -0.104596 0.03024995 -0.1742219 -0.102421 0.02239996 -0.1748639 -0.1026999 0.03024995 -0.174151 -0.104822 0.03024995 -0.173807 -0.107034 0.03024995 -0.1738409 -0.109273 0.03024995 -0.174254 -0.111473 0.03024995 -0.175032 -0.113573 0.02239996 -0.175032 -0.113573 0.03024995 -0.176154 -0.11551 0.03024995 -0.177588 -0.1172299 0.03024995 -0.179291 -0.118683 0.03024995 -0.181215 -0.119827 0.03024995 -0.183305 -0.12063 0.03024995 -0.185501 -0.121067 0.03024995 -0.187739 -0.121128 0.03024995 -0.1899549 -0.120809 0.02239996 -0.1899549 -0.120809 0.03024995 -0.192086 -0.12012 0.03024995 -0.192086 -0.12012 0.02239996 -0.194069 -0.119082 0.03024995 -0.195848 -0.117723 0.03024995 -0.197372 -0.116083 0.02239996 -0.197372 -0.116083 0.03024995 -0.198597 -0.114208 0.03024995 -0.199487 -0.112154 0.02239996 -0.199487 -0.112154 0.03024995 -0.200018 -0.109979 0.03024995 -0.200173 -0.107746 0.02239996 -0.200173 -0.107746 0.03024995 -0.199949 -0.105518 0.03024995 -0.199351 -0.1033599 0.02239996 -0.199351 -0.1033599 0.03024995 -0.1983979 -0.101335 0.03024995 -0.197115 -0.09949946 0.02239996 -0.197115 -0.09949946 0.03024995 -0.195541 -0.0979073 0.02239996 -0.195541 -0.0979073 0.03024995 -0.1937209 -0.09660398 0.02239996 -0.191706 -0.09562718 0.02239996 -0.1937209 -0.09660398 0.03024995 -0.191706 -0.09562718 0.03024995 -0.189556 -0.09500479 0.03024995 -0.187331 -0.09475475 0.02239996 -0.187331 -0.09475475 0.03024995 -0.185096 -0.09488439 0.03024995 -0.185096 -0.09488439 0.02239996 -0.182915 -0.0953899 0.02239996 -0.182915 -0.0953899 0.03024995 -0.18085 -0.09625679 0.03024995 -0.177305 -0.09896498 0.02239996 -0.1789619 -0.09745997 0.03024995 -0.177305 -0.09896498 0.03024995 -0.175925 -0.100728 0.02239996 -0.175925 -0.100728 0.03024995 -0.197242 -0.11732 0.02239996 -0.198597 -0.114208 0.02239996 -0.198644 -0.1155019 0.02239996 -0.200464 -0.111304 0.02239996 -0.200018 -0.109979 0.02239996 -0.200832 -0.109038 0.02239996 -0.199949 -0.105518 0.02239996 -0.1983979 -0.101335 0.02239996 -0.195465 -0.09694427 0.02239996 -0.193538 -0.09569686 0.02239996 -0.1914319 -0.09478378 0.02239996 -0.189556 -0.09500479 0.02239996 -0.189204 -0.09422987 0.02239996 -0.184628 -0.0942496 0.02239996 -0.18085 -0.09625679 0.02239996 -0.1789619 -0.09745997 0.02239996 -0.1748639 -0.1026999 0.02239996 -0.174151 -0.104822 0.02239996 -0.173807 -0.107034 0.02239996 -0.1738409 -0.109273 0.02239996 -0.1731179 -0.106862 0.02239996 -0.174254 -0.111473 0.02239996 -0.173515 -0.11142 0.02239996 -0.17427 -0.113588 0.02239996 -0.176154 -0.11551 0.02239996 -0.175371 -0.115603 0.02239996 -0.177588 -0.1172299 0.02239996 -0.179291 -0.118683 0.02239996 -0.178485 -0.118956 0.02239996 -0.1804119 -0.120203 0.02239996 -0.181215 -0.119827 0.02239996 -0.183305 -0.12063 0.02239996 -0.185501 -0.121067 0.02239996 -0.187739 -0.121128 0.02239996 -0.193643 -0.120146 0.02239996 -0.194069 -0.119082 0.02239996 -0.195848 -0.117723 0.02239996 -0.003092706 -0.2120029 0.02039998 0.003092706 -0.219797 0.02324998 0.003092706 -0.219797 0.02039998 0.003420591 -0.219512 0.02039998 0.003896832 -0.2128069 0.02039998 0.003896832 -0.2128069 0.02324998 -0.002224683 -0.22035 0.02324998 -0.001418173 -0.220669 0.02324998 -5.6858e-4 -0.220842 0.02324998 2.98297e-4 -0.220866 0.02324998 0.001156091 -0.220739 0.02324998 0.001978754 -0.220465 0.02324998 0.002741336 -0.220052 0.02824997 0.002741336 -0.220052 0.02324998 -0.004151523 -0.218641 0.02039998 -0.003896832 -0.218993 0.02039998 -0.003896832 -0.218993 0.02324998 -0.003092706 -0.2120029 0.02324998 0.002963602 -0.211904 0.02324998 0.002224683 -0.21145 0.02824997 0.002224683 -0.21145 0.02324998 0.001418173 -0.211131 0.02324998 5.6858e-4 -0.210958 0.02324998 5.6858e-4 -0.210958 0.02824997 -2.98297e-4 -0.210934 0.02324998 -0.001156091 -0.211061 0.02324998 -2.98297e-4 -0.210934 0.02824997 -0.001978754 -0.211335 0.02324998 -0.002741336 -0.211748 0.02324998 -0.003420591 -0.212288 0.02039998 -0.003420591 -0.212288 0.02824997 -0.003995954 -0.212936 0.02039998 -0.004449844 -0.213675 0.02039998 -0.004449844 -0.213675 0.02824997 -0.00476855 -0.214482 0.02039998 -0.004942357 -0.215331 0.02824997 -0.004942357 -0.215331 0.02039998 -0.00496602 -0.216198 0.02039998 -0.004838764 -0.217056 0.02039998 -0.00496602 -0.216198 0.02824997 -0.004838764 -0.217056 0.02824997 -0.004564523 -0.2178789 0.02039998 -0.004564523 -0.2178789 0.02824997 -0.003612458 -0.219321 0.02324998 -0.003612458 -0.219321 0.02824997 -0.002963602 -0.219896 0.02324998 0.003995954 -0.218864 0.02039998 0.004449844 -0.218125 0.02039998 0.00476855 -0.2173179 0.02039998 0.004449844 -0.218125 0.02824997 0.004942357 -0.216469 0.02039998 0.004942357 -0.216469 0.02824997 0.00496602 -0.215602 0.02039998 0.00496602 -0.215602 0.02824997 0.004838764 -0.214744 0.02039998 0.004564523 -0.213921 0.02039998 0.004151523 -0.213159 0.02039998 0.003612458 -0.2124789 0.02324998 -0.004545032 -0.216609 0.02824997 -0.004345357 -0.217409 0.02824997 -0.004006087 -0.218161 0.02824997 -0.004151523 -0.218641 0.02824997 -0.003538012 -0.21884 0.02824997 -0.002963602 -0.219896 0.02824997 -0.002956271 -0.219424 0.02824997 -0.00227946 -0.219895 0.02824997 -0.001529395 -0.220238 0.02824997 -0.002224683 -0.22035 0.02824997 -0.001418173 -0.220669 0.02824997 -5.6858e-4 -0.220842 0.02824997 -7.30219e-4 -0.2204419 0.02824997 9.24629e-5 -0.220499 0.02824997 9.12173e-4 -0.220409 0.02824997 2.98297e-4 -0.220866 0.02824997 0.001156091 -0.220739 0.02824997 0.001702547 -0.220173 0.02824997 0.001978754 -0.220465 0.02824997 0.002438187 -0.219801 0.02824997 0.003095507 -0.219303 0.02824997 0.003420591 -0.219512 0.02824997 0.003653347 -0.218695 0.02824997 0.004093706 -0.217998 0.02824997 0.003995954 -0.218864 0.02824997 0.004402518 -0.217233 0.02824997 0.00476855 -0.2173179 0.02824997 0.004569828 -0.216426 0.02824997 0.004590272 -0.215601 0.02824997 0.004463136 -0.2147859 0.02824997 0.004838764 -0.214744 0.02824997 0.004564523 -0.213921 0.02824997 0.00419259 -0.214007 0.02824997 0.003787279 -0.213289 0.02824997 0.004151523 -0.213159 0.02824997 0.003612458 -0.2124789 0.02824997 0.003260254 -0.212655 0.02824997 0.002628445 -0.212125 0.02824997 0.001912117 -0.2117159 0.02824997 0.002963602 -0.211904 0.02824997 0.001134335 -0.2114419 0.02824997 3.20167e-4 -0.211311 0.02824997 0.001418173 -0.211131 0.02824997 -5.04348e-4 -0.211328 0.02824997 -0.001312613 -0.211491 0.02824997 -0.001156091 -0.211061 0.02824997 -0.002078711 -0.211796 0.02824997 -0.001978754 -0.211335 0.02824997 -0.002778053 -0.212234 0.02824997 -0.002741336 -0.211748 0.02824997 -0.003388047 -0.2127889 0.02824997 -0.003889143 -0.2134439 0.02824997 -0.003995954 -0.212936 0.02824997 -0.004265308 -0.214177 0.02824997 -0.004504323 -0.214967 0.02824997 -0.00476855 -0.214482 0.02824997 -0.004598557 -0.215786 0.02824997 6.70663e-5 -0.20273 0.02109998 -0.001752793 -0.202847 0.02109998 -0.004425585 -0.202916 0.02109998 -0.003877401 -0.2033129 0.02109998 -0.00645101 -0.203794 0.02109998 -0.009400725 -0.206676 0.02109998 0.01265799 -0.219538 0.02109998 0.01285618 -0.220683 0.02109998 0.01370924 -0.2163659 0.02109998 0.01315349 -0.215231 0.02109998 0.01317477 -0.212081 0.02109998 -0.003997504 -0.21604 0.01739996 -0.003343403 -0.225849 0.01739996 -0.002826929 -0.226633 0.01739996 -0.005521655 -0.219869 0.01739996 -0.006409108 -0.222115 0.01739996 -0.006490707 -0.224904 0.01739996 -0.00802499 -0.223568 0.01739996 -0.007010877 -0.221877 0.01739996 -0.007413148 -0.22137 0.01739996 -0.009289622 -0.221974 0.01739996 -0.007508099 -0.22073 0.01739996 -0.01044809 -0.216897 0.01739996 -0.01109474 -0.216216 0.01739996 -0.005262255 -0.2216179 0.01739996 -2.8714e-4 -0.222505 0.01739996 -0.001220166 -0.222398 0.01739996 -0.009595632 -0.2172909 0.01739996 -0.007270276 -0.220129 0.01739996 -0.01085078 -0.218236 0.01739996 -0.01024216 -0.2201769 0.01739996 -0.01073318 -0.213073 0.01739996 -0.010037 -0.211162 0.01739996 -0.002126991 -0.222642 0.01739996 -0.005769073 -0.22202 0.01739996 -0.002879559 -0.223204 0.01739996 -0.003371715 -0.224004 0.01739996 -0.00473845 -0.225937 0.01739996 -0.003533959 -0.224929 0.01739996 -0.007767081 -0.217046 0.01739996 -0.008657872 -0.217343 0.01739996 -0.006123423 -0.219631 0.01739996 -0.006763458 -0.219726 0.01739996 -0.007048964 -0.21644 0.01739996 -0.006604909 -0.215613 0.01739996 -0.003861248 -0.214856 0.01739996 -0.003381907 -0.213764 0.01739996 -0.006497561 -0.21468 0.01739996 0.001391351 -0.2254959 0.01739996 0.003007054 -0.22654 0.01739996 9.96971e-4 -0.226348 0.01739996 0.002335488 -0.226751 0.01739996 3.1586e-4 -0.226995 0.01739996 -0.003778576 -0.217212 0.01739996 -0.005119383 -0.220376 0.01739996 -0.003223896 -0.218268 0.01739996 -0.005024433 -0.221016 0.01739996 -0.002382755 -0.2191129 0.01739996 -0.001329898 -0.219672 0.01739996 -1.5891e-4 -0.219897 0.01739996 0.001026213 -0.219766 0.01739996 0.003931939 -0.215166 0.01739996 0.003540813 -0.214039 0.01739996 0.003973782 -0.2163569 0.01739996 0.002834975 -0.213078 0.01739996 0.001877307 -0.212368 0.01739996 7.52833e-4 -0.211971 0.01739996 -0.00994873 -0.212557 0.01739996 -0.00902903 -0.212366 0.01739996 -0.008103966 -0.212528 0.01739996 -0.009679377 -0.210555 0.01739996 -4.38564e-4 -0.211924 0.01739996 -0.007304012 -0.21302 0.01739996 -0.001590967 -0.21223 0.01739996 -0.006742119 -0.213773 0.01739996 -0.00260204 -0.212862 0.01739996 0.002120196 -0.219292 0.01739996 0.00302577 -0.2185159 0.01739996 5.40463e-4 -0.222949 0.01739996 0.003662467 -0.217508 0.01739996 0.00114578 -0.223667 0.01739996 0.001443445 -0.2245579 0.01739996 0.004663944 -0.2231979 0.01739996 0.005161106 -0.224345 0.01739996 0.004276633 -0.226142 0.01739996 0.00607419 -0.22519 0.01739996 0.005762875 -0.224583 0.01739996 0.0070526 -0.222844 0.01739996 0.00900352 -0.222391 0.01739996 0.007667601 -0.2239249 0.01739996 0.006909728 -0.224086 0.01739996 0.006402909 -0.224488 0.01739996 0.01085078 -0.213565 0.01739996 0.01109474 -0.215584 0.01739996 0.01044809 -0.2149029 0.01739996 0.00994873 -0.219243 0.01739996 0.010037 -0.220638 0.01739996 0.01073318 -0.2187269 0.01739996 0.006650388 -0.222337 0.01739996 0.007304012 -0.21878 0.01739996 0.008103966 -0.219272 0.01739996 0.00902903 -0.219434 0.01739996 0.008657872 -0.214457 0.01739996 0.007767081 -0.214754 0.01739996 0.007048964 -0.21536 0.01739996 0.006604909 -0.216187 0.01739996 0.004901707 -0.222597 0.01739996 0.005408585 -0.222194 0.01739996 0.006497561 -0.2171199 0.01739996 0.006742119 -0.2180269 0.01739996 0.005262255 -0.210182 0.01739996 0.005024433 -0.210784 0.01739996 0.005119383 -0.2114239 0.01739996 0.005521655 -0.211931 0.01739996 0.006123423 -0.212169 0.01739996 0.0106402 -0.212893 0.01739996 0.009595632 -0.214509 0.01739996 0.006763458 -0.212074 0.01739996 0.007270276 -0.2116709 0.01739996 0.01024216 -0.211623 0.01739996 0.007508099 -0.21107 0.01739996 0.009289622 -0.2098259 0.01739996 0.00802499 -0.208232 0.01739996 0.007413148 -0.21043 0.01739996 0.007010877 -0.209923 0.01739996 0.006490707 -0.206896 0.01739996 0.006409108 -0.209685 0.01739996 0.005769073 -0.20978 0.01739996 0.005344629 -0.206221 0.01739996 -0.005408585 -0.209606 0.01739996 -0.006402909 -0.207312 0.01739996 0.004656255 -0.2122049 0.01739996 -0.006048619 -0.209701 0.01739996 -0.006909728 -0.207714 0.01739996 -0.007667601 -0.207875 0.01739996 -0.00714755 -0.208316 0.01739996 -0.00900352 -0.2094089 0.01739996 -0.0070526 -0.208956 0.01739996 -0.006650388 -0.209463 0.01739996 0.002126991 -0.209158 0.01739996 -9.96971e-4 -0.205452 0.01739996 -0.002335488 -0.205049 0.01739996 -3.1586e-4 -0.204805 0.01739996 0.001220166 -0.209402 0.01739996 2.8714e-4 -0.209295 0.01739996 -0.004901707 -0.209203 0.01739996 -5.40463e-4 -0.208851 0.01739996 -0.005762875 -0.207217 0.01739996 -0.005161106 -0.207455 0.01739996 -0.00607419 -0.20661 0.01739996 -0.004276633 -0.205658 0.01739996 -0.00114578 -0.208133 0.01739996 -0.004663944 -0.208602 0.01739996 -0.001443445 -0.207242 0.01739996 -0.004758894 -0.207962 0.01739996 -0.001391351 -0.206304 0.01739996 0.002879559 -0.208596 0.01739996 0.003371715 -0.207796 0.01739996 0.003533959 -0.206871 0.01739996 0.00473845 -0.2058629 0.01739996 0.003343403 -0.205951 0.01739996 0.002826929 -0.2051669 0.01739996 0.004758894 -0.223838 0.01739996 0.004748582 -0.222984 0.01889997 0.004758894 -0.223838 0.01889997 0.006048619 -0.222099 0.01739996 0.005820751 -0.222133 0.01889997 0.005408585 -0.222194 0.01889997 0.00714755 -0.223484 0.01889997 0.00714755 -0.223484 0.01739996 0.007302403 -0.209254 0.01889997 0.006143867 -0.205363 0.01889997 0.004280745 -0.2089059 0.01889997 -8.01933e-5 -0.203157 0.01889997 -0.002029657 -0.203326 0.01889997 0.003209829 -0.210317 0.01889997 0.005664229 -0.209863 0.01889997 0.006650388 -0.222337 0.01889997 0.01030755 -0.222421 0.01889997 0.0070526 -0.222844 0.01889997 0.005888164 -0.221547 0.01889997 0.006048619 -0.222099 0.01889997 0.007113754 -0.223256 0.01889997 0.006909728 -0.224086 0.01889997 0.006402909 -0.224488 0.01889997 0.005460381 -0.226806 0.01889997 0.005762875 -0.224583 0.01889997 0.005548655 -0.224498 0.01889997 0.004663944 -0.2231979 0.01889997 0.004340529 -0.221369 0.01889997 0.004901707 -0.222597 0.01889997 0.005769073 -0.20978 0.01889997 0.006409108 -0.209685 0.01889997 0.007010877 -0.209923 0.01889997 0.004047036 -0.210938 0.01889997 0.005119383 -0.2114239 0.01889997 0.005024433 -0.210784 0.01889997 0.004173099 -0.209842 0.01889997 0.01095116 -0.210622 0.01889997 0.007413148 -0.21043 0.01889997 0.007508099 -0.21107 0.01889997 0.01151895 -0.21189 0.01889997 0.007270276 -0.2116709 0.01889997 0.006999552 -0.211886 0.01889997 0.004410862 -0.211208 0.01889997 0.005438387 -0.211826 0.01889997 0.005374073 -0.212351 0.01889997 0.005377233 -0.2123579 0.01889997 0.005521655 -0.211931 0.01889997 -0.006999552 -0.219914 0.01889997 -0.006847083 -0.218589 0.01889997 -0.006763458 -0.219726 0.01889997 -0.006123423 -0.219631 0.01889997 -0.005521655 -0.219869 0.01889997 -0.005749702 -0.218801 0.01889997 -0.004925787 -0.220049 0.01889997 -0.005202651 -0.220271 0.01889997 -0.004617214 -0.220339 0.01889997 -0.004048287 -0.2208729 0.01889997 -0.005119383 -0.220376 0.01889997 -0.005024433 -0.221016 0.01889997 -0.007508099 -0.22073 0.01889997 -0.007413148 -0.22137 0.01889997 -0.007010877 -0.221877 0.01889997 -0.005262255 -0.2216179 0.01889997 -0.005498349 -0.221805 0.01889997 -0.005769073 -0.22202 0.01889997 -0.004921197 -0.2276549 0.01889997 -0.006409108 -0.222115 0.01889997 -0.006778001 -0.216029 0.01889997 -0.006507039 -0.215151 0.01889997 -0.007347762 -0.21675 0.01889997 -0.007165431 -0.220045 0.01889997 -0.007270276 -0.220129 0.01889997 -0.009395539 -0.212399 0.01889997 -0.008477032 -0.212419 0.01889997 -0.007627844 -0.21277 0.01889997 -0.00699377 -0.211619 0.01889997 -0.007175683 -0.213201 0.01889997 -0.006962776 -0.2134039 0.01889997 -0.006571531 -0.214235 0.01889997 -0.007601141 -0.216899 0.01889997 -0.008139371 -0.217216 0.01889997 -0.0112527 -0.21593 0.01889997 -0.01071536 -0.216675 0.01889997 -0.01149529 -0.211932 0.01889997 -0.01095187 -0.213315 0.01889997 -0.01137948 -0.214128 0.01889997 0.006047606 -0.213686 0.01889997 0.00574398 -0.2130849 0.01889997 0.006763458 -0.212074 0.01889997 0.006123423 -0.212169 0.01889997 0.006055593 -0.218092 0.01889997 0.006397783 -0.216636 0.01889997 0.006395041 -0.2151409 0.01889997 0.006847083 -0.2132109 0.01889997 -0.00256145 -0.209991 0.01889997 -0.001129806 -0.20956 0.01889997 3.62767e-4 -0.20947 0.01889997 0.001835763 -0.209727 0.01889997 -0.006263673 -0.217397 0.01889997 -0.005782544 -0.218711 0.01889997 -0.006439983 -0.215912 0.01889997 -0.006269097 -0.214426 0.01889997 -0.005760192 -0.21302 0.01889997 -0.0049932 -0.211849 0.01889997 0.001858174 -0.222066 0.01889997 3.86138e-4 -0.222328 0.01889997 -0.001106739 -0.222244 0.01889997 -0.002539992 -0.221818 0.01889997 -0.003836274 -0.221073 0.01889997 0.003496825 -0.221272 0.01889997 0.00416249 -0.222917 0.01889997 0.003230094 -0.221471 0.01889997 0.002814531 -0.221652 0.01889997 0.005386948 -0.219429 0.01889997 0.004954576 -0.219946 0.01889997 0.00443238 -0.220571 0.01889997 0.00442785 -0.220576 0.01889997 -0.004940807 -0.211769 0.01889997 -0.003855049 -0.210741 0.01889997 -0.00281322 -0.210137 0.01889997 -0.004748582 -0.208816 0.01889997 -0.004663944 -0.208602 0.01889997 -0.005161106 -0.207455 0.01889997 -0.004842102 -0.207857 0.01889997 -0.002580761 -0.208117 0.01889997 -0.004758894 -0.207962 0.01889997 -0.009429872 -0.207329 0.01889997 -0.01025938 -0.212712 0.01889997 -0.01119339 -0.211136 0.01889997 -0.006909728 -0.207714 0.01889997 -0.00714755 -0.208316 0.01889997 -0.009232044 -0.207929 0.01889997 -0.007113754 -0.208544 0.01889997 -0.009497106 -0.20827 0.01889997 -0.0070526 -0.208956 0.01889997 -0.004901707 -0.209203 0.01889997 -0.005408585 -0.209606 0.01889997 -0.005820751 -0.209667 0.01889997 -0.006057739 -0.211727 0.01889997 -0.006048619 -0.209701 0.01889997 -0.006650388 -0.209463 0.01889997 -0.006733596 -0.209358 0.01889997 -0.001227676 -0.207974 0.01889997 -0.001459479 -0.207085 0.01889997 -0.001354515 -0.206172 0.01889997 -9.26903e-4 -0.205359 0.01889997 -2.34406e-4 -0.204755 0.01889997 0.003517866 -0.207195 0.01889997 0.003453373 -0.206279 0.01889997 0.00476408 -0.2047049 0.01889997 0.003062188 -0.205447 0.01889997 0.004325866 -0.204496 0.01889997 0.00239706 -0.204813 0.01889997 0.002605795 -0.204002 0.01889997 0.001547932 -0.204463 0.01889997 0.003246963 -0.208073 0.01889997 0.002729296 -0.208728 0.01889997 0.002677202 -0.2087939 0.01889997 -9.92902e-4 -0.2082999 0.01889997 0.001885533 -0.20926 0.01889997 9.78961e-4 -0.2094089 0.01889997 -0.002688467 -0.209053 0.01889997 7.9815e-5 -0.2092199 0.01889997 -6.90422e-4 -0.208719 0.01889997 0.01120334 -0.218098 0.01889997 0.01063358 -0.218819 0.01889997 0.01194375 -0.220344 0.01889997 0.009841978 -0.219285 0.01889997 0.008036196 -0.219245 0.01889997 0.007265925 -0.218744 0.01889997 0.006057739 -0.220073 0.01889997 0.00858581 -0.214467 0.01889997 0.009504318 -0.214488 0.01889997 0.01035344 -0.214838 0.01889997 0.01264089 -0.214284 0.01889997 0.01101857 -0.215472 0.01889997 0.01250195 -0.21837 0.01889997 0.01140975 -0.216304 0.01889997 0.01147425 -0.21722 0.01889997 0.006728649 -0.217999 0.01889997 0.006496846 -0.21711 0.01889997 0.00660187 -0.216197 0.01889997 0.007029473 -0.215384 0.01889997 0.00772196 -0.21478 0.01889997 0.01090764 -0.22249 0.01889997 0.01107627 -0.222202 0.01889997 0.01110208 -0.222147 0.01889997 0.01176375 -0.22073 0.01889997 0.008935332 -0.219434 0.01889997 0.005161106 -0.224345 0.01889997 0.003630578 -0.22754 0.01889997 0.003590762 -0.227556 0.01889997 -0.002995491 -0.22334 0.01889997 -0.002303004 -0.222737 0.01889997 -0.004173099 -0.221958 0.01889997 -3.88581e-4 -0.228091 0.01889997 -0.001439154 -0.222424 0.01889997 -5.20642e-4 -0.2224439 0.01889997 0.002688467 -0.222747 0.01889997 3.28508e-4 -0.222795 0.01889997 9.93603e-4 -0.223429 0.01889997 0.001384794 -0.22426 0.01889997 0.001449286 -0.225176 0.01889997 0.002097487 -0.2278839 0.01889997 0.001178383 -0.226054 0.01889997 6.08628e-4 -0.226775 0.01889997 -1.83022e-4 -0.227241 0.01889997 -0.002971827 -0.228292 0.01889997 -0.002646744 -0.228366 0.01889997 -0.002758979 -0.2267 0.01889997 -0.001988768 -0.227201 0.01889997 -0.002286911 -0.227881 0.01889997 -0.001089632 -0.2273899 0.01889997 -0.003296315 -0.225955 0.01889997 -0.00483185 -0.227684 0.01889997 -0.003528118 -0.225066 0.01889997 -0.003423094 -0.224153 0.01889997 -0.01080089 -0.221566 0.01889997 -0.007198274 -0.221641 0.01889997 -0.007225751 -0.221607 0.01889997 -0.008568584 -0.225309 0.01889997 -0.008130729 -0.221502 0.01889997 -0.01159906 -0.2195349 0.01889997 -0.00795269 -0.219955 0.01889997 -0.01191306 -0.2185159 0.01889997 -0.007783114 -0.218481 0.01889997 -0.009046018 -0.217365 0.01889997 -0.009945154 -0.217176 0.01889997 -0.0114845 -0.215041 0.01889997 -0.01218116 -0.2165189 0.01889997 -0.01172238 -0.212531 0.01889997 -0.005548655 -0.207302 0.01889997 -0.005204677 -0.204312 0.01889997 -0.005762875 -0.207217 0.01889997 -0.00620824 -0.204791 0.01889997 -0.006402909 -0.207312 0.01889997 -0.006507813 -0.207395 0.01889997 -0.007719635 -0.20576 0.01889997 -0.00924617 -0.20713 0.01889997 -0.006804883 -0.207631 0.01889997 -0.00204581 -0.2034659 0.01889997 6.29438e-4 -0.204442 0.01889997 0.005754768 -0.209076 0.01889997 0.005498349 -0.209995 0.01889997 0.005262255 -0.210182 0.01889997 0.00779438 -0.2065179 0.01889997 0.007630288 -0.206404 0.01889997 0.007225751 -0.210193 0.01889997 0.01044726 -0.209616 0.01889997 0.007198274 -0.210159 0.01889997 0.01041829 -0.209558 0.01889997 0.009232223 -0.207929 0.01889997 -0.003279745 -0.229219 0.02109998 -0.01057058 -0.224642 0.02109998 -0.01179379 -0.222905 0.02109998 -0.006498992 -0.2263219 0.01785719 4.87411e-4 -0.2031559 0.01892137 2.53078e-4 -0.203159 0.01889997 7.12269e-4 -0.203137 0.01898735 9.15465e-4 -0.203101 0.01909875 0.001083672 -0.203046 0.01925247 0.001284122 -0.202794 0.0198611 0.001249015 -0.202697 0.02007198 0.001063764 -0.202511 0.02045458 7.59651e-4 -0.20235 0.02076917 0.002135574 -0.202216 0.02139997 3.66639e-4 -0.202235 0.02099364 -7.72897e-5 -0.203618 0.01785719 -0.002457559 -0.203419 0.01889997 -0.002046465 -0.2037889 0.01785719 -0.002123355 -0.203334 0.01889997 -0.003962635 -0.2042739 0.01785719 -0.004111468 -0.203838 0.01889997 -0.007440149 -0.206128 0.01785719 -0.005993187 -0.204653 0.01889997 -0.005776166 -0.205061 0.01785719 -0.01015186 -0.2089869 0.01785719 -0.01050317 -0.207551 0.02042227 -0.01144754 -0.208104 0.02139997 -0.01044768 -0.207302 0.0206784 -0.01011997 -0.20667 0.02105426 -0.01025968 -0.206885 0.02096515 -0.01028364 -0.207944 0.01948308 -0.01007407 -0.207881 0.01919859 -0.009789347 -0.2076849 0.01898097 -0.008911371 -0.207448 0.01785719 -0.00963366 -0.207543 0.01892119 -0.00947237 -0.207375 0.01889997 -0.009895026 -0.2064 0.02109998 -0.009948372 -0.2064639 0.02108919 -0.006513416 -0.2036769 0.02139997 -0.008309364 -0.204986 0.02109998 -8.6312e-5 -0.202184 0.02109736 -1.69584e-4 -0.202184 0.02109998 -0.00228554 -0.2023749 0.02109998 0.01067519 -0.221974 0.01785719 0.01079237 -0.2226949 0.01892155 0.01069635 -0.222899 0.01898759 0.01062625 -0.223093 0.01909917 0.01059007 -0.223266 0.01925337 0.01059269 -0.223407 0.01944094 0.01063358 -0.223507 0.01964718 0.01070857 -0.223565 0.01986187 0.01080995 -0.223583 0.0200721 0.01106417 -0.223516 0.02045518 0.0113554 -0.223332 0.02077007 0.01165205 -0.223049 0.02099418 0.01203775 -0.2227489 0.02139997 0.01227515 -0.2163169 0.01785719 0.01220178 -0.217304 0.01785719 0.01204925 -0.218281 0.01785719 0.01151138 -0.220183 0.01785719 0.01211905 -0.211959 0.01889997 0.01221799 -0.212278 0.01889997 0.01255315 -0.213868 0.01889997 0.01218318 -0.214343 0.01785719 0.01273638 -0.216333 0.01889997 0.01212918 -0.210878 0.0197677 0.01203155 -0.210972 0.01948314 0.01248216 -0.210979 0.02042227 0.01305305 -0.21175 0.02105396 0.01293754 -0.2115229 0.02096569 0.01267027 -0.211151 0.02067887 0.01198148 -0.211184 0.01919907 0.01200884 -0.211529 0.01898127 0.01205396 -0.211736 0.01892119 0.01177567 -0.212409 0.01785719 0.01314598 -0.212002 0.02108907 0.01327866 -0.2119629 0.02139997 0.01360654 -0.214161 0.02109998 0.013457 -0.218559 0.02109998 0.01358729 -0.218585 0.02139997 0.01192134 -0.222683 0.02109736 0.01196336 -0.222611 0.02109998 0.01298058 -0.22073 0.02139997 -0.01128 -0.22185 0.01892125 -0.01140826 -0.221665 0.01898699 -0.01154106 -0.221508 0.01909786 -0.01167285 -0.2213889 0.01925116 -0.01179605 -0.221321 0.01943814 -0.01199138 -0.22134 0.01985806 -0.01205807 -0.221418 0.02006858 -0.01212716 -0.22167 0.02045065 -0.01211434 -0.222015 0.02076786 -0.01291877 -0.220893 0.02139997 -0.01195055 -0.2229 0.02139997 -0.01116079 -0.222051 0.01889997 -0.010598 -0.222108 0.01785719 -0.0109961 -0.222341 0.01889997 -0.009820461 -0.224022 0.01889997 -0.009464859 -0.223728 0.01785719 -0.008390426 -0.225492 0.01889997 -0.007700145 -0.226004 0.01889997 -0.008086621 -0.225145 0.01785719 -0.002864241 -0.2278439 0.01785719 -0.004743039 -0.22723 0.01785719 -0.006743133 -0.226714 0.01889997 -0.001715481 -0.228915 0.01976728 -0.001747965 -0.228784 0.01948255 -0.001978933 -0.229171 0.02042216 -0.001763045 -0.229021 0.02001816 -0.002222359 -0.229247 0.02067846 -0.002677619 -0.229293 0.02096539 -0.001907587 -0.2286339 0.01919829 -0.002220153 -0.228485 0.0189808 -0.002421736 -0.228421 0.01892089 -0.003229796 -0.229368 0.02139997 -0.00319761 -0.229234 0.02108919 -0.002934217 -0.229279 0.0210545 -0.009118795 -0.226324 0.02139997 -0.007258296 -0.22754 0.02109998 -0.005348443 -0.228676 0.02139997 -0.005297183 -0.2285529 0.02109998 -0.01201808 -0.222414 0.02099329 -0.01183509 -0.222833 0.02109736 -0.01067286 -0.224727 0.02139997 -0.009031414 -0.226225 0.02109998 0.01224458 -0.210867 0.02001869 0.01247519 -0.209884 0.02139997 0.01106309 -0.210565 0.01785719 0.01006406 -0.208859 0.01785719 0.009928047 -0.206243 0.02139997 0.008804321 -0.207336 0.01785719 0.007316529 -0.206035 0.01785719 0.005639314 -0.204989 0.01785719 0.003816008 -0.204226 0.01785719 0.001271009 -0.202888 0.01964676 0.001893877 -0.203765 0.01785719 0.001204609 -0.202973 0.01944005 -0.001027524 -0.229712 0.02139997 -9.11258e-4 -0.228148 0.01785719 0.001065313 -0.228136 0.01785719 0.003014326 -0.227807 0.01785719 0.004885256 -0.227169 0.01785719 0.006629645 -0.226239 0.01785719 0.008202373 -0.225042 0.01785719 0.009562611 -0.223608 0.01785719 -0.01048129 -0.207813 0.02001816 -0.01041364 -0.207907 0.0197677 -0.01254987 -0.210041 0.02139997 -0.01112937 -0.210705 0.01785719 -0.01332718 -0.21213 0.02139997 -0.01181864 -0.212557 0.01785719 -0.01375925 -0.214317 0.02139997 -0.01220178 -0.214496 0.01785719 -0.01226896 -0.216472 0.01785719 -0.01201838 -0.218432 0.01785719 -0.01145648 -0.220328 0.01785719 -0.01190316 -0.221305 0.01964396 0.01321607 -0.21742 0.02139997 0.01375925 -0.217483 0.02139997 0.01384198 -0.2163709 0.02139997 0.01373815 -0.214144 0.02139997 0.0113486 -0.207961 0.02139997 0.008250415 -0.204776 0.02139997 0.008501291 -0.205668 0.02139997 0.006701111 -0.204408 0.02139997 0.0063591 -0.2035959 0.02139997 0.002606511 -0.202855 0.02139997 0.004303097 -0.202735 0.02139997 4.23825e-4 -0.2026039 0.02139997 -8.71547e-5 -0.20205 0.02139997 -0.002307653 -0.202244 0.02139997 -0.003916442 -0.203186 0.02139997 -0.005955636 -0.204004 0.02139997 -0.004468381 -0.202791 0.02139997 -0.007832407 -0.205147 0.02139997 -0.00838977 -0.2048799 0.02139997 -0.01004874 -0.206369 0.02139997 -0.01200628 -0.210171 0.02139997 -0.01278555 -0.212225 0.02139997 -0.01321607 -0.21438 0.02139997 -0.01328605 -0.216576 0.02139997 -0.01299369 -0.218753 0.02139997 -0.01383495 -0.216545 0.02139997 -0.01355236 -0.218756 0.02139997 -0.0123468 -0.220853 0.02139997 -0.01136314 -0.222818 0.02139997 -0.01006954 -0.2245939 0.02139997 -0.008501291 -0.226132 0.02139997 -0.00732851 -0.227652 0.02139997 0.001770436 -0.229085 0.02139997 0.001201272 -0.229698 0.02139997 0.003916442 -0.228614 0.02139997 0.003399074 -0.229326 0.02139997 0.00550878 -0.2286069 0.02139997 0.007832407 -0.226653 0.02139997 0.007475852 -0.227559 0.02139997 0.009249269 -0.226209 0.02139997 0.01078319 -0.224592 0.02139997 0.01278555 -0.219575 0.02139997 0.01015955 -0.222676 0.01893377 -0.01091855 -0.221358 0.01892197 -0.001770436 -0.202715 0.02139997 -0.00589621 -0.204123 0.02109998 -0.007754206 -0.205254 0.02109998 -0.009495437 -0.206583 0.02139997 -0.01024645 -0.2083399 0.02011227 -0.009563386 -0.208265 0.01899075 -0.009395003 -0.208106 0.01892215 -0.01020348 -0.208442 0.01989769 -0.009730339 -0.208395 0.01910698 -0.009993135 -0.208907 0.01889997 -0.009886682 -0.208483 0.01926767 -0.0100224 -0.2085199 0.01946336 -0.01024615 -0.208056 0.02049809 -0.01014375 -0.207704 0.0208075 -0.009946167 -0.207321 0.02101939 -0.009658336 -0.206946 0.02109998 -0.01154255 -0.220802 0.01967567 -0.01143449 -0.220812 0.01946008 -0.01175975 -0.221213 0.02049785 -0.01169526 -0.220935 0.02011168 -0.01131105 -0.22088 0.01926535 -0.01117897 -0.221001 0.01910549 -0.01098167 -0.221174 0.01889997 -0.01104587 -0.221166 0.01898986 -0.004718184 -0.228338 0.02139997 -0.006701111 -0.227392 0.02139997 -0.006634294 -0.2272779 0.02109998 -0.008416473 -0.2260299 0.02109998 -0.009969055 -0.224507 0.02109998 -0.01124978 -0.2227489 0.02109998 -0.01143938 -0.222427 0.02109998 -0.01163458 -0.221996 0.02101916 -0.01173979 -0.221579 0.0208081 -0.002606511 -0.228945 0.02139997 -0.002925336 -0.228741 0.02109998 -0.004671096 -0.228214 0.02109998 -0.001869678 -0.227986 0.01897448 -0.001684963 -0.228056 0.01907038 -0.001530706 -0.228136 0.01920437 -0.001418471 -0.228224 0.01937019 -0.001354515 -0.2283149 0.01955807 -0.001370191 -0.2284899 0.01995557 -0.001539826 -0.228636 0.0203278 -0.001817286 -0.228742 0.02064615 -0.002170801 -0.228798 0.02089476 -0.002576589 -0.228796 0.02105468 0.01013165 -0.223507 0.01996839 0.01002329 -0.223453 0.01969885 0.009963929 -0.223277 0.01935315 0.009466528 -0.223527 0.01889997 0.009981155 -0.223128 0.01918637 0.009993135 -0.2228929 0.01889997 0.01004338 -0.222928 0.01903849 0.0103603 -0.223478 0.02034449 0.01063287 -0.223341 0.02066439 0.0108273 -0.223195 0.02084028 0.01328605 -0.215224 0.02139997 0.01308417 -0.217405 0.02109998 0.01200628 -0.221629 0.02139997 0.01188647 -0.221572 0.02109998 0.0108996 -0.223527 0.02139997 0.01137226 -0.222543 0.02109998 0.01120549 -0.222793 0.02106696 0.01102179 -0.22301 0.02097755 0.01227647 -0.211362 0.02091449 0.01247894 -0.2117339 0.0210675 0.01258367 -0.212013 0.02109998 0.01299369 -0.213047 0.02139997 0.01286399 -0.213075 0.02109998 0.01147425 -0.210822 0.01969259 0.01158875 -0.210792 0.01995676 0.01177448 -0.210851 0.02028828 0.0123468 -0.210947 0.02139997 0.01204466 -0.211068 0.02066439 0.01143264 -0.2116079 0.01893389 0.01132005 -0.211359 0.01889997 0.01137697 -0.211336 0.01903849 0.01136398 -0.211077 0.01923495 0.001443266 -0.203558 0.01941758 0.001407682 -0.203161 0.02029955 0.001232206 -0.2030299 0.0205549 4.18958e-4 -0.202756 0.02105468 8.70144e-4 -0.202864 0.02086186 0.001526534 -0.203452 0.01967775 0.002389788 -0.203939 0.01889997 0.001245796 -0.203649 0.0191648 9.22253e-4 -0.203705 0.018974 4.93347e-4 -0.2037129 0.01889997 -0.01012879 -0.208505 0.01967775 -0.0108996 -0.2082729 0.02139997 -0.0110079 -0.210647 0.01889997 0.00153017 -0.203348 0.01991248 0.004718184 -0.203462 0.02139997 0.01141136 -0.210892 0.01949834 0.01136314 -0.208982 0.02139997 0.01006954 -0.207206 0.02139997 0.006179034 -0.205388 0.01889997 0.009495437 -0.225217 0.02139997 0.008705854 -0.224442 0.01889997 0.007181048 -0.225759 0.01889997 0.005955636 -0.227796 0.02139997 0.005274534 -0.226881 0.01889997 0.001623213 -0.227988 0.01889997 -4.23825e-4 -0.229196 0.02139997 -0.01163005 -0.2208459 0.01989668 -0.01132005 -0.220441 0.01889997 -0.01198267 -0.217998 0.01889997 -0.01209604 -0.217154 0.01889997 -0.01211708 -0.214506 0.01889997 0.00220406 -0.219238 0.03014999 0.002151548 -0.219938 0.03014999 0.002771317 -0.2195399 0.03014999 0.003319323 -0.219048 0.03014999 0.002750217 -0.218804 0.03014999 0.003212809 -0.2182829 0.03014999 0.003781378 -0.218475 0.03014999 0.003577768 -0.217689 0.03014999 0.004145503 -0.217835 0.03014999 0.003834009 -0.21704 0.03014999 0.004402279 -0.217145 0.03014999 0.003973782 -0.2163569 0.03014999 0.003992795 -0.21566 0.03014999 0.004544973 -0.216423 0.03014999 0.004570007 -0.215687 0.03014999 0.004476666 -0.2149569 0.03014999 0.003890454 -0.2149699 0.03014999 0.003669977 -0.214309 0.03014999 0.004267394 -0.214251 0.03014999 0.003337919 -0.213696 0.03014999 0.003947556 -0.2135879 0.03014999 0.002904474 -0.21315 0.03014999 -0.003992795 -0.21614 0.03014999 -0.004572331 -0.215745 0.03014999 -0.003890454 -0.21683 0.03014999 -0.004538059 -0.21648 0.03014999 -0.004386246 -0.2172 0.03014999 -0.004120826 -0.217887 0.03014999 -0.003669977 -0.217491 0.03014999 -0.003337919 -0.218104 0.03014999 -0.003748714 -0.218523 0.03014999 -0.002904474 -0.21865 0.03014999 -0.002382755 -0.2191129 0.03014999 -0.003279447 -0.21909 0.03014999 -0.001788675 -0.219478 0.03014999 -0.002725303 -0.219575 0.03014999 -0.002100527 -0.219964 0.03014999 -0.001140236 -0.219734 0.03014999 -0.001421391 -0.2202489 0.03014999 -4.5715e-4 -0.219874 0.03014999 -7.05451e-4 -0.22042 0.03014999 2.39837e-4 -0.219893 0.03014999 2.87893e-5 -0.220475 0.03014999 9.29536e-4 -0.2197909 0.03014999 7.62284e-4 -0.220411 0.03014999 0.001475989 -0.22023 0.03014999 0.001590967 -0.21957 0.03014999 0.003525495 -0.212984 0.03014999 0.002382755 -0.212687 0.03014999 0.00301218 -0.212457 0.03014999 0.002420783 -0.212018 0.03014999 0.001788675 -0.2123219 0.03014999 0.001766681 -0.2116799 0.03014999 0.001066863 -0.2114509 0.03014999 0.001140236 -0.2120659 0.03014999 4.5715e-4 -0.211926 0.03014999 3.39431e-4 -0.211338 0.03014999 -2.39837e-4 -0.211907 0.03014999 -3.96823e-4 -0.211342 0.03014999 -9.29536e-4 -0.21201 0.03014999 -0.001122772 -0.211465 0.03014999 -0.001590967 -0.21223 0.03014999 -0.00181967 -0.211702 0.03014999 -0.00246942 -0.212049 0.03014999 -0.00220406 -0.212562 0.03014999 -0.002750217 -0.2129949 0.03014999 -0.003055274 -0.212495 0.03014999 -0.003212809 -0.213517 0.03014999 -0.003577768 -0.214111 0.03014999 -0.003561913 -0.213029 0.03014999 -0.003976345 -0.2136369 0.03014999 -0.003834009 -0.21476 0.03014999 -0.003973782 -0.215443 0.03014999 -0.004287779 -0.214305 0.03014999 -0.00448817 -0.215013 0.03014999 0.004942357 -0.216469 0.02884995 0.004942357 -0.216469 0.02974998 0.004969596 -0.215668 0.02884995 0.00486809 -0.214874 0.02884995 0.004969596 -0.215668 0.02974998 0.00486809 -0.214874 0.02974998 0.00464046 -0.214107 0.02884995 0.00464046 -0.214107 0.02974998 0.004292726 -0.213385 0.02974998 0.004292726 -0.213385 0.02884995 0.00383377 -0.212729 0.02884995 0.00383377 -0.212729 0.02974998 0.003275513 -0.212155 0.02884995 0.003275513 -0.212155 0.02974998 0.002632439 -0.211679 0.02974998 0.002632439 -0.211679 0.02884995 0.001921176 -0.211311 0.02884995 0.001921176 -0.211311 0.02974998 0.001160144 -0.211062 0.02974998 0.001160144 -0.211062 0.02884995 3.69108e-4 -0.210939 0.02884995 3.69108e-4 -0.210939 0.02974998 -4.31518e-4 -0.2109439 0.02884995 -4.31518e-4 -0.2109439 0.02974998 -0.001220941 -0.211077 0.02974998 -0.001220941 -0.211077 0.02884995 -0.001978754 -0.211335 0.02974998 -0.001978754 -0.211335 0.02884995 -0.002685368 -0.211712 0.02884995 -0.002685368 -0.211712 0.02974998 -0.003322362 -0.212197 0.02974998 -0.003322362 -0.212197 0.02884995 -0.003873348 -0.212778 0.02974998 -0.003873348 -0.212778 0.02884995 -0.004324018 -0.21344 0.02974998 -0.004324018 -0.21344 0.02884995 -0.004662692 -0.214165 0.02974998 -0.004662692 -0.214165 0.02884995 -0.004880607 -0.214936 0.02974998 -0.004880607 -0.214936 0.02884995 -0.0049721 -0.215731 0.02974998 -0.0049721 -0.215731 0.02884995 -0.004934847 -0.216531 0.02884995 -0.004934847 -0.216531 0.02974998 -0.004769742 -0.217314 0.02884995 -0.004769742 -0.217314 0.02974998 -0.004481136 -0.218061 0.02974998 -0.004481136 -0.218061 0.02884995 -0.004076421 -0.218752 0.02884995 -0.004076421 -0.218752 0.02974998 -0.003566205 -0.2193689 0.02974998 -0.003566205 -0.2193689 0.02884995 -0.002963602 -0.219896 0.02974998 -0.002963602 -0.219896 0.02884995 -0.002284228 -0.22032 0.02884995 -0.002284228 -0.22032 0.02974998 -0.001545667 -0.220629 0.02884995 -7.67129e-4 -0.220815 0.02884995 -0.001545667 -0.220629 0.02974998 -7.67129e-4 -0.220815 0.02974998 3.13064e-5 -0.220875 0.02884995 3.13064e-5 -0.220875 0.02974998 8.28931e-4 -0.220805 0.02884995 8.28931e-4 -0.220805 0.02974998 0.001605033 -0.220609 0.02884995 0.001605033 -0.220609 0.02974998 0.002339661 -0.220291 0.02974998 0.002339661 -0.220291 0.02884995 0.00301361 -0.219858 0.02884995 0.00301361 -0.219858 0.02974998 0.003609597 -0.2193239 0.02884995 0.003609597 -0.2193239 0.02974998 0.004112005 -0.2186999 0.02884995 0.004112005 -0.2186999 0.02974998 0.004507958 -0.218004 0.02884995 0.004507958 -0.218004 0.02974998 0.004787147 -0.217254 0.02884995 0.004787147 -0.217254 0.02974998 0.004871785 -0.214775 0.03444999 0.004747033 -0.2174699 0.03444999 0.00499463 -0.216131 0.03444999 0.002525985 -0.220215 0.03744995 -0.003885149 -0.219047 0.03744995 -0.003046154 -0.219816 0.03744995 -0.002161443 -0.219847 0.03794997 -0.001204848 -0.220753 0.03744995 -5.66701e-4 -0.220826 0.03744995 0.001343011 -0.2207159 0.03744995 0.001208722 -0.220235 0.03794997 0.00227338 -0.219783 0.03794997 -0.003885149 -0.219047 0.03444999 -0.004020214 -0.218873 0.03444999 -0.004673182 -0.217678 0.03444999 -0.004916608 -0.214991 0.03444999 -0.003068923 -0.211953 0.03444999 -0.003800272 -0.2183099 0.03794997 -0.00268644 -0.211694 0.03744995 0.003800272 -0.21349 0.03794997 0.003095865 -0.212634 0.03794997 0.002401649 -0.211515 0.03744995 0.002161443 -0.211953 0.03794997 0.00124073 -0.211061 0.03744995 0.001084327 -0.211533 0.03794997 0.001204848 -0.2110469 0.03744995 -7.14634e-5 -0.210901 0.03744995 -6.43171e-5 -0.2114 0.03794997 -0.001343011 -0.211084 0.03744995 -0.001208722 -0.211565 0.03794997 -0.001449465 -0.211129 0.03744995 -0.002525985 -0.211585 0.03744995 -0.00227338 -0.212016 0.03794997 0.003885149 -0.2127529 0.03744995 0.001128971 -0.216888 0.03794997 0.0031538 -0.21911 0.03794997 -1.71431e-4 -0.21739 0.03794997 6.4317e-5 -0.2204 0.03794997 5.40723e-4 -0.217299 0.03794997 -1.90172e-4 -0.214412 0.03794997 -8.59849e-4 -0.214671 0.03794997 -0.0031538 -0.2126899 0.03794997 -0.003095865 -0.219166 0.03794997 -0.001084327 -0.2202669 0.03794997 0.001116454 -0.214898 0.03794997 5.40723e-4 -0.217299 0.03466236 -7.71393e-4 -0.217177 0.03677266 -8.44312e-4 -0.21714 0.03014999 -0.001044511 -0.216977 0.03484797 -0.001194059 -0.216808 0.03632497 -0.001274645 -0.216691 0.03612387 -0.001323759 -0.216605 0.03589636 -0.00149995 -0.215909 0.03794997 -8.44312e-4 -0.21714 0.03673756 -0.001323759 -0.216605 0.03794997 -0.001044631 -0.216976 0.03655177 4.65064e-4 -0.217326 0.0367825 1.60004e-4 -0.217391 0.03690576 -1.71431e-4 -0.21739 0.03694999 -8.44312e-4 -0.21714 0.03794997 -4.94626e-4 -0.217316 0.03690576 7.72851e-4 -0.217186 0.03655189 0.001458585 -0.21625 0.03794997 0.001061975 -0.2169589 0.03612339 0.001061797 -0.2169589 0.03527617 0.001128971 -0.216888 0.03550356 5.40723e-4 -0.217299 0.03014999 0.001128971 -0.216888 0.03014999 9.56771e-4 -0.217055 0.03507494 -1.71431e-4 -0.21739 0.03014999 1.59998e-4 -0.217391 0.03449416 0.001458585 -0.21625 0.03014999 0.001454114 -0.215532 0.03794997 0.001454114 -0.215532 0.03014999 0.001116454 -0.214898 0.03014999 5.23071e-4 -0.214494 0.03014999 5.23071e-4 -0.214494 0.03794997 1.71431e-4 -0.21441 0.03014999 -1.90172e-4 -0.214412 0.03014999 -8.59849e-4 -0.214671 0.03014999 -0.001332521 -0.215211 0.03794997 -0.001332521 -0.215211 0.03014999 -0.00149995 -0.215909 0.03014999 -0.001323759 -0.216605 0.03014999 -0.001323759 -0.216605 0.03550356 -0.001194059 -0.216808 0.03507494 -0.001633286 -0.2206259 0.03507494 3.15777e-4 -0.22089 0.0348162 4.61359e-4 -0.2173179 0.03462725 5.39496e-5 -0.2208999 0.03461748 6.44742e-4 -0.220858 0.03537559 5.17555e-4 -0.2208729 0.03507494 7.72952e-4 -0.217186 0.03484815 0.001128971 -0.216888 0.03589636 0.001147031 -0.216867 0.03569996 9.56771e-4 -0.217055 0.03632497 5.17555e-4 -0.2208729 0.03632497 5.37889e-4 -0.217293 0.03672796 -0.001440346 -0.220688 0.03658396 -0.001187801 -0.220757 0.0367825 -8.92354e-4 -0.22082 0.03690719 -2.4813e-4 -0.220894 0.03690719 -0.001633286 -0.2206259 0.03632497 -0.001336514 -0.216581 0.03569996 -0.001274824 -0.21669 0.03527665 -8.9271e-4 -0.22082 0.03449285 -1.71431e-4 -0.21739 0.03444999 -4.95316e-4 -0.217316 0.0344944 -0.001187801 -0.220757 0.03461748 -7.76746e-4 -0.2171829 0.03461748 -8.4012e-4 -0.2171339 0.03467196 -0.001440525 -0.220688 0.03481608 -0.003068923 -0.211953 0.03744995 -0.003728508 -0.2125689 0.03444999 -0.003985404 -0.2129499 0.03344994 -0.004489064 -0.213698 0.03444999 -0.00497961 -0.216351 0.03344994 -0.00497961 -0.216351 0.03444999 -0.004570662 -0.217865 0.03344994 -0.004020214 -0.218873 0.03344994 -0.003439843 -0.219529 0.03744995 0.003240168 -0.219708 0.03444999 0.003068923 -0.219847 0.03444999 0.002092599 -0.220441 0.03344994 0.003068923 -0.219847 0.03744995 0.004004955 -0.218852 0.03344994 0.00414741 -0.218693 0.03344994 0.004747033 -0.2174699 0.03344994 0.00414741 -0.218693 0.03444999 0.00499463 -0.216131 0.03344994 0.004551172 -0.213932 0.03344994 0.004387617 -0.213502 0.03344994 0.004387617 -0.213502 0.03444999 0.003578007 -0.2124069 0.03344994 0.003885149 -0.2127529 0.03444999 6.44827e-4 -0.220858 0.03602397 6.88518e-4 -0.220852 0.03569996 7.89898e-4 -0.2208369 0.03344994 -2.4865e-4 -0.220894 0.03449255 -5.71437e-4 -0.220867 0.03444999 -0.001890361 -0.220529 0.03344994 -0.001753926 -0.220582 0.03537625 -0.001795053 -0.220567 0.03569996 -0.001753926 -0.220582 0.03602379 -0.001875519 -0.2204909 0.03744995 7.14634e-5 -0.220899 0.03744995 -5.71437e-4 -0.220867 0.03694999 5.39496e-5 -0.2208999 0.0367825 3.15422e-4 -0.22089 0.03658407 -0.003069102 -0.219847 0.03344994 -0.002401649 -0.2202849 0.03744995 -0.002056479 -0.2204329 0.03344994 -0.00197637 -0.220479 0.03344994 -0.00145477 -0.211116 0.03344994 -9.75925e-4 -0.21104 0.03344994 -1.09568e-4 -0.210906 0.03744995 -1.10258e-4 -0.210901 0.03344994 0.002054035 -0.211388 0.03344994 0.002503037 -0.211572 0.03344994 0.00249505 -0.211583 0.03744995 0.003439843 -0.212271 0.03744995 0.003571391 -0.212414 0.03744995 7.84074e-4 -0.220797 0.03744995 0.0020774 -0.220405 0.03744995 0.009080946 -0.2149749 0.03214997 0.009797036 -0.215398 0.03214997 0.009797036 -0.215398 0.03344994 0.01027929 -0.216076 0.03214997 0.01044416 -0.216891 0.03214997 0.01026326 -0.217703 0.03214997 0.009767889 -0.218371 0.03344994 0.009043633 -0.21878 0.03214997 0.009043633 -0.21878 0.03344994 0.007427334 -0.218594 0.03344994 0.006483972 -0.217268 0.03344994 0.006492137 -0.216436 0.03214997 0.006837844 -0.21568 0.03344994 0.007461309 -0.21513 0.03214997 0.008254766 -0.2148799 0.03214997 0.008672833 -0.2148849 0.03214997 0.009080946 -0.2149749 0.03344994 0.003327906 -0.225669 0.03214997 0.003980159 -0.225607 0.03214997 0.004285991 -0.225434 0.03344994 0.004510164 -0.225308 0.03214997 0.004704415 -0.225198 0.03214997 0.005199849 -0.22453 0.03214997 0.005199849 -0.22453 0.03344994 0.005380749 -0.223718 0.03214997 0.004733622 -0.222226 0.03344994 0.004733622 -0.222226 0.03214997 0.003778815 -0.22175 0.03214997 0.004017531 -0.221803 0.03344994 0.003191292 -0.2217079 0.03344994 0.002397894 -0.221957 0.03214997 0.00177443 -0.2225069 0.03214997 0.00177443 -0.2225069 0.03344994 0.001428723 -0.223264 0.03214997 0.00236386 -0.225421 0.03344994 0.001751303 -0.224858 0.03214997 0.001751303 -0.224858 0.03344994 -0.003710627 -0.221254 0.03214997 -0.003739833 -0.224227 0.03344994 -0.003739833 -0.224227 0.03214997 -0.0032444 -0.223559 0.03214997 -0.003228425 -0.2219319 0.03344994 -0.003228425 -0.2219319 0.03214997 -0.005252957 -0.220736 0.03344994 -0.005964934 -0.22096 0.03344994 -0.006046354 -0.2209849 0.03344994 -0.006046354 -0.2209849 0.03214997 -0.006669819 -0.221536 0.03344994 -0.006669819 -0.221536 0.03214997 -0.007015526 -0.222292 0.03344994 -0.007015526 -0.222292 0.03214997 -0.007023692 -0.223124 0.03344994 -0.003934085 -0.224336 0.03214997 -0.004464089 -0.224635 0.03344994 -0.005291998 -0.224714 0.03214997 -0.005459249 -0.224658 0.03214997 -0.006080389 -0.224449 0.03344994 -0.006339013 -0.224212 0.03344994 -0.006528615 -0.224038 0.03214997 -0.006692886 -0.223887 0.03214997 -0.007023692 -0.223124 0.03214997 -0.007091462 -0.213455 0.03214997 -0.00660932 -0.214133 0.03344994 -0.006625235 -0.2157599 0.03214997 -0.007120668 -0.216428 0.03214997 -0.007844924 -0.216837 0.03214997 -0.007844924 -0.216837 0.03344994 -0.01007378 -0.2160879 0.03214997 -0.01040458 -0.2153249 0.03344994 -0.01040458 -0.2153249 0.03214997 -0.01039636 -0.214494 0.03214997 -0.009427249 -0.213187 0.03214997 -0.009427249 -0.213187 0.03344994 -0.008633792 -0.212938 0.03344994 -0.008615493 -0.212938 0.03214997 -0.007807612 -0.213033 0.03344994 -0.008215725 -0.212942 0.03214997 -0.009058177 -0.216786 0.03344994 -0.009461224 -0.216651 0.03344994 -0.002744138 -0.206205 0.03344994 -0.002744138 -0.206205 0.03214997 -0.00156182 -0.2089329 0.03344994 -0.001912057 -0.206791 0.03344994 -0.003152251 -0.2061139 0.03214997 -0.003570377 -0.20611 0.03344994 -0.004363775 -0.20636 0.03214997 -0.004987239 -0.20691 0.03344994 -0.002051949 -0.209594 0.03214997 -0.00278151 -0.210009 0.03214997 -0.002057194 -0.209601 0.03344994 -0.004397809 -0.209823 0.03214997 -0.005010306 -0.209261 0.03214997 -0.004656434 -0.209586 0.03344994 -0.005341112 -0.208498 0.03344994 -0.005341112 -0.208498 0.03214997 0.005662739 -0.210981 0.03344994 0.006882429 -0.209904 0.03214997 0.007063329 -0.209092 0.03214997 0.006898403 -0.208277 0.03214997 0.006416201 -0.2075999 0.03214997 0.005700111 -0.207177 0.03344994 0.005461394 -0.2071239 0.03214997 0.004873871 -0.207082 0.03214997 0.004080474 -0.207331 0.03214997 0.003930509 -0.207463 0.03344994 0.003457009 -0.207881 0.03214997 0.003430426 -0.210224 0.03214997 0.003103137 -0.209469 0.03214997 0.003111302 -0.208638 0.03214997 -0.0095281 -0.211399 0.03344994 -0.008577227 -0.211248 0.03214997 -0.008409321 -0.2111459 0.03214997 -0.007180452 -0.209975 0.03344994 -0.007180452 -0.209975 0.03214997 -0.007151603 -0.2098619 0.03344994 -0.006941676 -0.209043 0.03214997 -0.007555246 -0.207255 0.03344994 0.001144647 -0.227324 0.03344994 3.93879e-4 -0.22582 0.03214997 3.93879e-4 -0.22582 0.03344994 2.59715e-4 -0.225654 0.03214997 2.59715e-4 -0.225654 0.03344994 -5.8426e-4 -0.2251909 0.03214997 -0.00154072 -0.225081 0.03344994 -0.00154072 -0.225081 0.03214997 -0.00246787 -0.22534 0.03344994 -0.00246787 -0.22534 0.03214997 -0.003228127 -0.225931 0.03344994 -0.007699429 -0.20709 0.03194999 -0.009147167 -0.205434 0.03194999 -0.008963882 -0.2083809 0.03194999 -0.01200765 -0.208898 0.03194999 -0.01267069 -0.210185 0.03194999 -0.008662104 -0.2219009 0.03344994 -0.00831753 -0.221002 0.03344994 -0.008721172 -0.219156 0.03344994 -0.01030129 -0.21812 0.03344994 -0.01126408 -0.2181209 0.03344994 -0.01130336 -0.210802 0.03344994 -0.01358997 -0.2131839 0.03194999 -0.01231878 -0.214483 0.03344994 -0.01380884 -0.214311 0.03194999 -0.0138517 -0.215459 0.03194999 -0.01239007 -0.216397 0.03344994 -0.01216578 -0.218299 0.03344994 -0.01126408 -0.2181209 0.03214997 -0.01147896 -0.218163 0.03194999 -0.01146769 -0.2182199 0.03194999 -0.01242917 -0.222123 0.03194999 -0.01128488 -0.224016 0.03194999 -0.01123064 -0.22408 0.03194999 -0.009900569 -0.225656 0.03194999 -0.009724676 -0.225809 0.03194999 -0.008280217 -0.227065 0.03194999 -0.007956504 -0.227268 0.03194999 -0.005764901 -0.226878 0.03344994 -0.00400573 -0.227635 0.03344994 -0.00377959 -0.2269729 0.03194999 -0.004490256 -0.229055 0.03194999 -0.00133711 -0.227523 0.03194999 -0.001588582 -0.229709 0.03194999 7.05945e-4 -0.229782 0.03194999 0.001385807 -0.229731 0.03194999 0.002975761 -0.2294459 0.03194999 0.005167245 -0.228778 0.03194999 0.004038631 -0.227585 0.03344994 0.005528688 -0.228653 0.03194999 0.009147167 -0.226366 0.03194999 0.008160054 -0.225237 0.03344994 0.01121348 -0.212561 0.03194999 0.01043719 -0.210613 0.03194999 0.01242917 -0.209677 0.03194999 0.009498715 -0.209069 0.03194999 0.01069146 -0.224783 0.03194999 0.01064115 -0.220764 0.03194999 0.007555246 -0.224545 0.03344994 0.0095281 -0.220401 0.03344994 0.008577227 -0.220552 0.03344994 0.008577227 -0.220552 0.03214997 0.007753968 -0.221051 0.03344994 0.007380127 -0.221556 0.03344994 0.007753968 -0.221051 0.03214997 0.007255911 -0.221723 0.03214997 0.006941676 -0.222757 0.03344994 0.007073104 -0.223711 0.03214997 0.007073104 -0.223711 0.03344994 0.01066529 -0.2207109 0.03214997 0.01130336 -0.220998 0.03344994 0.01046556 -0.220621 0.03214997 0.01267069 -0.221615 0.03194999 0.0133996 -0.219596 0.03194999 0.01195359 -0.219197 0.03344994 0.01231878 -0.217317 0.03344994 0.0137369 -0.214055 0.03194999 0.01388877 -0.2153429 0.03194999 0.01239007 -0.215403 0.03344994 0.01380884 -0.217489 0.03194999 0.01358997 -0.218616 0.03194999 0.01216578 -0.213501 0.03344994 0.008721172 -0.212644 0.03344994 0.008662104 -0.209899 0.03214997 0.008321762 -0.2107869 0.03214997 0.00831753 -0.210798 0.03344994 0.009409606 -0.213317 0.03344994 0.01030129 -0.21368 0.03214997 0.004490256 -0.202745 0.03194999 0.005973994 -0.203384 0.03194999 0.005764901 -0.204922 0.03344994 0.007956504 -0.204532 0.03194999 0.009724676 -0.205991 0.03194999 0.009900569 -0.206144 0.03194999 0.009608328 -0.208117 0.03344994 -0.005986213 -0.2284449 0.03024995 -0.006462275 -0.228206 0.03194999 -0.01123547 -0.224084 0.03024995 -0.01242917 -0.222123 0.03024995 -0.01328396 -0.219992 0.03194999 -0.01363748 -0.218589 0.03194999 -0.0137369 -0.217745 0.03194999 -0.01388877 -0.216457 0.03194999 -0.01389288 -0.215457 0.03024995 -0.0133996 -0.212204 0.03194999 -0.01295906 -0.210984 0.03194999 -0.01069146 -0.207017 0.03194999 -0.009079873 -0.205384 0.03194999 -0.005175173 -0.2029989 0.03024995 -0.003498971 -0.202448 0.03194999 -0.002981185 -0.202323 0.03024995 -0.001385807 -0.202069 0.03194999 -7.05945e-4 -0.202018 0.03194999 0.001588582 -0.202091 0.03194999 0.006462275 -0.203594 0.03194999 0.008280217 -0.204735 0.03194999 0.009735226 -0.205979 0.03024995 0.01123547 -0.207716 0.03024995 0.01123064 -0.20772 0.03194999 0.01128488 -0.2077839 0.03194999 0.01328396 -0.211808 0.03194999 0.01363748 -0.2132109 0.03194999 0.01377636 -0.2140499 0.03024995 0.01389288 -0.216343 0.03024995 0.0138517 -0.216341 0.03194999 0.01363056 -0.2186239 0.03024995 0.01295906 -0.220816 0.03194999 0.01200765 -0.2229019 0.03024995 0.01200765 -0.2229019 0.03194999 0.01069146 -0.224783 0.03024995 0.009079873 -0.226416 0.03194999 0.0074265 -0.22765 0.03194999 0.007220447 -0.227759 0.03194999 0.007227957 -0.227773 0.03024995 0.005175173 -0.228801 0.03024995 0.003498971 -0.2293519 0.03194999 -0.00383979 -0.229259 0.03194999 -0.00383979 -0.229259 0.03024995 -0.005973994 -0.228416 0.03194999 0.00383979 -0.2025409 0.03194999 0.003708839 -0.205035 0.03344994 -0.001144647 -0.2044759 0.03344994 -3.93879e-4 -0.20598 0.03214997 -8.65998e-4 -0.205398 0.03344994 -2.59715e-4 -0.206146 0.03344994 -2.59715e-4 -0.206146 0.03214997 0.00154072 -0.206719 0.03214997 0.00246787 -0.2064599 0.03344994 0.002636134 -0.206329 0.03344994 -0.001166462 -0.204258 0.03214997 -0.001144647 -0.2044759 0.03214997 -0.001333713 -0.223993 0.03214997 -9.48586e-4 -0.224146 0.03344994 -5.38957e-4 -0.224085 0.03344994 -5.38957e-4 -0.224085 0.03214997 -2.1459e-4 -0.223827 0.03214997 -6.23975e-5 -0.223442 0.03344994 -6.23975e-5 -0.223442 0.03214997 -1.2316e-4 -0.223033 0.03214997 -7.65726e-4 -0.2225559 0.03344994 -7.65726e-4 -0.2225559 0.03214997 -0.001175343 -0.222617 0.03214997 -0.001499712 -0.222874 0.03344994 -0.001499712 -0.222874 0.03214997 -0.001591145 -0.2236689 0.03344994 0.005992352 -0.219591 0.03214997 0.005381464 -0.219891 0.03214997 0.005290031 -0.220686 0.03344994 0.005229294 -0.2202759 0.03214997 0.005547463 -0.22101 0.03344994 0.005547463 -0.22101 0.03214997 0.005816876 -0.221117 0.03214997 0.005816876 -0.221117 0.03344994 0.005932569 -0.221163 0.03344994 0.006342232 -0.2211019 0.03344994 0.006342232 -0.2211019 0.03214997 0.0066666 -0.220844 0.03214997 0.0066666 -0.220844 0.03344994 0.006758034 -0.22005 0.03344994 0.006758034 -0.22005 0.03214997 0.006500601 -0.219725 0.03344994 0.006500601 -0.219725 0.03214997 0.006115436 -0.219573 0.03344994 9.48586e-4 -0.2076539 0.03344994 9.48586e-4 -0.2076539 0.03214997 2.1459e-4 -0.207973 0.03214997 2.1459e-4 -0.207973 0.03344994 6.23974e-5 -0.208358 0.03344994 6.23974e-5 -0.208358 0.03214997 1.2316e-4 -0.2087669 0.03214997 3.80596e-4 -0.209092 0.03344994 7.65726e-4 -0.209244 0.03214997 7.65726e-4 -0.209244 0.03344994 0.001175343 -0.209183 0.03344994 0.001651883 -0.208541 0.03344994 0.001499712 -0.208926 0.03214997 0.001651883 -0.208541 0.03214997 0.001591145 -0.208131 0.03344994 0.001591145 -0.208131 0.03214997 -0.006818771 -0.211341 0.03214997 -0.006500601 -0.2120749 0.03344994 -0.005992352 -0.212209 0.03214997 -0.005381464 -0.2119089 0.03344994 -0.005381464 -0.2119089 0.03214997 -0.005229294 -0.211524 0.03344994 -0.005290031 -0.211114 0.03214997 -0.005547463 -0.21079 0.03214997 -0.005932569 -0.210637 0.03214997 -0.006780743 -0.211245 0.03214997 -0.006404638 -0.218241 0.03214997 -0.006616055 -0.21763 0.03214997 0.01126408 -0.213679 0.03214997 0.01162946 -0.214617 0.03214997 0.006611287 -0.225549 0.03214997 -0.008629739 -0.223796 0.03214997 -0.007450044 -0.224879 0.03214997 0.002287268 -0.213734 0.03214997 7.3201e-4 -0.218964 0.03214997 -3.60005e-4 -0.219029 0.03214997 -0.001408576 -0.2187179 0.03214997 -0.002187728 -0.21814 0.03214997 -0.002287268 -0.218066 0.03214997 -0.00289011 -0.217153 0.03214997 -0.001735687 -0.213271 0.03214997 -0.002530097 -0.214024 0.03214997 -0.004110753 -0.212936 0.03214997 -0.003019273 -0.215002 0.03214997 -0.003144323 -0.216089 0.03214997 0.001408576 -0.213082 0.03214997 -7.3201e-4 -0.212836 0.03214997 -0.001206219 -0.213042 0.03214997 -0.001622021 -0.213222 0.03214997 0.001622021 -0.218578 0.03214997 0.001735687 -0.218529 0.03214997 0.002530097 -0.217776 0.03214997 0.003019273 -0.216798 0.03214997 0.003144323 -0.2157109 0.03214997 0.00289011 -0.2146469 0.03214997 0.003609418 -0.2217119 0.03214997 0.003191292 -0.2217079 0.03214997 9.48644e-4 -0.220997 0.03214997 0.001420557 -0.224095 0.03214997 0.005215823 -0.222903 0.03214997 0.003827214 -0.221329 0.03214997 0.004017531 -0.221803 0.03214997 0.005323946 -0.225401 0.03214997 0.00236386 -0.225421 0.03214997 0.001144647 -0.227324 0.03214997 0.004813671 -0.226564 0.03214997 0.003152251 -0.225686 0.03214997 0.002832233 -0.227252 0.03214997 0.001166462 -0.227542 0.03214997 -0.002081334 -0.220649 0.03214997 -0.003063499 -0.222747 0.03214997 -0.004426717 -0.220831 0.03214997 -0.002636134 -0.225471 0.03214997 -0.00495994 -0.220318 0.03214997 -0.005252957 -0.220736 0.03214997 -0.005008399 -0.220739 0.03214997 -0.00483483 -0.22074 0.03214997 -0.003228127 -0.225931 0.03214997 -0.003708839 -0.226765 0.03214997 -0.00377959 -0.2269729 0.03214997 -0.004464089 -0.224635 0.03214997 -0.005628347 -0.226128 0.03214997 -0.006080389 -0.224449 0.03214997 -0.007109463 -0.225192 0.03214997 -0.007342457 -0.223944 0.03214997 -0.006444394 -0.2149479 0.03214997 -0.00660932 -0.214133 0.03214997 -0.006050348 -0.212713 0.03214997 -0.007807612 -0.213033 0.03214997 -0.009058177 -0.216786 0.03214997 -0.009461224 -0.216651 0.03214997 -0.01005065 -0.213737 0.03214997 -8.25785e-4 -0.209735 0.03214997 -0.00156182 -0.2089329 0.03214997 -0.00138092 -0.208121 0.03214997 -8.65998e-4 -0.205398 0.03214997 -0.001545846 -0.207306 0.03214997 -0.002028048 -0.206628 0.03214997 -0.001803219 -0.20434 0.03214997 -0.002057194 -0.209601 0.03214997 -0.001074969 -0.211901 0.03214997 -0.003609418 -0.210088 0.03214997 -0.003776669 -0.210032 0.03214997 -0.005816876 -0.210683 0.03214997 -0.003570377 -0.20611 0.03214997 -0.003325819 -0.206113 0.03214997 -0.003160774 -0.204679 0.03214997 -0.004987239 -0.20691 0.03214997 -0.005217134 -0.20547 0.03214997 -0.005332946 -0.207666 0.03214997 -0.005013823 -0.209253 0.03214997 0.003708839 -0.205035 0.03214997 0.00562638 -0.205689 0.03214997 0.003228127 -0.205869 0.03214997 0.0063923 -0.210565 0.03214997 0.007449269 -0.206927 0.03214997 0.006247878 -0.206008 0.03214997 0.005700111 -0.207177 0.03214997 0.005291998 -0.207086 0.03214997 0.001954972 -0.2122499 0.03214997 0.00483483 -0.2110599 0.03214997 0.002204179 -0.210083 0.03214997 0.003433942 -0.210232 0.03214997 0.00404644 -0.210795 0.03214997 -0.007699429 -0.20709 0.03214997 -0.007477223 -0.206901 0.03214997 -0.005750238 -0.205711 0.03214997 -0.007073104 -0.2080889 0.03214997 -0.006943285 -0.209031 0.03214997 -0.005643963 -0.2091799 0.03214997 -0.006342232 -0.210698 0.03214997 -0.007753968 -0.210749 0.03214997 -0.0066666 -0.210956 0.03214997 -0.008286237 -0.211071 0.03214997 -0.008556425 -0.212424 0.03214997 -0.006758034 -0.21175 0.03214997 -0.006500601 -0.2120749 0.03214997 -0.006115436 -0.212227 0.03214997 -0.0095281 -0.211399 0.03214997 -0.008633792 -0.212938 0.03214997 -0.01106625 -0.212136 0.03214997 -0.01046556 -0.211179 0.03214997 -0.01103436 -0.21201 0.03214997 -0.009409606 -0.218483 0.03214997 -0.01030129 -0.21812 0.03214997 -0.01159828 -0.217057 0.03214997 -0.008672833 -0.216915 0.03214997 -0.007615208 -0.219201 0.03214997 -0.008388638 -0.219923 0.03214997 -0.007357716 -0.2195259 0.03214997 -0.006789743 -0.218088 0.03214997 -0.009122133 -0.217342 0.03214997 -0.007523775 -0.218407 0.03214997 -0.009269177 -0.21862 0.03214997 -0.008721172 -0.219156 0.03214997 -0.009320914 -0.222603 0.03214997 -0.006899535 -0.220095 0.03214997 -0.008662104 -0.2219009 0.03214997 -0.00831753 -0.221002 0.03214997 -0.008338272 -0.220039 0.03214997 0.001915633 -0.225009 0.03214997 8.65998e-4 -0.226402 0.03214997 0.006941676 -0.222757 0.03214997 0.006640434 -0.225533 0.03214997 0.007555246 -0.224545 0.03214997 0.007180452 -0.221825 0.03214997 0.006818771 -0.220459 0.03214997 0.01103246 -0.2196609 0.03214997 0.005932569 -0.221163 0.03214997 0.0095281 -0.220401 0.03214997 0.007427334 -0.218594 0.03214997 0.006814777 -0.218031 0.03214997 0.006483972 -0.217268 0.03214997 0.006616055 -0.21417 0.03214997 0.008215725 -0.218858 0.03214997 0.009767889 -0.218371 0.03214997 0.0116716 -0.216714 0.03214997 0.006837844 -0.21568 0.03214997 0.01163208 -0.214747 0.03214997 0.006674051 -0.213666 0.03214997 0.007675945 -0.213008 0.03214997 0.007523775 -0.213393 0.03214997 0.007199406 -0.213651 0.03214997 0.006789743 -0.213712 0.03214997 0.007615208 -0.212599 0.03214997 0.00831753 -0.210798 0.03214997 0.008338272 -0.2117609 0.03214997 0.008721172 -0.212644 0.03214997 0.007660746 -0.212906 0.03214997 0.0091663 -0.213079 0.03214997 0.009409606 -0.213317 0.03214997 0.006849527 -0.21214 0.03214997 0.00702244 -0.210637 0.03214997 0.00697261 -0.212122 0.03214997 0.007357716 -0.212274 0.03214997 0.009325325 -0.2088339 0.03214997 0.009498715 -0.209069 0.03214997 0.009320914 -0.209197 0.03214997 5.38957e-4 -0.207715 0.03214997 3.80596e-4 -0.209092 0.03214997 5.8426e-4 -0.206609 0.03214997 0.001175343 -0.209183 0.03214997 0.002636134 -0.206329 0.03214997 0.00246787 -0.2064599 0.03214997 0.001333713 -0.207807 0.03214997 0.005290031 -0.220686 0.03214997 0.005766868 -0.221552 0.03214997 0.005705833 -0.2196339 0.03214997 0.004110753 -0.218864 0.03214997 0.001206219 -0.218758 0.03214997 0.006386995 -0.210572 0.03214997 0.006563007 -0.2121829 0.03214997 0.005662739 -0.210981 0.03214997 0.005010485 -0.211043 0.03214997 0.004833579 -0.212581 0.03214997 0.006238639 -0.21244 0.03214997 0.006124496 -0.212729 0.03214997 0.001823723 -0.2133899 0.03214997 0.002187728 -0.21366 0.03214997 0.006086409 -0.212825 0.03214997 0.006147205 -0.213235 0.03214997 -0.005705833 -0.212166 0.03214997 -0.003953576 -0.21157 0.03214997 -0.005229294 -0.211524 0.03214997 -0.005244433 -0.211421 0.03214997 -0.001823723 -0.21841 0.03214997 0.006115436 -0.219573 0.03214997 0.006050348 -0.219087 0.03214997 0.004676461 -0.2139469 0.03214997 0.006404638 -0.213559 0.03214997 3.60005e-4 -0.2127709 0.03214997 -3.80596e-4 -0.222708 0.03214997 -0.002524197 -0.224498 0.03214997 -9.48586e-4 -0.224146 0.03214997 -0.001651883 -0.223259 0.03214997 -0.001591145 -0.2236689 0.03214997 5.0578e-4 -0.224847 0.03214997 -0.006147205 -0.218565 0.03214997 -0.004676461 -0.217853 0.03214997 -0.006849527 -0.21966 0.03344994 -0.006849527 -0.21966 0.03214997 -0.006563007 -0.219617 0.03344994 -0.006563007 -0.219617 0.03214997 -0.006238639 -0.2193599 0.03344994 -0.006238639 -0.2193599 0.03214997 -0.006086409 -0.218975 0.03344994 -0.006086409 -0.218975 0.03214997 -0.006674051 -0.218134 0.03214997 -0.007199406 -0.218149 0.03214997 -0.007523775 -0.218407 0.03344994 -0.007675945 -0.218792 0.03214997 -0.00697261 -0.219678 0.03214997 -0.01006704 -0.22314 0.03344994 0.00596863 -0.210808 0.03344994 -5.71437e-4 -0.220867 0.03344994 9.69285e-4 -0.220818 0.03344994 0.004871785 -0.214775 0.03344994 0.004766821 -0.221255 0.03344994 0.003240168 -0.219708 0.03344994 -9.22929e-4 -0.210579 0.03344994 0.001242458 -0.211057 0.03344994 -0.003728508 -0.2125689 0.03344994 -0.004673182 -0.217678 0.03344994 -0.004916608 -0.214991 0.03344994 -0.004489064 -0.213698 0.03344994 -0.002060711 -0.2204689 0.03344994 0.001236259 -0.228238 0.03344994 0.003121376 -0.227901 0.03344994 0.001420557 -0.224095 0.03344994 8.25785e-4 -0.222065 0.03344994 0.001428723 -0.223264 0.03344994 8.65998e-4 -0.226402 0.03344994 0.003152251 -0.225686 0.03344994 0.003980159 -0.225607 0.03344994 0.004932045 -0.227277 0.03344994 0.004704415 -0.225198 0.03344994 0.005119621 -0.227178 0.03344994 0.005380749 -0.223718 0.03344994 0.005215823 -0.222903 0.03344994 0.004660129 -0.222182 0.03344994 0.005787491 -0.221372 0.03344994 0.004957854 -0.222541 0.03344994 8.84962e-4 -0.220808 0.03344994 9.73499e-4 -0.220781 0.03344994 0.002107918 -0.222213 0.03344994 0.002397894 -0.221957 0.03344994 -0.002636134 -0.225471 0.03344994 -0.006586432 -0.226362 0.03344994 -0.005291998 -0.224714 0.03344994 -0.003708839 -0.226765 0.03344994 -0.0032444 -0.223559 0.03344994 -0.003063499 -0.222747 0.03344994 -0.004426717 -0.220831 0.03344994 -0.003710627 -0.221254 0.03344994 -0.003486394 -0.221569 0.03344994 -0.007386624 -0.2258599 0.03344994 -0.006692886 -0.223887 0.03344994 -0.006336331 -0.2212409 0.03344994 -0.007091462 -0.213455 0.03344994 -0.006616055 -0.21763 0.03344994 -0.006444394 -0.2149479 0.03344994 -0.006625235 -0.2157599 0.03344994 -0.007120668 -0.216428 0.03344994 -0.008672833 -0.216915 0.03344994 -0.01007378 -0.2160879 0.03344994 -0.01195359 -0.212603 0.03344994 -0.01039636 -0.214494 0.03344994 -0.01005065 -0.213737 0.03344994 -0.008615672 -0.21294 0.03344994 -0.00138092 -0.208121 0.03344994 -0.002691447 -0.211686 0.03344994 -0.003609418 -0.210088 0.03344994 -0.00278151 -0.210009 0.03344994 -0.001545846 -0.207306 0.03344994 -3.93879e-4 -0.20598 0.03344994 -0.002028048 -0.206628 0.03344994 -0.004397809 -0.209823 0.03344994 -0.005741119 -0.210025 0.03344994 -0.005010306 -0.209261 0.03344994 -0.001236259 -0.203562 0.03344994 -0.004038631 -0.204215 0.03344994 -0.004282355 -0.2063339 0.03344994 -0.004363775 -0.20636 0.03344994 -0.004932045 -0.204523 0.03344994 -0.005119621 -0.204622 0.03344994 -0.005323946 -0.206399 0.03344994 -0.00451374 -0.206492 0.03344994 0.003103137 -0.209469 0.03344994 0.003111302 -0.208638 0.03344994 0.00483483 -0.2110599 0.03344994 0.00404644 -0.210795 0.03344994 0.003433942 -0.210232 0.03344994 0.006532192 -0.207763 0.03344994 0.006898403 -0.208277 0.03344994 0.006882429 -0.209904 0.03344994 0.003457009 -0.207881 0.03344994 0.004080474 -0.207331 0.03344994 0.003228127 -0.205869 0.03344994 -0.00785607 -0.206337 0.03344994 -0.007073104 -0.2080889 0.03344994 -0.005332946 -0.207666 0.03344994 -0.007589876 -0.206138 0.03344994 0.00154072 -0.206719 0.03344994 5.8426e-4 -0.206609 0.03344994 0.008832156 -0.2071959 0.03344994 0.007546782 -0.206079 0.03344994 0.006416201 -0.2075999 0.03344994 0.007386624 -0.20594 0.03344994 0.006342709 -0.207556 0.03344994 0.006586432 -0.205438 0.03344994 0.004873871 -0.207082 0.03344994 0.00400573 -0.204165 0.03344994 0.007063329 -0.209092 0.03344994 0.01006704 -0.20866 0.03344994 0.009320914 -0.209197 0.03344994 0.007342457 -0.2078559 0.03344994 0.008662104 -0.209899 0.03344994 0.007615208 -0.212599 0.03344994 0.008338272 -0.2117609 0.03344994 0.008335769 -0.2116439 0.03344994 0.007357716 -0.212274 0.03344994 0.00697261 -0.212122 0.03344994 0.01030129 -0.21368 0.03344994 0.01126408 -0.213679 0.03344994 0.007199406 -0.213651 0.03344994 0.006616055 -0.21417 0.03344994 0.01232194 -0.214826 0.03344994 0.007523775 -0.213393 0.03344994 0.007675945 -0.213008 0.03344994 0.01026326 -0.217703 0.03344994 0.01044416 -0.216891 0.03344994 0.01027929 -0.216076 0.03344994 0.008254766 -0.2148799 0.03344994 0.0117563 -0.219744 0.03344994 0.008215725 -0.218858 0.03344994 0.006050348 -0.219087 0.03344994 0.006814777 -0.218031 0.03344994 0.006492137 -0.216436 0.03344994 0.007461309 -0.21513 0.03344994 0.007180452 -0.221825 0.03344994 0.006818771 -0.220459 0.03344994 0.005992352 -0.219591 0.03344994 0.01046556 -0.220621 0.03344994 0.006943285 -0.222769 0.03344994 0.005643963 -0.22262 0.03344994 0.006625056 -0.226382 0.03344994 -0.001175343 -0.222617 0.03344994 -3.80596e-4 -0.222708 0.03344994 -1.2316e-4 -0.223033 0.03344994 -2.1459e-4 -0.223827 0.03344994 -5.8426e-4 -0.2251909 0.03344994 -0.001333713 -0.223993 0.03344994 -0.002204179 -0.221717 0.03344994 -0.001651883 -0.223259 0.03344994 -0.007546782 -0.225721 0.03344994 -0.009764075 -0.222922 0.03344994 -0.009320914 -0.222603 0.03344994 -0.009822487 -0.22343 0.03344994 -0.008832156 -0.224604 0.03344994 -0.00697261 -0.219678 0.03344994 -0.007199406 -0.218149 0.03344994 -0.007675945 -0.218792 0.03344994 -0.006878912 -0.219915 0.03344994 -0.008471548 -0.219732 0.03344994 -0.008338272 -0.220039 0.03344994 -0.00702244 -0.221163 0.03344994 -0.008321762 -0.221013 0.03344994 -0.007357716 -0.2195259 0.03344994 -0.007615208 -0.219201 0.03344994 -0.009269177 -0.21862 0.03344994 -0.009409606 -0.218483 0.03344994 -0.009122133 -0.217342 0.03344994 -0.01232194 -0.216974 0.03344994 -0.008577227 -0.211248 0.03344994 -0.008556425 -0.212424 0.03344994 -0.01046556 -0.211179 0.03344994 -0.0117563 -0.212056 0.03344994 -0.008409321 -0.2111459 0.03344994 -0.006758034 -0.21175 0.03344994 -0.006818771 -0.211341 0.03344994 -0.0066666 -0.210956 0.03344994 -0.007753968 -0.210749 0.03344994 -0.006342232 -0.210698 0.03344994 -0.006941676 -0.209043 0.03344994 -0.006050348 -0.212713 0.03344994 -0.005992352 -0.212209 0.03344994 -0.006115436 -0.212227 0.03344994 0.005381464 -0.219891 0.03344994 0.005229294 -0.2202759 0.03344994 0.006404638 -0.213559 0.03344994 0.006386995 -0.210572 0.03344994 0.005904614 -0.211364 0.03344994 0.006563007 -0.2121829 0.03344994 0.006925284 -0.211482 0.03344994 0.006849527 -0.21214 0.03344994 0.005595386 -0.214052 0.03344994 0.006147205 -0.213235 0.03344994 0.006086409 -0.212825 0.03344994 0.006238639 -0.21244 0.03344994 -0.005029678 -0.21283 0.03344994 -0.004720449 -0.210142 0.03344994 -0.005290031 -0.211114 0.03344994 -0.005932569 -0.210637 0.03344994 -0.005816876 -0.210683 0.03344994 -0.005547463 -0.21079 0.03344994 -0.006404638 -0.218241 0.03344994 -0.006147205 -0.218565 0.03344994 -0.005858242 -0.220033 0.03344994 0.006789743 -0.213712 0.03344994 0.006674051 -0.213666 0.03344994 0.005029678 -0.21897 0.03344994 0.005705833 -0.2196339 0.03344994 0.001333713 -0.207807 0.03344994 0.002524197 -0.207302 0.03344994 0.002107083 -0.210928 0.03344994 -5.0578e-4 -0.206953 0.03344994 5.38957e-4 -0.207715 0.03344994 0.001499712 -0.208926 0.03344994 1.2316e-4 -0.2087669 0.03344994 -0.005705833 -0.212166 0.03344994 -0.005595386 -0.217748 0.03344994 -0.006674051 -0.218134 0.03344994 -0.006789743 -0.218088 0.03344994 -0.006625056 -0.205418 0.03344994 -0.0074265 -0.20415 0.03194999 -0.007220447 -0.204041 0.03194999 -0.005528688 -0.2031469 0.03194999 -0.005167245 -0.203022 0.03194999 -0.003121376 -0.203899 0.03344994 -0.002975761 -0.202354 0.03194999 -0.008160054 -0.2065629 0.03344994 -0.007555246 -0.207255 0.03214997 -0.007914483 -0.206844 0.03344994 -0.001842498 -0.204346 0.02574998 0.01167428 -0.216675 0.02574998 -0.0108543 -0.2202669 0.02574998 -0.01086908 -0.22023 0.02574998 -0.009498715 -0.2227309 0.03214997 -0.003352999 -0.227109 0.02824997 -0.003352999 -0.227109 0.02574998 -0.003391087 -0.227098 0.02574998 -0.001166462 -0.204258 0.03194999 -7.2009e-4 -0.204222 0.02574998 -7.2009e-4 -0.204222 0.02824997 0.004381179 -0.205051 0.03214997 0.00377959 -0.204827 0.03214997 0.00377959 -0.204827 0.03194999 0.002373635 -0.204443 0.03194999 0.002373635 -0.204443 0.02824997 0.0108543 -0.211533 0.02824997 0.01043719 -0.210613 0.02824997 0.009325325 -0.2088339 0.02824997 0.01122474 -0.212599 0.02574998 0.01147896 -0.2136369 0.03194999 0.01122474 -0.212599 0.02824997 0.01121348 -0.212561 0.02574998 0.0108543 -0.211533 0.02574998 0.009601771 -0.222585 0.03194999 0.01064115 -0.220764 0.02824997 0.01066529 -0.2207109 0.03194999 0.009579002 -0.222618 0.02574998 0.006673097 -0.22551 0.02574998 0.006640434 -0.225533 0.02574998 0.007699429 -0.2247099 0.03214997 0.001166462 -0.227542 0.03194999 7.2009e-4 -0.227578 0.02574998 -0.00133711 -0.227523 0.02824997 -0.003391087 -0.227098 0.03194999 7.59753e-4 -0.227575 0.03194999 7.2009e-4 -0.227578 0.02824997 7.59753e-4 -0.227575 0.02574998 0.001842498 -0.227454 0.02824997 -0.004418015 -0.226734 0.02574998 -0.004418015 -0.226734 0.02824997 -0.008654415 -0.223773 0.02574998 -0.008681118 -0.223744 0.02574998 -0.008681118 -0.223744 0.02824997 -0.009921193 -0.222102 0.02824997 -0.009921193 -0.222102 0.03194999 -0.01122474 -0.219201 0.02574998 -0.01122474 -0.219201 0.02824997 -0.01147896 -0.218163 0.03214997 -0.0108543 -0.2202669 0.02824997 -0.01086908 -0.22023 0.03194999 -0.01146769 -0.2182199 0.02824997 -0.01169759 -0.216135 0.02824997 -0.01066529 -0.211089 0.03214997 -0.01018208 -0.210137 0.02824997 -0.009579002 -0.209182 0.02574998 -0.008963882 -0.2083809 0.02824997 -0.009579002 -0.209182 0.02824997 -0.01016235 -0.210102 0.03194999 -0.01016235 -0.210102 0.02574998 -0.01018208 -0.210137 0.02574998 0.003158807 -0.2271389 0.03214997 0.002832233 -0.227252 0.02824997 0.004813671 -0.226564 0.02824997 0.005715548 -0.226109 0.02574998 0.005715548 -0.226109 0.02824997 0.006673097 -0.22551 0.02824997 0.008253753 -0.224192 0.02824997 0.007699429 -0.2247099 0.03194999 0.008253753 -0.224192 0.03194999 0.009579002 -0.222618 0.02824997 0.009601771 -0.222585 0.02574998 0.01018208 -0.2216629 0.02824997 0.01018208 -0.2216629 0.02574998 0.00521636 -0.226337 0.03214997 0.01133865 -0.218785 0.02824997 0.01133865 -0.218785 0.03214997 0.0115453 -0.217797 0.02824997 0.01147896 -0.2136369 0.03214997 0.01162946 -0.214617 0.02824997 0.01167428 -0.216675 0.02824997 0.0116716 -0.216714 0.02574998 0.0115453 -0.217797 0.02574998 0.008681118 -0.208056 0.02574998 0.008681118 -0.208056 0.02824997 0.007913768 -0.207282 0.03214997 0.007913768 -0.207282 0.02574998 0.007884442 -0.207256 0.02824997 0.007884442 -0.207256 0.02574998 0.004381179 -0.205051 0.02574998 0.004418015 -0.205066 0.02574998 0.004418015 -0.205066 0.02824997 0.006247878 -0.206008 0.02824997 0.003352999 -0.2046909 0.02824997 0.003352999 -0.2046909 0.02574998 -0.001842498 -0.204346 0.02824997 -0.001803219 -0.20434 0.02574998 2.89872e-4 -0.204204 0.02824997 2.89872e-4 -0.204204 0.03194999 -0.005715548 -0.205691 0.02574998 -0.005715548 -0.205691 0.02824997 -0.007477223 -0.206901 0.02824997 -0.003838419 -0.204848 0.03214997 -0.003838419 -0.204848 0.02824997 -0.005750238 -0.205711 0.02574998 -0.006673097 -0.20629 0.02824997 -0.006673097 -0.20629 0.02574998 -0.01155155 -0.214043 0.02574998 -0.0115453 -0.214003 0.02574998 -0.01169759 -0.216135 0.03214997 -0.01066529 -0.211089 0.03194999 -0.01103436 -0.21201 0.02824997 -0.0115453 -0.214003 0.02824997 -0.01155155 -0.214043 0.03214997 -0.01167428 -0.215125 0.02824997 -0.01167428 -0.215125 0.02574998 -0.008654415 -0.223773 0.03214997 -0.007109463 -0.225192 0.02824997 -0.009498715 -0.2227309 0.03194999 -0.007884442 -0.224544 0.02824997 -0.007884442 -0.224544 0.02574998 -0.005336046 -0.226312 0.02824997 -0.005336046 -0.226312 0.03214997 0.002175271 -0.228412 0.02574998 0.002341449 -0.228891 0.02674996 0.001842498 -0.227454 0.02574998 0.002341449 -0.228891 0.02824997 0.00383979 -0.2025409 0.03024995 0.001588582 -0.202091 0.03024995 -7.05945e-4 -0.202018 0.03024995 -0.002981185 -0.202323 0.02239996 -0.007227957 -0.2040269 0.03024995 -0.007227957 -0.2040269 0.02239996 -0.009083628 -0.205379 0.03024995 -0.01069146 -0.207017 0.02239996 -0.01069146 -0.207017 0.03024995 -0.01200765 -0.208898 0.02239996 -0.01200765 -0.208898 0.03024995 -0.01299637 -0.21097 0.03024995 -0.01363056 -0.213177 0.02239996 -0.01363056 -0.213177 0.03024995 -0.01389288 -0.215457 0.02239996 -0.01377636 -0.21775 0.02239996 -0.01377636 -0.21775 0.03024995 -0.01328396 -0.219992 0.03024995 -0.01328396 -0.219992 0.02239996 -0.01242917 -0.222123 0.02239996 -0.01123547 -0.224084 0.02239996 -0.009735226 -0.225821 0.03024995 -0.007969439 -0.227288 0.03024995 -0.001588582 -0.229709 0.03024995 7.05945e-4 -0.229782 0.03024995 0.002981185 -0.229477 0.02239996 0.005175173 -0.228801 0.02239996 0.002981185 -0.229477 0.03024995 0.009083628 -0.2264209 0.03024995 0.01069146 -0.224783 0.02239996 0.01200765 -0.2229019 0.02239996 0.01299637 -0.22083 0.03024995 0.01377636 -0.2140499 0.02239996 0.01328396 -0.211808 0.03024995 0.01242917 -0.209677 0.03024995 0.01123547 -0.207716 0.02239996 0.007969439 -0.204512 0.02239996 0.007969439 -0.204512 0.03024995 0.005986213 -0.203355 0.03024995 0.001588582 -0.202091 0.02239996 0.001508533 -0.202786 0.02239996 0.001508533 -0.202786 0.03024995 0.003703057 -0.20323 0.03024995 0.007712364 -0.205187 0.02239996 0.005791008 -0.204038 0.03024995 0.007712364 -0.205187 0.03024995 0.009411871 -0.206645 0.02239996 0.009411871 -0.206645 0.03024995 0.01084059 -0.208369 0.03024995 0.01195746 -0.210309 0.03024995 0.01273036 -0.21241 0.03024995 0.01313698 -0.214612 0.02239996 0.01313698 -0.214612 0.03024995 0.01316565 -0.2168509 0.02239996 0.01316565 -0.2168509 0.03024995 0.01281565 -0.219062 0.02239996 0.01281565 -0.219062 0.03024995 0.012097 -0.221182 0.03024995 0.01103019 -0.223151 0.03024995 0.009646117 -0.224911 0.03024995 0.007984578 -0.226411 0.03024995 0.007984578 -0.226411 0.02239996 0.006093323 -0.227609 0.03024995 0.00402677 -0.228471 0.03024995 0.001844346 -0.228971 0.02239996 0.001844346 -0.228971 0.03024995 -3.91056e-4 -0.229094 0.03024995 -0.002615213 -0.228838 0.02239996 -0.002615213 -0.228838 0.03024995 -0.004764199 -0.22821 0.03024995 -0.006776094 -0.227228 0.02239996 -0.006776094 -0.227228 0.03024995 -0.008593082 -0.22592 0.02239996 -0.008593082 -0.22592 0.03024995 -0.01016288 -0.224324 0.03024995 -0.01144027 -0.222485 0.02239996 -0.01144027 -0.222485 0.03024995 -0.01238858 -0.220457 0.03024995 -0.01319885 -0.216069 0.02239996 -0.01298046 -0.218297 0.03024995 -0.01303768 -0.213836 0.02239996 -0.01319885 -0.216069 0.03024995 -0.01303768 -0.213836 0.03024995 -0.01250135 -0.211663 0.03024995 -0.01160538 -0.2096109 0.03024995 -0.01037555 -0.20774 0.03024995 -0.008847236 -0.206104 0.03024995 -0.007064402 -0.204749 0.03024995 -0.005078315 -0.203716 0.02239996 -0.005078315 -0.203716 0.03024995 -0.002946197 -0.203033 0.02239996 -0.002946197 -0.203033 0.03024995 -7.293e-4 -0.20272 0.02239996 -7.293e-4 -0.20272 0.03024995 -3.91056e-4 -0.229094 0.02239996 7.05945e-4 -0.229782 0.02239996 -0.001588582 -0.229709 0.02239996 -0.00383979 -0.229259 0.02239996 -0.005986213 -0.2284449 0.02239996 -0.004764199 -0.22821 0.02239996 -0.007969439 -0.227288 0.02239996 -0.009735226 -0.225821 0.02239996 -0.01016288 -0.224324 0.02239996 -0.01238858 -0.220457 0.02239996 -0.01298046 -0.218297 0.02239996 -0.01250135 -0.211663 0.02239996 -0.01299637 -0.21097 0.02239996 -0.01160538 -0.2096109 0.02239996 -0.01037555 -0.20774 0.02239996 -0.008847236 -0.206104 0.02239996 -0.009083628 -0.205379 0.02239996 -0.007064402 -0.204749 0.02239996 -0.005175173 -0.2029989 0.02239996 -7.05945e-4 -0.202018 0.02239996 0.003703057 -0.20323 0.02239996 0.005791008 -0.204038 0.02239996 0.00383979 -0.2025409 0.02239996 0.005986213 -0.203355 0.02239996 0.009735226 -0.205979 0.02239996 0.01084059 -0.208369 0.02239996 0.01195746 -0.210309 0.02239996 0.01242917 -0.209677 0.02239996 0.01328396 -0.211808 0.02239996 0.01273036 -0.21241 0.02239996 0.01389288 -0.216343 0.02239996 0.012097 -0.221182 0.02239996 0.01363056 -0.2186239 0.02239996 0.01299637 -0.22083 0.02239996 0.01103019 -0.223151 0.02239996 0.009646117 -0.224911 0.02239996 0.009083628 -0.2264209 0.02239996 0.006093323 -0.227609 0.02239996 0.00402677 -0.228471 0.02239996 0.007227957 -0.227773 0.02239996 0.189173 -0.103498 0.02974998 0.188344 -0.103172 0.02974998 0.188259 -0.103144 0.02974998 0.187469 -0.103008 0.02974998 0.187023 -0.103006 0.02990305 0.1870239 -0.102975 0.02974998 0.186578 -0.102999 0.02974998 0.186403 -0.103039 0.02990305 0.185792 -0.1031489 0.02990305 0.1856999 -0.103146 0.02974998 0.185189 -0.103307 0.02974998 0.184635 -0.103594 0.02990305 0.184621 -0.103567 0.02974998 0.18409 -0.103897 0.02974998 0.184108 -0.1039209 0.02990305 0.183605 -0.10429 0.02974998 0.183196 -0.104761 0.02990305 0.18342 -0.104483 0.02974998 0.1828539 -0.105172 0.02974998 0.1825219 -0.105801 0.02990305 0.182494 -0.105788 0.02974998 0.1821269 -0.106976 0.02990305 0.182043 -0.107591 0.02990305 0.182012 -0.1076779 0.02974998 0.182007 -0.108214 0.02974998 0.182258 -0.109432 0.02990305 0.182079 -0.108834 0.02974998 0.182229 -0.109441 0.02974998 0.18248 -0.110011 0.02990305 0.182579 -0.11026 0.02974998 0.183134 -0.111064 0.02990305 0.183059 -0.111011 0.02974998 0.183534 -0.1115429 0.02974998 0.184386 -0.112189 0.02974998 0.18455 -0.112259 0.02990305 0.18511 -0.112529 0.02990305 0.1850979 -0.112557 0.02974998 0.185183 -0.112586 0.02974998 0.18569 -0.112756 0.02974998 0.18604 -0.112827 0.02974998 0.186303 -0.112879 0.02974998 0.186926 -0.112925 0.02974998 0.187813 -0.112844 0.02974998 0.187546 -0.112861 0.02990305 0.18875 -0.112565 0.02990305 0.189314 -0.1123059 0.02990305 0.18948 -0.112239 0.02974998 0.190324 -0.111587 0.02990305 0.1907539 -0.1111389 0.02990305 0.191124 -0.11064 0.02990305 0.191662 -0.109524 0.02990305 0.191455 -0.110112 0.02974998 0.191691 -0.109534 0.02974998 0.191889 -0.108665 0.02974998 0.191823 -0.108924 0.02990305 0.191906 -0.108309 0.02990305 0.191828 -0.106893 0.02974998 0.1916919 -0.106468 0.02990305 0.191721 -0.106459 0.02974998 0.191561 -0.106043 0.02974998 0.191497 -0.105876 0.02974998 0.1911759 -0.105342 0.02990305 0.19115 -0.105253 0.02974998 0.1905969 -0.1045539 0.02974998 0.1903949 -0.1043789 0.02990305 0.190815 -0.104836 0.02990305 0.190748 -0.10489 0.03003275 0.191469 -0.105889 0.02990305 0.191841 -0.107071 0.02990305 0.1919119 -0.107688 0.02990305 0.19182 -0.108303 0.03003275 0.191738 -0.108907 0.03003275 0.191428 -0.110099 0.02990305 0.189842 -0.111979 0.02990305 0.189792 -0.111908 0.03003275 0.1892729 -0.11223 0.03003275 0.188719 -0.112484 0.03003275 0.188157 -0.112751 0.02990305 0.1881369 -0.112667 0.03003275 0.186926 -0.1128939 0.02990305 0.186927 -0.112808 0.03003275 0.186307 -0.1128489 0.02990305 0.185698 -0.112727 0.02990305 0.185721 -0.112643 0.03003275 0.185142 -0.112449 0.03003275 0.184593 -0.112184 0.03003275 0.184029 -0.111921 0.02990305 0.184081 -0.111852 0.03003275 0.183555 -0.111521 0.02990305 0.183615 -0.111458 0.03003275 0.182774 -0.110558 0.02990305 0.182848 -0.110513 0.03003275 0.18234 -0.109406 0.03003275 0.1821089 -0.108829 0.02990305 0.1821939 -0.108813 0.03003275 0.1820369 -0.108212 0.02990305 0.182124 -0.108207 0.03003275 0.1822119 -0.106993 0.03003275 0.182288 -0.106376 0.02990305 0.18237 -0.106404 0.03003275 0.1826 -0.105839 0.03003275 0.182826 -0.10526 0.02990305 0.1828989 -0.105307 0.03003275 0.183262 -0.104817 0.03003275 0.1836259 -0.104313 0.02990305 0.183684 -0.104376 0.03003275 0.184677 -0.10367 0.03003275 0.1852 -0.103335 0.02990305 0.185231 -0.103416 0.03003275 0.186413 -0.103125 0.03003275 0.187643 -0.103051 0.02990305 0.187631 -0.103137 0.03003275 0.188252 -0.103173 0.02990305 0.18884 -0.103371 0.02990305 0.189399 -0.103641 0.02990305 0.188807 -0.103451 0.03003275 0.189357 -0.103716 0.03003275 0.18992 -0.103978 0.02990305 0.190245 -0.104535 0.03011959 0.191102 -0.105387 0.03003275 0.190647 -0.104972 0.03011959 0.19139 -0.105925 0.03003275 0.191609 -0.106494 0.03003275 0.191273 -0.105979 0.03011959 0.191486 -0.106533 0.03011959 0.1917549 -0.107087 0.03003275 0.191628 -0.10711 0.03011959 0.191826 -0.107693 0.03003275 0.19169 -0.1082929 0.03011959 0.1915799 -0.1094959 0.03003275 0.19135 -0.110061 0.03003275 0.191051 -0.110593 0.03003275 0.191233 -0.110005 0.03011959 0.190942 -0.110523 0.03011959 0.190687 -0.111083 0.03003275 0.1902649 -0.111524 0.03003275 0.189212 -0.112115 0.03011959 0.188672 -0.112363 0.03011959 0.188106 -0.112541 0.03011959 0.187536 -0.112775 0.03003275 0.1863189 -0.112763 0.03003275 0.186928 -0.112678 0.03011959 0.185754 -0.112518 0.03011959 0.185191 -0.112329 0.03011959 0.184657 -0.112071 0.03011959 0.183705 -0.111365 0.03011959 0.183202 -0.11101 0.03003275 0.183302 -0.1109279 0.03011959 0.182958 -0.110444 0.03011959 0.182559 -0.109975 0.03003275 0.182253 -0.108201 0.03011959 0.18213 -0.107597 0.03003275 0.182259 -0.107607 0.03011959 0.182339 -0.107018 0.03011959 0.182717 -0.105895 0.03011959 0.183008 -0.105378 0.03011959 0.183362 -0.104901 0.03011959 0.184158 -0.103992 0.03003275 0.184738 -0.103785 0.03011959 0.185813 -0.103233 0.03003275 0.187023 -0.103092 0.03003275 0.188229 -0.103257 0.03003275 0.188758 -0.1035709 0.03011959 0.189869 -0.104048 0.03003275 0.189293 -0.103829 0.03011959 0.189791 -0.104152 0.03011959 0.190335 -0.104442 0.03003275 0.1901389 -0.104646 0.03014999 0.190528 -0.105069 0.03014999 0.1909919 -0.105456 0.03011959 0.1908619 -0.1055369 0.03014999 0.191133 -0.106043 0.03014999 0.19134 -0.106579 0.03014999 0.191477 -0.107137 0.03014999 0.191696 -0.107699 0.03011959 0.191543 -0.107708 0.03014999 0.191538 -0.108282 0.03014999 0.19161 -0.108882 0.03011959 0.19146 -0.108851 0.03014999 0.191312 -0.109406 0.03014999 0.191457 -0.109455 0.03011959 0.1910949 -0.109938 0.03014999 0.190813 -0.110439 0.03014999 0.1905879 -0.110999 0.03011959 0.1904709 -0.1109009 0.03014999 0.190177 -0.111428 0.03011959 0.189716 -0.111802 0.03011959 0.190074 -0.111316 0.03014999 0.189628 -0.111677 0.03014999 0.189139 -0.111981 0.03014999 0.188617 -0.11222 0.03014999 0.187521 -0.112646 0.03011959 0.188069 -0.112392 0.03014999 0.1875039 -0.112494 0.03014999 0.186336 -0.112635 0.03011959 0.18693 -0.112525 0.03014999 0.186357 -0.112483 0.03014999 0.1857939 -0.11237 0.03014999 0.185249 -0.112187 0.03014999 0.184732 -0.111937 0.03014999 0.1842499 -0.111625 0.03014999 0.184158 -0.111748 0.03011959 0.1838099 -0.111254 0.03014999 0.183421 -0.110831 0.03014999 0.183088 -0.110363 0.03014999 0.182677 -0.109921 0.03011959 0.182816 -0.109857 0.03014999 0.182464 -0.109367 0.03011959 0.18261 -0.1093209 0.03014999 0.182322 -0.10879 0.03011959 0.182473 -0.108763 0.03014999 0.182406 -0.108192 0.03014999 0.182412 -0.107618 0.03014999 0.1824899 -0.107049 0.03014999 0.182493 -0.106445 0.03011959 0.182638 -0.106494 0.03014999 0.182855 -0.105962 0.03014999 0.183136 -0.105461 0.03014999 0.183479 -0.104999 0.03014999 0.183772 -0.104472 0.03011959 0.183876 -0.104584 0.03014999 0.184233 -0.104098 0.03011959 0.1843219 -0.104223 0.03014999 0.18481 -0.103919 0.03014999 0.185333 -0.10368 0.03014999 0.1852779 -0.103537 0.03011959 0.185844 -0.103359 0.03011959 0.185881 -0.103508 0.03014999 0.186428 -0.103254 0.03011959 0.187021 -0.103222 0.03011959 0.186446 -0.103406 0.03014999 0.187613 -0.103265 0.03011959 0.18702 -0.103375 0.03014999 0.188196 -0.103382 0.03011959 0.187593 -0.103417 0.03014999 0.188156 -0.10353 0.03014999 0.188701 -0.103713 0.03014999 0.189218 -0.103963 0.03014999 0.1897 -0.104275 0.03014999 0.188345 -0.103168 0.02884995 0.188852 -0.103343 0.02974998 0.189177 -0.103489 0.02884995 0.189414 -0.103614 0.02974998 0.187647 -0.103021 0.02974998 0.187469 -0.103 0.02884995 0.1857849 -0.103119 0.02974998 0.186578 -0.102991 0.02884995 0.1863999 -0.103008 0.02974998 0.185698 -0.103142 0.02884995 0.18409 -0.103897 0.02884995 0.1848599 -0.103447 0.02884995 0.184864 -0.103455 0.02974998 0.182801 -0.105243 0.02974998 0.183173 -0.104741 0.02974998 0.18242 -0.1059499 0.02884995 0.182427 -0.105953 0.02974998 0.182259 -0.106366 0.02974998 0.182143 -0.106797 0.02974998 0.182097 -0.10697 0.02974998 0.182007 -0.1076779 0.02884995 0.182013 -0.107589 0.02974998 0.182039 -0.108569 0.02884995 0.182048 -0.108568 0.02974998 0.1825709 -0.110264 0.02884995 0.182229 -0.109441 0.02884995 0.182453 -0.110024 0.02974998 0.18367 -0.111658 0.02974998 0.183111 -0.111083 0.02974998 0.182748 -0.110574 0.02974998 0.183665 -0.1116639 0.02884995 0.184011 -0.111946 0.02974998 0.184535 -0.112286 0.02974998 0.186039 -0.112836 0.02884995 0.185181 -0.11259 0.02884995 0.18755 -0.112892 0.02974998 0.187815 -0.112854 0.02884995 0.189329 -0.1123329 0.02974998 0.1887609 -0.112593 0.02974998 0.1886759 -0.1126199 0.02974998 0.188165 -0.112781 0.02974998 0.189859 -0.112003 0.02974998 0.190206 -0.111722 0.02974998 0.190345 -0.1116099 0.02974998 0.190777 -0.111159 0.02974998 0.191332 -0.11035 0.02884995 0.1911489 -0.110657 0.02974998 0.190834 -0.11109 0.02884995 0.1908299 -0.111087 0.02974998 0.1913239 -0.110346 0.02974998 0.191852 -0.10893 0.02974998 0.191871 -0.107066 0.02974998 0.1918359 -0.106891 0.02884995 0.191943 -0.107686 0.02974998 0.191942 -0.107776 0.02974998 0.191937 -0.1083109 0.02974998 0.191569 -0.10604 0.02884995 0.191201 -0.1053259 0.02974998 0.190604 -0.104547 0.02884995 0.189938 -0.103954 0.02974998 0.190416 -0.104357 0.02974998 0.189938 -0.103954 0.02884995 0.1908389 -0.104817 0.02974998 0.182054 -0.10868 0.02039998 0.191896 -0.1072199 0.02039998 0.186245 -0.103029 0.02039998 0.186245 -0.103029 0.02324998 0.191947 -0.107776 0.02324998 0.187815 -0.112854 0.02824997 0.188677 -0.112625 0.02324998 0.188677 -0.112625 0.02824997 0.189485 -0.112246 0.02324998 0.1902109 -0.111728 0.02324998 0.189485 -0.112246 0.02824997 0.190834 -0.11109 0.02324998 0.190834 -0.11109 0.02824997 0.191332 -0.11035 0.02324998 0.191691 -0.109534 0.02324998 0.191691 -0.109534 0.02824997 0.191898 -0.108666 0.02324998 0.191947 -0.107776 0.02824997 0.187705 -0.112871 0.02039998 0.182039 -0.108569 0.02324998 0.18409 -0.103897 0.02324998 0.18409 -0.103897 0.02824997 0.183413 -0.104477 0.02824997 0.183413 -0.104477 0.02324998 0.18285 -0.1051689 0.02324998 0.18242 -0.1059499 0.02324998 0.18242 -0.1059499 0.02824997 0.1821359 -0.106795 0.02324998 0.182007 -0.1076779 0.02324998 0.182007 -0.1076779 0.02824997 0.182054 -0.10868 0.02324998 0.182229 -0.109441 0.02039998 0.1825709 -0.110264 0.02039998 0.1825709 -0.110264 0.02824997 0.183055 -0.111014 0.02039998 0.183665 -0.1116639 0.02039998 0.184381 -0.112196 0.02824997 0.184381 -0.112196 0.02039998 0.185181 -0.11259 0.02039998 0.186039 -0.112836 0.02039998 0.186039 -0.112836 0.02824997 0.186926 -0.112925 0.02039998 0.187705 -0.112871 0.02324998 0.187815 -0.112854 0.02324998 0.191896 -0.1072199 0.02324998 0.1918359 -0.106891 0.02824997 0.1918359 -0.106891 0.02039998 0.191569 -0.10604 0.02039998 0.191569 -0.10604 0.02824997 0.191154 -0.10525 0.02039998 0.190604 -0.104547 0.02039998 0.189938 -0.103954 0.02039998 0.189177 -0.103489 0.02039998 0.189938 -0.103954 0.02824997 0.188345 -0.103168 0.02039998 0.187469 -0.103 0.02039998 0.187469 -0.103 0.02824997 0.186578 -0.102991 0.02039998 0.185698 -0.103142 0.02824997 0.185698 -0.103142 0.02324998 0.1848599 -0.103447 0.02324998 0.184235 -0.111645 0.02824997 0.183665 -0.1116639 0.02824997 0.185181 -0.11259 0.02824997 0.185754 -0.112385 0.02824997 0.18659 -0.112534 0.02824997 0.186926 -0.112925 0.02824997 0.187439 -0.112527 0.02824997 0.189779 -0.111597 0.02824997 0.1902109 -0.111728 0.02824997 0.190907 -0.110338 0.02824997 0.191332 -0.11035 0.02824997 0.191898 -0.108666 0.02824997 0.191504 -0.108756 0.02824997 0.191575 -0.10791 0.02824997 0.19125 -0.106251 0.02824997 0.191154 -0.10525 0.02824997 0.190604 -0.104547 0.02824997 0.189715 -0.104255 0.02824997 0.1889899 -0.103815 0.02824997 0.189177 -0.103489 0.02824997 0.188345 -0.103168 0.02824997 0.186578 -0.102991 0.02824997 0.1848599 -0.103447 0.02824997 0.18285 -0.1051689 0.02824997 0.1821359 -0.106795 0.02824997 0.182375 -0.10799 0.02824997 0.182461 -0.108834 0.02824997 0.182039 -0.108569 0.02824997 0.182229 -0.109441 0.02824997 0.183085 -0.110405 0.02824997 0.183055 -0.111014 0.02824997 0.189715 -0.104255 0.02884995 0.188195 -0.103515 0.02824997 0.1873599 -0.103366 0.02824997 0.186511 -0.103373 0.02824997 0.185678 -0.103537 0.02824997 0.184889 -0.10385 0.02824997 0.184889 -0.10385 0.02884995 0.184171 -0.104303 0.02824997 0.183549 -0.104881 0.02884995 0.183549 -0.104881 0.02824997 0.183043 -0.105562 0.02824997 0.182671 -0.106326 0.02824997 0.182671 -0.106326 0.02884995 0.182446 -0.1071439 0.02824997 0.182446 -0.1071439 0.02884995 0.182461 -0.108834 0.02884995 0.1827 -0.109649 0.02824997 0.183602 -0.111078 0.02824997 0.183602 -0.111078 0.02884995 0.18496 -0.112085 0.02824997 0.185754 -0.112385 0.02884995 0.18659 -0.112534 0.02884995 0.1882719 -0.112363 0.02824997 0.187439 -0.112527 0.02884995 0.189061 -0.1120499 0.02884995 0.189061 -0.1120499 0.02824997 0.189779 -0.111597 0.02884995 0.190401 -0.111019 0.02824997 0.190907 -0.110338 0.02884995 0.191278 -0.109574 0.02824997 0.191278 -0.109574 0.02884995 0.191489 -0.107066 0.02824997 0.191489 -0.107066 0.02884995 0.190865 -0.105495 0.02824997 0.190347 -0.104822 0.02824997 0.184381 -0.112196 0.02884995 0.183055 -0.111014 0.02884995 0.183085 -0.110405 0.02884995 0.1827 -0.109649 0.02884995 0.182375 -0.10799 0.02884995 0.1821359 -0.106795 0.02884995 0.183043 -0.105562 0.02884995 0.18285 -0.1051689 0.02884995 0.184171 -0.104303 0.02884995 0.183413 -0.104477 0.02884995 0.185678 -0.103537 0.02884995 0.186511 -0.103373 0.02884995 0.1873599 -0.103366 0.02884995 0.188195 -0.103515 0.02884995 0.1889899 -0.103815 0.02884995 0.190347 -0.104822 0.02884995 0.190865 -0.105495 0.02884995 0.191154 -0.10525 0.02884995 0.19125 -0.106251 0.02884995 0.191575 -0.10791 0.02884995 0.191947 -0.107776 0.02884995 0.191504 -0.108756 0.02884995 0.191898 -0.108666 0.02884995 0.191691 -0.109534 0.02884995 0.190401 -0.111019 0.02884995 0.1902109 -0.111728 0.02884995 0.189485 -0.112246 0.02884995 0.1882719 -0.112363 0.02884995 0.188677 -0.112625 0.02884995 0.186926 -0.112925 0.02884995 0.18496 -0.112085 0.02884995 0.184235 -0.111645 0.02884995 0.188352 -0.105285 0.02614998 0.188762 -0.10554 0.02614998 0.188762 -0.10554 0.02494996 0.189125 -0.105858 0.02494996 0.189433 -0.10623 0.02494996 0.189125 -0.105858 0.02614998 0.189433 -0.10623 0.02614998 0.189677 -0.106647 0.02494996 0.189677 -0.106647 0.02614998 0.189851 -0.107097 0.02494996 0.189851 -0.107097 0.02614998 0.189951 -0.10757 0.02494996 0.1899729 -0.108052 0.02494996 0.189951 -0.10757 0.02614998 0.1899729 -0.108052 0.02614998 0.189918 -0.108532 0.02614998 0.189918 -0.108532 0.02494996 0.189787 -0.108996 0.02614998 0.189787 -0.108996 0.02494996 0.189582 -0.109434 0.02494996 0.189582 -0.109434 0.02614998 0.189311 -0.109833 0.02614998 0.189311 -0.109833 0.02494996 0.188978 -0.110183 0.02494996 0.188978 -0.110183 0.02614998 0.188594 -0.110475 0.02614998 0.188594 -0.110475 0.02494996 0.188168 -0.110702 0.02494996 0.188168 -0.110702 0.02614998 0.187711 -0.110858 0.02494996 0.187711 -0.110858 0.02614998 0.1872349 -0.110939 0.02494996 0.1872349 -0.110939 0.02614998 0.186752 -0.110942 0.02494996 0.186752 -0.110942 0.02614998 0.186275 -0.110867 0.02494996 0.186275 -0.110867 0.02614998 0.185816 -0.1107169 0.02614998 0.185816 -0.1107169 0.02494996 0.185387 -0.110496 0.02614998 0.185387 -0.110496 0.02494996 0.185 -0.110208 0.02494996 0.1846629 -0.109862 0.02494996 0.185 -0.110208 0.02614998 0.1846629 -0.109862 0.02614998 0.184386 -0.109466 0.02494996 0.184177 -0.109031 0.02494996 0.184386 -0.109466 0.02614998 0.1840389 -0.108569 0.02494996 0.184177 -0.109031 0.02614998 0.183978 -0.10809 0.02494996 0.1840389 -0.108569 0.02614998 0.183978 -0.10809 0.02614998 0.183995 -0.107607 0.02494996 0.183995 -0.107607 0.02614998 0.184088 -0.107134 0.02494996 0.184088 -0.107134 0.02614998 0.184256 -0.106681 0.02614998 0.184256 -0.106681 0.02494996 0.184495 -0.106261 0.02494996 0.184495 -0.106261 0.02614998 0.184798 -0.105885 0.02614998 0.184798 -0.105885 0.02494996 0.185158 -0.105563 0.02494996 0.185158 -0.105563 0.02614998 0.185564 -0.105302 0.02494996 0.185564 -0.105302 0.02614998 0.186007 -0.10511 0.02614998 0.186007 -0.10511 0.02494996 0.186475 -0.104992 0.02494996 0.186475 -0.104992 0.02614998 0.186956 -0.10495 0.02494996 0.186956 -0.10495 0.02614998 0.1874369 -0.104986 0.02614998 0.1874369 -0.104986 0.02494996 0.187907 -0.105098 0.02494996 0.187907 -0.105098 0.02614998 0.188352 -0.105285 0.02494996 0.1893579 -0.104737 0.02139997 0.189854 -0.105173 0.01739996 0.189854 -0.105173 0.02139997 0.190272 -0.105685 0.01739996 0.190272 -0.105685 0.02139997 0.1906 -0.106258 0.01739996 0.190829 -0.106878 0.01739996 0.1906 -0.106258 0.02139997 0.190829 -0.106878 0.02139997 0.190952 -0.107527 0.02139997 0.190952 -0.107527 0.01739996 0.190968 -0.108188 0.01739996 0.190874 -0.108842 0.01739996 0.190968 -0.108188 0.02139997 0.190674 -0.109471 0.01739996 0.190874 -0.108842 0.02139997 0.190674 -0.109471 0.02139997 0.190374 -0.110059 0.02139997 0.190374 -0.110059 0.01739996 0.18998 -0.11059 0.01739996 0.18998 -0.11059 0.02139997 0.189504 -0.1110489 0.01739996 0.189504 -0.1110489 0.02139997 0.18896 -0.111423 0.01739996 0.188361 -0.111702 0.01739996 0.18896 -0.111423 0.02139997 0.188361 -0.111702 0.02139997 0.187725 -0.111879 0.01739996 0.187725 -0.111879 0.02139997 0.187068 -0.111949 0.01739996 0.187068 -0.111949 0.02139997 0.186408 -0.11191 0.01739996 0.186408 -0.11191 0.02139997 0.185764 -0.111762 0.02139997 0.185764 -0.111762 0.01739996 0.185153 -0.111511 0.01739996 0.185153 -0.111511 0.02139997 0.184592 -0.111163 0.01739996 0.184592 -0.111163 0.02139997 0.184096 -0.110727 0.01739996 0.184096 -0.110727 0.02139997 0.183678 -0.110215 0.01739996 0.18335 -0.109642 0.01739996 0.183678 -0.110215 0.02139997 0.18335 -0.109642 0.02139997 0.183121 -0.109022 0.02139997 0.183121 -0.109022 0.01739996 0.182997 -0.108373 0.01739996 0.182982 -0.107712 0.01739996 0.182997 -0.108373 0.02139997 0.182982 -0.107712 0.02139997 0.183076 -0.107058 0.01739996 0.183076 -0.107058 0.02139997 0.183275 -0.106429 0.01739996 0.183275 -0.106429 0.02139997 0.183576 -0.105841 0.01739996 0.183576 -0.105841 0.02139997 0.18397 -0.10531 0.01739996 0.18397 -0.10531 0.02139997 0.184445 -0.104851 0.02139997 0.184445 -0.104851 0.01739996 0.1849899 -0.104477 0.01739996 0.1849899 -0.104477 0.02139997 0.185588 -0.104198 0.02139997 0.185588 -0.104198 0.01739996 0.1862249 -0.104021 0.01739996 0.1862249 -0.104021 0.02139997 0.186882 -0.103951 0.02139997 0.186882 -0.103951 0.01739996 0.187541 -0.10399 0.01739996 0.187541 -0.10399 0.02139997 0.188185 -0.104138 0.01739996 0.188185 -0.104138 0.02139997 0.188796 -0.104389 0.02139997 0.188796 -0.104389 0.01739996 0.1893579 -0.104737 0.01739996 0.194946 -0.115731 0.01741605 0.194857 -0.115765 0.01739996 0.1940349 -0.115832 0.01889997 0.1957679 -0.115323 0.01754516 0.195376 -0.11557 0.0174939 0.196705 -0.113779 0.01889997 0.196583 -0.114224 0.01754516 0.196381 -0.114639 0.01757097 0.196381 -0.114639 0.01889997 0.1957679 -0.115323 0.01889997 0.196105 -0.11501 0.01757085 0.1940349 -0.115832 0.01739996 0.193149 -0.115589 0.01739996 0.193149 -0.115589 0.01889997 0.192411 -0.115041 0.01739996 0.1919209 -0.114264 0.01739996 0.191744 -0.113363 0.01739996 0.191905 -0.112458 0.01889997 0.191905 -0.112458 0.01739996 0.192382 -0.1116729 0.01739996 0.1931099 -0.111113 0.01739996 0.193992 -0.110854 0.01739996 0.194907 -0.110931 0.01739996 0.194907 -0.110931 0.01889997 0.195733 -0.111333 0.01739996 0.195733 -0.111333 0.01889997 0.196358 -0.112007 0.01889997 0.196358 -0.112007 0.01739996 0.1966969 -0.11286 0.01739996 0.196741 -0.113224 0.01739996 0.196705 -0.113779 0.01749408 0.17882 -0.1094869 0.01739996 0.178725 -0.108847 0.01739996 0.178582 -0.110089 0.01889997 0.178582 -0.110089 0.01739996 0.1786659 -0.109874 0.01889997 0.178075 -0.110491 0.01739996 0.177942 -0.11051 0.01889997 0.176431 -0.109841 0.01739996 0.176833 -0.110348 0.01739996 0.177047 -0.110433 0.01889997 0.177435 -0.110586 0.01739996 0.176336 -0.109201 0.01739996 0.176574 -0.108599 0.01739996 0.176574 -0.108599 0.01889997 0.178322 -0.10834 0.01889997 0.177721 -0.108102 0.01889997 0.178322 -0.10834 0.01739996 0.177721 -0.108102 0.01739996 0.177588 -0.108122 0.01889997 0.177081 -0.108197 0.01739996 0.187144 -0.121666 0.02109998 0.186908 -0.12112 0.02109998 0.186779 -0.121644 0.02105039 0.186514 -0.121594 0.02095258 0.1862249 -0.121504 0.0207771 0.186272 -0.121036 0.02095258 0.185985 -0.121387 0.02054995 0.185563 -0.120684 0.02029085 0.185811 -0.121258 0.02029007 0.185459 -0.120543 0.01999998 0.1857089 -0.12112 0.01999998 0.186482 -0.120137 0.01889997 0.185894 -0.120164 0.01904737 0.185918 -0.120793 0.01922196 0.192968 -0.119197 0.01889997 0.192751 -0.118789 0.01785719 0.194415 -0.117722 0.01785719 0.193718 -0.09713649 0.01889997 0.1934739 -0.09752798 0.01785719 0.1762779 -0.100952 0.01898735 0.176182 -0.1011559 0.01892137 0.176348 -0.100758 0.01909875 0.177412 -0.100242 0.01785719 0.176385 -0.100584 0.01925247 0.176382 -0.100443 0.01944005 0.176192 -0.0992583 0.02139997 0.176267 -0.100285 0.0198611 0.176165 -0.100267 0.02007198 0.175911 -0.100334 0.02045458 0.17562 -0.100517 0.02076917 0.175324 -0.1008 0.02099364 0.174937 -0.101101 0.02139997 0.175464 -0.103667 0.01785719 0.1762999 -0.101876 0.01785719 0.175071 -0.103421 0.01889997 0.174926 -0.105569 0.01785719 0.174937 -0.103838 0.01889997 0.174792 -0.109507 0.01785719 0.1747 -0.107533 0.01785719 0.174238 -0.107517 0.01889997 0.1748459 -0.112972 0.0197677 0.174493 -0.112871 0.02042227 0.174731 -0.112983 0.02001816 0.173921 -0.112099 0.02105426 0.1740379 -0.112328 0.02096515 0.174305 -0.112699 0.0206784 0.174943 -0.112878 0.01948308 0.174993 -0.1126649 0.01919859 0.174966 -0.11232 0.01898097 0.175912 -0.113285 0.01785719 0.174921 -0.112115 0.01892119 0.1748369 -0.111831 0.01889997 0.175199 -0.111441 0.01785719 0.173696 -0.111887 0.02139997 0.1737999 -0.111769 0.02109998 0.173829 -0.1118479 0.02108919 0.173518 -0.105291 0.02109998 0.1732659 -0.107484 0.02109998 0.173368 -0.1096889 0.02109998 0.175053 -0.101167 0.02109736 0.1750119 -0.101239 0.02109998 0.173994 -0.10312 0.02139997 0.1741189 -0.1031669 0.02109998 0.198384 -0.102186 0.01898759 0.198431 -0.103522 0.01785719 0.198256 -0.102001 0.01892155 0.198517 -0.102344 0.01909917 0.198649 -0.102462 0.01925337 0.198773 -0.10253 0.01944094 0.199894 -0.102957 0.02139997 0.1989679 -0.102509 0.01986187 0.199034 -0.10243 0.0200721 0.199102 -0.102176 0.02045518 0.199089 -0.101832 0.02077007 0.198992 -0.101434 0.02099418 0.198926 -0.10095 0.02139997 0.197971 -0.101509 0.01889997 0.197573 -0.101742 0.01785719 0.19644 -0.100122 0.01785719 0.195062 -0.09870547 0.01785719 0.195365 -0.09835815 0.01889997 0.1942909 -0.09808468 0.01785719 0.189947 -0.09555757 0.01889997 0.189839 -0.09600627 0.01785719 0.191718 -0.09662038 0.01785719 0.191896 -0.0961948 0.01889997 0.18869 -0.09493488 0.0197677 0.188723 -0.09506618 0.01948314 0.1889539 -0.09467935 0.02042227 0.188738 -0.0948292 0.02001869 0.188002 -0.0941382 0.02139997 0.189907 -0.09457069 0.02105396 0.189653 -0.0945574 0.02096569 0.189198 -0.09460288 0.02067887 0.1888819 -0.09521585 0.01919907 0.189194 -0.09536439 0.01898127 0.189395 -0.0954287 0.01892119 0.189622 -0.09548407 0.01889997 0.190255 -0.09463059 0.02109998 0.190173 -0.09461635 0.02108907 0.192272 -0.0952968 0.02109998 0.194233 -0.09631037 0.02109998 0.196006 -0.09762549 0.02109998 0.19881 -0.1010169 0.02109736 0.197648 -0.09912329 0.02139997 0.198769 -0.100945 0.02109998 0.197546 -0.09920787 0.02109998 0.18614 -0.120732 0.01904737 0.185693 -0.120995 0.0197224 0.184839 -0.121634 0.02139997 0.18642 -0.120698 0.01893597 0.187052 -0.120232 0.01785719 0.189098 -0.120516 0.01889997 0.189021 -0.120061 0.01785719 0.1909379 -0.119576 0.01785719 0.1910859 -0.120012 0.01889997 0.196447 -0.116475 0.01889997 0.1946949 -0.11809 0.01889997 0.197127 -0.114863 0.01785719 0.197456 -0.116037 0.02001816 0.1974779 -0.116299 0.02042216 0.197094 -0.117181 0.0210545 0.197234 -0.116965 0.02096539 0.197423 -0.116548 0.02067846 0.1972579 -0.115906 0.01948255 0.197049 -0.115969 0.01919829 0.1967639 -0.116165 0.0189808 0.195886 -0.116402 0.01785719 0.1966069 -0.116308 0.01892089 0.197024 -0.117481 0.02139997 0.19687 -0.1174499 0.02109998 0.196923 -0.117386 0.02108919 0.189283 -0.121606 0.02139997 0.1913999 -0.120934 0.02109998 0.191443 -0.121059 0.02139997 0.193426 -0.120056 0.02109998 0.195284 -0.1188639 0.02109998 0.187061 -0.121666 0.02109736 0.18926 -0.121476 0.02109998 0.1878859 -0.09570145 0.01785719 0.18591 -0.09571397 0.01785719 0.183576 -0.0945236 0.02139997 0.183961 -0.09604328 0.01785719 0.18209 -0.09668099 0.01785719 0.181466 -0.09524267 0.02139997 0.1803449 -0.09761059 0.01785719 0.179499 -0.09629088 0.02139997 0.178773 -0.09880799 0.01785719 0.1763409 -0.100343 0.01964676 0.1973879 -0.115943 0.01976728 0.198422 -0.115746 0.02139997 0.198104 -0.113145 0.01785719 0.200302 -0.11172 0.02139997 0.198794 -0.111293 0.01785719 0.199177 -0.109354 0.01785719 0.199244 -0.107378 0.01785719 0.200527 -0.105094 0.02139997 0.198993 -0.105418 0.01785719 0.19888 -0.102545 0.01964718 0.1744999 -0.113966 0.02139997 0.1769109 -0.114991 0.01785719 0.175626 -0.115889 0.02139997 0.178171 -0.116514 0.01785719 0.1796579 -0.117815 0.01785719 0.180616 -0.120254 0.02139997 0.181336 -0.118861 0.01785719 0.1831589 -0.119624 0.01785719 0.185081 -0.120085 0.01785719 0.185766 -0.120881 0.01944994 0.195225 -0.09682559 0.02139997 0.194303 -0.09619778 0.02139997 0.1949 -0.0972647 0.02139997 0.192323 -0.09517437 0.02139997 0.1910009 -0.09527045 0.02139997 0.190205 -0.09448188 0.02139997 0.186666 -0.09465038 0.02139997 0.185774 -0.09415221 0.02139997 0.184481 -0.09488266 0.02139997 0.180373 -0.09640049 0.02139997 0.178562 -0.09764468 0.02139997 0.177726 -0.09764111 0.02139997 0.174006 -0.1049849 0.02139997 0.173388 -0.105265 0.02139997 0.173695 -0.10716 0.02139997 0.173133 -0.107479 0.02139997 0.173237 -0.109706 0.02139997 0.174158 -0.111515 0.02139997 0.17601 -0.115483 0.02139997 0.177047 -0.1176069 0.02139997 0.178724 -0.119074 0.02139997 0.180917 -0.119794 0.02139997 0.182672 -0.121115 0.02139997 0.189469 -0.121017 0.02139997 0.187062 -0.1218 0.02139997 0.191586 -0.120429 0.02139997 0.193577 -0.119499 0.02139997 0.195388 -0.118255 0.02139997 0.193488 -0.120173 0.02139997 0.195365 -0.11897 0.02139997 0.196969 -0.11673 0.02139997 0.1995249 -0.113809 0.02139997 0.200255 -0.10874 0.02139997 0.200734 -0.109533 0.02139997 0.200204 -0.106543 0.02139997 0.199792 -0.104385 0.02139997 0.20081 -0.107305 0.02139997 0.1979399 -0.100417 0.02139997 0.19655 -0.09871476 0.02139997 0.196094 -0.09752547 0.02139997 0.197923 -0.102539 0.01893377 0.1746709 -0.102891 0.02139997 0.174794 -0.102941 0.02109998 0.174136 -0.105015 0.02109998 0.173828 -0.107168 0.02109998 0.173878 -0.109342 0.02109998 0.173746 -0.1093569 0.02139997 0.174286 -0.111479 0.02109998 0.175058 -0.112901 0.02049809 0.175581 -0.112415 0.01899075 0.175528 -0.11219 0.01892215 0.1756179 -0.11236 0.01889997 0.175456 -0.1119599 0.01889997 0.175305 -0.113044 0.02011227 0.175414 -0.113057 0.01989769 0.17561 -0.112624 0.01910698 0.175608 -0.112804 0.01926767 0.175922 -0.113108 0.01889997 0.175573 -0.11294 0.01946336 0.1755059 -0.1130239 0.01967775 0.174805 -0.112637 0.0208075 0.174572 -0.112274 0.02101939 0.174391 -0.111837 0.02109998 0.185981 -0.12094 0.02077728 0.185738 -0.120818 0.02054995 0.185091 -0.121119 0.02139997 0.185443 -0.1204169 0.01972287 0.1855159 -0.120305 0.01944994 0.185671 -0.12022 0.01922094 0.186178 -0.120137 0.01893585 0.193511 -0.119384 0.02109998 0.19154 -0.120304 0.02109998 0.189444 -0.120887 0.02109998 0.187281 -0.121117 0.02109998 0.1872839 -0.12125 0.02139997 0.18658 -0.121097 0.02106058 0.195304 -0.118152 0.02109998 0.196507 -0.115612 0.01897448 0.19666 -0.115487 0.01907038 0.196806 -0.1153939 0.01920437 0.196938 -0.1153399 0.01937019 0.197193 -0.115432 0.01995557 0.197235 -0.115652 0.0203278 0.197188 -0.115945 0.02064615 0.198278 -0.114965 0.02139997 0.1970599 -0.116279 0.02089476 0.1968539 -0.116629 0.02105468 0.196633 -0.116904 0.02109998 0.198528 -0.103046 0.01969885 0.198345 -0.103009 0.01935315 0.198225 -0.1029199 0.01918637 0.198028 -0.102792 0.01889997 0.198083 -0.102766 0.01903849 0.1987349 -0.102462 0.02066439 0.198706 -0.102221 0.02084028 0.198644 -0.10196 0.02097755 0.192972 -0.0962243 0.02109998 0.193033 -0.09610611 0.02139997 0.194821 -0.09737139 0.02109998 0.196455 -0.09880697 0.02109998 0.19783 -0.100492 0.02109998 0.198414 -0.101423 0.02109998 0.19903 -0.102324 0.02139997 0.198547 -0.101692 0.02106696 0.189606 -0.09505969 0.0210675 0.188859 -0.0947808 0.02139997 0.1899 -0.0951085 0.02109998 0.190961 -0.09539705 0.02109998 0.188345 -0.09535968 0.01995676 0.18849 -0.09522849 0.02028828 0.188813 -0.09510308 0.02066439 0.1891829 -0.0950492 0.02091449 0.188702 -0.09587585 0.01889997 0.188974 -0.09590268 0.01893389 0.188711 -0.0958153 0.01903849 0.18848 -0.0956968 0.01923495 0.186756 -0.09576016 0.01889997 0.176647 -0.100361 0.02029955 0.176445 -0.100448 0.0205549 0.175603 -0.101307 0.02109998 0.1756719 -0.100935 0.02139997 0.1758019 -0.101015 0.02105468 0.176981 -0.09916996 0.02139997 0.17612 -0.100678 0.02086186 0.176958 -0.100404 0.01967775 0.177008 -0.100529 0.01941758 0.176988 -0.100746 0.0191648 0.1768749 -0.101054 0.018974 0.17492 -0.113576 0.02139997 0.1773999 -0.1171849 0.02139997 0.1768699 -0.100349 0.01991248 0.180922 -0.0973609 0.01889997 0.179662 -0.09822666 0.01889997 0.179262 -0.09850156 0.01889997 0.188344 -0.0955637 0.01949834 0.188314 -0.095474 0.01969259 0.182747 -0.09650909 0.01889997 0.182364 -0.09547138 0.02139997 0.182566 -0.09659379 0.01889997 0.180961 -0.09734278 0.01889997 0.198718 -0.102767 0.02034449 0.198629 -0.102979 0.01996839 0.199104 -0.10666 0.01889997 0.197049 -0.11533 0.01955807 0.199279 -0.113009 0.02139997 0.199943 -0.110915 0.02139997 0.183284 -0.119575 0.01889997 0.182949 -0.120629 0.02139997 0.1827999 -0.119376 0.01889997 0.181421 -0.118809 0.01889997 0.17905 -0.1186349 0.02139997 0.179709 -0.117747 0.01889997 0.178196 -0.116417 0.01889997 0.182013 -0.119052 0.01889997 0.197776 -0.102284 0.01889997 0.195368 -0.1058109 0.01889997 0.195875 -0.105409 0.01889997 0.196515 -0.105314 0.01889997 0.1983129 -0.103565 0.01889997 0.1952829 -0.106026 0.01889997 0.195627 -0.10756 0.01889997 0.195484 -0.10738 0.01889997 0.195225 -0.107053 0.01889997 0.1951299 -0.106413 0.01889997 0.196902 -0.105467 0.01889997 0.197117 -0.105552 0.01889997 0.1987259 -0.104682 0.01889997 0.197519 -0.106059 0.01889997 0.197614 -0.106699 0.01889997 0.19915 -0.108674 0.01889997 0.197376 -0.1073009 0.01889997 0.199122 -0.108873 0.01889997 0.197196 -0.107444 0.01889997 0.196869 -0.107703 0.01889997 0.189262 -0.09596925 0.01889997 0.184797 -0.09929198 0.01889997 0.18487 -0.09830278 0.01889997 0.185304 -0.0988897 0.01889997 0.183745 -0.102379 0.01889997 0.184701 -0.1019639 0.01889997 0.185056 -0.101041 0.01889997 0.185658 -0.101278 0.01889997 0.185117 -0.101784 0.01889997 0.183815 -0.101307 0.01889997 0.1846539 -0.100534 0.01889997 0.18461 -0.1002359 0.01889997 0.184579 -0.100026 0.01889997 0.184559 -0.09989368 0.01889997 0.185944 -0.09879475 0.01889997 0.186546 -0.09903258 0.01889997 0.186948 -0.09953939 0.01889997 0.186999 -0.09988129 0.01889997 0.187043 -0.100179 0.01889997 0.186596 -0.101522 0.01889997 0.187409 -0.101568 0.01889997 0.186589 -0.101522 0.01889997 0.186166 -0.101203 0.01889997 0.186298 -0.1011829 0.01889997 0.187002 -0.116361 0.01889997 0.186982 -0.116228 0.01889997 0.187404 -0.116867 0.01889997 0.188006 -0.117105 0.01889997 0.187761 -0.117793 0.01889997 0.188646 -0.1170099 0.01889997 0.191875 -0.11967 0.01889997 0.189153 -0.116608 0.01889997 0.189391 -0.116006 0.01889997 0.194765 -0.118027 0.01889997 0.1893399 -0.115664 0.01889997 0.183073 -0.113211 0.01889997 0.182247 -0.112809 0.01889997 0.179722 -0.113551 0.01889997 0.18045 -0.112991 0.01889997 0.181049 -0.112815 0.01889997 0.1813319 -0.112732 0.01889997 0.184045 -0.115657 0.01889997 0.1836979 -0.113885 0.01889997 0.18588 -0.115224 0.01889997 0.184037 -0.114738 0.01889997 0.18404 -0.115032 0.01889997 0.177253 -0.115262 0.01889997 0.179261 -0.116142 0.01889997 0.1777909 -0.115921 0.01889997 0.179751 -0.116919 0.01889997 0.183108 -0.117201 0.01889997 0.182289 -0.117618 0.01889997 0.181375 -0.1177099 0.01889997 0.180489 -0.117467 0.01889997 0.186805 -0.100781 0.01889997 0.188082 -0.101606 0.01889997 0.1895149 -0.102032 0.01889997 0.190811 -0.102777 0.01889997 0.179701 -0.106855 0.01889997 0.1805779 -0.107505 0.01889997 0.180577 -0.107214 0.01889997 0.180919 -0.105758 0.01889997 0.1815879 -0.104421 0.01889997 0.182547 -0.103274 0.01889997 0.181601 -0.111499 0.01889997 0.18097 -0.110249 0.01889997 0.180927 -0.110164 0.01889997 0.185139 -0.114123 0.01889997 0.1837649 -0.113533 0.01889997 0.180332 -0.11111 0.01889997 0.182564 -0.112642 0.01889997 0.192735 -0.11083 0.01889997 0.191916 -0.112081 0.01889997 0.1908299 -0.113109 0.01889997 0.189536 -0.1138589 0.01889997 0.193376 -0.107608 0.01889997 0.193415 -0.107938 0.01889997 0.193363 -0.108388 0.01889997 0.193244 -0.109424 0.01889997 0.191901 -0.103801 0.01889997 0.192725 -0.105049 0.01889997 0.192956 -0.105682 0.01889997 0.1932359 -0.106447 0.01889997 0.193239 -0.106453 0.01889997 0.193882 -0.106925 0.01889997 0.18058 -0.108709 0.01889997 0.178466 -0.10852 0.01889997 0.174856 -0.111891 0.01889997 0.179084 -0.115241 0.01889997 0.1792449 -0.114336 0.01889997 0.176922 -0.114857 0.01889997 0.176431 -0.109841 0.01889997 0.176833 -0.110348 0.01889997 0.177435 -0.110586 0.01889997 0.178725 -0.108847 0.01889997 0.17882 -0.1094869 0.01889997 0.179771 -0.1118659 0.01889997 0.178075 -0.110491 0.01889997 0.1798959 -0.10501 0.01889997 0.178944 -0.106293 0.01889997 0.179497 -0.10505 0.01889997 0.178611 -0.104806 0.01889997 0.177873 -0.104259 0.01889997 0.177383 -0.103482 0.01889997 0.177206 -0.102581 0.01889997 0.181195 -0.100551 0.01889997 0.1785719 -0.100331 0.01889997 0.180411 -0.104957 0.01889997 0.18182 -0.101224 0.01889997 0.183058 -0.100746 0.01889997 0.182128 -0.102 0.01889997 0.182159 -0.102078 0.01889997 0.1821669 -0.102997 0.01889997 0.181843 -0.103857 0.01889997 0.18123 -0.104541 0.01889997 0.191232 -0.0984528 0.01889997 0.191492 -0.0960626 0.01889997 0.1921139 -0.0981937 0.01889997 0.193029 -0.09827059 0.01889997 0.193855 -0.09867298 0.01889997 0.196795 -0.0998283 0.01889997 0.193071 -0.10308 0.01889997 0.191271 -0.102928 0.01889997 0.190533 -0.102381 0.01889997 0.1880699 -0.100676 0.01889997 0.190043 -0.101604 0.01889997 0.198136 -0.101799 0.01889997 0.1979359 -0.101459 0.01889997 0.19481 -0.105674 0.01889997 0.197039 -0.100177 0.01889997 0.1936179 -0.10479 0.01889997 0.196229 -0.107798 0.01889997 0.198871 -0.110626 0.01889997 0.195133 -0.107853 0.01889997 0.1988649 -0.110668 0.01889997 0.196207 -0.115921 0.01889997 0.194949 -0.11574 0.01889997 0.1919209 -0.114264 0.01889997 0.191744 -0.113363 0.01889997 0.194249 -0.109045 0.01889997 0.198402 -0.112126 0.01889997 0.198255 -0.112588 0.01889997 0.1966969 -0.11286 0.01889997 0.197338 -0.114382 0.01889997 0.1962209 -0.11672 0.01889997 0.192411 -0.115041 0.01889997 0.190135 -0.114593 0.01889997 0.192382 -0.1116729 0.01889997 0.1931099 -0.111113 0.01889997 0.193992 -0.110854 0.01889997 0.186052 -0.120098 0.01889997 0.186722 -0.120691 0.01889997 0.187055 -0.120693 0.01889997 0.1883479 -0.1170549 0.01889997 0.188304 -0.117061 0.01889997 0.1908389 -0.120075 0.01889997 0.185248 -0.120024 0.01889997 0.183721 -0.116517 0.01889997 0.189296 -0.115366 0.01889997 0.188893 -0.114859 0.01889997 0.189258 -0.113943 0.01889997 0.18851 -0.114168 0.01889997 0.188292 -0.1146219 0.01889997 0.188159 -0.114641 0.01889997 0.188105 -0.1142899 0.01889997 0.187652 -0.114717 0.01889997 0.186612 -0.11438 0.01889997 0.1871449 -0.115119 0.01889997 0.186518 -0.114363 0.01889997 0.1869069 -0.115721 0.01889997 0.186951 -0.116019 0.01889997 0.18651 -0.116865 0.01889997 0.1853179 -0.115981 0.01889997 0.184324 -0.119813 0.01889997 0.175184 -0.103505 0.01889997 0.175031 -0.103506 0.01889997 0.174473 -0.10548 0.01889997 0.177081 -0.108197 0.01889997 0.1767539 -0.108456 0.01889997 0.174337 -0.106663 0.01889997 0.176336 -0.109201 0.01889997 0.17425 -0.107772 0.01889997 0.176356 -0.109334 0.01889997 0.174334 -0.109566 0.01889997 0.174757 -0.111572 0.01889997 0.176411 -0.109709 0.01889997 0.177973 -0.09974408 0.01889997 0.177812 -0.09990006 0.01889997 0.1760669 -0.10136 0.01889997 0.175899 -0.101648 0.01889997 0.176667 -0.101429 0.01889997 0.177367 -0.101676 0.01889997 0.177844 -0.100891 0.01889997 0.179454 -0.100072 0.01889997 0.180369 -0.100149 0.01889997 0.183942 -0.09955406 0.01889997 0.1856459 -0.09883898 0.01889997 0.18788 -0.09582698 0.01889997 0.185602 -0.09884548 0.01889997 0.186691 -0.09575629 0.01889997 0.184688 -0.09596925 0.01889997 0.19448 -0.09934645 0.01752275 0.194663 -0.09969478 0.01747018 0.19346 -0.09843307 0.01756119 0.193855 -0.09867298 0.01757419 0.19448 -0.09934645 0.01889997 0.194199 -0.09898036 0.01756125 0.192641 -0.0981962 0.01747 0.193029 -0.09827059 0.01752275 0.19479 -0.100068 0.01739996 0.194819 -0.1001999 0.01889997 0.194819 -0.1001999 0.01739996 0.194827 -0.101119 0.01739996 0.194827 -0.101119 0.01889997 0.194503 -0.101979 0.01739996 0.19389 -0.102663 0.01739996 0.194503 -0.101979 0.01889997 0.19389 -0.102663 0.01889997 0.193071 -0.10308 0.01739996 0.192157 -0.103172 0.01889997 0.192157 -0.103172 0.01739996 0.191271 -0.102928 0.01739996 0.190533 -0.102381 0.01739996 0.190043 -0.101604 0.01739996 0.189866 -0.100703 0.01739996 0.189866 -0.100703 0.01889997 0.1900269 -0.09979808 0.01739996 0.190504 -0.09901279 0.01739996 0.1900269 -0.09979808 0.01889997 0.190504 -0.09901279 0.01889997 0.191232 -0.0984528 0.01739996 0.1921139 -0.0981937 0.01739996 0.192249 -0.09818369 0.01739996 0.187758 -0.112888 0.03444999 0.186178 -0.112886 0.03444999 0.184876 -0.112488 0.03444999 0.182823 -0.110737 0.03444999 0.187092 -0.102951 0.03444999 0.186192 -0.103012 0.03444999 0.190708 -0.104624 0.03444999 0.191928 -0.107266 0.03744995 0.187162 -0.112446 0.03794997 0.187758 -0.112888 0.03744995 0.188397 -0.112743 0.03744995 0.190958 -0.110904 0.03744995 0.19134 -0.110388 0.03744995 0.191817 -0.109195 0.03744995 0.1913329 -0.10907 0.03794997 0.191475 -0.107923 0.03794997 0.181989 -0.108173 0.03744995 0.182618 -0.109076 0.03794997 0.186192 -0.103012 0.03744995 0.1856949 -0.103636 0.03794997 0.184638 -0.104105 0.03794997 0.184378 -0.103677 0.03744995 0.183405 -0.104456 0.03744995 0.183375 -0.10448 0.03744995 0.182609 -0.105512 0.03744995 0.182617 -0.10683 0.03794997 0.181975 -0.10798 0.03744995 0.188446 -0.107657 0.03512865 0.188395 -0.107466 0.03014999 0.187121 -0.109443 0.03627115 0.186924 -0.109449 0.03014999 0.187309 -0.109412 0.03491866 0.186924 -0.109449 0.03589636 0.186896 -0.109448 0.0356999 0.187626 -0.109301 0.03794997 0.187626 -0.109301 0.03673756 0.186924 -0.109449 0.03794997 0.187411 -0.109385 0.03657495 0.18818 -0.108844 0.03694999 0.18792 -0.109115 0.03689318 0.188471 -0.107845 0.03648126 0.188457 -0.1081809 0.03794997 0.188457 -0.1081809 0.03673756 0.188364 -0.108516 0.03689318 0.1880069 -0.106862 0.03014999 0.188385 -0.1074399 0.03569996 0.188395 -0.107466 0.03589636 0.188395 -0.107466 0.03794997 0.188428 -0.107578 0.03615468 0.188457 -0.1081809 0.03014999 0.188475 -0.107951 0.03482484 0.187626 -0.109301 0.03014999 0.187626 -0.109301 0.03466236 0.187919 -0.109115 0.03450697 0.18818 -0.108844 0.03014999 0.18818 -0.108844 0.03444999 0.188364 -0.108516 0.03450679 0.188457 -0.1081809 0.03466236 0.188395 -0.107466 0.03550356 0.1873829 -0.106507 0.03014999 0.186666 -0.106482 0.03014999 0.186019 -0.1067939 0.03014999 0.18577 -0.107056 0.03014999 0.185591 -0.107371 0.03014999 0.185481 -0.10808 0.03014999 0.185712 -0.1087599 0.03014999 0.186233 -0.109254 0.03014999 0.186924 -0.109449 0.03550356 0.187041 -0.109449 0.03524518 0.1873829 -0.106507 0.03794997 0.186788 -0.103454 0.03794997 0.191332 -0.106824 0.03794997 0.1880069 -0.106862 0.03794997 0.186666 -0.106482 0.03794997 0.186019 -0.1067939 0.03794997 0.183735 -0.104827 0.03794997 0.183046 -0.105756 0.03794997 0.185591 -0.107371 0.03794997 0.185481 -0.10808 0.03794997 0.185712 -0.1087599 0.03794997 0.182475 -0.107977 0.03794997 0.186233 -0.109254 0.03794997 0.188255 -0.112264 0.03794997 0.189312 -0.111795 0.03794997 0.18818 -0.108844 0.03794997 0.190215 -0.111073 0.03794997 0.190904 -0.110144 0.03794997 0.182022 -0.108634 0.03744995 0.182022 -0.108634 0.03444999 0.18198 -0.108174 0.03344994 0.182226 -0.109513 0.03444999 0.182226 -0.109513 0.03344994 0.182428 -0.1099269 0.03344994 0.1837289 -0.111753 0.03444999 0.1837289 -0.111753 0.03344994 0.184876 -0.112488 0.03344994 0.187539 -0.112918 0.03444999 0.186392 -0.112891 0.03344994 0.187539 -0.112918 0.03344994 0.188859 -0.112582 0.03344994 0.188843 -0.112546 0.03744995 0.191928 -0.107266 0.03444999 0.191893 -0.107048 0.03444999 0.191534 -0.105958 0.03344994 0.191467 -0.105755 0.03444999 0.1896719 -0.10374 0.03344994 0.1896719 -0.10374 0.03444999 0.188437 -0.103168 0.03444999 0.188437 -0.103168 0.03344994 0.187092 -0.102951 0.03344994 0.191608 -0.109719 0.03744995 0.191561 -0.109942 0.0362311 0.1916069 -0.109832 0.03577488 0.191602 -0.109844 0.03550577 0.191568 -0.109925 0.03520947 0.191492 -0.110094 0.03490948 0.191354 -0.110364 0.0346443 0.191132 -0.110729 0.03447419 0.190991 -0.1109279 0.03444999 0.190991 -0.1109279 0.03344994 0.19084 -0.111122 0.03447425 0.190686 -0.111301 0.03454607 0.190401 -0.111592 0.03481656 0.190195 -0.111775 0.03522086 0.190138 -0.111822 0.03545629 0.190013 -0.11187 0.03744995 0.190119 -0.111838 0.03570038 0.190138 -0.111822 0.03594529 0.190195 -0.111775 0.03617995 0.190401 -0.111591 0.03658419 0.190687 -0.1113 0.0368545 0.190575 -0.11142 0.03744995 0.19084 -0.1111209 0.03692585 0.190991 -0.1109279 0.03694999 0.1912119 -0.110604 0.03688669 0.19139 -0.110297 0.03670418 0.191479 -0.110121 0.03652524 0.189572 -0.112223 0.03744995 0.1821179 -0.10682 0.03744995 0.182105 -0.106818 0.03344994 0.182132 -0.106705 0.03744995 0.182595 -0.105548 0.03744995 0.182591 -0.1055459 0.03344994 0.183402 -0.104452 0.03344994 0.184095 -0.103915 0.03344994 0.184483 -0.103631 0.03744995 0.185552 -0.103157 0.03744995 0.184478 -0.103618 0.03344994 0.185739 -0.103105 0.03344994 0.185741 -0.103114 0.03744995 0.191646 -0.109735 0.03344994 0.191689 -0.109548 0.03344994 0.191954 -0.108408 0.03344994 0.191915 -0.108403 0.03744995 0.1919749 -0.10792 0.03744995 0.190715 -0.09962338 0.03344994 0.192267 -0.09913575 0.03344994 0.193055 -0.09940057 0.03214997 0.193055 -0.09940057 0.03344994 0.1939899 -0.101558 0.03214997 0.193645 -0.102314 0.03214997 0.1930209 -0.102865 0.03214997 0.1930209 -0.102865 0.03344994 0.192228 -0.103114 0.03214997 0.192228 -0.103114 0.03344994 0.191402 -0.1030189 0.03214997 0.191402 -0.1030189 0.03344994 0.190203 -0.101918 0.03344994 0.190038 -0.101103 0.03214997 0.190038 -0.101103 0.03344994 0.190219 -0.100291 0.03344994 0.197099 -0.109952 0.03214997 0.1973789 -0.108525 0.03214997 0.197049 -0.107762 0.03344994 0.196436 -0.107199 0.03344994 0.196436 -0.107199 0.03214997 0.195648 -0.106935 0.03344994 0.194096 -0.107422 0.03214997 0.194096 -0.107422 0.03344994 0.193813 -0.10773 0.03214997 0.1935999 -0.10809 0.03344994 0.1935999 -0.10809 0.03214997 0.193419 -0.108902 0.03344994 0.193584 -0.109717 0.03344994 0.194783 -0.110817 0.03344994 0.197026 -0.110113 0.03344994 0.197026 -0.110113 0.03214997 0.196402 -0.1106629 0.03214997 0.195822 -0.110846 0.03214997 0.189756 -0.1138409 0.03214997 0.1923159 -0.115352 0.03344994 0.1923159 -0.115352 0.03214997 0.191985 -0.114589 0.03214997 0.191373 -0.114027 0.03214997 0.188749 -0.114557 0.03214997 0.188661 -0.114707 0.03214997 0.188537 -0.114917 0.03344994 0.188374 -0.115646 0.03344994 0.188433 -0.116108 0.03344994 0.189003 -0.117222 0.03344994 0.188521 -0.116544 0.03214997 0.189003 -0.117222 0.03214997 0.189719 -0.117645 0.03214997 0.192308 -0.1161839 0.03344994 0.191962 -0.11694 0.03344994 0.191339 -0.1174899 0.03214997 0.180588 -0.113278 0.03344994 0.1821399 -0.11279 0.03214997 0.181312 -0.112869 0.03344994 0.1821399 -0.11279 0.03344994 0.182928 -0.113055 0.03344994 0.1835409 -0.113618 0.03214997 0.183872 -0.114381 0.03214997 0.183872 -0.114381 0.03344994 0.1838639 -0.115212 0.03214997 0.180102 -0.11393 0.03214997 0.180305 -0.113586 0.03214997 0.180588 -0.113278 0.03214997 0.180103 -0.113931 0.03344994 0.180092 -0.113946 0.03214997 0.179912 -0.114758 0.03344994 0.180076 -0.115573 0.03214997 0.180559 -0.11625 0.03214997 0.1835179 -0.115969 0.03214997 0.1832129 -0.1162379 0.03344994 0.1832129 -0.1162379 0.03214997 0.182101 -0.116768 0.03214997 0.1772069 -0.105479 0.03214997 0.1772069 -0.105479 0.03344994 0.180491 -0.106582 0.03344994 0.18016 -0.105819 0.03344994 0.18016 -0.105819 0.03214997 0.179548 -0.105256 0.03344994 0.179548 -0.105256 0.03214997 0.178759 -0.104992 0.03344994 0.177931 -0.1050699 0.03214997 0.17813 -0.105052 0.03344994 0.176924 -0.105787 0.03214997 0.176712 -0.106147 0.03214997 0.176549 -0.106876 0.03344994 0.176696 -0.107774 0.03344994 0.177178 -0.108452 0.03344994 0.176696 -0.107774 0.03214997 0.180487 -0.1065739 0.03214997 0.180483 -0.107414 0.03214997 0.180137 -0.10817 0.03344994 0.179514 -0.10872 0.03214997 0.1787109 -0.108969 0.03214997 0.1778939 -0.108875 0.03344994 0.1778939 -0.108875 0.03214997 0.1852 -0.101343 0.03344994 0.185546 -0.1005859 0.03344994 0.185551 -0.09974658 0.03214997 0.1852239 -0.09899169 0.03214997 0.183823 -0.09816437 0.03344994 0.183194 -0.09822428 0.03344994 0.182995 -0.09824317 0.03214997 0.1822699 -0.09865188 0.03214997 0.181988 -0.09895986 0.03214997 0.181594 -0.100132 0.03344994 0.181594 -0.100132 0.03214997 0.1817589 -0.100947 0.03214997 0.183784 -0.102142 0.03214997 0.178313 -0.113951 0.03214997 0.177654 -0.114653 0.03344994 0.178653 -0.112856 0.03214997 0.178637 -0.112089 0.03214997 0.178254 -0.111206 0.03344994 0.178254 -0.111206 0.03214997 0.17817 -0.111125 0.03344994 0.177565 -0.1105329 0.03344994 0.177554 -0.110529 0.03214997 0.176674 -0.11017 0.03214997 0.194674 -0.11676 0.03194999 0.194977 -0.116486 0.03194999 0.196372 -0.11492 0.03194999 0.1993499 -0.11428 0.03194999 0.183877 -0.1215 0.03194999 0.186149 -0.121825 0.03194999 0.1852909 -0.119528 0.03194999 0.176908 -0.11519 0.03344994 0.1756899 -0.116066 0.03194999 0.176238 -0.116715 0.03194999 0.177074 -0.117706 0.03194999 0.178143 -0.116654 0.03344994 0.177828 -0.1183609 0.03194999 0.178695 -0.119115 0.03194999 0.179588 -0.11791 0.03344994 0.18121 -0.118928 0.03344994 0.181704 -0.120769 0.03194999 0.181744 -0.119158 0.03344994 0.1831949 -0.119023 0.03194999 0.182485 -0.121105 0.03194999 0.1872349 -0.117704 0.03214997 0.18812 -0.119374 0.03344994 0.18812 -0.119374 0.03214997 0.1878409 -0.118452 0.03344994 0.1872349 -0.117704 0.03344994 0.186058 -0.1172029 0.03344994 0.185434 -0.117131 0.03344994 0.184696 -0.117338 0.03344994 0.184507 -0.11739 0.03214997 0.1837469 -0.117981 0.03214997 0.188141 -0.119592 0.03194999 0.188361 -0.121781 0.03194999 0.190096 -0.119951 0.03344994 0.190474 -0.121402 0.03194999 0.190694 -0.121326 0.03194999 0.191907 -0.119327 0.03344994 0.1951349 -0.117287 0.03344994 0.194401 -0.1197 0.03194999 0.19453 -0.116595 0.03214997 0.196503 -0.112451 0.03214997 0.195763 -0.112569 0.03214997 0.195763 -0.112569 0.03344994 0.194729 -0.113101 0.03344994 0.194155 -0.113875 0.03214997 0.193917 -0.114807 0.03214997 0.194048 -0.115761 0.03214997 0.197566 -0.102977 0.03194999 0.199042 -0.101052 0.03194999 0.200374 -0.1116459 0.03194999 0.199113 -0.1102949 0.03344994 0.200711 -0.109914 0.03194999 0.199294 -0.109367 0.03344994 0.200855 -0.107626 0.03194999 0.199141 -0.105551 0.03344994 0.200622 -0.105345 0.03194999 0.199365 -0.107453 0.03344994 0.198239 -0.105729 0.03214997 0.198239 -0.105729 0.03344994 0.200612 -0.105261 0.03194999 0.196296 -0.101247 0.03214997 0.195637 -0.101949 0.03344994 0.195313 -0.103811 0.03214997 0.195313 -0.103811 0.03344994 0.195563 -0.104386 0.03344994 0.1956959 -0.104694 0.03344994 0.196385 -0.105367 0.03344994 0.196385 -0.105367 0.03214997 0.1972759 -0.1057299 0.03344994 0.1896899 -0.09656947 0.03194999 0.187615 -0.09626746 0.03194999 0.197712 -0.09918528 0.03194999 0.196875 -0.09819358 0.03194999 0.196122 -0.09753847 0.03194999 0.191465 -0.09479528 0.03194999 0.192245 -0.0951308 0.03194999 0.190981 -0.09621477 0.03344994 0.192206 -0.09674185 0.03344994 0.194362 -0.09799015 0.03344994 0.190684 -0.09708458 0.03214997 0.1907539 -0.09687727 0.03214997 0.1858299 -0.0965262 0.03344994 0.186109 -0.09744775 0.03214997 0.186708 -0.09818661 0.03214997 0.186715 -0.09819579 0.03214997 0.186715 -0.09819579 0.03344994 0.187559 -0.09865909 0.03214997 0.189115 -0.09860128 0.03214997 0.1894429 -0.0985096 0.03344994 0.190203 -0.0979188 0.03344994 0.190203 -0.0979188 0.03214997 0.178815 -0.09861338 0.03344994 0.18035 -0.09746819 0.03344994 0.181207 -0.09701478 0.03344994 0.183256 -0.09457349 0.03194999 0.185038 -0.09573715 0.03344994 0.185739 -0.09561181 0.03344994 0.185808 -0.09630829 0.03214997 0.1794199 -0.09930527 0.03214997 0.176509 -0.103229 0.03214997 0.177447 -0.103449 0.03214997 0.178187 -0.103331 0.03214997 0.178187 -0.103331 0.03344994 0.179794 -0.102025 0.03214997 0.180033 -0.101093 0.03214997 0.193168 -0.104606 0.03214997 0.193168 -0.104606 0.03344994 0.1932139 -0.10449 0.03344994 0.193122 -0.105285 0.03214997 0.1933799 -0.1056089 0.03214997 0.194174 -0.105701 0.03344994 0.194401 -0.105521 0.03344994 0.194401 -0.105521 0.03214997 0.194499 -0.105443 0.03344994 0.194651 -0.105058 0.03344994 0.194651 -0.105058 0.03214997 0.194333 -0.104324 0.03214997 0.193948 -0.104172 0.03344994 0.193538 -0.104233 0.03214997 0.1932139 -0.10449 0.03214997 0.180002 -0.111728 0.03344994 0.180782 -0.111294 0.03214997 0.180828 -0.110615 0.03344994 0.1808879 -0.111025 0.03214997 0.180828 -0.110615 0.03214997 0.18057 -0.110291 0.03214997 0.18057 -0.110291 0.03344994 0.180474 -0.110252 0.03214997 0.180185 -0.1101379 0.03344994 0.180185 -0.1101379 0.03214997 0.179549 -0.110379 0.03214997 0.1797749 -0.110199 0.03344994 0.179549 -0.110379 0.03344994 0.179451 -0.110457 0.03344994 0.1792989 -0.110842 0.03344994 0.179451 -0.110457 0.03214997 0.1792989 -0.110842 0.03214997 0.17936 -0.1112509 0.03214997 0.191679 -0.09723716 0.03214997 0.198637 -0.107049 0.03214997 0.19027 -0.118331 0.03214997 0.195609 -0.110912 0.03214997 0.1882359 -0.110784 0.03214997 0.189505 -0.109826 0.03214997 0.189994 -0.108848 0.03214997 0.188711 -0.110579 0.03214997 0.183845 -0.108016 0.03214997 0.183831 -0.108139 0.03214997 0.1863279 -0.112977 0.03214997 0.187707 -0.111014 0.03214997 0.184085 -0.109203 0.03214997 0.182352 -0.110028 0.03214997 0.184688 -0.110116 0.03214997 0.185566 -0.110768 0.03214997 0.186615 -0.111079 0.03214997 0.185239 -0.105321 0.03214997 0.184445 -0.106074 0.03214997 0.183956 -0.107052 0.03214997 0.1862429 -0.104886 0.03214997 0.187335 -0.104821 0.03214997 0.190119 -0.107761 0.03214997 0.1898649 -0.106697 0.03214997 0.189262 -0.1057839 0.03214997 0.188383 -0.105132 0.03214997 0.190105 -0.107884 0.03214997 0.190053 -0.108334 0.03214997 0.194066 -0.110395 0.03214997 0.194783 -0.110817 0.03214997 0.19393 -0.107602 0.03214997 0.191864 -0.109677 0.03214997 0.193419 -0.108902 0.03214997 0.193584 -0.109717 0.03214997 0.197377 -0.108748 0.03214997 0.197049 -0.107762 0.03214997 0.194753 -0.105782 0.03214997 0.195648 -0.106935 0.03214997 0.19482 -0.107013 0.03214997 0.19744 -0.112671 0.03214997 0.197371 -0.109356 0.03214997 0.198287 -0.110834 0.03214997 0.198222 -0.111173 0.03214997 0.19764 -0.112761 0.03214997 0.190584 -0.113762 0.03214997 0.189032 -0.114249 0.03214997 0.192314 -0.115575 0.03214997 0.193159 -0.114435 0.03214997 0.191026 -0.118892 0.03214997 0.192308 -0.1161839 0.03214997 0.194674 -0.11676 0.03214997 0.191962 -0.11694 0.03214997 0.19183 -0.117057 0.03214997 0.193324 -0.117777 0.03214997 0.190758 -0.117673 0.03214997 0.190545 -0.11774 0.03214997 0.188356 -0.115729 0.03214997 0.182928 -0.113055 0.03214997 0.181312 -0.112869 0.03214997 0.179687 -0.113622 0.03214997 0.182894 -0.116519 0.03214997 0.179912 -0.114758 0.03214997 0.18133 -0.118198 0.03214997 0.181275 -0.116673 0.03214997 0.178759 -0.104992 0.03214997 0.176062 -0.103732 0.03214997 0.180005 -0.108287 0.03214997 0.180137 -0.10817 0.03214997 0.180491 -0.106582 0.03214997 0.175676 -0.105077 0.03214997 0.176836 -0.105937 0.03214997 0.176531 -0.106959 0.03214997 0.179275 -0.0991404 0.03214997 0.180004 -0.100881 0.03214997 0.181775 -0.09931987 0.03214997 0.179902 -0.100139 0.03214997 0.182241 -0.101624 0.03214997 0.182929 -0.09701228 0.03214997 0.184611 -0.09842908 0.03214997 0.183823 -0.09816437 0.03214997 0.182105 -0.09883207 0.03214997 0.1829569 -0.102047 0.03214997 0.183775 -0.102141 0.03214997 0.184791 -0.104432 0.03214997 0.184577 -0.101893 0.03214997 0.1852 -0.101343 0.03214997 0.175711 -0.110171 0.03214997 0.1754429 -0.109926 0.03214997 0.175334 -0.107253 0.03214997 0.178333 -0.1094779 0.03214997 0.177565 -0.1105329 0.03214997 0.17865 -0.112712 0.03214997 0.179553 -0.111495 0.03214997 0.180736 -0.11141 0.03214997 0.1804119 -0.111667 0.03214997 0.180002 -0.111728 0.03214997 0.177654 -0.114653 0.03214997 0.179617 -0.111576 0.03214997 0.1786569 -0.113052 0.03214997 0.178182 -0.115652 0.03214997 0.178089 -0.115561 0.03214997 0.177476 -0.114781 0.03214997 0.182178 -0.118573 0.03214997 0.183266 -0.118815 0.03214997 0.1831949 -0.119023 0.03214997 0.185573 -0.114847 0.03214997 0.185165 -0.114545 0.03214997 0.183663 -0.116571 0.03214997 0.184696 -0.117338 0.03214997 0.185434 -0.117131 0.03214997 0.186026 -0.116196 0.03214997 0.186265 -0.117226 0.03214997 0.187158 -0.116022 0.03214997 0.1863909 -0.117241 0.03214997 0.188141 -0.119592 0.03214997 0.1878409 -0.118452 0.03214997 0.189498 -0.119372 0.03214997 0.1894659 -0.119382 0.03214997 0.193946 -0.115019 0.03214997 0.194976 -0.111985 0.03214997 0.195552 -0.112602 0.03214997 0.1972759 -0.1057299 0.03214997 0.197865 -0.10809 0.03214997 0.198454 -0.105687 0.03214997 0.194499 -0.105443 0.03214997 0.1956959 -0.104694 0.03214997 0.195646 -0.104578 0.03214997 0.19459 -0.104649 0.03214997 0.1927599 -0.104304 0.03214997 0.195748 -0.100276 0.03214997 0.195637 -0.101949 0.03214997 0.193948 -0.104172 0.03214997 0.1952919 -0.102848 0.03214997 0.195143 -0.09957307 0.03214997 0.1939989 -0.100726 0.03214997 0.193668 -0.09996306 0.03214997 0.192267 -0.09913575 0.03214997 0.191439 -0.09921467 0.03214997 0.190203 -0.101918 0.03214997 0.188785 -0.101355 0.03214997 0.190686 -0.102596 0.03214997 0.190715 -0.09962338 0.03214997 0.190432 -0.09993129 0.03214997 0.190219 -0.100291 0.03214997 0.188566 -0.100181 0.03214997 0.188377 -0.1010529 0.03214997 0.191792 -0.09729975 0.03214997 0.188475 -0.100976 0.03214997 0.188627 -0.100591 0.03214997 0.187923 -0.09970438 0.03214997 0.188212 -0.09981846 0.03214997 0.188516 -0.09876906 0.03214997 0.188309 -0.09985655 0.03214997 0.1894429 -0.0985096 0.03214997 0.187189 -0.100023 0.03214997 0.187514 -0.09976506 0.03214997 0.1858299 -0.0965262 0.03214997 0.1834689 -0.09678769 0.03214997 0.1801559 -0.103391 0.03214997 0.178398 -0.103298 0.03214997 0.180217 -0.1037999 0.03214997 0.180474 -0.104125 0.03214997 0.181223 -0.1055819 0.03214997 0.180859 -0.104277 0.03214997 0.181593 -0.103959 0.03214997 0.181746 -0.103574 0.03214997 0.180308 -0.103006 0.03214997 0.179221 -0.1027989 0.03214997 0.180633 -0.102748 0.03214997 0.181042 -0.102687 0.03214997 0.181427 -0.10284 0.03214997 0.181685 -0.103164 0.03214997 0.1930609 -0.104875 0.03214997 0.193765 -0.105762 0.03214997 0.19359 -0.10735 0.03214997 0.194174 -0.105701 0.03214997 0.185929 -0.09923708 0.03214997 0.185554 -0.09975469 0.03214997 0.187144 -0.100138 0.03214997 0.185546 -0.1005859 0.03214997 0.187037 -0.100408 0.03214997 0.187098 -0.100817 0.03214997 0.185274 -0.101182 0.03214997 0.187291 -0.101061 0.03214997 0.187355 -0.101142 0.03214997 0.1857129 -0.105116 0.03214997 0.186517 -0.102104 0.03214997 0.186129 -0.104936 0.03214997 0.187741 -0.101294 0.03214997 0.177178 -0.108452 0.03214997 0.1797749 -0.110199 0.03214997 0.1787199 -0.10897 0.03214997 0.181248 -0.109209 0.03214997 0.182974 -0.106881 0.03214997 0.183897 -0.1075659 0.03214997 0.188537 -0.114917 0.03214997 0.1883209 -0.114454 0.03214997 0.187821 -0.110964 0.03214997 0.186594 -0.114758 0.03214997 0.186209 -0.114606 0.03214997 0.191597 -0.105872 0.03214997 0.1876209 -0.102923 0.03214997 0.1881499 -0.101233 0.03214997 0.18304 -0.103133 0.03214997 0.181269 -0.104216 0.03214997 0.192356 -0.111941 0.03214997 0.194729 -0.113101 0.03214997 0.193641 -0.1128939 0.03214997 0.193794 -0.112509 0.03214997 0.193733 -0.1121 0.03214997 0.193475 -0.111775 0.03214997 0.19309 -0.111623 0.03214997 0.192681 -0.111684 0.03214997 0.1922039 -0.112326 0.03214997 0.192265 -0.112736 0.03214997 0.190047 -0.112127 0.03214997 0.192522 -0.1130599 0.03214997 0.192908 -0.113213 0.03214997 0.1933169 -0.113152 0.03214997 0.181189 -0.111596 0.03214997 0.186912 -0.115492 0.03214997 0.186912 -0.115492 0.03344994 0.186852 -0.115083 0.03214997 0.1858 -0.1146669 0.03214997 0.1858 -0.1146669 0.03344994 0.185475 -0.114924 0.03214997 0.185475 -0.114924 0.03344994 0.1853229 -0.115309 0.03214997 0.185384 -0.115719 0.03344994 0.185384 -0.115719 0.03214997 0.185641 -0.116043 0.03344994 0.185641 -0.116043 0.03214997 0.1864359 -0.116135 0.03214997 0.18676 -0.115877 0.03214997 0.186806 -0.115762 0.03214997 0.1808879 -0.111025 0.03344994 0.180782 -0.111294 0.03344994 0.181189 -0.111596 0.03344994 0.188585 -0.120221 0.03344994 0.188174 -0.119917 0.03344994 0.188211 -0.120288 0.03344994 0.174809 -0.1103489 0.03344994 0.1817589 -0.100947 0.03344994 0.188356 -0.115729 0.03344994 0.191467 -0.105755 0.03344994 0.191893 -0.107048 0.03344994 0.187546 -0.103025 0.03344994 0.190708 -0.104624 0.03344994 0.182278 -0.106365 0.03344994 0.186178 -0.112886 0.03344994 0.190038 -0.1119019 0.03344994 0.189952 -0.111951 0.03344994 0.189872 -0.111997 0.03344994 0.19744 -0.112671 0.03344994 0.198278 -0.113048 0.03344994 0.195609 -0.110912 0.03344994 0.194066 -0.110395 0.03344994 0.195616 -0.106422 0.03344994 0.1973789 -0.108525 0.03344994 0.1973749 -0.109005 0.03344994 0.197371 -0.109356 0.03344994 0.198929 -0.111247 0.03344994 0.196402 -0.1106629 0.03344994 0.196503 -0.112451 0.03344994 0.194746 -0.107055 0.03344994 0.19482 -0.107013 0.03344994 0.195205 -0.106977 0.03344994 0.193496 -0.109281 0.03344994 0.1917189 -0.10957 0.03344994 0.191668 -0.109638 0.03344994 0.190584 -0.113762 0.03344994 0.191373 -0.114027 0.03344994 0.19091 -0.112767 0.03344994 0.193946 -0.115019 0.03344994 0.1935999 -0.118432 0.03344994 0.19453 -0.116595 0.03344994 0.194048 -0.115761 0.03344994 0.191985 -0.114589 0.03344994 0.189032 -0.114249 0.03344994 0.189902 -0.112019 0.03344994 0.189756 -0.1138409 0.03344994 0.190141 -0.113804 0.03344994 0.188021 -0.116663 0.03344994 0.192742 -0.118885 0.03344994 0.191339 -0.1174899 0.03344994 0.191004 -0.117596 0.03344994 0.190545 -0.11774 0.03344994 0.191706 -0.119396 0.03344994 0.189719 -0.117645 0.03344994 0.188521 -0.116544 0.03344994 0.1838639 -0.115212 0.03344994 0.185165 -0.114545 0.03344994 0.183663 -0.116571 0.03344994 0.1835409 -0.113618 0.03344994 0.1835179 -0.115969 0.03344994 0.182894 -0.116519 0.03344994 0.182101 -0.116768 0.03344994 0.181275 -0.116673 0.03344994 0.180559 -0.11625 0.03344994 0.180076 -0.115573 0.03344994 0.177768 -0.116209 0.03344994 0.179687 -0.113622 0.03344994 0.180092 -0.113946 0.03344994 0.180483 -0.107414 0.03344994 0.181905 -0.106089 0.03344994 0.1765699 -0.107155 0.03344994 0.174648 -0.106745 0.03344994 0.176531 -0.106959 0.03344994 0.174656 -0.106533 0.03344994 0.174836 -0.105605 0.03344994 0.176712 -0.106147 0.03344994 0.1750209 -0.104653 0.03344994 0.179514 -0.10872 0.03344994 0.1791779 -0.108826 0.03344994 0.1787199 -0.10897 0.03344994 0.18555 -0.100235 0.03344994 0.184577 -0.101893 0.03344994 0.183784 -0.102142 0.03344994 0.183722 -0.103639 0.03344994 0.1829569 -0.102047 0.03344994 0.180791 -0.101465 0.03344994 0.182241 -0.101624 0.03344994 0.1852239 -0.09899169 0.03344994 0.184611 -0.09842908 0.03344994 0.1794199 -0.09930527 0.03344994 0.179902 -0.100139 0.03344994 0.180004 -0.100881 0.03344994 0.175175 -0.110276 0.03344994 0.176674 -0.11017 0.03344994 0.176084 -0.10781 0.03344994 0.174726 -0.109642 0.03344994 0.175711 -0.110171 0.03344994 0.181634 -0.100328 0.03344994 0.180033 -0.101093 0.03344994 0.179221 -0.1027989 0.03344994 0.178398 -0.103298 0.03344994 0.177931 -0.1050699 0.03344994 0.177447 -0.103449 0.03344994 0.176509 -0.103229 0.03344994 0.183853 -0.09594929 0.03344994 0.182243 -0.09650397 0.03344994 0.182995 -0.09824317 0.03344994 0.182043 -0.09657305 0.03344994 0.18292 -0.09828519 0.03344994 0.1822699 -0.09865188 0.03344994 0.181775 -0.09931987 0.03344994 0.187457 -0.09860306 0.03344994 0.1836799 -0.09756916 0.03344994 0.186109 -0.09744775 0.03344994 0.188309 -0.09985655 0.03344994 0.188516 -0.09876906 0.03344994 0.187923 -0.09970438 0.03344994 0.187514 -0.09976506 0.03344994 0.187559 -0.09865909 0.03344994 0.187189 -0.100023 0.03344994 0.1866109 -0.09974348 0.03344994 0.187144 -0.100138 0.03344994 0.190684 -0.09708458 0.03344994 0.188475 -0.100976 0.03344994 0.188627 -0.100591 0.03344994 0.188566 -0.100181 0.03344994 0.190686 -0.102596 0.03344994 0.193668 -0.09996306 0.03344994 0.196182 -0.09969067 0.03344994 0.195807 -0.09924638 0.03344994 0.19274 -0.09697157 0.03344994 0.191439 -0.09921467 0.03344994 0.188785 -0.101355 0.03344994 0.1939989 -0.100726 0.03344994 0.1939899 -0.101558 0.03344994 0.1927599 -0.104304 0.03344994 0.193645 -0.102314 0.03344994 0.194333 -0.104324 0.03344994 0.193538 -0.104233 0.03344994 0.19459 -0.104649 0.03344994 0.1952919 -0.102848 0.03344994 0.196296 -0.101247 0.03344994 0.197042 -0.10071 0.03344994 0.194608 -0.105674 0.03344994 0.196395 -0.1053709 0.03344994 0.199302 -0.1091549 0.03344994 0.193641 -0.1128939 0.03344994 0.193917 -0.114807 0.03344994 0.192727 -0.110318 0.03344994 0.192356 -0.111941 0.03344994 0.192681 -0.111684 0.03344994 0.1933169 -0.113152 0.03344994 0.192908 -0.113213 0.03344994 0.192522 -0.1130599 0.03344994 0.192265 -0.112736 0.03344994 0.1922039 -0.112326 0.03344994 0.194155 -0.113875 0.03344994 0.193794 -0.112509 0.03344994 0.195552 -0.112602 0.03344994 0.193733 -0.1121 0.03344994 0.193475 -0.111775 0.03344994 0.19309 -0.111623 0.03344994 0.187013 -0.115915 0.03344994 0.186806 -0.115762 0.03344994 0.1863909 -0.117241 0.03344994 0.187242 -0.117713 0.03344994 0.1853229 -0.115309 0.03344994 0.18676 -0.115877 0.03344994 0.1864359 -0.116135 0.03344994 0.186026 -0.116196 0.03344994 0.184507 -0.11739 0.03344994 0.1837469 -0.117981 0.03344994 0.183266 -0.118815 0.03344994 0.182969 -0.119685 0.03344994 0.178653 -0.112856 0.03344994 0.1786569 -0.113052 0.03344994 0.178313 -0.113951 0.03344994 0.180736 -0.11141 0.03344994 0.1804119 -0.111667 0.03344994 0.179617 -0.111576 0.03344994 0.178637 -0.112089 0.03344994 0.17936 -0.1112509 0.03344994 0.1790159 -0.109984 0.03344994 0.193996 -0.106499 0.03344994 0.193122 -0.105285 0.03344994 0.1933799 -0.1056089 0.03344994 0.193765 -0.105762 0.03344994 0.185554 -0.09975469 0.03344994 0.187037 -0.100408 0.03344994 0.1881499 -0.101233 0.03344994 0.187741 -0.101294 0.03344994 0.187355 -0.101142 0.03344994 0.185999 -0.100569 0.03344994 0.187098 -0.100817 0.03344994 0.182823 -0.110737 0.03344994 0.179628 -0.109159 0.03344994 0.185573 -0.114847 0.03344994 0.186209 -0.114606 0.03344994 0.185777 -0.1137199 0.03344994 0.186594 -0.114758 0.03344994 0.186852 -0.115083 0.03344994 0.187625 -0.11509 0.03344994 0.188377 -0.1010529 0.03344994 0.1881729 -0.10218 0.03344994 0.192148 -0.105129 0.03344994 0.1930609 -0.104875 0.03344994 0.181269 -0.104216 0.03344994 0.181593 -0.103959 0.03344994 0.1801559 -0.103391 0.03344994 0.180308 -0.103006 0.03344994 0.179794 -0.102025 0.03344994 0.180633 -0.102748 0.03344994 0.180859 -0.104277 0.03344994 0.180474 -0.104125 0.03344994 0.178974 -0.103914 0.03344994 0.180217 -0.1037999 0.03344994 0.181042 -0.102687 0.03344994 0.181427 -0.10284 0.03344994 0.181685 -0.103164 0.03344994 0.181746 -0.103574 0.03344994 0.181801 -0.110771 0.03344994 0.1756719 -0.102852 0.03344994 0.173756 -0.103754 0.03194999 0.173575 -0.104254 0.03194999 0.1732389 -0.1059859 0.03194999 0.173166 -0.106361 0.03194999 0.174585 -0.108447 0.03344994 0.173086 -0.108507 0.03194999 0.173328 -0.110555 0.03194999 0.174765 -0.109972 0.03344994 0.17631 -0.103139 0.03214997 0.1746 -0.10162 0.03194999 0.179275 -0.0991404 0.03194999 0.17824 -0.100166 0.03194999 0.17581 -0.09966975 0.03194999 0.173727 -0.103744 0.03024995 0.1746 -0.10162 0.03024995 0.177228 -0.0993483 0.03024995 0.178821 -0.09782469 0.03024995 0.179104 -0.0964933 0.03024995 0.1806499 -0.09659236 0.03024995 0.18266 -0.09568685 0.03024995 0.18325 -0.09455829 0.03024995 0.184795 -0.09513407 0.03024995 0.185505 -0.09412789 0.03024995 0.186992 -0.09494996 0.03024995 0.189189 -0.09513986 0.03024995 0.190073 -0.09439957 0.03024995 0.191322 -0.09569829 0.03024995 0.1933299 -0.09660917 0.03024995 0.195155 -0.09784638 0.03024995 0.196149 -0.09750729 0.03024995 0.196745 -0.09937417 0.03024995 0.198054 -0.101149 0.03024995 0.199044 -0.103119 0.03024995 0.199042 -0.101052 0.03024995 0.199687 -0.105228 0.03024995 0.199964 -0.107416 0.03024995 0.199867 -0.109618 0.03024995 0.1994 -0.111773 0.03024995 0.198575 -0.113818 0.03024995 0.1993499 -0.11428 0.03024995 0.197417 -0.115694 0.03024995 0.195958 -0.117347 0.03024995 0.19424 -0.11873 0.03024995 0.194846 -0.1194069 0.03024995 0.192314 -0.119803 0.03024995 0.190234 -0.120535 0.03024995 0.18806 -0.120905 0.03024995 0.188444 -0.121772 0.03024995 0.185855 -0.120902 0.03024995 0.183682 -0.120526 0.03024995 0.181604 -0.119789 0.03024995 0.179681 -0.118711 0.03024995 0.177967 -0.117323 0.03024995 0.177801 -0.118393 0.03024995 0.176513 -0.115666 0.03024995 0.175359 -0.113787 0.03024995 0.174907 -0.114848 0.03024995 0.17454 -0.11174 0.03024995 0.173937 -0.112768 0.03024995 0.174078 -0.109584 0.03024995 0.173987 -0.107381 0.03024995 0.173321 -0.110556 0.03024995 0.17427 -0.105194 0.03024995 0.174919 -0.103087 0.03024995 0.175914 -0.101119 0.03024995 0.192842 -0.120524 0.03194999 0.192504 -0.120703 0.03194999 0.190699 -0.121342 0.03024995 0.188443 -0.121766 0.03194999 0.186149 -0.121825 0.03024995 0.181689 -0.120806 0.03024995 0.180513 -0.120256 0.03194999 0.179645 -0.11976 0.03024995 0.1796669 -0.119725 0.03194999 0.173095 -0.108274 0.03194999 0.173215 -0.105982 0.03024995 0.174304 -0.102235 0.03194999 0.17581 -0.09966975 0.03024995 0.177325 -0.09794509 0.03194999 0.177828 -0.09748387 0.03194999 0.179122 -0.09651809 0.03194999 0.179548 -0.09620016 0.03194999 0.181097 -0.09535396 0.03024995 0.1811079 -0.09537547 0.03194999 0.181446 -0.09519678 0.03194999 0.183476 -0.09449756 0.03194999 0.185506 -0.09413409 0.03194999 0.185589 -0.09411931 0.03194999 0.1877999 -0.09407448 0.03194999 0.1877999 -0.09407448 0.03024995 0.190073 -0.09439957 0.03194999 0.193437 -0.09564357 0.03194999 0.194283 -0.09617477 0.03194999 0.195255 -0.09678536 0.03194999 0.19826 -0.09983438 0.03194999 0.200013 -0.103132 0.03194999 0.200013 -0.103132 0.03024995 0.200628 -0.1053439 0.03024995 0.200864 -0.107393 0.03194999 0.200871 -0.107627 0.03024995 0.200784 -0.109539 0.03194999 0.200223 -0.112156 0.03024995 0.200194 -0.112146 0.03194999 0.1996459 -0.113665 0.03194999 0.198139 -0.11623 0.03024995 0.198139 -0.11623 0.03194999 0.196624 -0.117955 0.03194999 0.196624 -0.117955 0.03024995 0.196122 -0.118416 0.03194999 0.194827 -0.119382 0.03194999 0.175496 -0.110213 0.03194999 0.173337 -0.110639 0.03194999 0.173937 -0.112768 0.03194999 0.176873 -0.113852 0.03194999 0.177476 -0.114781 0.03194999 0.174907 -0.114848 0.03194999 0.176048 -0.103769 0.02574998 0.176062 -0.103732 0.02574998 0.1934829 -0.09822708 0.02574998 0.18533 -0.119534 0.02574998 0.195006 -0.1164579 0.02574998 0.178944 -0.09944158 0.02574998 0.176502 -0.102735 0.02574998 0.17699 -0.101851 0.03194999 0.17824 -0.100166 0.02824997 0.187615 -0.09626746 0.02824997 0.189729 -0.09657865 0.02574998 0.189729 -0.09657865 0.02824997 0.1896899 -0.09656947 0.02574998 0.18862 -0.09636616 0.02824997 0.18862 -0.09636616 0.02574998 0.196507 -0.101166 0.02824997 0.196507 -0.101166 0.03194999 0.196474 -0.101119 0.03194999 0.196474 -0.101119 0.03214997 0.197582 -0.103013 0.02574998 0.198634 -0.106976 0.02824997 0.198638 -0.107016 0.02574998 0.198638 -0.107016 0.03214997 0.198454 -0.105687 0.03194999 0.19764 -0.112761 0.03194999 0.198222 -0.111173 0.02824997 0.197448 -0.113165 0.02574998 0.197448 -0.113165 0.02824997 0.195006 -0.1164579 0.02824997 0.196372 -0.11492 0.02824997 0.197466 -0.11313 0.02574998 0.197466 -0.11313 0.03194999 0.197902 -0.1121309 0.02824997 0.197902 -0.1121309 0.02574998 0.194148 -0.117193 0.02574998 0.194977 -0.116486 0.02574998 0.194148 -0.117193 0.02824997 0.193324 -0.117777 0.02824997 0.189427 -0.11939 0.02574998 0.187385 -0.119643 0.03194999 0.187385 -0.119643 0.02824997 0.18533 -0.119534 0.02824997 0.1852909 -0.119528 0.02574998 0.184221 -0.119321 0.02574998 0.184221 -0.119321 0.02824997 0.18325 -0.119041 0.03194999 0.18325 -0.119041 0.02824997 0.176873 -0.113852 0.02574998 0.176367 -0.112887 0.02574998 0.1754429 -0.109926 0.02824997 0.175981 -0.111953 0.03194999 0.175981 -0.111953 0.02824997 0.176367 -0.112887 0.02824997 0.1768929 -0.1138859 0.02824997 0.1768929 -0.1138859 0.02574998 0.198674 -0.108105 0.02574998 0.198283 -0.104948 0.03194999 0.198283 -0.104948 0.02824997 0.197582 -0.103013 0.02824997 0.197566 -0.102977 0.02574998 0.197057 -0.102014 0.02824997 0.197057 -0.102014 0.02574998 0.198617 -0.109113 0.03214997 0.198617 -0.109113 0.02824997 0.198621 -0.108651 0.03214997 0.198674 -0.108105 0.02824997 0.195143 -0.09957307 0.02824997 0.1943899 -0.09889978 0.02824997 0.1907539 -0.09687727 0.03194999 0.191679 -0.09723716 0.02824997 0.1934829 -0.09822708 0.02824997 0.193516 -0.09824919 0.02574998 0.193516 -0.09824919 0.03214997 0.1943899 -0.09889978 0.02574998 0.184522 -0.09650987 0.02574998 0.185808 -0.09630829 0.03194999 0.185518 -0.09634095 0.02824997 0.185518 -0.09634095 0.03214997 0.184522 -0.09650987 0.02824997 0.1834689 -0.09678769 0.02574998 0.183431 -0.09679961 0.02824997 0.183431 -0.09679961 0.02574998 0.179802 -0.09870696 0.02574998 0.179802 -0.09870696 0.02824997 0.178944 -0.09944158 0.02824997 0.1797699 -0.09873139 0.02574998 0.1797699 -0.09873139 0.03214997 0.180945 -0.09797209 0.03214997 0.181532 -0.09759306 0.03214997 0.181532 -0.09759306 0.02824997 0.175484 -0.1057479 0.02824997 0.176048 -0.103769 0.02824997 0.17631 -0.103139 0.03194999 0.176502 -0.102735 0.02824997 0.17699 -0.101851 0.02824997 0.175276 -0.107795 0.02574998 0.175496 -0.110213 0.03214997 0.175275 -0.107835 0.03214997 0.175484 -0.1057479 0.03214997 0.175276 -0.107795 0.02824997 0.175275 -0.107835 0.02574998 0.175315 -0.108924 0.02824997 0.175315 -0.108924 0.02574998 0.179591 -0.117025 0.02574998 0.17956 -0.117 0.02574998 0.18133 -0.118198 0.02824997 0.178089 -0.115561 0.02824997 0.17956 -0.117 0.02824997 0.179591 -0.117025 0.03214997 0.180467 -0.117673 0.02824997 0.180467 -0.117673 0.02574998 0.191467 -0.118753 0.02824997 0.189427 -0.11939 0.02824997 0.1894659 -0.119382 0.02574998 0.190519 -0.1191 0.02824997 0.190519 -0.1191 0.02574998 0.191467 -0.118753 0.03214997 0.193018 -0.117938 0.03214997 0.199615 -0.106716 0.02574998 0.2001039 -0.106586 0.02674996 0.198634 -0.106976 0.02574998 0.2001039 -0.106586 0.02824997 0.177325 -0.09794509 0.03024995 0.17581 -0.09966975 0.02239996 0.173079 -0.108273 0.03024995 0.173321 -0.110556 0.02239996 0.174907 -0.114848 0.02239996 0.176207 -0.11674 0.03024995 0.183877 -0.1215 0.02239996 0.183877 -0.1215 0.03024995 0.186149 -0.121825 0.02239996 0.190699 -0.121342 0.02239996 0.192853 -0.120546 0.03024995 0.194846 -0.1194069 0.02239996 0.1993499 -0.11428 0.02239996 0.200223 -0.112156 0.02239996 0.200735 -0.1099179 0.03024995 0.200735 -0.1099179 0.02239996 0.200628 -0.1053439 0.02239996 0.197742 -0.09915965 0.02239996 0.197742 -0.09915965 0.03024995 0.194305 -0.09613978 0.02239996 0.194305 -0.09613978 0.03024995 0.192261 -0.09509438 0.02239996 0.192261 -0.09509438 0.03024995 0.185505 -0.09412789 0.02239996 0.18325 -0.09455829 0.02239996 0.176373 -0.100087 0.02239996 0.176373 -0.100087 0.03024995 0.177854 -0.0984081 0.02239996 0.177854 -0.0984081 0.03024995 0.179598 -0.09700387 0.03024995 0.181554 -0.0959146 0.03024995 0.181554 -0.0959146 0.02239996 0.183666 -0.09517151 0.02239996 0.183666 -0.09517151 0.03024995 0.185873 -0.09479606 0.02239996 0.185873 -0.09479606 0.03024995 0.188112 -0.09479898 0.02239996 0.188112 -0.09479898 0.03024995 0.190318 -0.09518027 0.03024995 0.1924279 -0.09592896 0.02239996 0.1924279 -0.09592896 0.03024995 0.1943809 -0.09702348 0.02239996 0.1943809 -0.09702348 0.03024995 0.196121 -0.0984323 0.02239996 0.196121 -0.0984323 0.03024995 0.197598 -0.100115 0.02239996 0.197598 -0.100115 0.03024995 0.198769 -0.102023 0.03024995 0.1996009 -0.104101 0.02239996 0.1996009 -0.104101 0.03024995 0.20007 -0.1062909 0.03024995 0.2001619 -0.108528 0.03024995 0.2001619 -0.108528 0.02239996 0.1998749 -0.110748 0.03024995 0.199216 -0.112888 0.03024995 0.199216 -0.112888 0.02239996 0.198206 -0.114886 0.03024995 0.195254 -0.1182309 0.02239996 0.1968719 -0.116684 0.03024995 0.195254 -0.1182309 0.03024995 0.191356 -0.120402 0.02239996 0.193397 -0.119482 0.03024995 0.189188 -0.120963 0.02239996 0.191356 -0.120402 0.03024995 0.189188 -0.120963 0.03024995 0.186957 -0.12115 0.03024995 0.184727 -0.120957 0.02239996 0.184727 -0.120957 0.03024995 0.182561 -0.1203899 0.03024995 0.182561 -0.1203899 0.02239996 0.180522 -0.119465 0.02239996 0.180522 -0.119465 0.03024995 0.178669 -0.118209 0.03024995 0.177054 -0.116658 0.03024995 0.1757259 -0.114856 0.03024995 0.1747199 -0.112855 0.03024995 0.174067 -0.110714 0.02239996 0.174067 -0.110714 0.03024995 0.173786 -0.108493 0.03024995 0.173884 -0.106256 0.03024995 0.174359 -0.104068 0.03024995 0.175196 -0.101992 0.02239996 0.175196 -0.101992 0.03024995 0.173884 -0.106256 0.02239996 0.173215 -0.105982 0.02239996 0.173727 -0.103744 0.02239996 0.174359 -0.104068 0.02239996 0.1746 -0.10162 0.02239996 0.179598 -0.09700387 0.02239996 0.177325 -0.09794509 0.02239996 0.179104 -0.0964933 0.02239996 0.181097 -0.09535396 0.02239996 0.1877999 -0.09407448 0.02239996 0.190073 -0.09439957 0.02239996 0.190318 -0.09518027 0.02239996 0.196149 -0.09750729 0.02239996 0.198769 -0.102023 0.02239996 0.199042 -0.101052 0.02239996 0.20007 -0.1062909 0.02239996 0.200013 -0.103132 0.02239996 0.200871 -0.107627 0.02239996 0.1998749 -0.110748 0.02239996 0.198206 -0.114886 0.02239996 0.1968719 -0.116684 0.02239996 0.198139 -0.11623 0.02239996 0.196624 -0.117955 0.02239996 0.193397 -0.119482 0.02239996 0.192853 -0.120546 0.02239996 0.186957 -0.12115 0.02239996 0.188444 -0.121772 0.02239996 0.181689 -0.120806 0.02239996 0.178669 -0.118209 0.02239996 0.179645 -0.11976 0.02239996 0.177801 -0.118393 0.02239996 0.177054 -0.116658 0.02239996 0.176207 -0.11674 0.02239996 0.1757259 -0.114856 0.02239996 0.1747199 -0.112855 0.02239996 0.173937 -0.112768 0.02239996 0.173786 -0.108493 0.02239996 0.173079 -0.108273 0.02239996 0.07395756 0.112002 -0.06950485 0.07395756 0.110574 -0.0703299 0.07345759 0.110641 -0.07044595 0.07345759 0.112069 -0.06962096 0.07309156 0.110824 -0.07076299 0.07295757 0.111074 -0.07119596 0.07295757 0.112503 -0.07037097 0.07309156 0.112752 -0.07080399 0.07395756 0.111574 -0.07206195 0.07445758 0.1115069 -0.07194596 0.07482355 0.110824 -0.07076299 0.07482355 0.1122519 -0.069938 0.07445758 0.112069 -0.06962096 0.08037215 0.111987 -0.07277756 0.08037215 0.113416 -0.07195258 0.08035326 0.112203 -0.07315218 0.0801534 0.112395 -0.07348465 0.0801534 0.113824 -0.07265967 0.07980996 0.113956 -0.07288789 0.06923305 0.112574 -0.073794 0.07938736 0.114002 -0.07296895 0.05737495 0.06786477 0.003643691 0.05908244 0.06701105 0.005122482 0.05908244 0.06463611 0.009236097 0.05924999 0.0643236 0.009777367 0.05691748 0.06463611 0.009236097 0.05862498 0.06786477 0.003643691 0.05908244 0.06763607 0.004039943 0.06309205 0.06298667 0.01209288 0.07445758 0.110641 -0.07044595 0.0749576 0.111074 -0.07119596 0.05096828 0.06316035 0.01179206 0.05674999 0.0643236 0.009777367 0.05098706 0.06294405 0.01216655 0.05195307 0.06257361 0.0128085 0.06210726 0.06257361 0.0128085 0.06255608 0.06262665 0.01271635 0.06290948 0.06277495 0.01245957 0.07482355 0.111324 -0.07162898 0.05691748 0.06701105 0.005122482 0.05737495 0.06678229 0.005518734 0.05862498 0.06486475 0.008839845 0.05799996 0.06669861 0.005663752 0.05153048 0.0626204 0.01272737 0.05118697 0.06275218 0.01249909 0.07938736 0.112574 -0.073794 0.07345759 0.1115069 -0.07194596 0.06878429 0.11252 -0.07370185 0.07309156 0.111324 -0.07162898 0.06843096 0.112372 -0.0734452 0.06824827 0.11216 -0.07307839 0.05799996 0.06794857 0.003498673 0.07980996 0.112527 -0.07371288 0.05674999 0.06732356 0.004581212 0.05691748 0.06763607 0.004039943 0.05908244 0.06906497 0.004864931 0.05924999 0.06732356 0.004581212 0.05908244 0.06843996 0.00594747 0.05862498 0.06678229 0.005518734 0.05691748 0.06843996 0.00594747 0.05674999 0.06875246 0.0054062 0.05096828 0.06458926 0.01261705 0.05691748 0.06906497 0.004864931 0.05737495 0.06929379 0.004468739 0.07345759 0.112936 -0.07112097 0.07395756 0.113003 -0.07123696 0.06923305 0.114002 -0.07296895 0.05098706 0.06437307 0.01299154 0.05737495 0.06629377 0.009664893 0.05737495 0.06821119 0.006343722 0.05799996 0.06637746 0.009519815 0.05195307 0.06400245 0.01363348 0.05153048 0.0640493 0.01355236 0.05691748 0.06543999 0.01114368 0.05118697 0.06418108 0.01332408 0.05862498 0.06521117 0.01153987 0.06210726 0.06400245 0.01363348 0.06255608 0.06405568 0.0135414 0.05908244 0.06543999 0.01114368 0.06290948 0.06420385 0.01328456 0.05924999 0.0657525 0.01060235 0.06309205 0.06441569 0.01291787 0.05924999 0.06875246 0.0054062 0.05862498 0.06821119 0.006343722 0.05799996 0.06812745 0.00648874 0.07445758 0.112936 -0.07112097 0.07482355 0.112752 -0.07080399 0.05799996 0.06937748 0.004323661 0.07309156 0.1122519 -0.069938 0.06824827 0.113589 -0.0722534 0.06843096 0.113801 -0.07262015 0.06878429 0.113949 -0.07287687 0.05862498 0.06929379 0.004468739 0.0749576 0.112503 -0.07037097 0.08035326 0.113632 -0.07232719 0.05799996 0.06369858 0.01085984 0.05799996 0.06512749 0.01168489 0.05737495 0.06521117 0.01153987 0.05737495 0.06378227 0.01071488 0.05691748 0.06401109 0.01031869 0.05674999 0.0657525 0.01060235 0.05691748 0.06606495 0.01006108 0.05737495 0.06486475 0.008839845 0.05799996 0.06494855 0.008694827 0.05862498 0.06629377 0.009664893 0.05908244 0.06606495 0.01006108 0.05908244 0.06401109 0.01031869 0.05862498 0.06378227 0.01071488 0.129272 0.115935 -0.07320755 0.129272 0.114395 -0.07300537 -0.0907275 0.112961 -0.07360017 0.129272 0.112016 -0.07483255 -0.0907275 0.112016 -0.07483255 -0.0907275 0.111814 -0.07637226 -0.0907275 0.112409 -0.07780677 -0.0907275 0.115181 -0.0789538 0.129272 0.115181 -0.0789538 -0.0907275 0.1166149 -0.078359 0.129272 0.11756 -0.07712668 -0.0907275 0.117762 -0.07558697 -0.0907275 0.1171669 -0.07415246 -0.0907275 0.115935 -0.07320755 -0.0907275 0.114395 -0.07300537 0.145379 0.11525 -0.06801927 0.146024 0.116455 -0.06875628 0.146906 0.117012 -0.06990671 0.151546 0.116352 -0.06797987 0.147788 0.116773 -0.0711624 0.148433 0.1158 -0.07218688 0.152607 0.113916 -0.06937146 0.148433 0.112826 -0.07257956 0.147788 0.111621 -0.07184261 0.151546 0.111201 -0.06865996 0.149425 0.110923 -0.06655687 0.148649 0.11191 -0.06564337 0.141713 0.115544 -0.07024657 0.142211 0.116761 -0.07107287 0.148669 0.114356 -0.07270556 0.144254 0.11471 -0.07538795 0.1440719 0.113176 -0.07522928 0.146906 0.111064 -0.07069206 0.142211 0.111609 -0.07175296 0.146024 0.111304 -0.06943637 0.145379 0.112276 -0.068412 0.145143 0.1137199 -0.06789326 0.141713 0.11257 -0.07063925 0.142892 0.117334 -0.07234525 0.143573 0.117111 -0.07372289 0.139346 0.116406 -0.07677727 0.1440719 0.11615 -0.07483661 0.143573 0.111959 -0.07440298 0.139006 0.112207 -0.07627826 0.142892 0.111386 -0.0731306 0.138079 0.111833 -0.07344967 0.14153 0.11401 -0.0700879 0.138079 0.116985 -0.07276958 0.138543 0.11757 -0.0741313 0.133731 0.117121 -0.07380455 0.139006 0.117358 -0.07559818 0.1343719 0.116563 -0.07796108 0.13947 0.114969 -0.07735258 0.139346 0.113432 -0.07716989 0.1342 0.112358 -0.07742226 0.138543 0.111622 -0.0749166 0.133731 0.11197 -0.0744847 0.13774 0.112785 -0.07227057 0.137616 0.114222 -0.07169526 0.13774 0.11576 -0.07187795 0.129272 0.1171669 -0.07415246 0.133966 0.117714 -0.07522076 0.1342 0.117509 -0.07674217 0.129272 0.117762 -0.07558697 0.129272 0.1166149 -0.078359 0.1344349 0.115128 -0.07855099 0.1343719 0.113588 -0.07835376 0.129272 0.113641 -0.07875168 0.129272 0.112409 -0.07780677 0.133966 0.111765 -0.07600605 0.129272 0.111814 -0.07637226 0.133559 0.112917 -0.07326579 0.129272 0.112961 -0.07360017 0.133496 0.114352 -0.07267588 0.133559 0.115891 -0.07287305 0.151193 0.1154479 -0.0677427 0.1504859 0.115621 -0.06700658 0.1504859 0.116612 -0.06687569 0.149425 0.116075 -0.06587678 0.148649 0.114885 -0.06525075 0.1492609 0.112486 -0.06618505 0.148364 0.11336 -0.06516528 0.149779 0.111828 -0.06679409 0.1504859 0.1116549 -0.06753015 0.1504859 0.110664 -0.0676611 0.152323 0.112391 -0.0692861 0.15171 0.11479 -0.06835168 0.152323 0.115365 -0.06889337 0.146318 0.112215 -0.06972408 0.146906 0.112055 -0.07056117 0.147494 0.1124269 -0.07132816 0.151193 0.112013 -0.06819605 0.15171 0.112807 -0.06861346 0.1518999 0.1138229 -0.06867051 0.148082 0.11425 -0.07190346 0.147494 0.1158609 -0.07087481 0.146906 0.116021 -0.0700376 0.149779 0.115263 -0.06634068 0.1492609 0.114469 -0.06592327 0.146318 0.115649 -0.06927067 0.145888 0.114846 -0.06877928 0.149071 0.113453 -0.06586641 0.145888 0.112863 -0.06904107 0.142892 0.112377 -0.07299965 0.143346 0.11276 -0.073848 0.147924 0.11323 -0.07181948 0.143679 0.115553 -0.07413697 0.147924 0.115213 -0.0715577 0.143346 0.116194 -0.07339459 0.1424379 0.115961 -0.07162785 0.14573 0.113826 -0.0686953 0.1421059 0.115149 -0.0710771 0.1424379 0.1125259 -0.07208126 0.138852 0.113003 -0.07569348 0.143679 0.113571 -0.07439875 0.139078 0.11382 -0.07628786 0.1438 0.114593 -0.07450455 0.139161 0.114845 -0.07640969 0.139078 0.115803 -0.0760262 0.142892 0.116343 -0.0724762 0.141984 0.114127 -0.07097131 0.1421059 0.113167 -0.07133877 0.133653 0.114481 -0.07365506 0.1380079 0.113389 -0.0730217 0.138234 0.112754 -0.07380777 0.138543 0.112613 -0.0747857 0.133966 0.112757 -0.07587516 0.134122 0.113152 -0.0768193 0.1342779 0.114998 -0.0775718 0.138852 0.116437 -0.07524007 0.134122 0.116586 -0.07636588 0.138543 0.1165789 -0.0742622 0.138234 0.116189 -0.07335436 0.1380079 0.115372 -0.07275986 0.133695 0.115507 -0.07378649 0.137925 0.114347 -0.07263815 0.133809 0.112893 -0.07486099 0.129272 0.112805 -0.07624137 0.129272 0.113202 -0.07719767 0.134236 0.113972 -0.07744038 0.129272 0.114023 -0.07782769 0.129272 0.11505 -0.07796239 0.134236 0.115955 -0.07717859 0.129272 0.116636 -0.07674425 0.133966 0.116722 -0.07535165 0.133809 0.116328 -0.07440745 0.129272 0.114526 -0.07399678 0.133695 0.113524 -0.07404828 0.129272 0.115553 -0.0741316 -0.0907275 0.115553 -0.0741316 0.129272 0.116374 -0.0747615 0.129272 0.116771 -0.0757178 -0.0907275 0.116636 -0.07674425 0.129272 0.116006 -0.0775659 -0.0907275 0.11505 -0.07796239 -0.0907275 0.114023 -0.07782769 -0.0907275 0.113202 -0.07719767 -0.0907275 0.112805 -0.07624137 0.129272 0.11294 -0.07521486 -0.0907275 0.11357 -0.07439339 0.129272 0.11357 -0.07439339 -0.0907275 0.116771 -0.0757178 -0.0907275 0.116006 -0.0775659 -0.0907275 0.11756 -0.07712668 -0.0907275 0.113641 -0.07875168 -0.0907275 0.11294 -0.07521486 -0.0907275 0.114526 -0.07399678 -0.0907275 0.116374 -0.0747615 -0.06665539 0.07789856 -0.01373517 -0.0672304 0.07925045 -0.01277679 -0.06765127 0.07761108 -0.01323717 -0.06765127 0.07846498 -0.01141625 -0.06665539 0.07817751 -0.01091825 -0.06608039 0.07825446 -0.01105177 -0.06565946 0.07703608 -0.0122413 -0.06565946 0.07761108 -0.01323717 -0.06565946 0.07903999 -0.01241219 -0.06608039 0.07925045 -0.01277679 -0.0616554 0.07789856 -0.01373517 -0.06265127 0.07903999 -0.01241219 -0.06265127 0.07761108 -0.01323717 -0.06223034 0.07682555 -0.01187676 -0.06108039 0.07825446 -0.01105177 -0.06108039 0.07682555 -0.01187676 -0.06050539 0.07875245 -0.01191425 -0.06050539 0.07732355 -0.0127393 -0.04204237 0.110574 -0.0703299 -0.04254239 0.110641 -0.07044595 -0.04254239 0.112069 -0.06962096 -0.04290837 0.110824 -0.07076299 -0.04290837 0.1122519 -0.069938 -0.04304236 0.112503 -0.07037097 -0.04304236 0.111074 -0.07119596 -0.04290837 0.112752 -0.07080399 -0.04254239 0.1115069 -0.07194596 -0.04204237 0.113003 -0.07123696 -0.04117637 0.111324 -0.07162898 -0.04117637 0.1122519 -0.069938 -0.04154235 0.112069 -0.06962096 -0.05799996 0.06512749 0.01168489 -0.05862498 0.06521117 0.01153987 -0.05862498 0.06378227 0.01071488 -0.05908244 0.06401109 0.01031869 -0.05924999 0.0643236 0.009777367 -0.05908244 0.06606495 0.01006108 -0.05799996 0.06494855 0.008694827 -0.05737495 0.06486475 0.008839845 -0.05691748 0.06606495 0.01006108 -0.05737495 0.06378227 0.01071488 -0.05799996 0.06369858 0.01085984 -0.05954569 0.07987666 -0.01716148 -0.05919235 0.08145385 -0.01659327 -0.05900967 0.08166569 -0.01695996 -0.04775166 0.11216 -0.07307839 -0.03661257 0.112574 -0.073794 -0.03562778 0.113416 -0.07195258 -0.03564667 0.113632 -0.07232719 -0.03564667 0.112203 -0.07315218 -0.03584659 0.112395 -0.07348465 -0.03584659 0.113824 -0.07265967 -0.03618997 0.113956 -0.07288789 -0.03661257 0.114002 -0.07296895 -0.0650317 0.06316035 0.01179206 -0.06179147 0.07234859 -0.004122257 -0.06112557 0.07423669 -0.007392704 -0.06211036 0.07625246 -0.007584095 -0.06211036 0.07482355 -0.008409082 -0.06915539 0.07625246 -0.007584095 -0.06915539 0.07482355 -0.008409082 -0.07015538 0.08075249 -0.01537835 -0.07015538 0.07532358 -0.009275138 -0.05862498 0.06929379 0.004468739 -0.06665539 0.07932746 -0.01291018 -0.07015538 0.07675248 -0.00845015 -0.0678054 0.07875245 -0.01191425 -0.06765127 0.07903999 -0.01241219 -0.07002139 0.08100247 -0.01581138 -0.06223034 0.07925045 -0.01277679 -0.05999445 0.08125245 -0.01624435 -0.0616554 0.07932746 -0.01291018 -0.05987769 0.08126628 -0.01626837 -0.06108039 0.07925045 -0.01277679 -0.06065946 0.07903999 -0.01241219 -0.06565946 0.07846498 -0.01141625 -0.06550538 0.07875245 -0.01191425 -0.06265127 0.07846498 -0.01141625 -0.06280535 0.07875245 -0.01191425 -0.0616554 0.07817751 -0.01091825 -0.06168776 0.07620567 -0.007502973 -0.06134438 0.07607388 -0.007274746 -0.06114447 0.07588189 -0.006942212 -0.06065946 0.07846498 -0.01141625 -0.06223034 0.07825446 -0.01105177 -0.06965535 0.07631945 -0.007700145 -0.07002139 0.0765025 -0.008017122 -0.0672304 0.07825446 -0.01105177 -0.04254239 0.112936 -0.07112097 -0.04676687 0.114002 -0.07296895 -0.04204237 0.112002 -0.06950485 -0.04154235 0.112936 -0.07112097 -0.04117637 0.112752 -0.07080399 -0.05954569 0.08130568 -0.0163365 -0.04104238 0.112503 -0.07037097 -0.0472157 0.113949 -0.07287687 -0.04756897 0.113801 -0.07262015 -0.04775166 0.113589 -0.0722534 -0.04960638 0.07377749 -0.003297269 -0.05862498 0.06821119 0.006343722 -0.05987769 0.06400245 0.01363348 -0.05691748 0.06906497 0.004864931 -0.05674999 0.06875246 0.0054062 -0.05691748 0.06843996 0.00594747 -0.05389267 0.06400245 0.01363348 -0.05737495 0.06521117 0.01153987 -0.05799996 0.06637746 0.009519815 -0.05691748 0.06543999 0.01114368 -0.05344384 0.06405568 0.0135414 -0.05309045 0.06420385 0.01328456 -0.05674999 0.0657525 0.01060235 -0.05290788 0.06441569 0.01291787 -0.05737495 0.06629377 0.009664893 -0.05908244 0.06543999 0.01114368 -0.05924999 0.0657525 0.01060235 -0.05862498 0.06629377 0.009664893 -0.06446945 0.0640493 0.01355236 -0.06501287 0.06437307 0.01299154 -0.0650317 0.06458926 0.01261705 -0.06481295 0.06418108 0.01332408 -0.06404685 0.06400245 0.01363348 -0.05987769 0.07377749 -0.003297269 -0.06179147 0.07377749 -0.003297269 -0.06112557 0.07566565 -0.006567716 -0.05737495 0.06821119 0.006343722 -0.05799996 0.06812745 0.00648874 -0.05862498 0.06678229 0.005518734 -0.05908244 0.06843996 0.00594747 -0.05924999 0.06732356 0.004581212 -0.05924999 0.06875246 0.0054062 -0.05908244 0.06906497 0.004864931 -0.05862498 0.06786477 0.003643691 -0.05799996 0.06794857 0.003498673 -0.05799996 0.06937748 0.004323661 -0.05737495 0.06786477 0.003643691 -0.05737495 0.06929379 0.004468739 -0.05691748 0.06763607 0.004039943 -0.05737495 0.06678229 0.005518734 -0.0678054 0.07732355 -0.0127393 -0.06765127 0.07703608 -0.0122413 -0.07002139 0.07507359 -0.00884211 -0.06965535 0.07489049 -0.008525133 -0.0672304 0.07682555 -0.01187676 -0.06168776 0.0747767 -0.00832796 -0.06280535 0.07732355 -0.0127393 -0.06265127 0.07703608 -0.0122413 -0.06608039 0.07682555 -0.01187676 -0.05987769 0.07234859 -0.004122257 -0.06114447 0.07445299 -0.0077672 -0.06134438 0.07464498 -0.008099734 -0.0616554 0.0767486 -0.01174324 -0.06665539 0.0767486 -0.01174324 -0.05987769 0.07983738 -0.01709336 -0.06065946 0.07761108 -0.01323717 -0.05999445 0.07982355 -0.01706939 -0.06108039 0.07782149 -0.01360177 -0.07015538 0.07932358 -0.0162034 -0.0672304 0.07782149 -0.01360177 -0.06965535 0.07975655 -0.01695334 -0.06915539 0.07982355 -0.01706939 -0.06608039 0.07782149 -0.01360177 -0.06550538 0.07732355 -0.0127393 -0.06223034 0.07782149 -0.01360177 -0.06481295 0.06275218 0.01249909 -0.06501287 0.06294405 0.01216655 -0.06404685 0.06257361 0.0128085 -0.06446945 0.0626204 0.01272737 -0.05674999 0.0643236 0.009777367 -0.05799996 0.06669861 0.005663752 -0.05290788 0.06298667 0.01209288 -0.04960638 0.07234859 -0.004122257 -0.05691748 0.06463611 0.009236097 -0.05691748 0.06701105 0.005122482 -0.05674999 0.06732356 0.004581212 -0.05389267 0.06257361 0.0128085 -0.05691748 0.06401109 0.01031869 -0.05344384 0.06262665 0.01271635 -0.05309045 0.06277495 0.01245957 -0.05908244 0.06763607 0.004039943 -0.05987769 0.06257361 0.0128085 -0.05908244 0.06463611 0.009236097 -0.05862498 0.06486475 0.008839845 -0.05908244 0.06701105 0.005122482 -0.05900967 0.08023667 -0.01778495 -0.05919235 0.08002495 -0.01741826 -0.06065946 0.07703608 -0.0122413 -0.04154235 0.110641 -0.07044595 -0.03562778 0.111987 -0.07277756 -0.04117637 0.110824 -0.07076299 -0.03618997 0.112527 -0.07371288 -0.04104238 0.111074 -0.07119596 -0.04154235 0.1115069 -0.07194596 -0.04676687 0.112574 -0.073794 -0.04204237 0.111574 -0.07206195 -0.0472157 0.11252 -0.07370185 -0.04756897 0.112372 -0.0734452 -0.04290837 0.111324 -0.07162898 -0.07002139 0.07957357 -0.01663637 -0.06965535 0.08118546 -0.01612836 -0.06915539 0.08125245 -0.01624435 -0.05677866 0.05023056 0.0097 -0.05748748 0.05111229 0.0097 -0.05701869 0.05170369 0.0097 -0.0571233 0.05146896 0.0097 -0.05901056 0.05217087 0.0097 -0.06014299 0.05217295 0.0097 -0.05893635 0.05241686 0.0097 -0.05596059 0.05131918 0.0097 -0.0572828 0.05126768 0.0097 -0.05651056 0.05044937 0.0097 -0.05741494 0.05284166 0.0097 -0.05789285 0.0530194 0.0097 -0.05764269 0.05296069 0.0097 -0.05774074 0.05413424 0.0097 -0.05861967 0.05281639 0.0097 -0.05839717 0.05294489 0.0097 -0.05907499 0.05386197 0.0097 -0.05843007 0.05410647 0.0097 -0.05814969 0.05301398 0.0097 -0.0600875 0.05251449 0.0097 -0.05880326 0.05263668 0.0097 -0.05935978 0.05366539 0.0097 -0.05896794 0.05166286 0.0097 -0.0600875 0.05148547 0.0097 -0.05902135 0.05191415 0.0097 -0.05596059 0.05268079 0.0097 -0.05699735 0.05221307 0.0097 -0.0569759 0.05195707 0.0097 -0.0558778 0.05234485 0.0097 -0.05584996 0.05199998 0.0097 -0.05960929 0.0505743 0.0097 -0.05885368 0.05143278 0.0097 -0.05677866 0.05376935 0.0097 -0.05722409 0.05266976 0.0097 -0.05708187 0.05245566 0.0097 -0.05847489 0.05109155 0.0097 -0.05868589 0.05123829 0.0097 -0.05740177 0.04993486 0.0097 -0.05772435 0.05101275 0.0097 -0.05774074 0.04986566 0.0097 -0.05808657 0.04985165 0.0097 -0.05797845 0.0509752 0.0097 -0.05823409 0.05100208 0.0097 -0.05876237 0.0499897 0.0097 -0.05679994 0.04992145 0.01069998 -0.05697107 0.04983168 0.009949982 -0.05697107 0.04983168 0.01069998 -0.05733227 0.04969477 0.01069998 -0.05771064 0.04961746 0.01069998 -0.05809658 0.04960185 0.01069998 -0.05848008 0.04964846 0.01069998 -0.05885106 0.04975599 0.01069998 -0.05885106 0.04975599 0.009949982 -0.05919998 0.04992145 0.009949982 -0.05919998 0.04992145 0.01069998 -0.05951786 0.05014085 0.01069998 -0.05979639 0.05040848 0.01069998 -0.06002849 0.05071729 0.01069998 -0.06020796 0.0510593 0.009949982 -0.06020796 0.0510593 0.01069998 -0.06033027 0.05142557 0.01069998 -0.0603922 0.05180686 0.01069998 -0.0603922 0.0521931 0.01069998 -0.0603922 0.05180686 0.009949982 -0.0603922 0.0521931 0.009949982 -0.06033027 0.05257439 0.01069998 -0.06033027 0.05257439 0.009949982 -0.06020796 0.05294066 0.01069998 -0.06002849 0.05328267 0.01069998 -0.05979639 0.05359148 0.01069998 -0.05951786 0.05385905 0.009949982 -0.05951786 0.05385905 0.01069998 -0.05919998 0.05407845 0.01069998 -0.05885106 0.05424398 0.01069998 -0.05885106 0.05424398 0.009949982 -0.05848008 0.05435144 0.01069998 -0.05809658 0.05439805 0.01069998 -0.05771064 0.0543825 0.009949982 -0.05771064 0.0543825 0.01069998 -0.05733227 0.05430519 0.01069998 -0.05733227 0.05430519 0.009949982 -0.05697107 0.05416828 0.01069998 -0.05663657 0.05397516 0.01069998 -0.05633747 0.0537309 0.01069998 -0.05608129 0.05344176 0.01069998 -0.05587488 0.05311524 0.01069998 -0.05572348 0.05275994 0.01069998 -0.0556311 0.05238497 0.01069998 -0.05559998 0.05199998 0.01069998 -0.0556311 0.05161499 0.01069998 -0.05572348 0.05123996 0.01069998 -0.05587488 0.05088466 0.01069998 -0.05608129 0.05055814 0.01069998 -0.05633747 0.05026906 0.01069998 -0.05663657 0.05002474 0.01069998 -0.05960929 0.05342566 0.0097 -0.05979639 0.05359148 0.009949982 -0.06002849 0.05328267 0.009949982 -0.06020796 0.05294066 0.009949982 -0.05981719 0.0531491 0.0097 -0.05997794 0.05284267 0.0097 -0.06033027 0.05142557 0.009949982 -0.06014299 0.05182695 0.0097 -0.05997794 0.05115729 0.0097 -0.06002849 0.05071729 0.009949982 -0.05979639 0.05040848 0.009949982 -0.05981719 0.05085086 0.0097 -0.05935978 0.05033457 0.0097 -0.05951786 0.05014085 0.009949982 -0.05907499 0.05013799 0.0097 -0.05848008 0.04964846 0.009949982 -0.05809658 0.04960185 0.009949982 -0.05843007 0.04989337 0.0097 -0.05771064 0.04961746 0.009949982 -0.05733227 0.04969477 0.009949982 -0.0570783 0.05005759 0.0097 -0.05679994 0.04992145 0.009949982 -0.05692499 0.05013799 0.0097 -0.05663657 0.05002474 0.009949982 -0.05633747 0.05026906 0.009949982 -0.05608129 0.05055814 0.009949982 -0.05587488 0.05088466 0.009949982 -0.05628114 0.05070835 0.0097 -0.05609625 0.05100077 0.0097 -0.05572348 0.05123996 0.009949982 -0.0556311 0.05161499 0.009949982 -0.0558778 0.05165505 0.0097 -0.05559998 0.05199998 0.009949982 -0.0556311 0.05238497 0.009949982 -0.05572348 0.05275994 0.009949982 -0.05587488 0.05311524 0.009949982 -0.05609625 0.05299919 0.0097 -0.05608129 0.05344176 0.009949982 -0.05633747 0.0537309 0.009949982 -0.05628114 0.05329155 0.0097 -0.05651056 0.0535506 0.0097 -0.05663657 0.05397516 0.009949982 -0.05697107 0.05416828 0.009949982 -0.0570783 0.05394238 0.0097 -0.05740177 0.05406504 0.0097 -0.05808657 0.05414825 0.0097 -0.05809658 0.05439805 0.009949982 -0.05848008 0.05435144 0.009949982 -0.05919998 0.05407845 0.009949982 -0.05876237 0.05401027 0.0097 -0.05760276 -0.05105507 0.0097 -0.05738025 -0.05118358 0.0097 -0.05719667 -0.05136328 0.0097 -0.0578503 -0.05098599 0.0097 -0.05756986 -0.04989337 0.0097 -0.05723756 -0.0499897 0.0097 -0.05835729 -0.05103927 0.0097 -0.05810707 -0.05098056 0.0097 -0.05825918 -0.04986566 0.0097 -0.05714625 -0.05256718 0.0097 -0.05731409 -0.05276167 0.0097 -0.05664014 -0.05366539 0.0097 -0.05851244 -0.05288767 0.0097 -0.05907499 -0.05386197 0.0097 -0.05703198 -0.05233705 0.0097 -0.05602198 -0.05284267 0.0097 -0.0561828 -0.0531491 0.0097 -0.05664014 -0.05033457 0.0097 -0.05706357 -0.05158305 0.0097 -0.0561828 -0.05085086 0.0097 -0.05948936 -0.0535506 0.0097 -0.05871719 -0.05273228 0.0097 -0.05887669 -0.052531 0.0097 -0.05971878 -0.05329155 0.0097 -0.05990368 -0.05299919 0.0097 -0.05802148 -0.05302476 0.0097 -0.05827558 -0.05298715 0.0097 -0.05859816 -0.05406504 0.0097 -0.05892169 -0.05394238 0.0097 -0.05602198 -0.05115729 0.0097 -0.05698937 -0.05182909 0.0097 -0.055857 -0.05182695 0.0097 -0.05697858 -0.05208575 0.0097 -0.0600394 -0.05268079 0.0097 -0.05898129 -0.05229628 0.0097 -0.05902409 -0.0520429 0.0097 -0.05900257 -0.05178689 0.0097 -0.05752509 -0.05290836 0.0097 -0.0577659 -0.05299788 0.0097 -0.05723756 -0.05401027 0.0097 -0.05791336 -0.05414825 0.0097 -0.05825918 -0.05413424 0.0097 -0.05891805 -0.05154418 0.0097 -0.0600394 -0.05131918 0.0097 -0.05990368 -0.05100077 0.0097 -0.0587759 -0.05133014 0.0097 -0.05858498 -0.05115824 0.0097 -0.05922126 -0.05023056 0.0097 -0.05919998 -0.05407845 0.009949982 -0.05919998 -0.05407845 0.01069998 -0.05936336 -0.05397516 0.009949982 -0.05936336 -0.05397516 0.01069998 -0.05966246 -0.0537309 0.01069998 -0.0599187 -0.05344176 0.01069998 -0.06012505 -0.05311524 0.01069998 -0.06027644 -0.05275994 0.01069998 -0.06027644 -0.05275994 0.009949982 -0.06036889 -0.05238497 0.01069998 -0.06036889 -0.05238497 0.009949982 -0.06039994 -0.05199998 0.01069998 -0.06036889 -0.05161499 0.01069998 -0.06036889 -0.05161499 0.009949982 -0.06027644 -0.05123996 0.01069998 -0.06027644 -0.05123996 0.009949982 -0.06012505 -0.05088466 0.01069998 -0.06012505 -0.05088466 0.009949982 -0.0599187 -0.05055814 0.01069998 -0.05966246 -0.05026906 0.01069998 -0.05936336 -0.05002474 0.01069998 -0.05902886 -0.04983168 0.01069998 -0.05902886 -0.04983168 0.009949982 -0.05866765 -0.04969477 0.01069998 -0.05828928 -0.04961746 0.009949982 -0.05828928 -0.04961746 0.01069998 -0.05790334 -0.04960185 0.01069998 -0.05790334 -0.04960185 0.009949982 -0.05751985 -0.04964846 0.01069998 -0.05714887 -0.04975599 0.01069998 -0.05751985 -0.04964846 0.009949982 -0.05679994 -0.04992145 0.01069998 -0.05679994 -0.04992145 0.009949982 -0.05648207 -0.05014085 0.01069998 -0.0562036 -0.05040848 0.01069998 -0.0562036 -0.05040848 0.009949982 -0.0559715 -0.05071729 0.01069998 -0.0559715 -0.05071729 0.009949982 -0.05579197 -0.0510593 0.009949982 -0.05579197 -0.0510593 0.01069998 -0.05566966 -0.05142557 0.01069998 -0.05566966 -0.05142557 0.009949982 -0.05560779 -0.05180686 0.01069998 -0.05560779 -0.05180686 0.009949982 -0.05560779 -0.0521931 0.009949982 -0.05560779 -0.0521931 0.01069998 -0.05566966 -0.05257439 0.01069998 -0.05566966 -0.05257439 0.009949982 -0.05579197 -0.05294066 0.01069998 -0.0559715 -0.05328267 0.01069998 -0.0562036 -0.05359148 0.01069998 -0.05648207 -0.05385905 0.009949982 -0.05648207 -0.05385905 0.01069998 -0.05679994 -0.05407845 0.009949982 -0.05679994 -0.05407845 0.01069998 -0.05714887 -0.05424398 0.009949982 -0.05714887 -0.05424398 0.01069998 -0.05751985 -0.05435144 0.01069998 -0.05790334 -0.05439805 0.01069998 -0.05828928 -0.0543825 0.01069998 -0.05790334 -0.05439805 0.009949982 -0.05828928 -0.0543825 0.009949982 -0.05866765 -0.05430519 0.01069998 -0.05902886 -0.05416828 0.01069998 -0.05902886 -0.05416828 0.009949982 -0.05714887 -0.04975599 0.009949982 -0.05791336 -0.04985165 0.0097 -0.05866765 -0.04969477 0.009949982 -0.05859816 -0.04993486 0.0097 -0.05892169 -0.05005759 0.0097 -0.05936336 -0.05002474 0.009949982 -0.05966246 -0.05026906 0.009949982 -0.05948936 -0.05044937 0.0097 -0.0599187 -0.05055814 0.009949982 -0.05971878 -0.05070835 0.0097 -0.06012219 -0.05165505 0.0097 -0.06039994 -0.05199998 0.009949982 -0.06014996 -0.05199998 0.0097 -0.06012219 -0.05234485 0.0097 -0.06012505 -0.05311524 0.009949982 -0.0599187 -0.05344176 0.009949982 -0.05966246 -0.0537309 0.009949982 -0.05922126 -0.05376935 0.0097 -0.05866765 -0.05430519 0.009949982 -0.05751985 -0.05435144 0.009949982 -0.05756986 -0.05410647 0.0097 -0.05692499 -0.05386197 0.0097 -0.0563907 -0.05342566 0.0097 -0.0562036 -0.05359148 0.009949982 -0.0559715 -0.05328267 0.009949982 -0.05579197 -0.05294066 0.009949982 -0.05591249 -0.05251449 0.0097 -0.055857 -0.05217295 0.0097 -0.05591249 -0.05148547 0.0097 -0.05648207 -0.05014085 0.009949982 -0.0563907 -0.0505743 0.0097 -0.05692499 -0.05013799 0.0097 5.16985e-4 0.223515 0.01124995 5.22388e-4 0.22371 0.01124995 5.32168e-4 0.224061 0.01124995 5.37571e-4 0.224255 0.01124995 5.5926e-4 0.2239339 0.01118856 0.001313805 0.2240239 0.009680747 5.54228e-4 0.22382 0.01119226 0.001297593 0.22354 0.009686291 -5.16985e-4 0.224285 0.01124995 -5.22388e-4 0.22409 0.01124995 -0.001295506 0.224306 0.00968784 -5.32168e-4 0.223739 0.01124995 -5.5926e-4 0.223866 0.01118856 -5.37571e-4 0.223545 0.01124995 -0.00131607 0.2235659 0.00968784 -5.54228e-4 0.22398 0.01119226 -0.001304864 0.224097 0.009680747 0.002798914 0.2238219 0.01189994 0.002795755 0.224054 0.01050347 0.002773523 0.2242839 0.01189994 0.002773523 0.2242839 0.01050347 0.002732336 0.224512 0.01050347 0.002672493 0.224735 0.01189994 0.002498626 0.2251639 0.01189994 0.002498626 0.2251639 0.01050347 0.002385735 0.2253659 0.01050347 0.002256572 0.225558 0.01189994 0.002256572 0.225558 0.01050347 0.001952946 0.225906 0.01189994 0.001780569 0.226061 0.01050347 0.001596033 0.2262009 0.01189994 0.001400589 0.226324 0.01050347 0.001195609 0.226432 0.01189994 7.62602e-4 0.226594 0.01189994 5.37517e-4 0.226648 0.01050347 3.08759e-4 0.226683 0.01189994 -1.53506e-4 0.226696 0.01189994 -3.83856e-4 0.226674 0.01050347 -6.11584e-4 0.2266319 0.01189994 -8.35135e-4 0.226573 0.01050347 -0.001052975 0.226494 0.01050347 -0.001052975 0.226494 0.01189994 -0.001465618 0.2262859 0.01189994 -0.001263618 0.226399 0.01050347 -0.001838326 0.226012 0.01050347 -0.001838326 0.226012 0.01189994 -0.002160847 0.225681 0.01189994 -0.002160847 0.225681 0.01050347 -0.00230056 0.2254959 0.01050347 -0.002424478 0.225301 0.01050347 -0.002424478 0.225301 0.01189994 -0.002621948 0.224882 0.01189994 -0.002747893 0.224438 0.01189994 -0.002747893 0.224438 0.01050347 -0.002798914 0.223978 0.01189994 -0.002773523 0.223516 0.01189994 -0.002672493 0.223065 0.01189994 -0.002672493 0.223065 0.01050347 -0.002498626 0.222636 0.01050347 -0.002385735 0.222434 0.01050347 -0.002498626 0.222636 0.01189994 -0.002256572 0.2222419 0.01189994 -0.001952946 0.221894 0.01189994 -0.001780569 0.2217389 0.01050347 -0.001596033 0.221599 0.01189994 -9.82479e-4 0.221278 0.01050347 -0.001195609 0.221368 0.01189994 -7.62602e-4 0.221206 0.01050347 -7.62602e-4 0.221206 0.01189994 -3.08759e-4 0.221117 0.01189994 1.53506e-4 0.221104 0.01189994 6.11584e-4 0.221168 0.01189994 0.001052975 0.221306 0.01189994 8.35135e-4 0.221227 0.01050347 0.001465618 0.221514 0.01189994 0.001838326 0.221788 0.01189994 0.002160847 0.222119 0.01189994 0.00230056 0.222304 0.01050347 0.002424478 0.222499 0.01189994 0.002424478 0.222499 0.01050347 0.002621948 0.222918 0.01189994 0.002694129 0.223137 0.01050347 0.002747893 0.223362 0.01189994 0.002612829 0.224467 0.01027536 0.002552688 0.224698 0.01027536 0.002540171 0.224931 0.01033556 0.002446413 0.2251369 0.01033556 0.002400636 0.225076 0.01027536 0.002386569 0.225107 0.01027536 0.002049088 0.225616 0.01027536 0.001743376 0.226016 0.01033556 0.001700699 0.225964 0.01027536 0.001371324 0.226274 0.01033556 0.001016676 0.226371 0.01027536 5.26281e-4 0.22659 0.01033556 7.11869e-4 0.226477 0.01027536 7.43989e-5 0.226573 0.01027536 -3.75833e-4 0.226616 0.01033556 -5.98801e-4 0.226575 0.01033556 -5.84155e-4 0.2265099 0.01027536 -7.97678e-4 0.226453 0.01027536 -0.001030921 0.22644 0.01033556 -0.001175999 0.226301 0.01027536 -0.001583278 0.226055 0.01027536 -0.001799881 0.225968 0.01033556 -0.001964509 0.225812 0.01033556 -0.002115726 0.225643 0.01033556 -0.002156317 0.225479 0.01027536 -0.002197325 0.225424 0.01027536 -0.002315759 0.225238 0.01027536 -0.002331495 0.225208 0.01027536 -0.002471268 0.2249169 0.01027536 -0.002504348 0.224838 0.01027536 -0.002567112 0.224862 0.01033556 -0.002577245 0.2246119 0.01027536 -0.002690434 0.224426 0.01033556 -0.00262463 0.224413 0.01027536 -0.002642631 0.224296 0.01027536 -0.002724707 0.224202 0.01033556 -0.002740383 0.223976 0.01033556 -0.002737343 0.2237499 0.01033556 -0.002660572 0.223652 0.01027536 -0.002715587 0.223524 0.01033556 -0.002675235 0.2233009 0.01033556 -0.002609789 0.223316 0.01027536 -0.002552688 0.223102 0.01027536 -0.002523958 0.223022 0.01027536 -0.002446413 0.222663 0.01033556 -0.002386569 0.222693 0.01027536 -0.002240777 0.2224439 0.01027536 -0.001562654 0.221648 0.01033556 -0.001578688 0.221744 0.01027536 -0.001337766 0.221584 0.01027536 -0.001307666 0.221568 0.01027536 -0.001371324 0.221526 0.01033556 -0.001141965 0.221482 0.01027536 -0.001016676 0.221429 0.01027536 -9.38414e-4 0.221396 0.01027536 -7.11869e-4 0.221323 0.01027536 -5.13409e-4 0.221275 0.01027536 -3.95754e-4 0.221257 0.01027536 -2.94911e-4 0.221242 0.01027536 -7.43989e-5 0.221227 0.01027536 1.46621e-4 0.22123 0.01027536 1.50298e-4 0.221163 0.01033556 2.48166e-4 0.221239 0.01027536 3.75833e-4 0.221184 0.01033556 5.6743e-4 0.221287 0.01027536 5.84155e-4 0.2212899 0.01027536 5.98801e-4 0.221225 0.01033556 8.17678e-4 0.221283 0.01033556 7.97678e-4 0.221347 0.01027536 8.77701e-4 0.221376 0.01027536 0.001005709 0.221422 0.01027536 0.001175999 0.221499 0.01027536 0.001237213 0.221454 0.01033556 0.001399874 0.221621 0.01027536 0.001799881 0.221832 0.01033556 0.001950502 0.222073 0.01027536 0.002115726 0.222157 0.01033556 0.002252459 0.222337 0.01033556 0.002373814 0.2225289 0.01033556 0.002331495 0.2225919 0.01027536 0.002478957 0.222729 0.01033556 0.002567112 0.222938 0.01033556 0.002418279 0.2227579 0.01027536 0.002573251 0.223172 0.01027536 0.002577245 0.223188 0.01027536 0.002637803 0.2231529 0.01033556 0.002690434 0.223374 0.01033556 0.00262463 0.223387 0.01027536 0.002658069 0.223605 0.01027536 0.002724707 0.223598 0.01033556 0.002740383 0.223824 0.01033556 0.002670347 0.224047 0.01027536 0.002737343 0.22405 0.01033556 0.002783834 0.223823 0.0104146 0.002780735 0.224053 0.0104146 0.002715587 0.224276 0.01033556 0.002758622 0.224282 0.0104146 0.002675235 0.224499 0.01033556 0.002616643 0.224718 0.01033556 0.002335846 0.225335 0.01033556 0.00237292 0.225358 0.0104146 0.002209365 0.2255229 0.01033556 0.002244412 0.225549 0.0104146 0.002067804 0.2257 0.01033556 0.001912117 0.225865 0.01033556 0.002100586 0.225728 0.0104146 0.001942455 0.225896 0.0104146 0.001770973 0.226049 0.0104146 0.001562654 0.226152 0.01033556 0.001170635 0.226379 0.01033556 0.001189172 0.226418 0.0104146 9.61942e-4 0.226467 0.01033556 9.77197e-4 0.226508 0.0104146 7.46662e-4 0.226538 0.01033556 5.34627e-4 0.226633 0.0104146 3.02305e-4 0.226625 0.01033556 7.62643e-5 0.22664 0.01033556 7.74737e-5 0.226684 0.0104146 -1.52681e-4 0.2266809 0.0104146 -1.50298e-4 0.226637 0.01033556 -3.81793e-4 0.2266589 0.0104146 -6.08297e-4 0.226618 0.0104146 -8.17678e-4 0.226517 0.01033556 -8.30645e-4 0.226558 0.0104146 -0.001237213 0.226346 0.01033556 -0.001434981 0.226236 0.01033556 -0.001622974 0.226109 0.01033556 -0.00145775 0.226273 0.0104146 -0.001648724 0.226144 0.0104146 -0.001995682 0.2258419 0.0104146 -0.002252459 0.225463 0.01033556 -0.002288162 0.2254869 0.0104146 -0.002373814 0.225271 0.01033556 -0.002478957 0.225071 0.01033556 -0.002607822 0.2248769 0.0104146 -0.002637803 0.224647 0.01033556 -0.00276792 0.224207 0.0104146 -0.002780735 0.223747 0.0104146 -0.002717673 0.2232919 0.0104146 -0.002616643 0.223082 0.01033556 -0.002540171 0.222869 0.01033556 -0.00237292 0.222442 0.0104146 -0.002335846 0.222465 0.01033556 -0.002209365 0.222277 0.01033556 -0.002244412 0.2222509 0.0104146 -0.002067804 0.2221 0.01033556 -0.002100586 0.222072 0.0104146 -0.001912117 0.221935 0.01033556 -0.001743376 0.2217839 0.01033556 -0.001770973 0.221751 0.0104146 -0.00158745 0.221612 0.0104146 -0.001170635 0.221421 0.01033556 -9.61942e-4 0.221333 0.01033556 -7.46662e-4 0.221262 0.01033556 -7.58503e-4 0.22122 0.0104146 -5.26281e-4 0.22121 0.01033556 -5.34627e-4 0.221167 0.0104146 -3.02305e-4 0.221175 0.01033556 -7.62642e-5 0.2211599 0.01033556 -7.74737e-5 0.221116 0.0104146 1.52681e-4 0.221119 0.0104146 0.001030921 0.22136 0.01033556 0.001047313 0.221319 0.0104146 0.001256823 0.221415 0.0104146 0.001434981 0.2215639 0.01033556 0.001622974 0.221691 0.01033556 0.001828432 0.221799 0.0104146 0.001964509 0.221988 0.01033556 0.001995682 0.221958 0.0104146 0.002149224 0.222129 0.0104146 0.002411425 0.2225069 0.0104146 0.002733111 0.223365 0.0104146 0.00276792 0.2235929 0.0104146 0.002782881 0.223591 0.01050347 0.002798914 0.2238219 0.01050347 0.002717673 0.224508 0.0104146 0.002658188 0.224731 0.0104146 0.002672493 0.224735 0.01050347 0.002580463 0.224947 0.0104146 0.002594411 0.2249529 0.01050347 0.002485156 0.225157 0.0104146 0.002111971 0.225738 0.01050347 0.001952946 0.225906 0.01050347 0.00158745 0.226188 0.0104146 0.001596033 0.2262009 0.01050347 0.001393079 0.226311 0.0104146 0.001195609 0.226432 0.01050347 9.82479e-4 0.226522 0.01050347 7.58503e-4 0.22658 0.0104146 7.62602e-4 0.226594 0.01050347 3.07099e-4 0.226668 0.0104146 3.08759e-4 0.226683 0.01050347 7.78924e-5 0.2266989 0.01050347 -1.53506e-4 0.226696 0.01050347 -6.11584e-4 0.2266319 0.01050347 -0.001047313 0.226481 0.0104146 -0.001256823 0.2263849 0.0104146 -0.001465618 0.2262859 0.01050347 -0.001657605 0.226157 0.01050347 -0.001828432 0.226001 0.0104146 -0.002149224 0.2256709 0.0104146 -0.002006411 0.225853 0.01050347 -0.002411425 0.225293 0.0104146 -0.002518236 0.225089 0.0104146 -0.002531826 0.225096 0.01050347 -0.002621948 0.224882 0.01050347 -0.002679646 0.224659 0.0104146 -0.002733111 0.224435 0.0104146 -0.002694129 0.224663 0.01050347 -0.002783834 0.223977 0.0104146 -0.002782881 0.224209 0.01050347 -0.002798914 0.223978 0.01050347 -0.002795755 0.223746 0.01050347 -0.002758622 0.223518 0.0104146 -0.002773523 0.223516 0.01050347 -0.002732336 0.2232879 0.01050347 -0.002658188 0.223069 0.0104146 -0.002580463 0.222853 0.0104146 -0.002594411 0.222847 0.01050347 -0.002485156 0.222643 0.0104146 -0.002256572 0.2222419 0.01050347 -0.002111971 0.222062 0.01050347 -0.001952946 0.221894 0.01050347 -0.001942455 0.221904 0.0104146 -0.001596033 0.221599 0.01050347 -0.001393079 0.221489 0.0104146 -0.001400589 0.221475 0.01050347 -0.001195609 0.221368 0.01050347 -0.001189172 0.221382 0.0104146 -9.77197e-4 0.221292 0.0104146 -3.07099e-4 0.221132 0.0104146 -5.37517e-4 0.221152 0.01050347 -3.08759e-4 0.221117 0.01050347 -7.78924e-5 0.221101 0.01050347 1.53506e-4 0.221104 0.01050347 3.83856e-4 0.221126 0.01050347 3.81793e-4 0.221141 0.0104146 6.08297e-4 0.221182 0.0104146 6.11584e-4 0.221168 0.01050347 8.30645e-4 0.221242 0.0104146 0.001052975 0.221306 0.01050347 0.001263618 0.221401 0.01050347 0.00145775 0.221527 0.0104146 0.001465618 0.221514 0.01050347 0.001657605 0.221643 0.01050347 0.001648724 0.221656 0.0104146 0.001838326 0.221788 0.01050347 0.002006411 0.221947 0.01050347 0.002160847 0.222119 0.01050347 0.002288162 0.222313 0.0104146 0.002518236 0.222711 0.0104146 0.002607822 0.222923 0.0104146 0.002531826 0.2227039 0.01050347 0.002621948 0.222918 0.01050347 0.002679646 0.223141 0.0104146 0.002747893 0.223362 0.01050347 -0.001126348 0.2218919 0.0100618 -0.001700699 0.221836 0.01027536 -0.002649128 0.223533 0.01027536 -0.002670347 0.223753 0.01027536 -0.002277195 0.224241 0.0100618 -2.48166e-4 0.226561 0.01027536 -2.13854e-4 0.226193 0.0100618 3.95754e-4 0.226543 0.01027536 5.13409e-4 0.226525 0.01027536 0.001307666 0.2262319 0.01027536 0.002673327 0.223826 0.01027536 0.002642631 0.223504 0.01027536 2.13854e-4 0.221607 0.0100618 3.98509e-4 0.224919 0.009623944 4.17446e-4 0.224915 0.009621858 5.74934e-4 0.225297 0.009733796 3.97289e-4 0.224875 0.009613811 3.95957e-4 0.224828 0.009602725 5.36704e-4 0.224857 0.009621858 3.90375e-4 0.224627 0.009572148 3.98849e-4 0.224445 0.009545743 6.48135e-4 0.224785 0.009621858 3.85568e-4 0.224454 0.009545743 9.9601e-4 0.224242 0.009613811 0.001315593 0.224187 0.009686291 0.001019239 0.223501 0.009623944 0.00101459 0.223483 0.009621858 9.75424e-4 0.2235029 0.009613811 9.27583e-4 0.223504 0.009602725 5.44769e-4 0.223501 0.009545743 3.33516e-4 0.222584 0.00968784 -3.97289e-4 0.222925 0.009613811 -3.98509e-4 0.222881 0.009623944 -4.17446e-4 0.222885 0.009621858 -3.95957e-4 0.222972 0.009602725 -4.61606e-4 0.223407 0.009545743 -3.98849e-4 0.2233549 0.009545743 -9.9601e-4 0.223558 0.009613811 -9.85295e-4 0.223417 0.009621858 -0.001427233 0.223404 0.009733796 -9.75424e-4 0.224297 0.009613811 -0.00101459 0.224317 0.009621858 -9.27583e-4 0.224296 0.009602725 -4.92721e-4 0.224362 0.009545743 -5.44769e-4 0.224299 0.009545743 -2.238e-4 0.222406 0.009733796 -2.83458e-4 0.222007 0.009880781 3.6664e-4 0.221251 0.01027536 4.88645e-4 0.22165 0.0100618 1.77751e-4 0.221994 0.009880781 -5.32419e-5 0.221987 0.009880781 -4.20363e-5 0.2223899 0.009733796 7.56311e-4 0.221725 0.0100618 4.06151e-4 0.22203 0.009880781 0.001012921 0.221832 0.0100618 0.00145632 0.221659 0.01027536 0.001206934 0.221513 0.01027536 8.41941e-4 0.222181 0.009880781 6.2863e-4 0.222092 0.009880781 3.20671e-4 0.222423 0.009733796 2.86997e-4 0.222584 0.009686291 1.4034e-4 0.222395 0.009733796 1.23881e-4 0.222586 0.009680747 -3.6514e-5 0.222588 0.009675323 -1.96758e-4 0.222595 0.009680747 -3.59721e-4 0.222602 0.009686291 0.001716077 0.221851 0.01027536 0.001583278 0.221745 0.01027536 0.001254796 0.221969 0.0100618 0.001042962 0.222295 0.009880781 6.64741e-4 0.222543 0.009733796 4.96325e-4 0.222473 0.009733796 3.60369e-4 0.222864 0.009621858 0.00206393 0.222199 0.01027536 0.001916468 0.222035 0.01027536 0.001755893 0.2218829 0.01027536 0.001680374 0.222326 0.0100618 0.001478374 0.222135 0.0100618 3.42425e-4 0.222904 0.009613811 3.41205e-4 0.22286 0.009623944 3.43756e-4 0.222952 0.009602725 4.82653e-4 0.2229149 0.009621858 9.70179e-4 0.222741 0.009733796 8.23464e-4 0.222633 0.009733796 0.001228749 0.222433 0.009880781 0.001396656 0.222591 0.009880781 0.001857876 0.22254 0.0100618 0.002197325 0.222376 0.01027536 0.002156317 0.222321 0.01027536 0.002315759 0.222562 0.01027536 0.001102745 0.222867 0.009733796 7.04424e-4 0.2230589 0.009621858 5.97898e-4 0.22298 0.009621858 3.49339e-4 0.223152 0.009572148 3.54146e-4 0.223325 0.009545743 3.67934e-4 0.223334 0.009545743 4.33488e-4 0.2233819 0.009545743 8.00678e-4 0.22315 0.009621858 0.001219213 0.223007 0.009733796 0.001544237 0.222769 0.009880781 0.002008259 0.222774 0.0100618 0.002504348 0.222962 0.01027536 0.002471268 0.222883 0.01027536 0.002219498 0.223287 0.0100618 0.002129435 0.223024 0.0100618 0.0017699 0.223172 0.009880781 0.001669228 0.222964 0.009880781 4.92721e-4 0.223438 0.009545743 0.001397371 0.223325 0.009733796 9.56927e-4 0.223363 0.009621858 0.001317918 0.223161 0.009733796 8.85257e-4 0.2232519 0.009621858 7.26975e-4 0.22351 0.009572148 5.54249e-4 0.223514 0.009545743 0.002277195 0.223559 0.0100618 0.001844763 0.22339 0.009880781 0.001456499 0.223498 0.009733796 0.001295506 0.2234939 0.00968784 0.002660572 0.224148 0.01027536 0.002301692 0.223836 0.0100618 0.00191313 0.223847 0.009880781 0.001494407 0.223676 0.009733796 0.001892745 0.223617 0.009880781 0.002250134 0.224389 0.0100618 0.002649128 0.224267 0.01027536 0.002292633 0.224114 0.0100618 0.002523958 0.2247779 0.01027536 0.002609789 0.224484 0.01027536 0.001870274 0.224306 0.009880781 0.00190562 0.2240779 0.009880781 0.002478063 0.224906 0.01027536 0.002174854 0.224656 0.0100618 0.001807689 0.224529 0.009880781 0.002155363 0.225483 0.01027536 0.001930654 0.2251549 0.0100618 0.002240777 0.225356 0.01027536 0.002278745 0.2253 0.01027536 0.002067804 0.224913 0.0100618 0.001718699 0.2247419 0.009880781 0.001476645 0.224221 0.009733796 0.00150454 0.22404 0.009733796 0.001510441 0.2238579 0.009733796 0.001312017 0.223863 0.009675323 0.001304864 0.223703 0.009680747 0.00131607 0.224234 0.00968784 0.001036286 0.22426 0.009621858 0.001427233 0.224396 0.009733796 0.001604676 0.224943 0.009880781 0.002017259 0.225656 0.01027536 0.00176531 0.225378 0.0100618 0.001827359 0.2258509 0.01027536 0.001865327 0.225816 0.01027536 0.001467287 0.225129 0.009880781 0.001356959 0.224565 0.009733796 0.001266956 0.224723 0.009733796 9.85295e-4 0.2243829 0.009621858 0.001039803 0.224241 0.009623944 9.48169e-4 0.2242439 0.009602725 7.47561e-4 0.224249 0.009572148 0.001308441 0.225297 0.009880781 0.001574277 0.22558 0.0100618 0.001524448 0.226097 0.01027536 0.001578688 0.226056 0.01027536 0.001337766 0.226216 0.01027536 0.001126348 0.225908 0.0100618 0.001360237 0.225758 0.0100618 0.001158475 0.22487 0.009733796 9.19934e-4 0.224498 0.009621858 5.74834e-4 0.224254 0.009545743 5.66108e-4 0.224268 0.009545743 5.17631e-4 0.224333 0.009545743 8.41158e-4 0.224604 0.009621858 7.50116e-4 0.224701 0.009621858 0.001033067 0.225003 0.009733796 8.92655e-4 0.2251189 0.009733796 0.00113058 0.225444 0.009880781 0.001141965 0.226318 0.01027536 9.38414e-4 0.226404 0.01027536 8.76098e-4 0.226029 0.0100618 7.28399e-4 0.226473 0.01027536 9.36228e-4 0.225569 0.009880781 4.61606e-4 0.224393 0.009545743 6.13035e-4 0.2261199 0.0100618 5.09541e-4 0.225745 0.009880781 7.28194e-4 0.22567 0.009880781 7.39184e-4 0.2252179 0.009733796 2.94911e-4 0.226558 0.01027536 2.83458e-4 0.225793 0.009880781 3.41032e-4 0.226177 0.0100618 4.06197e-4 0.225196 0.00968784 -1.46621e-4 0.22657 0.01027536 6.4056e-5 0.226202 0.0100618 -5.6743e-4 0.226513 0.01027536 -3.6664e-4 0.226549 0.01027536 5.32419e-5 0.225813 0.009880781 -1.77751e-4 0.2258059 0.009880781 4.20363e-5 0.22541 0.009733796 -7.56311e-4 0.2260749 0.0100618 -8.77701e-4 0.226424 0.01027536 -4.88645e-4 0.22615 0.0100618 -1.4034e-4 0.225405 0.009733796 -0.001005709 0.226378 0.01027536 -6.2863e-4 0.225708 0.009880781 -4.06151e-4 0.2257699 0.009880781 -0.00145632 0.226141 0.01027536 -0.001399874 0.226179 0.01027536 -0.001206934 0.226287 0.01027536 -0.001012921 0.225968 0.0100618 -3.20671e-4 0.225377 0.009733796 -2.86997e-4 0.225216 0.009686291 -1.23881e-4 0.225214 0.009680747 1.96758e-4 0.225205 0.009680747 2.238e-4 0.225394 0.009733796 4.023e-4 0.2253569 0.009733796 -0.001716077 0.225949 0.01027536 -0.001478374 0.225665 0.0100618 -0.001254796 0.225831 0.0100618 -0.001042962 0.2255049 0.009880781 -8.41941e-4 0.225619 0.009880781 -4.96325e-4 0.225327 0.009733796 -3.41205e-4 0.22494 0.009623944 -0.001950502 0.225727 0.01027536 -0.001916468 0.225765 0.01027536 -0.001680374 0.2254739 0.0100618 -0.001755893 0.225917 0.01027536 -6.64741e-4 0.225257 0.009733796 -3.60369e-4 0.224936 0.009621858 -3.42425e-4 0.224896 0.009613811 -4.82653e-4 0.224885 0.009621858 -5.97898e-4 0.22482 0.009621858 -9.70179e-4 0.225058 0.009733796 -8.23464e-4 0.225167 0.009733796 -0.001228749 0.225367 0.009880781 -0.001857876 0.22526 0.0100618 -0.00206393 0.225601 0.01027536 -0.002008259 0.225026 0.0100618 -0.001396656 0.2252089 0.009880781 -0.001102745 0.224933 0.009733796 -3.67934e-4 0.224466 0.009545743 -3.49339e-4 0.2246479 0.009572148 -7.04424e-4 0.224741 0.009621858 -4.33488e-4 0.224418 0.009545743 -8.00678e-4 0.22465 0.009621858 -0.001219213 0.224793 0.009733796 -0.001544237 0.225031 0.009880781 -0.001669228 0.224836 0.009880781 -0.002129435 0.224776 0.0100618 -0.002418279 0.225042 0.01027536 -0.002573251 0.224628 0.01027536 -0.0017699 0.224628 0.009880781 -8.85257e-4 0.224548 0.009621858 -0.002219498 0.2245129 0.0100618 -0.001844763 0.2244099 0.009880781 -0.001397371 0.224475 0.009733796 -0.001317918 0.2246389 0.009733796 -9.56927e-4 0.2244369 0.009621858 -7.26975e-4 0.22429 0.009572148 -5.54249e-4 0.224286 0.009545743 -0.002673327 0.223974 0.01027536 -0.002658069 0.224195 0.01027536 -0.001892745 0.224183 0.009880781 -0.001019239 0.224299 0.009623944 -0.002301692 0.223964 0.0100618 -0.00191313 0.223953 0.009880781 -0.002612829 0.223333 0.01027536 -0.002250134 0.223411 0.0100618 -0.002292633 0.223686 0.0100618 -0.002174854 0.2231439 0.0100618 -0.001870274 0.2234939 0.009880781 -0.00190562 0.223722 0.009880781 -0.002400636 0.222724 0.01027536 -0.002478063 0.222894 0.01027536 -0.002067804 0.222887 0.0100618 -0.001807689 0.223271 0.009880781 -0.001476645 0.223579 0.009733796 -0.002278745 0.2225 0.01027536 -0.001930654 0.222645 0.0100618 -0.001315593 0.223613 0.009686291 -0.001313805 0.223776 0.009680747 -0.00150454 0.22376 0.009733796 -0.001510441 0.223942 0.009733796 -0.001312017 0.223937 0.009675323 -0.001494407 0.224124 0.009733796 -0.001456499 0.2243019 0.009733796 -0.001297593 0.22426 0.009686291 -0.001036286 0.22354 0.009621858 -0.001356959 0.223235 0.009733796 -0.001718699 0.223058 0.009880781 -0.00176531 0.222422 0.0100618 -0.002155363 0.222317 0.01027536 -0.002017259 0.222144 0.01027536 -0.002049088 0.222184 0.01027536 -0.001827359 0.221949 0.01027536 -0.001865327 0.221984 0.01027536 -0.001467287 0.222671 0.009880781 -0.001604676 0.2228569 0.009880781 -0.001266956 0.2230769 0.009733796 -0.001039803 0.223559 0.009623944 -9.48169e-4 0.223556 0.009602725 -7.47561e-4 0.223551 0.009572148 -9.19933e-4 0.223302 0.009621858 -0.001574277 0.22222 0.0100618 -0.001524448 0.2217029 0.01027536 -0.001360237 0.222042 0.0100618 -0.001308441 0.222503 0.009880781 -0.001158475 0.22293 0.009733796 -5.66108e-4 0.223532 0.009545743 -5.74834e-4 0.223546 0.009545743 -8.41158e-4 0.223196 0.009621858 -7.50116e-4 0.2230989 0.009621858 -8.92655e-4 0.222681 0.009733796 -0.001033067 0.222797 0.009733796 -0.00113058 0.222356 0.009880781 -9.36228e-4 0.222231 0.009880781 -7.28399e-4 0.221327 0.01027536 -6.13035e-4 0.22168 0.0100618 -8.76098e-4 0.221771 0.0100618 -6.48135e-4 0.223015 0.009621858 -5.17631e-4 0.2234669 0.009545743 -3.41032e-4 0.221623 0.0100618 -5.09541e-4 0.222055 0.009880781 -7.28194e-4 0.22213 0.009880781 -5.74934e-4 0.222503 0.009733796 -7.39184e-4 0.222582 0.009733796 -5.36704e-4 0.222943 0.009621858 -3.90375e-4 0.223173 0.009572148 -3.85568e-4 0.2233459 0.009545743 -6.40559e-5 0.221598 0.0100618 -4.023e-4 0.222443 0.009733796 -4.06197e-4 0.222604 0.00968784 -3.55183e-4 0.224438 0.01124995 -3.58312e-4 0.224325 0.01124995 -3.57608e-4 0.22435 0.01097637 -3.54611e-4 0.224458 0.009744763 -3.54146e-4 0.224475 0.009545743 -3.43756e-4 0.224848 0.009602725 3.84531e-4 0.224417 0.01124995 1.90386e-4 0.224422 0.01124995 3.59721e-4 0.225198 0.009686291 -1.61038e-4 0.224432 0.01124995 -3.33516e-4 0.225216 0.00968784 -3.40237e-5 0.2244589 0.01118856 8.04378e-5 0.224454 0.01119226 3.6514e-5 0.225212 0.009675323 0.001449346 0.223514 0.01989996 0.001499414 0.2238579 0.01199996 0.001499414 0.2238579 0.01989996 0.001468598 0.224205 0.01199996 0.001468598 0.224205 0.01989996 0.001358628 0.224536 0.01199996 0.001358628 0.224536 0.01989996 0.001175403 0.2248319 0.01989996 0.001175403 0.2248319 0.01199996 9.28862e-4 0.225078 0.01199996 6.32205e-4 0.22526 0.01199996 9.28862e-4 0.225078 0.01989996 6.32205e-4 0.22526 0.01989996 3.01466e-4 0.225369 0.01199996 -4.5526e-5 0.225399 0.01199996 3.01466e-4 0.225369 0.01989996 -4.5526e-5 0.225399 0.01989996 -3.90063e-4 0.2253479 0.01199996 -3.90063e-4 0.2253479 0.01989996 -7.13572e-4 0.225219 0.01199996 -9.98612e-4 0.225019 0.01199996 -7.13572e-4 0.225219 0.01989996 -9.98612e-4 0.225019 0.01989996 -0.001229763 0.224759 0.01199996 -0.001394689 0.224452 0.01199996 -0.001229763 0.224759 0.01989996 -0.001484394 0.224116 0.01199996 -0.001394689 0.224452 0.01989996 -0.001484394 0.224116 0.01989996 -0.001494109 0.223767 0.01199996 -0.001494109 0.223767 0.01989996 -0.001423239 0.223426 0.01199996 -0.001423239 0.223426 0.01989996 -0.001275658 0.223111 0.01989996 -0.001275658 0.223111 0.01199996 -0.001059293 0.222838 0.01199996 -0.001059293 0.222838 0.01989996 -7.85847e-4 0.222622 0.01199996 -7.85847e-4 0.222622 0.01989996 -4.70013e-4 0.222476 0.01199996 -4.70013e-4 0.222476 0.01989996 -1.28841e-4 0.222406 0.01199996 2.19277e-4 0.222416 0.01199996 -1.28841e-4 0.222406 0.01989996 2.19277e-4 0.222416 0.01989996 5.55574e-4 0.2225069 0.01989996 5.55574e-4 0.2225069 0.01199996 8.6192e-4 0.222672 0.01199996 0.001121759 0.222904 0.01199996 8.6192e-4 0.222672 0.01989996 0.001321196 0.22319 0.01199996 0.001121759 0.222904 0.01989996 0.001449346 0.223514 0.01199996 0.001321196 0.22319 0.01989996 0.194576 0.1118929 0.009545743 0.194444 0.111822 0.01124995 0.1945739 0.111877 0.009545743 0.194561 0.111797 0.009545743 0.194436 0.111791 0.01124995 0.194537 0.1117179 0.009545743 0.194426 0.111761 0.01124995 0.194497 0.111629 0.009545743 0.1932629 0.112025 0.01124995 0.193356 0.111854 0.01124995 0.1925989 0.111613 0.009686291 0.193523 0.111544 0.01124995 0.193615 0.111374 0.01124995 0.193436 0.111641 0.01118856 0.192749 0.111326 0.009675323 0.193383 0.111743 0.01119226 0.195622 0.10974 0.01189994 0.195622 0.10974 0.01050347 0.1957989 0.109889 0.01050347 0.195963 0.110053 0.01189994 0.195963 0.110053 0.01050347 0.196112 0.11023 0.01050347 0.196247 0.110418 0.01189994 0.1963649 0.110617 0.01050347 0.196467 0.110825 0.01189994 0.196551 0.1110399 0.01050347 0.196617 0.111262 0.01189994 0.196693 0.1117179 0.01189994 0.196694 0.1121799 0.01050347 0.196694 0.1121799 0.01189994 0.196618 0.112637 0.01189994 0.1964679 0.113074 0.01050347 0.1964679 0.113074 0.01189994 0.1962479 0.113481 0.01189994 0.196366 0.113282 0.01050347 0.195964 0.113846 0.01189994 0.195623 0.114159 0.01050347 0.195623 0.114159 0.01189994 0.195435 0.114294 0.01050347 0.195236 0.114412 0.01050347 0.195236 0.114412 0.01189994 0.195029 0.114514 0.01050347 0.194813 0.114598 0.01189994 0.194365 0.1147119 0.01050347 0.194365 0.1147119 0.01189994 0.193904 0.11475 0.01189994 0.193904 0.11475 0.01050347 0.193673 0.11474 0.01050347 0.193443 0.1147119 0.01189994 0.193216 0.114665 0.01050347 0.192995 0.114599 0.01050347 0.192995 0.114599 0.01189994 0.192571 0.114413 0.01189994 0.192184 0.11416 0.01050347 0.192184 0.11416 0.01189994 0.192007 0.114011 0.01050347 0.191844 0.113847 0.01050347 0.191844 0.113847 0.01189994 0.191559 0.1134819 0.01189994 0.191694 0.11367 0.01050347 0.191339 0.113075 0.01189994 0.191339 0.113075 0.01050347 0.191189 0.1126379 0.01050347 0.191189 0.1126379 0.01189994 0.1911129 0.112182 0.01189994 0.1911129 0.11172 0.01050347 0.1911129 0.11172 0.01189994 0.191189 0.111263 0.01189994 0.191141 0.11149 0.01050347 0.191255 0.111042 0.01050347 0.191339 0.110826 0.01189994 0.191559 0.110419 0.01189994 0.191693 0.110231 0.01050347 0.191843 0.110054 0.01050347 0.191843 0.110054 0.01189994 0.192006 0.10989 0.01050347 0.192183 0.109741 0.01189994 0.192183 0.109741 0.01050347 0.192371 0.109606 0.01050347 0.19257 0.109488 0.01189994 0.19257 0.109488 0.01050347 0.192993 0.109302 0.01050347 0.192993 0.109302 0.01189994 0.193441 0.109188 0.01189994 0.193215 0.109236 0.01050347 0.193902 0.10915 0.01189994 0.193902 0.10915 0.01050347 0.1941339 0.109159 0.01050347 0.1943629 0.109188 0.01050347 0.1943629 0.109188 0.01189994 0.19459 0.109235 0.01050347 0.1948119 0.109301 0.01189994 0.195235 0.1094869 0.01050347 0.195235 0.1094869 0.01189994 0.195586 0.109786 0.01033556 0.1957589 0.109933 0.01033556 0.1959199 0.1100929 0.01033556 0.196066 0.110266 0.01033556 0.1959249 0.110203 0.01027536 0.196122 0.110459 0.01027536 0.196198 0.11045 0.01033556 0.196314 0.1106449 0.01033556 0.1964139 0.111033 0.01027536 0.196496 0.111293 0.01027536 0.196506 0.111343 0.01027536 0.196635 0.111723 0.01033556 0.196568 0.111728 0.01027536 0.196578 0.111949 0.01027536 0.196635 0.112176 0.01033556 0.196568 0.11217 0.01027536 0.196561 0.112622 0.01033556 0.196496 0.112606 0.01027536 0.196496 0.112839 0.01033556 0.196491 0.112622 0.01027536 0.1964139 0.1130509 0.01033556 0.196142 0.113412 0.01027536 0.1961989 0.113449 0.01033556 0.196014 0.113592 0.01027536 0.195882 0.113748 0.01027536 0.19565 0.113972 0.01027536 0.195546 0.11406 0.01027536 0.195366 0.114189 0.01027536 0.195177 0.114302 0.01027536 0.195403 0.1142449 0.01033556 0.1947939 0.114543 0.01033556 0.1949779 0.114399 0.01027536 0.19482 0.114461 0.01027536 0.194772 0.114479 0.01027536 0.1945599 0.114542 0.01027536 0.19451 0.114553 0.01027536 0.194355 0.114654 0.01033556 0.194344 0.114588 0.01027536 0.19413 0.114682 0.01033556 0.193904 0.114624 0.01027536 0.193677 0.114682 0.01033556 0.193548 0.114599 0.01027536 0.193464 0.114588 0.01027536 0.193453 0.114654 0.01033556 0.193035 0.11448 0.01027536 0.192803 0.114461 0.01033556 0.192631 0.114302 0.01027536 0.1925989 0.114361 0.01033556 0.192441 0.114189 0.01027536 0.192404 0.1142449 0.01033556 0.192358 0.11413 0.01027536 0.192261 0.1140609 0.01027536 0.19222 0.114114 0.01033556 0.1920469 0.113967 0.01033556 0.191887 0.113807 0.01033556 0.191881 0.113697 0.01027536 0.191684 0.113441 0.01027536 0.191551 0.113224 0.01027536 0.191393 0.113052 0.01033556 0.191374 0.112819 0.01027536 0.1913099 0.112841 0.01033556 0.191199 0.112402 0.01033556 0.1913 0.112557 0.01027536 0.191171 0.112177 0.01033556 0.191229 0.111951 0.01027536 0.191162 0.111951 0.01033556 0.1912299 0.111917 0.01027536 0.191171 0.111724 0.01033556 0.191238 0.11173 0.01027536 0.191265 0.111511 0.01027536 0.191199 0.111499 0.01033556 0.1913099 0.111294 0.01027536 0.1913149 0.1112779 0.01027536 0.191417 0.110971 0.01027536 0.191551 0.110678 0.01027536 0.191492 0.110646 0.01033556 0.191608 0.110451 0.01033556 0.191723 0.110405 0.01027536 0.191924 0.110152 0.01027536 0.191886 0.110094 0.01033556 0.191935 0.110139 0.01027536 0.192091 0.109983 0.01027536 0.192156 0.109928 0.01027536 0.192046 0.109934 0.01033556 0.192219 0.109787 0.01033556 0.192412 0.109731 0.01027536 0.19244 0.109711 0.01027536 0.192403 0.109655 0.01033556 0.1926299 0.109598 0.01027536 0.192598 0.109539 0.01033556 0.1928009 0.10944 0.01033556 0.192691 0.1095679 0.01027536 0.1930119 0.1093569 0.01033556 0.1930339 0.109421 0.01027536 0.193246 0.109358 0.01027536 0.193229 0.109293 0.01033556 0.193296 0.109347 0.01027536 0.193462 0.1093119 0.01027536 0.194129 0.109218 0.01033556 0.193936 0.109277 0.01027536 0.194343 0.1093119 0.01027536 0.194575 0.109362 0.01027536 0.194575 0.109292 0.01033556 0.194793 0.1093569 0.01033556 0.194771 0.10942 0.01027536 0.194882 0.109463 0.01027536 0.194977 0.109501 0.01027536 0.195402 0.109655 0.01033556 0.195365 0.109711 0.01027536 0.195545 0.109839 0.01027536 0.195701 0.109971 0.01027536 0.195228 0.1095 0.0104146 0.196352 0.110624 0.0104146 0.196453 0.110831 0.0104146 0.196413 0.110848 0.01033556 0.196496 0.111059 0.01033556 0.19656 0.111276 0.01033556 0.1966069 0.1114979 0.01033556 0.19665 0.111491 0.0104146 0.196645 0.111949 0.01033556 0.1966069 0.112401 0.01033556 0.196603 0.112633 0.0104146 0.196314 0.113254 0.01033556 0.196067 0.113633 0.01033556 0.196101 0.11366 0.0104146 0.195953 0.113836 0.0104146 0.195921 0.113806 0.01033556 0.19576 0.113966 0.01033556 0.1957899 0.113998 0.0104146 0.1955879 0.114113 0.01033556 0.195614 0.114147 0.0104146 0.195209 0.114361 0.01033556 0.1952289 0.114399 0.0104146 0.1950049 0.11446 0.01033556 0.195022 0.1145 0.0104146 0.194808 0.114584 0.0104146 0.1945869 0.11465 0.0104146 0.194577 0.114607 0.01033556 0.194362 0.114697 0.0104146 0.1941339 0.114725 0.0104146 0.193904 0.114735 0.0104146 0.193904 0.114691 0.01033556 0.193674 0.114726 0.0104146 0.193445 0.114697 0.0104146 0.193231 0.114608 0.01033556 0.193014 0.114543 0.01033556 0.193 0.114584 0.0104146 0.192785 0.1145009 0.0104146 0.192578 0.1144 0.0104146 0.192017 0.113999 0.0104146 0.191855 0.113837 0.0104146 0.19174 0.113634 0.01033556 0.191706 0.113661 0.0104146 0.191572 0.113474 0.0104146 0.191608 0.11345 0.01033556 0.191492 0.113255 0.01033556 0.1914539 0.113276 0.0104146 0.191246 0.112624 0.01033556 0.191204 0.112634 0.0104146 0.191118 0.111951 0.0104146 0.191245 0.1112779 0.01033556 0.1912029 0.111267 0.0104146 0.1913099 0.111061 0.01033556 0.191392 0.110849 0.01033556 0.191352 0.110832 0.0104146 0.1915709 0.110427 0.0104146 0.191739 0.110267 0.01033556 0.191854 0.110064 0.0104146 0.192016 0.109902 0.0104146 0.1923789 0.109619 0.0104146 0.192577 0.109501 0.0104146 0.192998 0.109316 0.0104146 0.193451 0.109246 0.01033556 0.193444 0.109203 0.0104146 0.1936759 0.109218 0.01033556 0.193902 0.109209 0.01033556 0.193902 0.109165 0.0104146 0.1943539 0.109246 0.01033556 0.1948069 0.109316 0.0104146 0.195004 0.109439 0.01033556 0.1952069 0.109539 0.01033556 0.195426 0.109618 0.0104146 0.195434 0.109606 0.01050347 0.195613 0.1097519 0.0104146 0.195789 0.109901 0.0104146 0.1959519 0.110063 0.0104146 0.1960999 0.110239 0.0104146 0.196247 0.110418 0.01050347 0.196234 0.110426 0.0104146 0.196467 0.110825 0.01050347 0.196537 0.111045 0.0104146 0.196603 0.111266 0.0104146 0.196617 0.111262 0.01050347 0.196678 0.111719 0.0104146 0.196665 0.111488 0.01050347 0.1966879 0.111949 0.0104146 0.196693 0.1117179 0.01050347 0.196703 0.111949 0.01050347 0.1966789 0.112179 0.0104146 0.19665 0.112408 0.0104146 0.196665 0.11241 0.01050347 0.196618 0.112637 0.01050347 0.196552 0.1128579 0.01050347 0.196537 0.112854 0.0104146 0.196454 0.113068 0.0104146 0.196353 0.113275 0.0104146 0.196235 0.1134729 0.0104146 0.1962479 0.113481 0.01050347 0.196113 0.113669 0.01050347 0.195964 0.113846 0.01050347 0.1958 0.11401 0.01050347 0.195427 0.1142809 0.0104146 0.194813 0.114598 0.01050347 0.194591 0.114664 0.01050347 0.194135 0.11474 0.01050347 0.193443 0.1147119 0.01050347 0.19322 0.11465 0.0104146 0.192779 0.114514 0.01050347 0.192571 0.114413 0.01050347 0.19238 0.114282 0.0104146 0.192372 0.114294 0.01050347 0.192193 0.114148 0.0104146 0.191559 0.1134819 0.01050347 0.191353 0.1130689 0.0104146 0.1914409 0.113283 0.01050347 0.191269 0.112855 0.0104146 0.191255 0.11286 0.01050347 0.191156 0.112409 0.0104146 0.191141 0.112412 0.01050347 0.191128 0.112181 0.0104146 0.1911129 0.112182 0.01050347 0.191103 0.111951 0.01050347 0.191128 0.111721 0.0104146 0.191156 0.111492 0.0104146 0.191189 0.111263 0.01050347 0.191269 0.111046 0.0104146 0.191339 0.110826 0.01050347 0.191453 0.110625 0.0104146 0.19144 0.110618 0.01050347 0.191559 0.110419 0.01050347 0.191705 0.11024 0.0104146 0.192192 0.109753 0.0104146 0.192784 0.1094 0.0104146 0.192778 0.109386 0.01050347 0.193219 0.10925 0.0104146 0.193441 0.109188 0.01050347 0.193672 0.109175 0.0104146 0.193671 0.10916 0.01050347 0.194132 0.109175 0.0104146 0.194361 0.109203 0.0104146 0.194586 0.10925 0.0104146 0.1948119 0.109301 0.01050347 0.195021 0.109399 0.0104146 0.1950269 0.109386 0.01050347 0.191373 0.111082 0.01027536 0.191265 0.112391 0.01027536 0.192092 0.113918 0.01027536 0.193683 0.114615 0.01027536 0.19387 0.114623 0.01027536 0.195394 0.114169 0.01027536 0.1965759 0.111983 0.01027536 0.196206 0.111979 0.0100618 0.196066 0.11116 0.0100618 0.196142 0.110487 0.01027536 0.195814 0.110666 0.0100618 0.194482 0.109721 0.0100618 0.1939319 0.109648 0.0100618 0.1933799 0.109708 0.0100618 0.191664 0.1104879 0.01027536 0.193173 0.111135 0.009623944 0.194876 0.112897 0.00968784 0.194552 0.112722 0.009602725 0.194985 0.112115 0.009623944 0.1949909 0.112096 0.009621858 0.194946 0.112094 0.009613811 0.194904 0.112071 0.009602725 0.195 0.111964 0.009621858 0.194728 0.111975 0.009572148 0.194047 0.110907 0.009613811 0.194049 0.110863 0.009621858 0.193917 0.110853 0.009621858 0.194024 0.110949 0.009602725 0.1937839 0.110859 0.009621858 0.19383 0.111279 0.009545743 0.1932539 0.111178 0.009602725 0.19286 0.111806 0.009613811 0.192816 0.111804 0.009621858 0.192405 0.111749 0.009733796 0.192902 0.111829 0.009602725 0.192806 0.111936 0.009621858 0.1932319 0.112023 0.009545743 0.19323 0.112007 0.009545743 0.193109 0.112641 0.009613811 0.193131 0.112599 0.009602725 0.192956 0.112923 0.00968784 0.1927599 0.112938 0.009733796 0.193702 0.113448 0.009733796 0.193759 0.112993 0.009613811 0.193782 0.112951 0.009602725 0.1937569 0.113037 0.009621858 0.193889 0.113047 0.009621858 0.193976 0.112621 0.009545743 0.19396 0.112623 0.009545743 0.1920239 0.110618 0.0100618 0.19222 0.1110399 0.009880781 0.191878 0.110855 0.0100618 0.192122 0.111249 0.009880781 0.192199 0.110402 0.0100618 0.191792 0.110308 0.01027536 0.192497 0.111397 0.009733796 0.192398 0.110208 0.0100618 0.192486 0.1106629 0.009880781 0.192342 0.110843 0.009880781 0.192574 0.111231 0.009733796 0.19226 0.10984 0.01027536 0.1928279 0.109501 0.01027536 0.192619 0.110039 0.0100618 0.192652 0.110502 0.009880781 0.192915 0.110807 0.009733796 0.192785 0.110934 0.009733796 0.192907 0.111044 0.009686291 0.192827 0.111186 0.009680747 0.19267 0.1110759 0.009733796 0.192441 0.11157 0.009733796 0.1926749 0.111468 0.009680747 0.19293 0.111003 0.00968784 0.193186 0.11112 0.009621858 0.192836 0.110361 0.009880781 0.19306 0.110696 0.009733796 0.192858 0.109898 0.0100618 0.193035 0.110244 0.009880781 0.193113 0.109787 0.0100618 0.192987 0.109439 0.01027536 0.193247 0.110152 0.009880781 0.1932179 0.110603 0.009733796 0.193212 0.111155 0.009613811 0.193291 0.111039 0.009621858 0.193385 0.110531 0.009733796 0.193468 0.110086 0.009880781 0.193654 0.109661 0.0100618 0.193682 0.1092849 0.01027536 0.193614 0.109293 0.01027536 0.193902 0.1092759 0.01027536 0.193696 0.110047 0.009880781 0.193597 0.111348 0.009545743 0.193405 0.110972 0.009621858 0.19343 0.111274 0.009572148 0.1935819 0.111356 0.009545743 0.193527 0.1109189 0.009621858 0.193672 0.111316 0.009545743 0.193654 0.110882 0.009621858 0.19356 0.110478 0.009733796 0.193927 0.110036 0.009880781 0.194258 0.109301 0.01027536 0.194123 0.1092849 0.01027536 0.194559 0.1093569 0.01027536 0.194209 0.109668 0.0100618 0.194157 0.110053 0.009880781 0.19374 0.110448 0.009733796 0.19375 0.111292 0.009545743 0.194746 0.109807 0.0100618 0.194104 0.1104519 0.009733796 0.193922 0.110439 0.009733796 0.193928 0.111125 0.009572148 0.193846 0.111277 0.009545743 0.1951749 0.109598 0.01027536 0.194604 0.110169 0.009880781 0.194384 0.110098 0.009880781 0.194199 0.110625 0.00968784 0.194068 0.110868 0.009623944 0.195448 0.1097699 0.01027536 0.194998 0.109925 0.0100618 0.195451 0.110246 0.0100618 0.195235 0.110071 0.0100618 0.194814 0.110267 0.009880781 0.194456 0.110544 0.009733796 0.196013 0.110307 0.01027536 0.19587 0.1101379 0.01027536 0.195646 0.110445 0.0100618 0.1957139 0.109982 0.01027536 0.19519 0.1105329 0.009880781 0.194777 0.1107169 0.009733796 0.19501 0.110389 0.009880781 0.194919 0.110832 0.009733796 0.196352 0.110875 0.01027536 0.196285 0.110738 0.01027536 0.196255 0.110676 0.01027536 0.195492 0.110882 0.009880781 0.195351 0.1106989 0.009880781 0.195047 0.110962 0.009733796 0.194809 0.110954 0.009686291 0.194622 0.110621 0.009733796 0.194667 0.1108739 0.009680747 0.194527 0.110795 0.009675323 0.194283 0.110487 0.009733796 0.1943849 0.110722 0.009680747 0.19424 0.110646 0.009686291 0.195955 0.110905 0.0100618 0.195609 0.111082 0.009880781 0.195157 0.111107 0.009733796 0.194733 0.111233 0.009621858 0.19485 0.110977 0.00968784 0.194719 0.11122 0.009623944 0.1961449 0.111427 0.0100618 0.1964319 0.111081 0.01027536 0.19525 0.111264 0.009733796 0.194814 0.111338 0.009621858 0.194698 0.111259 0.009613811 0.194675 0.111301 0.009602725 0.195701 0.111294 0.009880781 0.196541 0.111509 0.01027536 0.19656 0.111661 0.01027536 0.196192 0.111701 0.0100618 0.195806 0.111743 0.009880781 0.195767 0.111515 0.009880781 0.195323 0.111432 0.009733796 0.194881 0.111452 0.009621858 0.194579 0.111477 0.009572148 0.194505 0.111644 0.009545743 0.194934 0.111574 0.009621858 0.194972 0.111701 0.009621858 0.195375 0.111607 0.009733796 0.1961849 0.112256 0.0100618 0.196541 0.112389 0.01027536 0.196552 0.112305 0.01027536 0.196132 0.112529 0.0100618 0.1958169 0.111974 0.009880781 0.1958 0.112204 0.009880781 0.195414 0.111969 0.009733796 0.195405 0.111787 0.009733796 0.194994 0.111831 0.009621858 0.194549 0.111758 0.009545743 0.19639 0.112929 0.01027536 0.196433 0.112818 0.01027536 0.1960459 0.112793 0.0100618 0.195756 0.112431 0.009880781 0.195401 0.112151 0.009733796 0.196256 0.113222 0.01027536 0.196353 0.1130239 0.01027536 0.195928 0.113045 0.0100618 0.195684 0.112651 0.009880781 0.195228 0.112246 0.00968784 0.196083 0.113495 0.01027536 0.195782 0.113282 0.0100618 0.195587 0.11286 0.009880781 0.195607 0.113498 0.0100618 0.195715 0.113917 0.01027536 0.1958709 0.113761 0.01027536 0.195465 0.113057 0.009880781 0.195187 0.113861 0.0100618 0.195408 0.113692 0.0100618 0.19532 0.113237 0.009880781 0.195022 0.112966 0.009733796 0.195136 0.112824 0.009733796 0.195116 0.114332 0.01027536 0.195154 0.113398 0.009880781 0.194899 0.112856 0.009686291 0.194979 0.112714 0.009680747 0.195232 0.112669 0.009733796 0.195309 0.112503 0.009733796 0.195366 0.11233 0.009733796 0.194891 0.113093 0.009733796 0.194746 0.113204 0.009733796 0.194971 0.113539 0.009880781 0.194948 0.114002 0.0100618 0.194693 0.114113 0.0100618 0.194771 0.113656 0.009880781 0.194559 0.113748 0.009880781 0.194589 0.113297 0.009733796 0.19462 0.11278 0.009621858 0.194594 0.112745 0.009613811 0.194633 0.112765 0.009623944 0.194515 0.112861 0.009621858 0.194401 0.112928 0.009621858 0.1944209 0.113369 0.009733796 0.194426 0.114192 0.0100618 0.1941249 0.114615 0.01027536 0.1941919 0.114607 0.01027536 0.19411 0.113853 0.009880781 0.1941519 0.114239 0.0100618 0.1942459 0.113422 0.009733796 0.194338 0.1138139 0.009880781 0.194376 0.112626 0.009572148 0.1942239 0.112544 0.009545743 0.194209 0.112552 0.009545743 0.194135 0.112584 0.009545743 0.194279 0.112981 0.009621858 0.1941519 0.113018 0.009621858 0.194067 0.113452 0.009733796 0.193874 0.114252 0.0100618 0.193879 0.113864 0.009880781 0.193597 0.114232 0.0100618 0.193247 0.114543 0.01027536 0.193231 0.114538 0.01027536 0.193324 0.114179 0.0100618 0.194056 0.112608 0.009545743 0.192924 0.114437 0.01027536 0.19306 0.114093 0.0100618 0.1936489 0.113847 0.009880781 0.193884 0.113461 0.009733796 0.1938779 0.112775 0.009572148 0.1940219 0.113041 0.009621858 0.192829 0.114399 0.01027536 0.192808 0.113975 0.0100618 0.193202 0.113731 0.009880781 0.193422 0.113802 0.009880781 0.193523 0.113413 0.009733796 0.193607 0.113275 0.00968784 0.1937389 0.113032 0.009623944 0.1925719 0.113829 0.0100618 0.19335 0.113356 0.009733796 0.1921049 0.113929 0.01027536 0.192355 0.113654 0.0100618 0.192993 0.113633 0.009880781 0.191936 0.113762 0.01027536 0.192161 0.1134549 0.0100618 0.192796 0.113511 0.009880781 0.193029 0.113183 0.009733796 0.193184 0.113279 0.009733796 0.191793 0.113593 0.01027536 0.1924549 0.113201 0.009880781 0.192616 0.113367 0.009880781 0.192887 0.113068 0.009733796 0.1914539 0.113025 0.01027536 0.191521 0.113162 0.01027536 0.191851 0.112995 0.0100618 0.1916649 0.113413 0.01027536 0.191992 0.113234 0.0100618 0.192315 0.113018 0.009880781 0.192997 0.112946 0.009686291 0.193139 0.113026 0.009680747 0.193279 0.1131049 0.009675323 0.193421 0.113178 0.009680747 0.193566 0.113254 0.009686291 0.192197 0.112818 0.009880781 0.19174 0.11274 0.0100618 0.191392 0.1128669 0.01027536 0.191311 0.112607 0.01027536 0.1921049 0.112606 0.009880781 0.192556 0.112636 0.009733796 0.192649 0.112793 0.009733796 0.193073 0.112667 0.009621858 0.1930879 0.11268 0.009623944 0.192992 0.112562 0.009621858 0.191661 0.112473 0.0100618 0.191238 0.112172 0.01027536 0.191246 0.112239 0.01027536 0.191614 0.112199 0.0100618 0.192 0.112157 0.009880781 0.192432 0.112293 0.009733796 0.192039 0.112385 0.009880781 0.192484 0.112468 0.009733796 0.192872 0.112326 0.009621858 0.192925 0.112448 0.009621858 0.1932269 0.112423 0.009572148 0.193309 0.112271 0.009545743 0.193301 0.112256 0.009545743 0.192835 0.112199 0.009621858 0.192401 0.1121129 0.009733796 0.191989 0.111926 0.009880781 0.191601 0.111921 0.0100618 0.191255 0.111595 0.01027536 0.191621 0.111644 0.0100618 0.192006 0.111696 0.009880781 0.192392 0.111931 0.009733796 0.192812 0.112069 0.009621858 0.193246 0.112103 0.009545743 0.193269 0.112182 0.009545743 0.19176 0.111107 0.0100618 0.1920509 0.111469 0.009880781 0.1916739 0.111371 0.0100618 0.193078 0.111925 0.009572148 0.1914539 0.110876 0.01027536 0.192578 0.111654 0.00968784 0.192821 0.111785 0.009623944 0.194543 0.1118749 0.01124995 0.194451 0.112046 0.01124995 0.1952069 0.112287 0.009686291 0.194283 0.112356 0.01124995 0.194191 0.1125259 0.01124995 0.19437 0.112259 0.01118856 0.195058 0.112574 0.009675323 0.194423 0.112157 0.01119226 0.195132 0.112432 0.009680747 0.194546 -0.1119109 0.01124995 0.19445 -0.111852 0.01124995 0.194472 -0.1118659 0.01097637 0.194725 -0.112021 0.009572148 0.194896 -0.112126 0.009602725 0.194564 -0.111922 0.009744763 0.194063 -0.112483 0.01124995 0.194175 -0.112568 0.009545743 0.194032 -0.112491 0.01124995 0.19402 -0.112615 0.009545743 0.194001 -0.112497 0.01124995 0.193939 -0.112624 0.009545743 0.193922 -0.112625 0.009545743 0.192638 -0.114448 0.01050347 0.192849 -0.114544 0.01189994 0.1932899 -0.114682 0.01189994 0.1937479 -0.114746 0.01189994 0.1942099 -0.114733 0.01189994 0.19398 -0.114749 0.01050347 0.1942099 -0.114733 0.01050347 0.1944389 -0.114698 0.01050347 0.194664 -0.114645 0.01189994 0.194884 -0.114572 0.01050347 0.195097 -0.1144829 0.01050347 0.195302 -0.114375 0.01050347 0.195097 -0.1144829 0.01189994 0.195498 -0.114251 0.01050347 0.195498 -0.114251 0.01189994 0.195855 -0.113958 0.01189994 0.195855 -0.113958 0.01050347 0.196159 -0.113609 0.01189994 0.196288 -0.113417 0.01050347 0.196401 -0.113215 0.01189994 0.196575 -0.112787 0.01189994 0.196676 -0.112335 0.01189994 0.196699 -0.112105 0.01050347 0.196702 -0.111874 0.01189994 0.196651 -0.111414 0.01189994 0.1965979 -0.111189 0.01050347 0.196526 -0.110969 0.01189994 0.196436 -0.110756 0.01050347 0.196328 -0.1105509 0.01189994 0.196204 -0.110355 0.01050347 0.196065 -0.110171 0.01050347 0.195911 -0.109998 0.01050347 0.196065 -0.110171 0.01189994 0.195743 -0.109839 0.01050347 0.195743 -0.109839 0.01189994 0.195562 -0.109694 0.01050347 0.19537 -0.109565 0.01189994 0.195168 -0.109452 0.01050347 0.194957 -0.109356 0.01189994 0.194516 -0.109218 0.01189994 0.1947399 -0.109278 0.01050347 0.194516 -0.109218 0.01050347 0.194058 -0.109154 0.01189994 0.193596 -0.109167 0.01189994 0.193596 -0.109167 0.01050347 0.1931419 -0.109255 0.01189994 0.1929219 -0.109328 0.01050347 0.192709 -0.109417 0.01050347 0.192709 -0.109417 0.01189994 0.192308 -0.109649 0.01189994 0.192124 -0.109788 0.01050347 0.191951 -0.109942 0.01189994 0.191792 -0.1101109 0.01050347 0.191518 -0.110483 0.01050347 0.1916469 -0.110291 0.01189994 0.1914049 -0.110685 0.01189994 0.191309 -0.110896 0.01050347 0.191231 -0.111113 0.01189994 0.191231 -0.111113 0.01050347 0.19113 -0.111565 0.01189994 0.19113 -0.111565 0.01050347 0.191107 -0.111795 0.01050347 0.1911039 -0.112026 0.01189994 0.19112 -0.112257 0.01050347 0.191155 -0.112486 0.01189994 0.191281 -0.112931 0.01189994 0.191209 -0.112711 0.01050347 0.191478 -0.113349 0.01189994 0.191478 -0.113349 0.01050347 0.191741 -0.113729 0.01189994 0.191741 -0.113729 0.01050347 0.192064 -0.1140609 0.01189994 0.192436 -0.114335 0.01050347 0.192436 -0.114335 0.01189994 0.193084 -0.114566 0.01033556 0.193318 -0.11456 0.01027536 0.193303 -0.114625 0.01033556 0.193526 -0.114665 0.01033556 0.1940439 -0.114619 0.01027536 0.1941969 -0.114608 0.01027536 0.19463 -0.114524 0.01027536 0.19484 -0.114455 0.01027536 0.194981 -0.114395 0.01027536 0.195044 -0.114369 0.01027536 0.195273 -0.114325 0.01033556 0.19524 -0.114266 0.01027536 0.195465 -0.114203 0.01033556 0.195268 -0.114248 0.01027536 0.195426 -0.114148 0.01027536 0.195535 -0.114066 0.01027536 0.195603 -0.114015 0.01027536 0.195767 -0.113867 0.01027536 0.195779 -0.113855 0.01027536 0.1959699 -0.113751 0.01033556 0.196112 -0.113574 0.01033556 0.196058 -0.113534 0.01027536 0.1961809 -0.113351 0.01027536 0.196289 -0.113158 0.01027536 0.196349 -0.113189 0.01033556 0.196331 -0.113065 0.01027536 0.196443 -0.112982 0.01033556 0.1964499 -0.112765 0.01027536 0.196455 -0.112749 0.01027536 0.196519 -0.112769 0.01033556 0.1965129 -0.112536 0.01027536 0.196528 -0.112452 0.01027536 0.19657 -0.112132 0.01027536 0.196577 -0.111877 0.01027536 0.196644 -0.1118749 0.01033556 0.196561 -0.111656 0.01027536 0.1965939 -0.111425 0.01033556 0.1964769 -0.111223 0.01027536 0.196461 -0.111175 0.01027536 0.196471 -0.110989 0.01033556 0.196408 -0.111013 0.01027536 0.1963829 -0.110781 0.01033556 0.196348 -0.110872 0.01027536 0.196201 -0.110585 0.01027536 0.196156 -0.110388 0.01033556 0.195821 -0.110086 0.01027536 0.195869 -0.110039 0.01033556 0.1956599 -0.109934 0.01027536 0.195527 -0.109741 0.01033556 0.195339 -0.109615 0.01033556 0.194935 -0.10941 0.01033556 0.1949099 -0.109472 0.01027536 0.194503 -0.109275 0.01033556 0.194405 -0.109325 0.01027536 0.19428 -0.109235 0.01033556 0.194055 -0.109213 0.01033556 0.194051 -0.10928 0.01027536 0.19383 -0.109277 0.01027536 0.193762 -0.109281 0.01027536 0.193828 -0.10921 0.01033556 0.19361 -0.109292 0.01027536 0.193602 -0.109225 0.01033556 0.193378 -0.109259 0.01033556 0.192943 -0.109382 0.01033556 0.192566 -0.109634 0.01027536 0.192734 -0.10947 0.01033556 0.192342 -0.109697 0.01033556 0.19238 -0.1097519 0.01027536 0.192161 -0.109833 0.01033556 0.192203 -0.109885 0.01027536 0.191695 -0.110326 0.01033556 0.191749 -0.110366 0.01027536 0.1916249 -0.110549 0.01027536 0.191426 -0.110943 0.01027536 0.191363 -0.110918 0.01033556 0.1913509 -0.111151 0.01027536 0.191294 -0.111364 0.01027536 0.191287 -0.111131 0.01033556 0.191278 -0.111448 0.01027536 0.191236 -0.111768 0.01027536 0.191166 -0.111798 0.01033556 0.191163 -0.112025 0.01033556 0.1912339 -0.112091 0.01027536 0.191245 -0.112244 0.01027536 0.191278 -0.112462 0.01027536 0.191424 -0.113119 0.01033556 0.191529 -0.11332 0.01033556 0.191605 -0.113315 0.01027536 0.19165 -0.113512 0.01033556 0.191705 -0.1134729 0.01027536 0.191786 -0.113692 0.01033556 0.191787 -0.113582 0.01027536 0.191998 -0.113826 0.01027536 0.191938 -0.113861 0.01033556 0.192102 -0.114017 0.01033556 0.192146 -0.113966 0.01027536 0.192279 -0.114159 0.01033556 0.192467 -0.114285 0.01033556 0.192502 -0.114228 0.01027536 0.192695 -0.114336 0.01027536 0.192665 -0.114396 0.01033556 0.192788 -0.114378 0.01027536 0.192871 -0.11449 0.01033556 0.192854 -0.11453 0.0104146 0.193071 -0.114608 0.0104146 0.193749 -0.114731 0.0104146 0.193751 -0.114687 0.01033556 0.193978 -0.11469 0.01033556 0.194204 -0.114675 0.01033556 0.193979 -0.114734 0.0104146 0.194428 -0.114641 0.01033556 0.194209 -0.114718 0.0104146 0.194648 -0.114588 0.01033556 0.19466 -0.11463 0.0104146 0.194864 -0.114518 0.01033556 0.1950719 -0.11443 0.01033556 0.195295 -0.114362 0.0104146 0.195489 -0.114239 0.0104146 0.195645 -0.114067 0.01033556 0.195845 -0.113947 0.0104146 0.195814 -0.113916 0.01033556 0.196003 -0.11378 0.0104146 0.1962749 -0.113409 0.0104146 0.196238 -0.113386 0.01033556 0.196483 -0.112999 0.0104146 0.196578 -0.11255 0.01033556 0.196618 -0.112327 0.01033556 0.196662 -0.1123329 0.0104146 0.19664 -0.112102 0.01033556 0.196684 -0.1121039 0.0104146 0.196628 -0.111649 0.01033556 0.196671 -0.111644 0.0104146 0.196637 -0.111417 0.0104146 0.196541 -0.111205 0.01033556 0.196422 -0.110762 0.0104146 0.196278 -0.11058 0.01033556 0.196315 -0.110558 0.0104146 0.19602 -0.110208 0.01033556 0.196053 -0.11018 0.0104146 0.1959 -0.110009 0.0104146 0.195704 -0.109883 0.01033556 0.195362 -0.109578 0.0104146 0.195142 -0.109504 0.01033556 0.195161 -0.109465 0.0104146 0.194952 -0.10937 0.0104146 0.1947219 -0.109334 0.01033556 0.194513 -0.109233 0.0104146 0.193827 -0.109166 0.0104146 0.193597 -0.109182 0.0104146 0.193158 -0.1093119 0.01033556 0.192927 -0.109342 0.0104146 0.192715 -0.109431 0.0104146 0.192533 -0.109575 0.01033556 0.191992 -0.109984 0.01033556 0.192133 -0.1098 0.0104146 0.191962 -0.109953 0.0104146 0.1918359 -0.110149 0.01033556 0.191803 -0.1101199 0.0104146 0.191568 -0.110514 0.01033556 0.191419 -0.110692 0.0104146 0.191457 -0.110711 0.01033556 0.191245 -0.111118 0.0104146 0.191228 -0.1113499 0.01033556 0.191188 -0.111573 0.01033556 0.191145 -0.111567 0.0104146 0.191119 -0.112026 0.0104146 0.191178 -0.112251 0.01033556 0.191135 -0.112256 0.0104146 0.1912119 -0.112475 0.01033556 0.19117 -0.112483 0.0104146 0.191265 -0.112695 0.01033556 0.191295 -0.112926 0.0104146 0.191335 -0.112911 0.01033556 0.191491 -0.113342 0.0104146 0.191753 -0.1137199 0.0104146 0.192074 -0.11405 0.0104146 0.1922529 -0.114194 0.0104146 0.192444 -0.114322 0.0104146 0.192645 -0.114435 0.0104146 0.192849 -0.114544 0.01050347 0.193067 -0.1146219 0.01050347 0.1932899 -0.114682 0.01050347 0.193293 -0.1146669 0.0104146 0.19352 -0.114708 0.0104146 0.193518 -0.114723 0.01050347 0.1937479 -0.114746 0.01050347 0.194436 -0.114683 0.0104146 0.194664 -0.114645 0.01050347 0.1948789 -0.114558 0.0104146 0.195091 -0.114469 0.0104146 0.195673 -0.1141 0.0104146 0.195683 -0.114112 0.01050347 0.196014 -0.113789 0.01050347 0.196159 -0.113609 0.01050347 0.196147 -0.1136 0.0104146 0.196401 -0.113215 0.01050347 0.196388 -0.113208 0.0104146 0.196497 -0.113004 0.01050347 0.196561 -0.112782 0.0104146 0.196575 -0.112787 0.01050347 0.19662 -0.11256 0.0104146 0.196635 -0.112563 0.01050347 0.196676 -0.112335 0.01050347 0.196687 -0.111874 0.0104146 0.196702 -0.111874 0.01050347 0.196686 -0.111643 0.01050347 0.196651 -0.111414 0.01050347 0.196583 -0.111193 0.0104146 0.196511 -0.110974 0.0104146 0.196526 -0.110969 0.01050347 0.196192 -0.110364 0.0104146 0.196328 -0.1105509 0.01050347 0.195733 -0.10985 0.0104146 0.195553 -0.109706 0.0104146 0.19537 -0.109565 0.01050347 0.194957 -0.109356 0.01050347 0.194735 -0.109292 0.0104146 0.194286 -0.109192 0.0104146 0.194057 -0.109169 0.0104146 0.194288 -0.109177 0.01050347 0.194058 -0.109154 0.01050347 0.193827 -0.109151 0.01050347 0.19337 -0.109217 0.0104146 0.193367 -0.109202 0.01050347 0.193146 -0.10927 0.0104146 0.1931419 -0.109255 0.01050347 0.192511 -0.109538 0.0104146 0.192504 -0.109525 0.01050347 0.192317 -0.109661 0.0104146 0.192308 -0.109649 0.01050347 0.191951 -0.109942 0.01050347 0.19166 -0.1103 0.0104146 0.1916469 -0.110291 0.01050347 0.191531 -0.110491 0.0104146 0.1914049 -0.110685 0.01050347 0.191323 -0.1109009 0.0104146 0.191186 -0.11134 0.0104146 0.191171 -0.111337 0.01050347 0.1911219 -0.111796 0.0104146 0.1911039 -0.112026 0.01050347 0.191155 -0.112486 0.01050347 0.191223 -0.112707 0.0104146 0.191281 -0.112931 0.01050347 0.191384 -0.113138 0.0104146 0.191371 -0.113144 0.01050347 0.191602 -0.113545 0.01050347 0.191614 -0.113536 0.0104146 0.191906 -0.113891 0.0104146 0.191896 -0.113902 0.01050347 0.192064 -0.1140609 0.01050347 0.1922439 -0.114206 0.01050347 0.191812 -0.1102859 0.01027536 0.192027 -0.110045 0.01027536 0.192538 -0.109652 0.01027536 0.193128 -0.109392 0.01027536 0.194085 -0.109283 0.01027536 0.194718 -0.109403 0.01027536 0.195111 -0.109564 0.01027536 0.195304 -0.109672 0.01027536 0.195488 -0.109795 0.01027536 0.195567 -0.109859 0.01027536 0.1958079 -0.110074 0.01027536 0.195544 -0.110334 0.0100618 0.196536 -0.111488 0.01027536 0.196171 -0.111552 0.0100618 0.196381 -0.112957 0.01027536 0.195994 -0.113614 0.01027536 0.194365 -0.114583 0.01027536 0.193746 -0.114247 0.0100618 0.192697 -0.113911 0.0100618 0.192319 -0.114105 0.01027536 0.192239 -0.114041 0.01027536 0.1922619 -0.113566 0.0100618 0.191357 -0.111135 0.01027536 0.1917099 -0.111248 0.0100618 0.1915169 -0.110742 0.01027536 0.194937 -0.112151 0.009613811 0.1945869 -0.112805 0.009623944 0.194573 -0.112819 0.009621858 0.194549 -0.112782 0.009613811 0.194463 -0.112893 0.009621858 0.194099 -0.112596 0.009545743 0.193619 -0.113434 0.009733796 0.1930339 -0.1126199 0.009621858 0.193071 -0.112596 0.009613811 0.19296 -0.11251 0.009621858 0.193096 -0.112555 0.009602725 0.193285 -0.112222 0.009545743 0.19291 -0.111774 0.009602725 0.193233 -0.111081 0.009621858 0.1929799 -0.1107529 0.009733796 0.193257 -0.111118 0.009613811 0.193298 -0.111143 0.009602725 0.193707 -0.111304 0.009545743 0.1936309 -0.1113319 0.009545743 0.193616 -0.111339 0.009545743 0.194079 -0.110957 0.009602725 0.194312 -0.110667 0.009686291 0.194735 -0.111304 0.009613811 0.194772 -0.11128 0.009621858 0.19471 -0.111345 0.009602725 0.194846 -0.1113899 0.009621858 0.194521 -0.111678 0.009545743 0.191475 -0.110835 0.01027536 0.1924059 -0.110758 0.009880781 0.191811 -0.110989 0.0100618 0.192273 -0.110947 0.009880781 0.191254 -0.111582 0.01027536 0.19208 -0.111367 0.009880781 0.19253 -0.111319 0.009733796 0.192164 -0.111151 0.009880781 0.191606 -0.111793 0.0100618 0.191641 -0.111518 0.0100618 0.191604 -0.112071 0.0100618 0.1912299 -0.112023 0.01027536 0.191233 -0.111802 0.01027536 0.192023 -0.111591 0.009880781 0.1924639 -0.1114889 0.009733796 0.19262 -0.111541 0.009686291 0.192703 -0.1114 0.009680747 0.192616 -0.111158 0.009733796 0.192785 -0.111262 0.009675323 0.192721 -0.111009 0.009733796 0.192871 -0.111127 0.009680747 0.192959 -0.11099 0.009686291 0.192984 -0.11095 0.00968784 0.1912699 -0.112412 0.01027536 0.191992 -0.112051 0.009880781 0.191994 -0.11182 0.009880781 0.1924189 -0.111666 0.009733796 0.192597 -0.111581 0.00968784 0.192825 -0.111744 0.009621858 0.1928319 -0.111726 0.009623944 0.191345 -0.112725 0.01027536 0.1917 -0.112618 0.0100618 0.191329 -0.112677 0.01027536 0.192018 -0.112281 0.009880781 0.191635 -0.112348 0.0100618 0.192394 -0.11203 0.009733796 0.192396 -0.111847 0.009733796 0.192869 -0.111749 0.009613811 0.192808 -0.1118749 0.009621858 0.1924149 -0.112211 0.009733796 0.192072 -0.112505 0.009880781 0.191587 -0.113287 0.01027536 0.191484 -0.113091 0.01027536 0.191458 -0.113028 0.01027536 0.191398 -0.112887 0.01027536 0.191923 -0.113126 0.0100618 0.191796 -0.112879 0.0100618 0.192822 -0.112139 0.009621858 0.193229 -0.111986 0.009545743 0.192807 -0.112008 0.009621858 0.193081 -0.111879 0.009572148 0.193228 -0.111969 0.009545743 0.193238 -0.112067 0.009545743 0.192457 -0.112388 0.009733796 0.19252 -0.11256 0.009733796 0.192152 -0.112722 0.009880781 0.192258 -0.112928 0.009880781 0.19208 -0.113356 0.0100618 0.191838 -0.11365 0.01027536 0.191986 -0.1138139 0.01027536 0.192387 -0.113119 0.009880781 0.193257 -0.112146 0.009545743 0.192853 -0.112268 0.009621858 0.192469 -0.113752 0.0100618 0.192604 -0.112722 0.009733796 0.192706 -0.112873 0.009733796 0.193202 -0.112384 0.009572148 0.192899 -0.112393 0.009621858 0.193292 -0.112237 0.009545743 0.192539 -0.113293 0.009880781 0.192826 -0.11301 0.009733796 0.1929039 -0.112869 0.00968784 0.193048 -0.112633 0.009623944 0.192942 -0.114042 0.0100618 0.192962 -0.1131319 0.009733796 0.1927109 -0.113447 0.009880781 0.1930879 -0.114497 0.01027536 0.192896 -0.114428 0.01027536 0.193201 -0.114143 0.0100618 0.1929 -0.11358 0.009880781 0.193401 -0.114575 0.01027536 0.193104 -0.114502 0.01027536 0.19332 -0.113773 0.009880781 0.193104 -0.113689 0.009880781 0.1937209 -0.114617 0.01027536 0.193535 -0.114599 0.01027536 0.193471 -0.114212 0.0100618 0.193976 -0.114623 0.01027536 0.194024 -0.114249 0.0100618 0.193755 -0.11462 0.01027536 0.193544 -0.11383 0.009880781 0.193494 -0.113233 0.009686291 0.193442 -0.113389 0.009733796 0.1932719 -0.113323 0.009733796 0.1933529 -0.11315 0.009680747 0.193111 -0.113237 0.009733796 0.193215 -0.113068 0.009675323 0.19308 -0.112982 0.009680747 0.192943 -0.1128939 0.009686291 0.194301 -0.1142179 0.0100618 0.193773 -0.1138589 0.009880781 0.1938 -0.113458 0.009733796 0.193534 -0.113257 0.00968784 0.193679 -0.113021 0.009623944 0.194679 -0.114508 0.01027536 0.194415 -0.114575 0.01027536 0.1940039 -0.113861 0.009880781 0.193697 -0.113028 0.009621858 0.193702 -0.112984 0.009613811 0.193727 -0.112943 0.009602725 0.193828 -0.113045 0.009621858 0.193832 -0.112772 0.009572148 0.193961 -0.113046 0.009621858 0.193983 -0.113459 0.009733796 0.194164 -0.113438 0.009733796 0.194234 -0.113835 0.009880781 0.194458 -0.113782 0.009880781 0.194571 -0.114154 0.0100618 0.194832 -0.114057 0.0100618 0.194675 -0.113701 0.009880781 0.194342 -0.113396 0.009733796 0.194093 -0.113031 0.009621858 0.194059 -0.112606 0.009545743 0.194513 -0.113333 0.009733796 0.194881 -0.113595 0.009880781 0.195079 -0.11393 0.0100618 0.195309 -0.113773 0.0100618 0.194675 -0.113249 0.009733796 0.194221 -0.113 0.009621858 0.1957049 -0.113384 0.0100618 0.195919 -0.113707 0.01027536 0.195519 -0.113591 0.0100618 0.1950719 -0.113466 0.009880781 0.194346 -0.112954 0.009621858 0.194337 -0.112652 0.009572148 0.195864 -0.113156 0.0100618 0.195246 -0.113314 0.009880781 0.194826 -0.113147 0.009733796 0.195996 -0.112911 0.0100618 0.195533 -0.112953 0.009880781 0.195085 -0.112891 0.009733796 0.195401 -0.113142 0.009880781 0.196096 -0.112652 0.0100618 0.1956419 -0.112749 0.009880781 0.19519 -0.112742 0.009733796 0.196165 -0.112382 0.0100618 0.195276 -0.112581 0.009733796 0.196552 -0.112318 0.01027536 0.1962 -0.112107 0.0100618 0.195342 -0.112411 0.009733796 0.195726 -0.112533 0.009880781 0.196572 -0.111809 0.01027536 0.1962029 -0.111829 0.0100618 0.196573 -0.112098 0.01027536 0.195783 -0.112309 0.009880781 0.195186 -0.112359 0.009686291 0.195103 -0.1125 0.009680747 0.195021 -0.1126379 0.009675323 0.194963 -0.113027 0.009733796 0.194935 -0.112773 0.009680747 0.194847 -0.11291 0.009686291 0.194822 -0.11295 0.00968784 0.195814 -0.111849 0.009880781 0.195813 -0.11208 0.009880781 0.195411 -0.112053 0.009733796 0.195387 -0.1122339 0.009733796 0.19521 -0.112319 0.00968784 0.196528 -0.111438 0.01027536 0.195788 -0.111619 0.009880781 0.194981 -0.112156 0.009621858 0.194974 -0.112174 0.009623944 0.194998 -0.112025 0.009621858 0.194999 -0.111892 0.009621858 0.195412 -0.11187 0.009733796 0.1953909 -0.111689 0.009733796 0.195735 -0.111395 0.009880781 0.196107 -0.111282 0.0100618 0.1960099 -0.111021 0.0100618 0.19622 -0.110613 0.01027536 0.196322 -0.110809 0.01027536 0.195883 -0.110774 0.0100618 0.195654 -0.111178 0.009880781 0.195349 -0.111512 0.009733796 0.194984 -0.111761 0.009621858 0.194578 -0.111931 0.009545743 0.194577 -0.111914 0.009545743 0.194568 -0.111833 0.009545743 0.195968 -0.1102499 0.01027536 0.1960189 -0.110318 0.01027536 0.196101 -0.110427 0.01027536 0.195419 -0.110781 0.009880781 0.195727 -0.110544 0.0100618 0.195549 -0.110972 0.009880781 0.195286 -0.11134 0.009733796 0.194907 -0.1115069 0.009621858 0.194549 -0.111754 0.009545743 0.194953 -0.111632 0.009621858 0.195267 -0.110607 0.009880781 0.1951 -0.111027 0.009733796 0.1952019 -0.111178 0.009733796 0.1946049 -0.1115159 0.009572148 0.194514 -0.111663 0.009545743 0.195095 -0.110453 0.009880781 0.1953369 -0.110148 0.0100618 0.19498 -0.11089 0.009733796 0.1947579 -0.111267 0.009623944 0.1950179 -0.109522 0.01027536 0.194864 -0.109858 0.0100618 0.195109 -0.109989 0.0100618 0.1949059 -0.11032 0.009880781 0.194844 -0.110768 0.009733796 0.194489 -0.10934 0.01027536 0.1943359 -0.109688 0.0100618 0.194702 -0.109398 0.01027536 0.1946049 -0.109757 0.0100618 0.194702 -0.110211 0.009880781 0.194534 -0.110577 0.009733796 0.1946949 -0.1106629 0.009733796 0.194271 -0.109301 0.01027536 0.194263 -0.11007 0.009880781 0.194486 -0.110127 0.009880781 0.194364 -0.110511 0.009733796 0.19406 -0.1096529 0.0100618 0.194453 -0.11075 0.009680747 0.194591 -0.110832 0.009675323 0.194726 -0.110918 0.009680747 0.194863 -0.111006 0.009686291 0.194903 -0.111031 0.00968784 0.194272 -0.110643 0.00968784 0.194109 -0.110872 0.009621858 0.194187 -0.110466 0.009733796 0.194006 -0.110442 0.009733796 0.194033 -0.110041 0.009880781 0.193782 -0.109651 0.0100618 0.193505 -0.109682 0.0100618 0.193391 -0.109325 0.01027536 0.193441 -0.109317 0.01027536 0.193176 -0.109376 0.01027536 0.193235 -0.109746 0.0100618 0.1938019 -0.110039 0.009880781 0.193978 -0.110855 0.009621858 0.194105 -0.110916 0.009613811 0.194128 -0.110879 0.009623944 0.193845 -0.110854 0.009621858 0.193823 -0.110441 0.009733796 0.193642 -0.110462 0.009733796 0.1935729 -0.110065 0.009880781 0.192762 -0.109531 0.01027536 0.192825 -0.1095049 0.01027536 0.192974 -0.109843 0.0100618 0.192966 -0.109445 0.01027536 0.193131 -0.110199 0.009880781 0.193348 -0.110118 0.009880781 0.1934649 -0.110504 0.009733796 0.193868 -0.111276 0.009545743 0.193974 -0.111128 0.009572148 0.193884 -0.111275 0.009545743 0.193786 -0.111285 0.009545743 0.193714 -0.110869 0.009621858 0.193585 -0.1109 0.009621858 0.193294 -0.110567 0.009733796 0.192926 -0.110305 0.009880781 0.192727 -0.10997 0.0100618 0.192497 -0.110127 0.0100618 0.1922709 -0.109834 0.01027536 0.192039 -0.110033 0.01027536 0.192287 -0.110309 0.0100618 0.193131 -0.110651 0.009733796 0.191887 -0.110193 0.01027536 0.19256 -0.110586 0.009880781 0.192734 -0.110434 0.009880781 0.193343 -0.111007 0.009621858 0.193469 -0.111248 0.009572148 0.19346 -0.1109459 0.009621858 0.191942 -0.1107439 0.0100618 0.192101 -0.110516 0.0100618 0.192843 -0.110873 0.009733796 0.19322 -0.111095 0.009623944 0.194159 -0.112542 0.01124995 0.19419 -0.112561 0.009545743 0.194508 -0.112757 0.009602725 -3.81402e-4 -0.224305 0.01124995 -3.84531e-4 -0.224417 0.01124995 -3.82106e-4 -0.22433 0.01097637 -3.97289e-4 -0.224875 0.009613811 -3.95957e-4 -0.224828 0.009602725 -3.90375e-4 -0.224627 0.009572148 -3.85103e-4 -0.224438 0.009744763 5.37571e-4 -0.223545 0.01124995 4.25146e-4 -0.223542 0.01124995 0.00131607 -0.2235659 0.00968784 4.50438e-4 -0.223542 0.01097637 5.58128e-4 -0.223545 0.009744763 0.001039803 -0.223559 0.009623944 -0.002773523 -0.2242839 0.01050347 -0.002773523 -0.2242839 0.01189994 -0.002672493 -0.224735 0.01189994 -0.002594411 -0.2249529 0.01050347 -0.002498626 -0.2251639 0.01189994 -0.002256572 -0.225558 0.01189994 -0.001952946 -0.225906 0.01189994 -0.001952946 -0.225906 0.01050347 -0.001780569 -0.226061 0.01050347 -0.001596033 -0.2262009 0.01189994 -0.001596033 -0.2262009 0.01050347 -0.001195609 -0.226432 0.01050347 -0.001195609 -0.226432 0.01189994 -9.82479e-4 -0.226522 0.01050347 -7.62602e-4 -0.226594 0.01189994 -3.08759e-4 -0.226683 0.01189994 -3.08759e-4 -0.226683 0.01050347 1.53506e-4 -0.226696 0.01189994 6.11584e-4 -0.2266319 0.01189994 0.001052975 -0.226494 0.01050347 0.001263618 -0.226399 0.01050347 0.001052975 -0.226494 0.01189994 0.001465618 -0.2262859 0.01189994 0.001465618 -0.2262859 0.01050347 0.001657605 -0.226157 0.01050347 0.001838326 -0.226012 0.01189994 0.001838326 -0.226012 0.01050347 0.002160847 -0.225681 0.01189994 0.002160847 -0.225681 0.01050347 0.00230056 -0.2254959 0.01050347 0.002424478 -0.225301 0.01189994 0.002424478 -0.225301 0.01050347 0.002621948 -0.224882 0.01189994 0.002694129 -0.224663 0.01050347 0.002747893 -0.224438 0.01189994 0.002798914 -0.223978 0.01189994 0.002795755 -0.223746 0.01050347 0.002773523 -0.223516 0.01189994 0.002672493 -0.223065 0.01189994 0.002498626 -0.222636 0.01189994 0.002256572 -0.2222419 0.01189994 0.001952946 -0.221894 0.01050347 0.001952946 -0.221894 0.01189994 0.001400589 -0.221475 0.01050347 0.001596033 -0.221599 0.01189994 0.001195609 -0.221368 0.01189994 7.62602e-4 -0.221206 0.01189994 7.62602e-4 -0.221206 0.01050347 5.37517e-4 -0.221152 0.01050347 3.08759e-4 -0.221117 0.01189994 7.78924e-5 -0.221101 0.01050347 -1.53506e-4 -0.221104 0.01189994 -1.53506e-4 -0.221104 0.01050347 -3.83856e-4 -0.221126 0.01050347 -6.11584e-4 -0.221168 0.01189994 -0.001052975 -0.221306 0.01050347 -0.001052975 -0.221306 0.01189994 -0.001465618 -0.221514 0.01189994 -0.001657605 -0.221643 0.01050347 -0.001838326 -0.221788 0.01189994 -0.002160847 -0.222119 0.01189994 -0.00230056 -0.222304 0.01050347 -0.002424478 -0.222499 0.01189994 -0.002531826 -0.2227039 0.01050347 -0.002621948 -0.222918 0.01189994 -0.002621948 -0.222918 0.01050347 -0.002694129 -0.223137 0.01050347 -0.002747893 -0.223362 0.01189994 -0.002798914 -0.2238219 0.01189994 -0.002798914 -0.2238219 0.01050347 -0.002609789 -0.224484 0.01027536 -0.002155363 -0.225483 0.01027536 -0.002017259 -0.225656 0.01027536 -0.002067804 -0.2257 0.01033556 -0.001865327 -0.225816 0.01027536 -0.001827359 -0.2258509 0.01027536 -0.001524448 -0.226097 0.01027536 -0.001337766 -0.226216 0.01027536 -0.001562654 -0.226152 0.01033556 -0.001170635 -0.226379 0.01033556 -0.001016676 -0.226371 0.01027536 -7.28399e-4 -0.226473 0.01027536 -7.11869e-4 -0.226477 0.01027536 -5.26281e-4 -0.22659 0.01033556 -5.13409e-4 -0.226525 0.01027536 -3.95754e-4 -0.226543 0.01027536 -2.94911e-4 -0.226558 0.01027536 -3.02305e-4 -0.226625 0.01033556 -7.43989e-5 -0.226573 0.01027536 1.50298e-4 -0.226637 0.01033556 5.6743e-4 -0.226513 0.01027536 7.97678e-4 -0.226453 0.01027536 8.17678e-4 -0.226517 0.01033556 0.001030921 -0.22644 0.01033556 0.001175999 -0.226301 0.01027536 0.001237213 -0.226346 0.01033556 0.001622974 -0.226109 0.01033556 0.001583278 -0.226055 0.01027536 0.001799881 -0.225968 0.01033556 0.001964509 -0.225812 0.01033556 0.001916468 -0.225765 0.01027536 0.001950502 -0.225727 0.01027536 0.00206393 -0.225601 0.01027536 0.002315759 -0.225238 0.01027536 0.002373814 -0.225271 0.01033556 0.002573251 -0.224628 0.01027536 0.002637803 -0.224647 0.01033556 0.002577245 -0.2246119 0.01027536 0.002724707 -0.224202 0.01033556 0.002660572 -0.223652 0.01027536 0.002715587 -0.223524 0.01033556 0.002552688 -0.223102 0.01027536 0.002616643 -0.223082 0.01033556 0.002446413 -0.222663 0.01033556 0.002278745 -0.2225 0.01027536 0.002240777 -0.2224439 0.01027536 0.002209365 -0.222277 0.01033556 0.002155363 -0.222317 0.01027536 0.001912117 -0.221935 0.01033556 0.001700699 -0.221836 0.01027536 0.001578688 -0.221744 0.01027536 0.001170635 -0.221421 0.01033556 0.001016676 -0.221429 0.01027536 9.61942e-4 -0.221333 0.01033556 7.28399e-4 -0.221327 0.01027536 7.43989e-5 -0.221227 0.01027536 -1.46621e-4 -0.22123 0.01027536 -2.48166e-4 -0.221239 0.01027536 -3.6664e-4 -0.221251 0.01027536 -3.75833e-4 -0.221184 0.01033556 -8.17678e-4 -0.221283 0.01033556 -7.97678e-4 -0.221347 0.01027536 -8.77701e-4 -0.221376 0.01027536 -0.001030921 -0.22136 0.01033556 -0.001005709 -0.221422 0.01027536 -0.001583278 -0.221745 0.01027536 -0.001716077 -0.221851 0.01027536 -0.001755893 -0.2218829 0.01027536 -0.001799881 -0.221832 0.01033556 -0.001950502 -0.222073 0.01027536 -0.00206393 -0.222199 0.01027536 -0.002252459 -0.222337 0.01033556 -0.002156317 -0.222321 0.01027536 -0.002197325 -0.222376 0.01027536 -0.002331495 -0.2225919 0.01027536 -0.002567112 -0.222938 0.01033556 -0.002418279 -0.2227579 0.01027536 -0.002637803 -0.2231529 0.01033556 -0.002573251 -0.223172 0.01027536 -0.002690434 -0.223374 0.01033556 -0.002577245 -0.223188 0.01027536 -0.002724707 -0.223598 0.01033556 -0.002737343 -0.22405 0.01033556 -0.00276792 -0.2235929 0.0104146 -0.002758622 -0.224282 0.0104146 -0.002715587 -0.224276 0.01033556 -0.002675235 -0.224499 0.01033556 -0.002616643 -0.224718 0.01033556 -0.002717673 -0.224508 0.0104146 -0.002658188 -0.224731 0.0104146 -0.002540171 -0.224931 0.01033556 -0.002446413 -0.2251369 0.01033556 -0.002335846 -0.225335 0.01033556 -0.00237292 -0.225358 0.0104146 -0.002209365 -0.2255229 0.01033556 -0.002100586 -0.225728 0.0104146 -0.001912117 -0.225865 0.01033556 -0.001942455 -0.225896 0.0104146 -0.001743376 -0.226016 0.01033556 -0.001770973 -0.226049 0.0104146 -0.001393079 -0.226311 0.0104146 -0.001371324 -0.226274 0.01033556 -9.61942e-4 -0.226467 0.01033556 -9.77197e-4 -0.226508 0.0104146 -7.58503e-4 -0.22658 0.0104146 -7.46662e-4 -0.226538 0.01033556 -3.07099e-4 -0.226668 0.0104146 -7.62642e-5 -0.22664 0.01033556 1.52681e-4 -0.2266809 0.0104146 3.75833e-4 -0.226616 0.01033556 5.98801e-4 -0.226575 0.01033556 8.30645e-4 -0.226558 0.0104146 0.001434981 -0.226236 0.01033556 0.001256823 -0.2263849 0.0104146 0.001648724 -0.226144 0.0104146 0.001995682 -0.2258419 0.0104146 0.002115726 -0.225643 0.01033556 0.002149224 -0.2256709 0.0104146 0.002252459 -0.225463 0.01033556 0.002411425 -0.225293 0.0104146 0.002518236 -0.225089 0.0104146 0.002478957 -0.225071 0.01033556 0.002567112 -0.224862 0.01033556 0.002690434 -0.224426 0.01033556 0.002733111 -0.224435 0.0104146 0.00276792 -0.224207 0.0104146 0.002783834 -0.223977 0.0104146 0.002740383 -0.223976 0.01033556 0.002737343 -0.2237499 0.01033556 0.002780735 -0.223747 0.0104146 0.002758622 -0.223518 0.0104146 0.002675235 -0.2233009 0.01033556 0.002658188 -0.223069 0.0104146 0.002540171 -0.222869 0.01033556 0.002580463 -0.222853 0.0104146 0.002335846 -0.222465 0.01033556 0.002485156 -0.222643 0.0104146 0.002244412 -0.2222509 0.0104146 0.002067804 -0.2221 0.01033556 0.001942455 -0.221904 0.0104146 0.001743376 -0.2217839 0.01033556 0.001770973 -0.221751 0.0104146 0.00158745 -0.221612 0.0104146 0.001562654 -0.221648 0.01033556 0.001371324 -0.221526 0.01033556 0.001393079 -0.221489 0.0104146 7.46662e-4 -0.221262 0.01033556 7.58503e-4 -0.22122 0.0104146 5.34627e-4 -0.221167 0.0104146 5.26281e-4 -0.22121 0.01033556 3.02305e-4 -0.221175 0.01033556 7.62642e-5 -0.2211599 0.01033556 -1.50298e-4 -0.221163 0.01033556 -5.98801e-4 -0.221225 0.01033556 -6.08297e-4 -0.221182 0.0104146 -0.001047313 -0.221319 0.0104146 -0.001237213 -0.221454 0.01033556 -0.001434981 -0.2215639 0.01033556 -0.00145775 -0.221527 0.0104146 -0.001622974 -0.221691 0.01033556 -0.001995682 -0.221958 0.0104146 -0.001964509 -0.221988 0.01033556 -0.002115726 -0.222157 0.01033556 -0.002149224 -0.222129 0.0104146 -0.002288162 -0.222313 0.0104146 -0.002373814 -0.2225289 0.01033556 -0.002411425 -0.2225069 0.0104146 -0.002478957 -0.222729 0.01033556 -0.002679646 -0.223141 0.0104146 -0.002733111 -0.223365 0.0104146 -0.002740383 -0.223824 0.01033556 -0.002783834 -0.223823 0.0104146 -0.002780735 -0.224053 0.0104146 -0.002795755 -0.224054 0.01050347 -0.002732336 -0.224512 0.01050347 -0.002672493 -0.224735 0.01050347 -0.002580463 -0.224947 0.0104146 -0.002485156 -0.225157 0.0104146 -0.002498626 -0.2251639 0.01050347 -0.002385735 -0.2253659 0.01050347 -0.002256572 -0.225558 0.01050347 -0.002244412 -0.225549 0.0104146 -0.002111971 -0.225738 0.01050347 -0.00158745 -0.226188 0.0104146 -0.001400589 -0.226324 0.01050347 -0.001189172 -0.226418 0.0104146 -7.62602e-4 -0.226594 0.01050347 -5.34627e-4 -0.226633 0.0104146 -5.37517e-4 -0.226648 0.01050347 -7.74737e-5 -0.226684 0.0104146 -7.78924e-5 -0.2266989 0.01050347 1.53506e-4 -0.226696 0.01050347 3.81793e-4 -0.2266589 0.0104146 3.83856e-4 -0.226674 0.01050347 6.08297e-4 -0.226618 0.0104146 6.11584e-4 -0.2266319 0.01050347 0.001047313 -0.226481 0.0104146 8.35135e-4 -0.226573 0.01050347 0.00145775 -0.226273 0.0104146 0.001828432 -0.226001 0.0104146 0.002006411 -0.225853 0.01050347 0.002288162 -0.2254869 0.0104146 0.002531826 -0.225096 0.01050347 0.002607822 -0.2248769 0.0104146 0.002621948 -0.224882 0.01050347 0.002679646 -0.224659 0.0104146 0.002747893 -0.224438 0.01050347 0.002782881 -0.224209 0.01050347 0.002798914 -0.223978 0.01050347 0.002717673 -0.2232919 0.0104146 0.002773523 -0.223516 0.01050347 0.002732336 -0.2232879 0.01050347 0.002672493 -0.223065 0.01050347 0.002594411 -0.222847 0.01050347 0.00237292 -0.222442 0.0104146 0.002498626 -0.222636 0.01050347 0.002385735 -0.222434 0.01050347 0.002256572 -0.2222419 0.01050347 0.002100586 -0.222072 0.0104146 0.002111971 -0.222062 0.01050347 0.001780569 -0.2217389 0.01050347 0.001596033 -0.221599 0.01050347 0.001189172 -0.221382 0.0104146 0.001195609 -0.221368 0.01050347 9.82479e-4 -0.221278 0.01050347 9.77197e-4 -0.221292 0.0104146 3.07099e-4 -0.221132 0.0104146 3.08759e-4 -0.221117 0.01050347 7.74737e-5 -0.221116 0.0104146 -1.52681e-4 -0.221119 0.0104146 -3.81793e-4 -0.221141 0.0104146 -6.11584e-4 -0.221168 0.01050347 -8.30645e-4 -0.221242 0.0104146 -8.35135e-4 -0.221227 0.01050347 -0.001263618 -0.221401 0.01050347 -0.001256823 -0.221415 0.0104146 -0.001465618 -0.221514 0.01050347 -0.001648724 -0.221656 0.0104146 -0.001828432 -0.221799 0.0104146 -0.001838326 -0.221788 0.01050347 -0.002006411 -0.221947 0.01050347 -0.002160847 -0.222119 0.01050347 -0.002424478 -0.222499 0.01050347 -0.002518236 -0.222711 0.0104146 -0.002607822 -0.222923 0.0104146 -0.002747893 -0.223362 0.01050347 -0.002782881 -0.223591 0.01050347 3.95754e-4 -0.221257 0.01027536 0.001307666 -0.221568 0.01027536 0.001827359 -0.221949 0.01027536 0.002400636 -0.222724 0.01027536 0.002673327 -0.223974 0.01027536 0.002642631 -0.224296 0.01027536 0.00262463 -0.224413 0.01027536 0.002418279 -0.225042 0.01027536 0.001680374 -0.2254739 0.0100618 0.001206934 -0.226287 0.01027536 2.48166e-4 -0.226561 0.01027536 -0.001126348 -0.225908 0.0100618 -0.002386569 -0.225107 0.01027536 -0.002400636 -0.225076 0.01027536 -0.002612829 -0.224467 0.01027536 -0.002660572 -0.224148 0.01027536 -0.002658069 -0.223605 0.01027536 -0.002277195 -0.223559 0.0100618 -0.00262463 -0.223387 0.01027536 -0.002008259 -0.222774 0.0100618 -0.001175999 -0.221499 0.01027536 -5.84155e-4 -0.2212899 0.01027536 -3.33516e-4 -0.222584 0.00968784 -0.001039803 -0.224241 0.009623944 4.82653e-4 -0.224885 0.009621858 2.86997e-4 -0.225216 0.009686291 4.96325e-4 -0.225327 0.009733796 -3.98509e-4 -0.224919 0.009623944 -4.17446e-4 -0.224915 0.009621858 -5.36704e-4 -0.224857 0.009621858 -3.98849e-4 -0.224445 0.009545743 -6.48135e-4 -0.224785 0.009621858 -0.00101459 -0.223483 0.009621858 -0.001019239 -0.223501 0.009623944 -9.75424e-4 -0.2235029 0.009613811 -9.27583e-4 -0.223504 0.009602725 -7.26975e-4 -0.22351 0.009572148 -5.44769e-4 -0.223501 0.009545743 -8.85257e-4 -0.2232519 0.009621858 3.98509e-4 -0.222881 0.009623944 4.17446e-4 -0.222885 0.009621858 3.97289e-4 -0.222925 0.009613811 3.95957e-4 -0.222972 0.009602725 5.36704e-4 -0.222943 0.009621858 4.61606e-4 -0.223407 0.009545743 3.98849e-4 -0.2233549 0.009545743 6.48135e-4 -0.223015 0.009621858 0.001315593 -0.223613 0.009686291 0.001427233 -0.223404 0.009733796 9.75424e-4 -0.224297 0.009613811 0.00101459 -0.224317 0.009621858 9.27583e-4 -0.224296 0.009602725 7.26975e-4 -0.22429 0.009572148 5.44769e-4 -0.224299 0.009545743 5.54249e-4 -0.224286 0.009545743 6.4056e-5 -0.221598 0.0100618 4.023e-4 -0.222443 0.009733796 -5.6743e-4 -0.221287 0.01027536 -2.13854e-4 -0.221607 0.0100618 -4.88645e-4 -0.22165 0.0100618 5.32419e-5 -0.221987 0.009880781 -7.56311e-4 -0.221725 0.0100618 -4.06151e-4 -0.22203 0.009880781 -1.4034e-4 -0.222395 0.009733796 -1.77751e-4 -0.221994 0.009880781 -3.20671e-4 -0.222423 0.009733796 -0.00145632 -0.221659 0.01027536 -0.001399874 -0.221621 0.01027536 -0.001254796 -0.221969 0.0100618 -0.001206934 -0.221513 0.01027536 -0.001012921 -0.221832 0.0100618 -6.2863e-4 -0.222092 0.009880781 -4.96325e-4 -0.222473 0.009733796 -2.86997e-4 -0.222584 0.009686291 4.20363e-5 -0.2223899 0.009733796 -1.23881e-4 -0.222586 0.009680747 3.6514e-5 -0.222588 0.009675323 2.238e-4 -0.222406 0.009733796 1.96758e-4 -0.222595 0.009680747 3.59721e-4 -0.222602 0.009686291 -8.41941e-4 -0.222181 0.009880781 -0.001916468 -0.222035 0.01027536 -0.001478374 -0.222135 0.0100618 -0.001042962 -0.222295 0.009880781 -0.001228749 -0.222433 0.009880781 -8.23464e-4 -0.222633 0.009733796 -4.82653e-4 -0.2229149 0.009621858 -6.64741e-4 -0.222543 0.009733796 -3.60369e-4 -0.222864 0.009621858 -3.42425e-4 -0.222904 0.009613811 -3.41205e-4 -0.22286 0.009623944 -3.43756e-4 -0.222952 0.009602725 -3.49339e-4 -0.223152 0.009572148 -0.001396656 -0.222591 0.009880781 -0.001680374 -0.222326 0.0100618 -0.001857876 -0.22254 0.0100618 -0.002315759 -0.222562 0.01027536 -0.001102745 -0.222867 0.009733796 -9.70179e-4 -0.222741 0.009733796 -7.04424e-4 -0.2230589 0.009621858 -5.97898e-4 -0.22298 0.009621858 -3.54146e-4 -0.223325 0.009545743 -3.67934e-4 -0.223334 0.009545743 -8.00678e-4 -0.22315 0.009621858 -0.001219213 -0.223007 0.009733796 -0.001544237 -0.222769 0.009880781 -0.002504348 -0.222962 0.01027536 -0.002471268 -0.222883 0.01027536 -0.002219498 -0.223287 0.0100618 -0.0017699 -0.223172 0.009880781 -0.002129435 -0.223024 0.0100618 -0.001669228 -0.222964 0.009880781 -4.92721e-4 -0.223438 0.009545743 -4.33488e-4 -0.2233819 0.009545743 -0.002642631 -0.223504 0.01027536 -0.001844763 -0.22339 0.009880781 -0.001317918 -0.223161 0.009733796 -9.56927e-4 -0.223363 0.009621858 -5.54249e-4 -0.223514 0.009545743 -0.002673327 -0.223826 0.01027536 -0.002301692 -0.223836 0.0100618 -0.001892745 -0.223617 0.009880781 -0.001397371 -0.223325 0.009733796 -0.001295506 -0.2234939 0.00968784 -0.002670347 -0.224047 0.01027536 -0.00191313 -0.223847 0.009880781 -0.001456499 -0.223498 0.009733796 -0.002649128 -0.224267 0.01027536 -0.002250134 -0.224389 0.0100618 -0.002292633 -0.224114 0.0100618 -0.002523958 -0.2247779 0.01027536 -0.002552688 -0.224698 0.01027536 -0.00190562 -0.2240779 0.009880781 -0.002478063 -0.224906 0.01027536 -0.002174854 -0.224656 0.0100618 -0.001807689 -0.224529 0.009880781 -0.001870274 -0.224306 0.009880781 -0.002240777 -0.225356 0.01027536 -0.002278745 -0.2253 0.01027536 -0.001930654 -0.2251549 0.0100618 -0.002067804 -0.224913 0.0100618 -0.001476645 -0.224221 0.009733796 -0.001427233 -0.224396 0.009733796 -0.001315593 -0.224187 0.009686291 -0.00150454 -0.22404 0.009733796 -0.001510441 -0.2238579 0.009733796 -0.001313805 -0.2240239 0.009680747 -0.001312017 -0.223863 0.009675323 -0.001304864 -0.223703 0.009680747 -0.001494407 -0.223676 0.009733796 -0.001297593 -0.22354 0.009686291 -0.00131607 -0.224234 0.00968784 -0.001036286 -0.22426 0.009621858 -0.001718699 -0.2247419 0.009880781 -0.001604676 -0.224943 0.009880781 -0.002049088 -0.225616 0.01027536 -0.001574277 -0.22558 0.0100618 -0.00176531 -0.225378 0.0100618 -0.001356959 -0.224565 0.009733796 -9.85295e-4 -0.2243829 0.009621858 -9.9601e-4 -0.224242 0.009613811 -9.48169e-4 -0.2242439 0.009602725 -0.001266956 -0.224723 0.009733796 -0.001467287 -0.225129 0.009880781 -0.001308441 -0.225297 0.009880781 -0.001578688 -0.226056 0.01027536 -0.001360237 -0.225758 0.0100618 -0.001700699 -0.225964 0.01027536 -0.001307666 -0.2262319 0.01027536 -0.001033067 -0.225003 0.009733796 -0.001158475 -0.22487 0.009733796 -8.41158e-4 -0.224604 0.009621858 -9.19933e-4 -0.224498 0.009621858 -7.47561e-4 -0.224249 0.009572148 -5.74834e-4 -0.224254 0.009545743 -5.66108e-4 -0.224268 0.009545743 -5.17631e-4 -0.224333 0.009545743 -7.50116e-4 -0.224701 0.009621858 -0.00113058 -0.225444 0.009880781 -9.36228e-4 -0.225569 0.009880781 -8.76098e-4 -0.226029 0.0100618 -0.001141965 -0.226318 0.01027536 -9.38414e-4 -0.226404 0.01027536 -6.13035e-4 -0.2261199 0.0100618 -8.92655e-4 -0.2251189 0.009733796 -4.61606e-4 -0.224393 0.009545743 -5.09541e-4 -0.225745 0.009880781 -7.28194e-4 -0.22567 0.009880781 -5.74934e-4 -0.225297 0.009733796 -7.39184e-4 -0.2252179 0.009733796 -3.85568e-4 -0.224454 0.009545743 -3.41032e-4 -0.226177 0.0100618 -4.023e-4 -0.2253569 0.009733796 -4.06197e-4 -0.225196 0.00968784 1.46621e-4 -0.22657 0.01027536 -6.4056e-5 -0.226202 0.0100618 -2.83458e-4 -0.225793 0.009880781 -5.32419e-5 -0.225813 0.009880781 4.88645e-4 -0.22615 0.0100618 3.6664e-4 -0.226549 0.01027536 2.13854e-4 -0.226193 0.0100618 -2.238e-4 -0.225394 0.009733796 0.001005709 -0.226378 0.01027536 8.77701e-4 -0.226424 0.01027536 5.84155e-4 -0.2265099 0.01027536 1.77751e-4 -0.2258059 0.009880781 7.56311e-4 -0.2260749 0.0100618 0.001012921 -0.225968 0.0100618 4.06151e-4 -0.2257699 0.009880781 1.4034e-4 -0.225405 0.009733796 0.00145632 -0.226141 0.01027536 0.001399874 -0.226179 0.01027536 6.2863e-4 -0.225708 0.009880781 3.20671e-4 -0.225377 0.009733796 1.23881e-4 -0.225214 0.009680747 -4.20363e-5 -0.22541 0.009733796 -1.96758e-4 -0.225205 0.009680747 -3.59721e-4 -0.225198 0.009686291 3.33516e-4 -0.225216 0.00968784 8.41941e-4 -0.225619 0.009880781 0.001254796 -0.225831 0.0100618 0.001755893 -0.225917 0.01027536 0.001716077 -0.225949 0.01027536 0.001478374 -0.225665 0.0100618 0.001042962 -0.2255049 0.009880781 8.23464e-4 -0.225167 0.009733796 6.64741e-4 -0.225257 0.009733796 3.60369e-4 -0.224936 0.009621858 3.42425e-4 -0.224896 0.009613811 3.43756e-4 -0.224848 0.009602725 5.97898e-4 -0.22482 0.009621858 9.70179e-4 -0.225058 0.009733796 0.001228749 -0.225367 0.009880781 0.001396656 -0.2252089 0.009880781 0.002197325 -0.225424 0.01027536 0.002156317 -0.225479 0.01027536 0.002331495 -0.225208 0.01027536 0.001857876 -0.22526 0.0100618 0.002008259 -0.225026 0.0100618 0.001544237 -0.225031 0.009880781 7.04424e-4 -0.224741 0.009621858 3.49339e-4 -0.2246479 0.009572148 3.67934e-4 -0.224466 0.009545743 4.33488e-4 -0.224418 0.009545743 0.001219213 -0.224793 0.009733796 0.001102745 -0.224933 0.009733796 0.001669228 -0.224836 0.009880781 0.002504348 -0.224838 0.01027536 0.002471268 -0.2249169 0.01027536 0.002129435 -0.224776 0.0100618 0.001317918 -0.2246389 0.009733796 8.00678e-4 -0.22465 0.009621858 4.92721e-4 -0.224362 0.009545743 0.002277195 -0.224241 0.0100618 0.002219498 -0.2245129 0.0100618 0.0017699 -0.224628 0.009880781 9.56927e-4 -0.2244369 0.009621858 8.85257e-4 -0.224548 0.009621858 0.002658069 -0.224195 0.01027536 0.002301692 -0.223964 0.0100618 0.001844763 -0.2244099 0.009880781 0.001892745 -0.224183 0.009880781 0.001456499 -0.2243019 0.009733796 0.001295506 -0.224306 0.00968784 0.001397371 -0.224475 0.009733796 0.001019239 -0.224299 0.009623944 0.002670347 -0.223753 0.01027536 0.00191313 -0.223953 0.009880781 0.001494407 -0.224124 0.009733796 0.002612829 -0.223333 0.01027536 0.002649128 -0.223533 0.01027536 0.002292633 -0.223686 0.0100618 0.002523958 -0.223022 0.01027536 0.002609789 -0.223316 0.01027536 0.002250134 -0.223411 0.0100618 0.001870274 -0.2234939 0.009880781 0.00190562 -0.223722 0.009880781 0.001510441 -0.223942 0.009733796 0.002478063 -0.222894 0.01027536 0.002174854 -0.2231439 0.0100618 0.001476645 -0.223579 0.009733796 0.00150454 -0.22376 0.009733796 0.002386569 -0.222693 0.01027536 0.002067804 -0.222887 0.0100618 0.001807689 -0.223271 0.009880781 0.001313805 -0.223776 0.009680747 0.001312017 -0.223937 0.009675323 0.001304864 -0.224097 0.009680747 0.001297593 -0.22426 0.009686291 0.001036286 -0.22354 0.009621858 0.001356959 -0.223235 0.009733796 0.001718699 -0.223058 0.009880781 0.001604676 -0.2228569 0.009880781 0.00176531 -0.222422 0.0100618 0.001930654 -0.222645 0.0100618 0.002017259 -0.222144 0.01027536 0.002049088 -0.222184 0.01027536 0.001865327 -0.221984 0.01027536 0.001467287 -0.222671 0.009880781 9.85295e-4 -0.223417 0.009621858 9.9601e-4 -0.223558 0.009613811 9.48169e-4 -0.223556 0.009602725 7.47561e-4 -0.223551 0.009572148 9.19933e-4 -0.223302 0.009621858 0.001266956 -0.2230769 0.009733796 0.001158475 -0.22293 0.009733796 0.001574277 -0.22222 0.0100618 0.001337766 -0.221584 0.01027536 0.001360237 -0.222042 0.0100618 0.001524448 -0.2217029 0.01027536 0.001126348 -0.2218919 0.0100618 0.00113058 -0.222356 0.009880781 0.001308441 -0.222503 0.009880781 0.001033067 -0.222797 0.009733796 8.41158e-4 -0.223196 0.009621858 5.66108e-4 -0.223532 0.009545743 5.74834e-4 -0.223546 0.009545743 5.17631e-4 -0.2234669 0.009545743 8.92655e-4 -0.222681 0.009733796 9.36228e-4 -0.222231 0.009880781 9.38414e-4 -0.221396 0.01027536 8.76098e-4 -0.221771 0.0100618 0.001141965 -0.221482 0.01027536 7.11869e-4 -0.221323 0.01027536 7.39184e-4 -0.222582 0.009733796 7.50116e-4 -0.2230989 0.009621858 5.13409e-4 -0.221275 0.01027536 6.13035e-4 -0.22168 0.0100618 5.09541e-4 -0.222055 0.009880781 5.74934e-4 -0.222503 0.009733796 7.28194e-4 -0.22213 0.009880781 3.90375e-4 -0.223173 0.009572148 3.85568e-4 -0.2233459 0.009545743 2.94911e-4 -0.221242 0.01027536 3.41032e-4 -0.221623 0.0100618 2.83458e-4 -0.222007 0.009880781 4.06197e-4 -0.222604 0.00968784 3.58312e-4 -0.224325 0.01124995 3.57608e-4 -0.22435 0.01097637 3.41205e-4 -0.22494 0.009623944 3.54146e-4 -0.224475 0.009545743 3.54611e-4 -0.224458 0.009744763 -1.90386e-4 -0.224422 0.01124995 1.61038e-4 -0.224432 0.01124995 3.55183e-4 -0.224438 0.01124995 3.40237e-5 -0.2244589 0.01118856 -8.04378e-5 -0.224454 0.01119226 -3.6514e-5 -0.225212 0.009675323 -0.001449346 -0.223514 0.01989996 -0.001499414 -0.2238579 0.01989996 -0.001499414 -0.2238579 0.01199996 -0.001468598 -0.224205 0.01989996 -0.001468598 -0.224205 0.01199996 -0.001358628 -0.224536 0.01199996 -0.001358628 -0.224536 0.01989996 -0.001175403 -0.2248319 0.01199996 -9.28862e-4 -0.225078 0.01199996 -0.001175403 -0.2248319 0.01989996 -9.28862e-4 -0.225078 0.01989996 -6.32205e-4 -0.22526 0.01989996 -6.32205e-4 -0.22526 0.01199996 -3.01466e-4 -0.225369 0.01199996 -3.01466e-4 -0.225369 0.01989996 4.5526e-5 -0.225399 0.01199996 4.5526e-5 -0.225399 0.01989996 3.90063e-4 -0.2253479 0.01989996 3.90063e-4 -0.2253479 0.01199996 7.13572e-4 -0.225219 0.01199996 7.13572e-4 -0.225219 0.01989996 9.98612e-4 -0.225019 0.01199996 9.98612e-4 -0.225019 0.01989996 0.001229763 -0.224759 0.01199996 0.001394689 -0.224452 0.01199996 0.001229763 -0.224759 0.01989996 0.001484394 -0.224116 0.01199996 0.001394689 -0.224452 0.01989996 0.001484394 -0.224116 0.01989996 0.001494109 -0.223767 0.01199996 0.001494109 -0.223767 0.01989996 0.001423239 -0.223426 0.01989996 0.001423239 -0.223426 0.01199996 0.001275658 -0.223111 0.01199996 0.001275658 -0.223111 0.01989996 0.001059293 -0.222838 0.01199996 0.001059293 -0.222838 0.01989996 7.85847e-4 -0.222622 0.01199996 7.85847e-4 -0.222622 0.01989996 4.70013e-4 -0.222476 0.01199996 4.70013e-4 -0.222476 0.01989996 1.28841e-4 -0.222406 0.01199996 -2.19277e-4 -0.222416 0.01199996 1.28841e-4 -0.222406 0.01989996 -2.19277e-4 -0.222416 0.01989996 -5.55574e-4 -0.2225069 0.01989996 -5.55574e-4 -0.2225069 0.01199996 -8.6192e-4 -0.222672 0.01989996 -8.6192e-4 -0.222672 0.01199996 -0.001121759 -0.222904 0.01199996 -0.001121759 -0.222904 0.01989996 -0.001321196 -0.22319 0.01199996 -0.001449346 -0.223514 0.01199996 -0.001321196 -0.22319 0.01989996 -0.194191 -0.1125259 0.01124995 -0.194092 -0.112473 0.01124995 -0.194114 -0.112485 0.01097637 -0.194209 -0.112536 0.009744763 -0.194376 -0.112626 0.009572148 -0.194552 -0.112722 0.009602725 -0.194594 -0.112745 0.009613811 -0.194633 -0.112765 0.009623944 -0.194444 -0.111822 0.01124995 -0.194543 -0.1118749 0.01124995 -0.195228 -0.112246 0.00968784 -0.1944659 -0.111834 0.01097637 -0.194985 -0.112115 0.009623944 -0.194561 -0.111885 0.009744763 -0.194576 -0.1118929 0.009545743 -0.195434 -0.109606 0.01050347 -0.195622 -0.10974 0.01050347 -0.195622 -0.10974 0.01189994 -0.195963 -0.110053 0.01189994 -0.196112 -0.11023 0.01050347 -0.196247 -0.110418 0.01189994 -0.196467 -0.110825 0.01189994 -0.1963649 -0.110617 0.01050347 -0.196467 -0.110825 0.01050347 -0.196551 -0.1110399 0.01050347 -0.196617 -0.111262 0.01050347 -0.196617 -0.111262 0.01189994 -0.196693 -0.1117179 0.01189994 -0.196693 -0.1117179 0.01050347 -0.196703 -0.111949 0.01050347 -0.196694 -0.1121799 0.01189994 -0.196694 -0.1121799 0.01050347 -0.196665 -0.11241 0.01050347 -0.196618 -0.112637 0.01189994 -0.1964679 -0.113074 0.01050347 -0.1964679 -0.113074 0.01189994 -0.196366 -0.113282 0.01050347 -0.1962479 -0.113481 0.01189994 -0.195964 -0.113846 0.01189994 -0.196113 -0.113669 0.01050347 -0.195964 -0.113846 0.01050347 -0.195623 -0.114159 0.01050347 -0.195623 -0.114159 0.01189994 -0.195236 -0.114412 0.01189994 -0.194813 -0.114598 0.01050347 -0.194813 -0.114598 0.01189994 -0.194365 -0.1147119 0.01189994 -0.194135 -0.11474 0.01050347 -0.193904 -0.11475 0.01050347 -0.193904 -0.11475 0.01189994 -0.193443 -0.1147119 0.01189994 -0.193443 -0.1147119 0.01050347 -0.193216 -0.114665 0.01050347 -0.192995 -0.114599 0.01050347 -0.192779 -0.114514 0.01050347 -0.192995 -0.114599 0.01189994 -0.192571 -0.114413 0.01050347 -0.192571 -0.114413 0.01189994 -0.192372 -0.114294 0.01050347 -0.192184 -0.11416 0.01189994 -0.192184 -0.11416 0.01050347 -0.192007 -0.114011 0.01050347 -0.191844 -0.113847 0.01050347 -0.191844 -0.113847 0.01189994 -0.191559 -0.1134819 0.01189994 -0.1914409 -0.113283 0.01050347 -0.191339 -0.113075 0.01189994 -0.191255 -0.11286 0.01050347 -0.191189 -0.1126379 0.01189994 -0.191189 -0.1126379 0.01050347 -0.1911129 -0.112182 0.01050347 -0.1911129 -0.112182 0.01189994 -0.1911129 -0.11172 0.01050347 -0.1911129 -0.11172 0.01189994 -0.191189 -0.111263 0.01189994 -0.191255 -0.111042 0.01050347 -0.191339 -0.110826 0.01189994 -0.19144 -0.110618 0.01050347 -0.191559 -0.110419 0.01189994 -0.191843 -0.110054 0.01189994 -0.192006 -0.10989 0.01050347 -0.192183 -0.109741 0.01050347 -0.192183 -0.109741 0.01189994 -0.19257 -0.109488 0.01189994 -0.192371 -0.109606 0.01050347 -0.19257 -0.109488 0.01050347 -0.192778 -0.109386 0.01050347 -0.192993 -0.109302 0.01050347 -0.192993 -0.109302 0.01189994 -0.193441 -0.109188 0.01189994 -0.193902 -0.10915 0.01189994 -0.1943629 -0.109188 0.01189994 -0.1943629 -0.109188 0.01050347 -0.1948119 -0.109301 0.01189994 -0.1950269 -0.109386 0.01050347 -0.195235 -0.1094869 0.01050347 -0.195235 -0.1094869 0.01189994 -0.195701 -0.109971 0.01027536 -0.1959249 -0.110203 0.01027536 -0.196066 -0.110266 0.01033556 -0.196122 -0.110459 0.01027536 -0.196198 -0.11045 0.01033556 -0.196314 -0.1106449 0.01033556 -0.196413 -0.110848 0.01033556 -0.196496 -0.111059 0.01033556 -0.1966069 -0.1114979 0.01033556 -0.196506 -0.111343 0.01027536 -0.196635 -0.111723 0.01033556 -0.196541 -0.111509 0.01027536 -0.196568 -0.111728 0.01027536 -0.196645 -0.111949 0.01033556 -0.196578 -0.111949 0.01027536 -0.196635 -0.112176 0.01033556 -0.196541 -0.112389 0.01027536 -0.196496 -0.112606 0.01027536 -0.196491 -0.112622 0.01027536 -0.19639 -0.112929 0.01027536 -0.196353 -0.1130239 0.01027536 -0.1964139 -0.1130509 0.01033556 -0.196083 -0.113495 0.01027536 -0.195882 -0.113748 0.01027536 -0.195921 -0.113806 0.01033556 -0.19565 -0.113972 0.01027536 -0.195394 -0.114169 0.01027536 -0.195366 -0.114189 0.01027536 -0.195177 -0.114302 0.01027536 -0.195116 -0.114332 0.01027536 -0.1950049 -0.11446 0.01033556 -0.19451 -0.114553 0.01027536 -0.1941249 -0.114615 0.01027536 -0.19387 -0.114623 0.01027536 -0.193677 -0.114682 0.01033556 -0.193464 -0.114588 0.01027536 -0.193231 -0.114608 0.01033556 -0.193035 -0.11448 0.01027536 -0.192803 -0.114461 0.01033556 -0.192829 -0.114399 0.01027536 -0.1925989 -0.114361 0.01033556 -0.192631 -0.114302 0.01027536 -0.192441 -0.114189 0.01027536 -0.192404 -0.1142449 0.01033556 -0.192358 -0.11413 0.01027536 -0.192261 -0.1140609 0.01027536 -0.19222 -0.114114 0.01033556 -0.1920469 -0.113967 0.01033556 -0.191936 -0.113762 0.01027536 -0.191887 -0.113807 0.01033556 -0.191793 -0.113593 0.01027536 -0.191608 -0.11345 0.01033556 -0.191492 -0.113255 0.01033556 -0.191521 -0.113162 0.01027536 -0.191392 -0.1128669 0.01027536 -0.191374 -0.112819 0.01027536 -0.191311 -0.112607 0.01027536 -0.1913 -0.112557 0.01027536 -0.191265 -0.112391 0.01027536 -0.191246 -0.112239 0.01027536 -0.191171 -0.112177 0.01033556 -0.191162 -0.111951 0.01033556 -0.191171 -0.111724 0.01033556 -0.191199 -0.111499 0.01033556 -0.191245 -0.1112779 0.01033556 -0.1913099 -0.111061 0.01033556 -0.191373 -0.111082 0.01027536 -0.191417 -0.110971 0.01027536 -0.191492 -0.110646 0.01033556 -0.191886 -0.110094 0.01033556 -0.192046 -0.109934 0.01033556 -0.19244 -0.109711 0.01027536 -0.192403 -0.109655 0.01033556 -0.1926299 -0.109598 0.01027536 -0.1928279 -0.109501 0.01027536 -0.1928009 -0.10944 0.01033556 -0.1930119 -0.1093569 0.01033556 -0.192987 -0.109439 0.01027536 -0.193462 -0.1093119 0.01027536 -0.193614 -0.109293 0.01027536 -0.1936759 -0.109218 0.01033556 -0.194123 -0.1092849 0.01027536 -0.194258 -0.109301 0.01027536 -0.194882 -0.109463 0.01027536 -0.195004 -0.109439 0.01033556 -0.1951749 -0.109598 0.01027536 -0.195402 -0.109655 0.01033556 -0.195448 -0.1097699 0.01027536 -0.195021 -0.109399 0.0104146 -0.195613 -0.1097519 0.0104146 -0.195586 -0.109786 0.01033556 -0.1957589 -0.109933 0.01033556 -0.1959199 -0.1100929 0.01033556 -0.1959519 -0.110063 0.0104146 -0.1960999 -0.110239 0.0104146 -0.196234 -0.110426 0.0104146 -0.196453 -0.110831 0.0104146 -0.19656 -0.111276 0.01033556 -0.196678 -0.111719 0.0104146 -0.1966879 -0.111949 0.0104146 -0.1966789 -0.112179 0.0104146 -0.1966069 -0.112401 0.01033556 -0.19665 -0.112408 0.0104146 -0.196561 -0.112622 0.01033556 -0.196496 -0.112839 0.01033556 -0.196537 -0.112854 0.0104146 -0.196314 -0.113254 0.01033556 -0.196353 -0.113275 0.0104146 -0.1961989 -0.113449 0.01033556 -0.196067 -0.113633 0.01033556 -0.196101 -0.11366 0.0104146 -0.195953 -0.113836 0.0104146 -0.19576 -0.113966 0.01033556 -0.1955879 -0.114113 0.01033556 -0.1957899 -0.113998 0.0104146 -0.195403 -0.1142449 0.01033556 -0.195614 -0.114147 0.0104146 -0.195427 -0.1142809 0.0104146 -0.195209 -0.114361 0.01033556 -0.1947939 -0.114543 0.01033556 -0.194577 -0.114607 0.01033556 -0.1945869 -0.11465 0.0104146 -0.194355 -0.114654 0.01033556 -0.19413 -0.114682 0.01033556 -0.193904 -0.114691 0.01033556 -0.193904 -0.114735 0.0104146 -0.193674 -0.114726 0.0104146 -0.193453 -0.114654 0.01033556 -0.193014 -0.114543 0.01033556 -0.193 -0.114584 0.0104146 -0.192785 -0.1145009 0.0104146 -0.19174 -0.113634 0.01033556 -0.191706 -0.113661 0.0104146 -0.1914539 -0.113276 0.0104146 -0.191393 -0.113052 0.01033556 -0.1913099 -0.112841 0.01033556 -0.191269 -0.112855 0.0104146 -0.191246 -0.112624 0.01033556 -0.191199 -0.112402 0.01033556 -0.191156 -0.111492 0.0104146 -0.191269 -0.111046 0.0104146 -0.191352 -0.110832 0.0104146 -0.191392 -0.110849 0.01033556 -0.191608 -0.110451 0.01033556 -0.1915709 -0.110427 0.0104146 -0.191739 -0.110267 0.01033556 -0.191705 -0.11024 0.0104146 -0.192192 -0.109753 0.0104146 -0.192219 -0.109787 0.01033556 -0.192598 -0.109539 0.01033556 -0.193229 -0.109293 0.01033556 -0.192998 -0.109316 0.0104146 -0.193219 -0.10925 0.0104146 -0.193451 -0.109246 0.01033556 -0.193444 -0.109203 0.0104146 -0.193902 -0.109209 0.01033556 -0.194129 -0.109218 0.01033556 -0.194132 -0.109175 0.0104146 -0.1943539 -0.109246 0.01033556 -0.194575 -0.109292 0.01033556 -0.194793 -0.1093569 0.01033556 -0.1952069 -0.109539 0.01033556 -0.195228 -0.1095 0.0104146 -0.195426 -0.109618 0.0104146 -0.195789 -0.109901 0.0104146 -0.1957989 -0.109889 0.01050347 -0.195963 -0.110053 0.01050347 -0.196247 -0.110418 0.01050347 -0.196352 -0.110624 0.0104146 -0.196537 -0.111045 0.0104146 -0.196603 -0.111266 0.0104146 -0.19665 -0.111491 0.0104146 -0.196665 -0.111488 0.01050347 -0.196603 -0.112633 0.0104146 -0.196618 -0.112637 0.01050347 -0.196552 -0.1128579 0.01050347 -0.196454 -0.113068 0.0104146 -0.1962479 -0.113481 0.01050347 -0.196235 -0.1134729 0.0104146 -0.1958 -0.11401 0.01050347 -0.195435 -0.114294 0.01050347 -0.1952289 -0.114399 0.0104146 -0.195236 -0.114412 0.01050347 -0.195022 -0.1145 0.0104146 -0.195029 -0.114514 0.01050347 -0.194808 -0.114584 0.0104146 -0.194591 -0.114664 0.01050347 -0.194362 -0.114697 0.0104146 -0.194365 -0.1147119 0.01050347 -0.1941339 -0.114725 0.0104146 -0.193673 -0.11474 0.01050347 -0.193445 -0.114697 0.0104146 -0.19322 -0.11465 0.0104146 -0.192578 -0.1144 0.0104146 -0.19238 -0.114282 0.0104146 -0.192193 -0.114148 0.0104146 -0.192017 -0.113999 0.0104146 -0.191855 -0.113837 0.0104146 -0.191694 -0.11367 0.01050347 -0.191572 -0.113474 0.0104146 -0.191559 -0.1134819 0.01050347 -0.191353 -0.1130689 0.0104146 -0.191339 -0.113075 0.01050347 -0.191204 -0.112634 0.0104146 -0.191156 -0.112409 0.0104146 -0.191141 -0.112412 0.01050347 -0.191128 -0.112181 0.0104146 -0.191118 -0.111951 0.0104146 -0.191103 -0.111951 0.01050347 -0.191128 -0.111721 0.0104146 -0.191141 -0.11149 0.01050347 -0.1912029 -0.111267 0.0104146 -0.191189 -0.111263 0.01050347 -0.191339 -0.110826 0.01050347 -0.191453 -0.110625 0.0104146 -0.191559 -0.110419 0.01050347 -0.191693 -0.110231 0.01050347 -0.191843 -0.110054 0.01050347 -0.191854 -0.110064 0.0104146 -0.192016 -0.109902 0.0104146 -0.1923789 -0.109619 0.0104146 -0.192577 -0.109501 0.0104146 -0.192784 -0.1094 0.0104146 -0.193215 -0.109236 0.01050347 -0.193441 -0.109188 0.01050347 -0.193672 -0.109175 0.0104146 -0.193671 -0.10916 0.01050347 -0.193902 -0.109165 0.0104146 -0.193902 -0.10915 0.01050347 -0.1941339 -0.109159 0.01050347 -0.194361 -0.109203 0.0104146 -0.194586 -0.10925 0.0104146 -0.1948069 -0.109316 0.0104146 -0.19459 -0.109235 0.01050347 -0.1948119 -0.109301 0.01050347 -0.1914539 -0.110876 0.01027536 -0.1913149 -0.1112779 0.01027536 -0.1912299 -0.111917 0.01027536 -0.1916649 -0.113413 0.01027536 -0.191684 -0.113441 0.01027536 -0.19482 -0.114461 0.01027536 -0.195187 -0.113861 0.0100618 -0.196142 -0.113412 0.01027536 -0.196433 -0.112818 0.01027536 -0.196568 -0.11217 0.01027536 -0.1964139 -0.111033 0.01027536 -0.196142 -0.110487 0.01027536 -0.195814 -0.110666 0.0100618 -0.195365 -0.109711 0.01027536 -0.194998 -0.109925 0.0100618 -0.194977 -0.109501 0.01027536 -0.193113 -0.109787 0.0100618 -0.192412 -0.109731 0.01027536 -0.191924 -0.110152 0.01027536 -0.191792 -0.110308 0.01027536 -0.191723 -0.110405 0.01027536 -0.191551 -0.110678 0.01027536 -0.194876 -0.112897 0.00968784 -0.195 -0.111964 0.009621858 -0.194946 -0.112094 0.009613811 -0.194904 -0.112071 0.009602725 -0.1949909 -0.112096 0.009621858 -0.194728 -0.111975 0.009572148 -0.1945739 -0.111877 0.009545743 -0.194698 -0.111259 0.009613811 -0.194809 -0.110954 0.009686291 -0.193917 -0.110853 0.009621858 -0.194047 -0.110907 0.009613811 -0.194049 -0.110863 0.009621858 -0.194024 -0.110949 0.009602725 -0.19375 -0.111292 0.009545743 -0.19383 -0.111279 0.009545743 -0.193846 -0.111277 0.009545743 -0.19286 -0.111806 0.009613811 -0.192821 -0.111785 0.009623944 -0.192816 -0.111804 0.009621858 -0.192806 -0.111936 0.009621858 -0.192902 -0.111829 0.009602725 -0.193078 -0.111925 0.009572148 -0.1932319 -0.112023 0.009545743 -0.19323 -0.112007 0.009545743 -0.193109 -0.112641 0.009613811 -0.193131 -0.112599 0.009602725 -0.192992 -0.112562 0.009621858 -0.1927599 -0.112938 0.009733796 -0.1937389 -0.113032 0.009623944 -0.1937569 -0.113037 0.009621858 -0.193702 -0.113448 0.009733796 -0.193759 -0.112993 0.009613811 -0.193782 -0.112951 0.009602725 -0.1938779 -0.112775 0.009572148 -0.193976 -0.112621 0.009545743 -0.1940219 -0.113041 0.009621858 -0.1920239 -0.110618 0.0100618 -0.191664 -0.1104879 0.01027536 -0.191878 -0.110855 0.0100618 -0.192497 -0.111397 0.009733796 -0.19222 -0.1110399 0.009880781 -0.192574 -0.111231 0.009733796 -0.19226 -0.10984 0.01027536 -0.192398 -0.110208 0.0100618 -0.192156 -0.109928 0.01027536 -0.192091 -0.109983 0.01027536 -0.191935 -0.110139 0.01027536 -0.192199 -0.110402 0.0100618 -0.192342 -0.110843 0.009880781 -0.192652 -0.110502 0.009880781 -0.192486 -0.1106629 0.009880781 -0.192691 -0.1095679 0.01027536 -0.192619 -0.110039 0.0100618 -0.192836 -0.110361 0.009880781 -0.192785 -0.110934 0.009733796 -0.192907 -0.111044 0.009686291 -0.19267 -0.1110759 0.009733796 -0.192827 -0.111186 0.009680747 -0.192749 -0.111326 0.009675323 -0.192441 -0.11157 0.009733796 -0.192578 -0.111654 0.00968784 -0.192858 -0.109898 0.0100618 -0.193035 -0.110244 0.009880781 -0.19306 -0.110696 0.009733796 -0.192915 -0.110807 0.009733796 -0.19293 -0.111003 0.00968784 -0.1933799 -0.109708 0.0100618 -0.193296 -0.109347 0.01027536 -0.193246 -0.109358 0.01027536 -0.1930339 -0.109421 0.01027536 -0.193186 -0.11112 0.009621858 -0.193212 -0.111155 0.009613811 -0.193173 -0.111135 0.009623944 -0.1932539 -0.111178 0.009602725 -0.193291 -0.111039 0.009621858 -0.19343 -0.111274 0.009572148 -0.1932179 -0.110603 0.009733796 -0.193247 -0.110152 0.009880781 -0.193682 -0.1092849 0.01027536 -0.193654 -0.109661 0.0100618 -0.193936 -0.109277 0.01027536 -0.193902 -0.1092759 0.01027536 -0.193468 -0.110086 0.009880781 -0.193696 -0.110047 0.009880781 -0.193385 -0.110531 0.009733796 -0.193527 -0.1109189 0.009621858 -0.193597 -0.111348 0.009545743 -0.193405 -0.110972 0.009621858 -0.1935819 -0.111356 0.009545743 -0.193672 -0.111316 0.009545743 -0.19356 -0.110478 0.009733796 -0.193654 -0.110882 0.009621858 -0.1939319 -0.109648 0.0100618 -0.194209 -0.109668 0.0100618 -0.194343 -0.1093119 0.01027536 -0.194575 -0.109362 0.01027536 -0.194559 -0.1093569 0.01027536 -0.194482 -0.109721 0.0100618 -0.193927 -0.110036 0.009880781 -0.19374 -0.110448 0.009733796 -0.193922 -0.110439 0.009733796 -0.194771 -0.10942 0.01027536 -0.194746 -0.109807 0.0100618 -0.194384 -0.110098 0.009880781 -0.194157 -0.110053 0.009880781 -0.1937839 -0.110859 0.009621858 -0.193928 -0.111125 0.009572148 -0.194604 -0.110169 0.009880781 -0.194283 -0.110487 0.009733796 -0.194104 -0.1104519 0.009733796 -0.194068 -0.110868 0.009623944 -0.195235 -0.110071 0.0100618 -0.194814 -0.110267 0.009880781 -0.194456 -0.110544 0.009733796 -0.195545 -0.109839 0.01027536 -0.19587 -0.1101379 0.01027536 -0.1957139 -0.109982 0.01027536 -0.195451 -0.110246 0.0100618 -0.195646 -0.110445 0.0100618 -0.194777 -0.1107169 0.009733796 -0.19501 -0.110389 0.009880781 -0.194622 -0.110621 0.009733796 -0.196013 -0.110307 0.01027536 -0.19519 -0.1105329 0.009880781 -0.196352 -0.110875 0.01027536 -0.196285 -0.110738 0.01027536 -0.196255 -0.110676 0.01027536 -0.195955 -0.110905 0.0100618 -0.195351 -0.1106989 0.009880781 -0.195047 -0.110962 0.009733796 -0.194919 -0.110832 0.009733796 -0.194667 -0.1108739 0.009680747 -0.194527 -0.110795 0.009675323 -0.1943849 -0.110722 0.009680747 -0.19424 -0.110646 0.009686291 -0.194199 -0.110625 0.00968784 -0.195492 -0.110882 0.009880781 -0.195157 -0.111107 0.009733796 -0.19485 -0.110977 0.00968784 -0.196496 -0.111293 0.01027536 -0.1964319 -0.111081 0.01027536 -0.1961449 -0.111427 0.0100618 -0.196066 -0.11116 0.0100618 -0.195609 -0.111082 0.009880781 -0.194814 -0.111338 0.009621858 -0.194733 -0.111233 0.009621858 -0.194719 -0.11122 0.009623944 -0.194675 -0.111301 0.009602725 -0.194881 -0.111452 0.009621858 -0.19525 -0.111264 0.009733796 -0.195323 -0.111432 0.009733796 -0.195701 -0.111294 0.009880781 -0.195767 -0.111515 0.009880781 -0.196192 -0.111701 0.0100618 -0.19656 -0.111661 0.01027536 -0.1965759 -0.111983 0.01027536 -0.196206 -0.111979 0.0100618 -0.195375 -0.111607 0.009733796 -0.194505 -0.111644 0.009545743 -0.194579 -0.111477 0.009572148 -0.194497 -0.111629 0.009545743 -0.194537 -0.1117179 0.009545743 -0.194934 -0.111574 0.009621858 -0.194972 -0.111701 0.009621858 -0.195806 -0.111743 0.009880781 -0.1958169 -0.111974 0.009880781 -0.1961849 -0.112256 0.0100618 -0.196552 -0.112305 0.01027536 -0.196132 -0.112529 0.0100618 -0.1958 -0.112204 0.009880781 -0.195405 -0.111787 0.009733796 -0.194561 -0.111797 0.009545743 -0.1960459 -0.112793 0.0100618 -0.195414 -0.111969 0.009733796 -0.194994 -0.111831 0.009621858 -0.196256 -0.113222 0.01027536 -0.195756 -0.112431 0.009880781 -0.195401 -0.112151 0.009733796 -0.195928 -0.113045 0.0100618 -0.195587 -0.11286 0.009880781 -0.195684 -0.112651 0.009880781 -0.195366 -0.11233 0.009733796 -0.196014 -0.113592 0.01027536 -0.195782 -0.113282 0.0100618 -0.195546 -0.11406 0.01027536 -0.195715 -0.113917 0.01027536 -0.1958709 -0.113761 0.01027536 -0.195607 -0.113498 0.0100618 -0.195465 -0.113057 0.009880781 -0.19532 -0.113237 0.009880781 -0.195408 -0.113692 0.0100618 -0.194971 -0.113539 0.009880781 -0.195154 -0.113398 0.009880781 -0.195022 -0.112966 0.009733796 -0.194899 -0.112856 0.009686291 -0.195136 -0.112824 0.009733796 -0.194979 -0.112714 0.009680747 -0.195232 -0.112669 0.009733796 -0.195309 -0.112503 0.009733796 -0.195058 -0.112574 0.009675323 -0.195132 -0.112432 0.009680747 -0.1952069 -0.112287 0.009686291 -0.1949779 -0.114399 0.01027536 -0.194948 -0.114002 0.0100618 -0.194891 -0.113093 0.009733796 -0.194426 -0.114192 0.0100618 -0.1945599 -0.114542 0.01027536 -0.194772 -0.114479 0.01027536 -0.194693 -0.114113 0.0100618 -0.194771 -0.113656 0.009880781 -0.194589 -0.113297 0.009733796 -0.194746 -0.113204 0.009733796 -0.194515 -0.112861 0.009621858 -0.19462 -0.11278 0.009621858 -0.194559 -0.113748 0.009880781 -0.194338 -0.1138139 0.009880781 -0.194344 -0.114588 0.01027536 -0.193904 -0.114624 0.01027536 -0.1941919 -0.114607 0.01027536 -0.1941519 -0.114239 0.0100618 -0.19411 -0.113853 0.009880781 -0.1942459 -0.113422 0.009733796 -0.1944209 -0.113369 0.009733796 -0.194401 -0.112928 0.009621858 -0.194209 -0.112552 0.009545743 -0.1942239 -0.112544 0.009545743 -0.194279 -0.112981 0.009621858 -0.1941519 -0.113018 0.009621858 -0.194067 -0.113452 0.009733796 -0.193874 -0.114252 0.0100618 -0.193683 -0.114615 0.01027536 -0.193597 -0.114232 0.0100618 -0.193548 -0.114599 0.01027536 -0.193231 -0.114538 0.01027536 -0.193247 -0.114543 0.01027536 -0.193879 -0.113864 0.009880781 -0.194056 -0.112608 0.009545743 -0.194135 -0.112584 0.009545743 -0.192924 -0.114437 0.01027536 -0.193324 -0.114179 0.0100618 -0.1936489 -0.113847 0.009880781 -0.193884 -0.113461 0.009733796 -0.193889 -0.113047 0.009621858 -0.19396 -0.112623 0.009545743 -0.19306 -0.114093 0.0100618 -0.193422 -0.113802 0.009880781 -0.193523 -0.113413 0.009733796 -0.193607 -0.113275 0.00968784 -0.192808 -0.113975 0.0100618 -0.192993 -0.113633 0.009880781 -0.193202 -0.113731 0.009880781 -0.1921049 -0.113929 0.01027536 -0.1925719 -0.113829 0.0100618 -0.191881 -0.113697 0.01027536 -0.192092 -0.113918 0.01027536 -0.192616 -0.113367 0.009880781 -0.192355 -0.113654 0.0100618 -0.192796 -0.113511 0.009880781 -0.191992 -0.113234 0.0100618 -0.192161 -0.1134549 0.0100618 -0.1924549 -0.113201 0.009880781 -0.192887 -0.113068 0.009733796 -0.191551 -0.113224 0.01027536 -0.191851 -0.112995 0.0100618 -0.192315 -0.113018 0.009880781 -0.192997 -0.112946 0.009686291 -0.193139 -0.113026 0.009680747 -0.193029 -0.113183 0.009733796 -0.193279 -0.1131049 0.009675323 -0.193184 -0.113279 0.009733796 -0.19335 -0.113356 0.009733796 -0.193421 -0.113178 0.009680747 -0.193566 -0.113254 0.009686291 -0.1914539 -0.113025 0.01027536 -0.192649 -0.112793 0.009733796 -0.193073 -0.112667 0.009621858 -0.192956 -0.112923 0.00968784 -0.1930879 -0.11268 0.009623944 -0.19174 -0.11274 0.0100618 -0.191661 -0.112473 0.0100618 -0.1921049 -0.112606 0.009880781 -0.192556 -0.112636 0.009733796 -0.192197 -0.112818 0.009880781 -0.192925 -0.112448 0.009621858 -0.192484 -0.112468 0.009733796 -0.192039 -0.112385 0.009880781 -0.191229 -0.111951 0.01027536 -0.191238 -0.112172 0.01027536 -0.191614 -0.112199 0.0100618 -0.192432 -0.112293 0.009733796 -0.192872 -0.112326 0.009621858 -0.1932269 -0.112423 0.009572148 -0.193309 -0.112271 0.009545743 -0.193301 -0.112256 0.009545743 -0.191989 -0.111926 0.009880781 -0.192 -0.112157 0.009880781 -0.191601 -0.111921 0.0100618 -0.191265 -0.111511 0.01027536 -0.191621 -0.111644 0.0100618 -0.191255 -0.111595 0.01027536 -0.191238 -0.11173 0.01027536 -0.1913099 -0.111294 0.01027536 -0.1916739 -0.111371 0.0100618 -0.192006 -0.111696 0.009880781 -0.192401 -0.1121129 0.009733796 -0.192812 -0.112069 0.009621858 -0.193246 -0.112103 0.009545743 -0.192835 -0.112199 0.009621858 -0.193269 -0.112182 0.009545743 -0.19176 -0.111107 0.0100618 -0.1920509 -0.111469 0.009880781 -0.192392 -0.111931 0.009733796 -0.192122 -0.111249 0.009880781 -0.192405 -0.111749 0.009733796 -0.1932629 -0.112025 0.01124995 -0.193356 -0.111854 0.01124995 -0.193523 -0.111544 0.01124995 -0.193615 -0.111374 0.01124995 -0.193436 -0.111641 0.01118856 -0.193383 -0.111743 0.01119226 -0.1926749 -0.111468 0.009680747 -0.1925989 -0.111613 0.009686291 3.11723e-4 0.207336 0.01124995 3.96918e-4 0.207511 0.01124995 4.71371e-4 0.207598 0.01119226 0.00103271 0.207036 0.009686291 5.51132e-4 0.207827 0.01124995 5.2328e-4 0.2077 0.01118856 6.36327e-4 0.208001 0.01124995 0.001336216 0.207659 0.00968784 0.001316487 0.207617 0.009686291 -0.002609014 0.208916 0.01050347 -0.002684056 0.208697 0.01189994 -0.00251621 0.209128 0.01189994 -0.002684056 0.208697 0.01050347 -0.002778708 0.208245 0.01189994 -0.002778708 0.208245 0.01050347 -0.002797663 0.208014 0.01050347 -0.002797484 0.207783 0.01189994 -0.002740025 0.207324 0.01189994 -0.002607822 0.206881 0.01189994 -0.002404451 0.206465 0.01189994 -0.002277731 0.206272 0.01050347 -0.002135515 0.206089 0.01050347 -0.002135515 0.206089 0.01189994 -0.001808345 0.205762 0.01189994 -0.001431822 0.205494 0.01189994 -0.001016199 0.205291 0.01189994 -7.97322e-4 0.205216 0.01050347 -5.72949e-4 0.205159 0.01189994 -1.14022e-4 0.205102 0.01050347 -1.14022e-4 0.205102 0.01189994 3.48016e-4 0.2051219 0.01189994 8.0056e-4 0.205217 0.01189994 0.001019358 0.205292 0.01050347 0.001231253 0.205385 0.01189994 0.001434683 0.205496 0.01050347 0.001628339 0.205622 0.01189994 0.001981079 0.2059209 0.01189994 0.001981079 0.2059209 0.01050347 0.00213772 0.206092 0.01050347 0.002279758 0.206274 0.01050347 0.002406179 0.206468 0.01050347 0.002279758 0.206274 0.01189994 0.00251621 0.206672 0.01189994 0.002609014 0.206884 0.01050347 0.002684056 0.207103 0.01050347 0.002684056 0.207103 0.01189994 0.002797663 0.207786 0.01050347 0.002778708 0.2075549 0.01189994 0.002797484 0.208017 0.01189994 0.002778232 0.208248 0.01050347 0.002740025 0.208476 0.01189994 0.002607822 0.208919 0.01189994 0.002607822 0.208919 0.01050347 0.002404451 0.209335 0.01189994 0.002404451 0.209335 0.01050347 0.002135515 0.209711 0.01050347 0.002135515 0.209711 0.01189994 0.001808345 0.210038 0.01189994 0.001625597 0.21018 0.01050347 0.001431822 0.210306 0.01189994 0.001431822 0.210306 0.01050347 0.001228213 0.210416 0.01050347 0.001016199 0.210509 0.01189994 0.001016199 0.210509 0.01050347 7.97322e-4 0.210584 0.01050347 5.72949e-4 0.210641 0.01189994 1.14022e-4 0.210698 0.01189994 1.14022e-4 0.210698 0.01050347 -3.48016e-4 0.210678 0.01189994 -8.0056e-4 0.210583 0.01189994 -5.76256e-4 0.21064 0.01050347 -8.0056e-4 0.210583 0.01050347 -0.001019358 0.210508 0.01050347 -0.001231253 0.210415 0.01189994 -0.001434683 0.210304 0.01050347 -0.001628339 0.210178 0.01189994 -0.001810908 0.210036 0.01050347 -0.001981079 0.209879 0.01189994 -0.00213772 0.209708 0.01050347 -0.002279758 0.209526 0.01189994 -0.002406179 0.209332 0.01050347 -0.002654075 0.208229 0.01027536 -0.002672076 0.207822 0.01027536 -0.002653658 0.207568 0.01027536 -0.002682745 0.207336 0.01033556 -0.002562761 0.207135 0.01027536 -0.002490878 0.206926 0.01027536 -0.002553284 0.206902 0.01033556 -0.002462148 0.206694 0.01033556 -0.002470314 0.20688 0.01027536 -0.002328991 0.206589 0.01027536 -0.002296626 0.20653 0.01027536 -0.002175629 0.206345 0.01027536 -0.002354204 0.206495 0.01033556 -0.002154707 0.206318 0.01027536 -0.002090871 0.206127 0.01033556 -0.001937329 0.20596 0.01033556 -0.001889944 0.206008 0.01027536 -0.001727223 0.2058579 0.01027536 -0.001713812 0.205848 0.01027536 -0.0015527 0.205722 0.01027536 -0.001453042 0.205657 0.01027536 -0.001401841 0.2055439 0.01033556 -9.95006e-4 0.205345 0.01033556 -8.7416e-4 0.205375 0.01027536 -1.11639e-4 0.205161 0.01033556 3.32407e-4 0.205246 0.01027536 3.99475e-4 0.205258 0.01027536 3.40741e-4 0.2051799 0.01033556 7.83827e-4 0.205273 0.01033556 9.73676e-4 0.205409 0.01027536 0.001020312 0.20543 0.01027536 0.001205503 0.205438 0.01033556 0.001310586 0.2055709 0.01027536 0.001555323 0.205724 0.01027536 0.001773059 0.2058089 0.01033556 0.001582145 0.205745 0.01027536 0.001939654 0.205963 0.01033556 0.001892209 0.20601 0.01027536 0.002093017 0.206129 0.01033556 0.002041816 0.206173 0.01027536 0.002298295 0.206532 0.01027536 0.002355873 0.206498 0.01033556 0.002403378 0.206727 0.01027536 0.002463638 0.206697 0.01033556 0.002563655 0.207138 0.01027536 0.002683401 0.207339 0.01033556 0.002654075 0.207571 0.01027536 0.002661049 0.207656 0.01027536 0.002720594 0.207563 0.01033556 0.002739191 0.207788 0.01033556 0.002672195 0.207791 0.01027536 0.002672076 0.207978 0.01027536 0.002720177 0.208241 0.01033556 0.002682745 0.208464 0.01033556 0.002627015 0.208684 0.01033556 0.002575278 0.208615 0.01027536 0.002490878 0.208874 0.01027536 0.002470314 0.20892 0.01027536 0.002354204 0.209305 0.01033556 0.002328991 0.209211 0.01027536 0.002296626 0.20927 0.01027536 0.002175629 0.209455 0.01027536 0.002154707 0.209482 0.01027536 0.001947522 0.20973 0.01027536 0.001889944 0.209792 0.01027536 0.001591622 0.210132 0.01033556 0.001401841 0.210256 0.01033556 0.001202523 0.210364 0.01033556 9.95006e-4 0.210455 0.01033556 7.61562e-4 0.210464 0.01027536 7.80656e-4 0.210528 0.01033556 5.47252e-4 0.210518 0.01027536 5.60973e-4 0.210583 0.01033556 1.11639e-4 0.2106389 0.01033556 2.44482e-4 0.210561 0.01027536 1.08908e-4 0.210572 0.01027536 -7.81376e-5 0.210572 0.01027536 -1.12132e-4 0.210572 0.01027536 -1.14944e-4 0.2106389 0.01033556 -3.32407e-4 0.210554 0.01027536 -3.99475e-4 0.210542 0.01027536 -5.64211e-4 0.210583 0.01033556 -7.15226e-4 0.210475 0.01027536 -7.64655e-4 0.210463 0.01027536 -9.73676e-4 0.210391 0.01027536 -0.001205503 0.210362 0.01033556 -0.001175999 0.2103019 0.01027536 -0.001310586 0.210229 0.01027536 -0.001404702 0.210254 0.01033556 -0.001582145 0.2100549 0.01027536 -0.002093017 0.209671 0.01033556 -0.002041816 0.209627 0.01027536 -0.002052247 0.209614 0.01027536 -0.002242505 0.209353 0.01027536 -0.002298295 0.209268 0.01027536 -0.002463638 0.209103 0.01033556 -0.002554476 0.208895 0.01033556 -0.00249201 0.208871 0.01027536 -0.002525091 0.208774 0.01027536 -0.002563655 0.208662 0.01027536 -0.002393245 0.209324 0.0104146 -0.002502679 0.209122 0.0104146 -0.002595007 0.208911 0.0104146 -0.002627968 0.208681 0.01033556 -0.002683401 0.208461 0.01033556 -0.002763748 0.208243 0.0104146 -0.002720594 0.2082369 0.01033556 -0.002739191 0.208012 0.01033556 -0.002739012 0.207785 0.01033556 -0.002720177 0.207559 0.01033556 -0.002668678 0.207104 0.0104146 -0.002627015 0.207116 0.01033556 -0.002230167 0.206306 0.01033556 -0.002265512 0.2062799 0.0104146 -0.001770496 0.205807 0.01033556 -0.001591622 0.205668 0.01033556 -0.001202523 0.205436 0.01033556 -0.001010775 0.205305 0.0104146 -7.80656e-4 0.205272 0.01033556 -5.60973e-4 0.205217 0.01033556 -3.37458e-4 0.205179 0.01033556 -3.4281e-4 0.205136 0.0104146 1.14944e-4 0.205161 0.01033556 1.16767e-4 0.205117 0.0104146 5.64211e-4 0.205217 0.01033556 9.98088e-4 0.205347 0.01033556 0.001224637 0.205399 0.0104146 0.001426994 0.2055079 0.0104146 0.001404702 0.205546 0.01033556 0.001594305 0.2056699 0.01033556 0.001801133 0.205776 0.0104146 0.00197041 0.205932 0.0104146 0.002232074 0.206308 0.01033556 0.002393245 0.206476 0.0104146 0.002502679 0.206678 0.0104146 0.002554476 0.206905 0.01033556 0.002627968 0.207119 0.01033556 0.002669632 0.207107 0.0104146 0.002763748 0.207557 0.0104146 0.002739012 0.208015 0.01033556 0.002782583 0.207787 0.0104146 0.00276333 0.2082459 0.0104146 0.002725303 0.208473 0.0104146 0.002668678 0.208696 0.0104146 0.002553284 0.208898 0.01033556 0.002593815 0.208914 0.0104146 0.002501189 0.209125 0.0104146 0.002462148 0.209106 0.01033556 0.002230167 0.2094939 0.01033556 0.002090871 0.209673 0.01033556 0.002124011 0.209701 0.0104146 0.001937329 0.2098399 0.01033556 0.001770496 0.209993 0.01033556 0.001616895 0.210167 0.0104146 0.001221597 0.210403 0.0104146 0.001010775 0.2104949 0.0104146 7.93036e-4 0.21057 0.0104146 5.6987e-4 0.210626 0.0104146 3.37459e-4 0.2106209 0.01033556 3.4281e-4 0.210664 0.0104146 -3.40741e-4 0.21062 0.01033556 -1.16767e-4 0.210682 0.0104146 -3.46145e-4 0.210663 0.0104146 -7.83827e-4 0.210527 0.01033556 -5.73159e-4 0.2106249 0.0104146 -9.98088e-4 0.210453 0.01033556 -0.001426994 0.210292 0.0104146 -0.001594305 0.21013 0.01033556 -0.001773059 0.209991 0.01033556 -0.001939654 0.209837 0.01033556 -0.002232074 0.209492 0.01033556 -0.002355873 0.209302 0.01033556 -0.00251621 0.209128 0.01050347 -0.002669632 0.208693 0.0104146 -0.002726018 0.20847 0.0104146 -0.00274074 0.208473 0.01050347 -0.002782583 0.2080129 0.0104146 -0.002782464 0.207783 0.0104146 -0.002797484 0.207783 0.01050347 -0.00276333 0.207554 0.0104146 -0.002778232 0.207552 0.01050347 -0.002725303 0.207327 0.0104146 -0.002740025 0.207324 0.01050347 -0.002683103 0.207099 0.01050347 -0.002593815 0.2068859 0.0104146 -0.002607822 0.206881 0.01050347 -0.002501189 0.2066749 0.0104146 -0.002391517 0.2064729 0.0104146 -0.002514719 0.206669 0.01050347 -0.002404451 0.206465 0.01050347 -0.002124011 0.206099 0.0104146 -0.001968026 0.2059299 0.0104146 -0.001978695 0.205919 0.01050347 -0.001798629 0.205774 0.0104146 -0.001808345 0.205762 0.01050347 -0.001616895 0.205632 0.0104146 -0.001424074 0.205507 0.0104146 -0.001625597 0.2056199 0.01050347 -0.001431822 0.205494 0.01050347 -0.001228213 0.205384 0.01050347 -0.001221597 0.205397 0.0104146 -0.001016199 0.205291 0.01050347 -7.93036e-4 0.2052299 0.0104146 -5.72949e-4 0.205159 0.01050347 -5.6987e-4 0.205174 0.0104146 -3.44663e-4 0.205121 0.01050347 -1.13409e-4 0.205117 0.0104146 1.17398e-4 0.205102 0.01050347 3.46145e-4 0.205137 0.0104146 5.73159e-4 0.205175 0.0104146 3.48016e-4 0.2051219 0.01050347 5.76256e-4 0.20516 0.01050347 8.0056e-4 0.205217 0.01050347 7.96257e-4 0.205231 0.0104146 0.001013875 0.2053059 0.0104146 0.001231253 0.205385 0.01050347 0.001619637 0.2056339 0.0104146 0.001628339 0.205622 0.01050347 0.001810908 0.2057639 0.01050347 0.002126216 0.206101 0.0104146 0.002267479 0.206283 0.0104146 0.00251621 0.206672 0.01050347 0.002595007 0.206889 0.0104146 0.00274074 0.207327 0.01050347 0.002726018 0.2073299 0.0104146 0.002778708 0.2075549 0.01050347 0.002782464 0.208017 0.0104146 0.002797484 0.208017 0.01050347 0.002740025 0.208476 0.01050347 0.002683103 0.208701 0.01050347 0.002391517 0.209327 0.0104146 0.002514719 0.209131 0.01050347 0.002265512 0.20952 0.0104146 0.002277731 0.209528 0.01050347 0.001968026 0.20987 0.0104146 0.001978695 0.209881 0.01050347 0.001808345 0.210038 0.01050347 0.001798629 0.210026 0.0104146 0.001424074 0.2102929 0.0104146 5.72949e-4 0.210641 0.01050347 3.44663e-4 0.2106789 0.01050347 1.13409e-4 0.210683 0.0104146 -1.17398e-4 0.210698 0.01050347 -3.48016e-4 0.210678 0.01050347 -7.96257e-4 0.210569 0.0104146 -0.001013875 0.210494 0.0104146 -0.001224637 0.2104009 0.0104146 -0.001231253 0.210415 0.01050347 -0.001619637 0.210166 0.0104146 -0.001628339 0.210178 0.01050347 -0.001801133 0.2100239 0.0104146 -0.001981079 0.209879 0.01050347 -0.00197041 0.209868 0.0104146 -0.002126216 0.209699 0.0104146 -0.002267479 0.209517 0.0104146 -0.002279758 0.209526 0.01050347 0.001367568 0.210198 0.01027536 0.002617776 0.2073529 0.01027536 0.00249201 0.206929 0.01027536 0.002242505 0.206447 0.01027536 0.002052247 0.2061859 0.01027536 8.79076e-4 0.205772 0.0100618 1.12133e-4 0.205228 0.01027536 7.81376e-5 0.205228 0.01027536 -5.47252e-4 0.205282 0.01027536 -5.6373e-4 0.205286 0.01027536 -7.61562e-4 0.205336 0.01027536 -7.53268e-4 0.205724 0.0100618 -9.70669e-4 0.205408 0.01027536 -0.001173138 0.205497 0.01027536 -0.001367568 0.205602 0.01027536 -0.001855969 0.206537 0.0100618 -0.002672016 0.207788 0.01027536 -0.002613663 0.208464 0.01027536 -0.002175927 0.208653 0.0100618 -0.002403378 0.209073 0.01027536 -0.0013628 0.209756 0.0100618 8.7416e-4 0.210425 0.01027536 7.53268e-4 0.210076 0.0100618 9.70669e-4 0.2103919 0.01027536 0.001173138 0.210303 0.01027536 1.19294e-4 0.208988 0.009623944 -1.19294e-4 0.206812 0.009623944 -1.0037e-4 0.206807 0.009621858 -7.90601e-5 0.2068949 0.009602725 -7.65059e-4 0.207176 0.009613811 -7.99628e-4 0.207149 0.009621858 -7.84299e-4 0.207137 0.009623944 -7.44065e-4 0.207219 0.009602725 -5.8841e-4 0.207569 0.009545743 -5.80237e-4 0.2075549 0.009545743 -0.001005411 0.207979 0.009602725 -7.23861e-4 0.208665 0.009613811 -7.51235e-4 0.2087 0.009621858 -6.80852e-4 0.208644 0.009602725 -3.311e-4 0.208488 0.009545743 -3.45223e-4 0.20848 0.009545743 1.00054e-4 0.208948 0.009613811 7.90601e-5 0.208905 0.009602725 2.82671e-4 0.209217 0.009686291 2.40526e-4 0.209236 0.00968784 7.84299e-4 0.208663 0.009623944 7.99628e-4 0.208651 0.009621858 0.001101255 0.208935 0.009733796 8.8435e-4 0.208549 0.009621858 7.65059e-4 0.208624 0.009613811 7.44065e-4 0.208581 0.009602725 6.56034e-4 0.208401 0.009572148 6.2403e-4 0.208158 0.009545743 5.8841e-4 0.208231 0.009545743 9.56175e-4 0.208438 0.009621858 0.001048445 0.2078 0.009613811 0.001034617 0.206799 0.009733796 7.23861e-4 0.207135 0.009613811 6.80852e-4 0.207156 0.009602725 7.51235e-4 0.2071 0.009621858 5.00504e-4 0.207244 0.009572148 3.311e-4 0.207312 0.009545743 5.38042e-4 0.206944 0.009621858 3.45223e-4 0.20732 0.009545743 0.00101 0.209969 0.0100618 0.001040697 0.209506 0.009880781 5.6373e-4 0.210514 0.01027536 4.85497e-4 0.210151 0.0100618 8.39536e-4 0.2096199 0.009880781 8.21691e-4 0.209168 0.009733796 3.29205e-4 0.210554 0.01027536 2.10647e-4 0.210193 0.0100618 6.261e-4 0.209709 0.009880781 -6.72755e-5 0.210202 0.0100618 4.03535e-4 0.209771 0.009880781 1.75085e-4 0.209806 0.009880781 1.38236e-4 0.209405 0.009733796 3.18605e-4 0.209377 0.009733796 4.94328e-4 0.2093279 0.009733796 4.3045e-4 0.209147 0.009680747 5.75764e-4 0.20908 0.009675323 6.62842e-4 0.209258 0.009733796 7.18706e-4 0.209007 0.009680747 9.68558e-4 0.20906 0.009733796 8.64073e-4 0.2089329 0.009686291 -4.41492e-5 0.20941 0.009733796 -5.5918e-5 0.2098129 0.009880781 -2.86106e-4 0.209792 0.009880781 -6.16139e-4 0.210119 0.0100618 -3.44217e-4 0.210177 0.0100618 -5.50411e-4 0.210517 0.01027536 -0.001020312 0.21037 0.01027536 -8.79076e-4 0.2100279 0.0100618 -2.2589e-4 0.209394 0.009733796 1.0037e-4 0.208993 0.009621858 -3.20556e-5 0.208997 0.009621858 -1.64013e-4 0.208985 0.009621858 -4.04337e-4 0.209356 0.009733796 -5.12121e-4 0.209744 0.009880781 -0.001555323 0.210076 0.01027536 -0.00137037 0.210197 0.01027536 -0.00112915 0.2099069 0.0100618 -9.38562e-4 0.209568 0.009880781 -7.30669e-4 0.2096689 0.009880781 -2.9358e-4 0.208957 0.009621858 -8.97166e-6 0.208725 0.009572148 -8.47681e-5 0.20857 0.009545743 -1.00931e-4 0.208568 0.009545743 -1.80663e-4 0.208551 0.009545743 -7.41027e-4 0.209217 0.009733796 -5.76888e-4 0.209297 0.009733796 -0.001132726 0.209443 0.009880781 -0.001892209 0.2097899 0.01027536 -0.001829683 0.209848 0.01027536 -0.001729667 0.20994 0.01027536 -0.001576602 0.209578 0.0100618 -8.94359e-4 0.209118 0.009733796 -5.38042e-4 0.208856 0.009621858 -4.18865e-4 0.208914 0.009621858 -2.57761e-4 0.208524 0.009545743 -0.002177476 0.209453 0.01027536 -0.001767396 0.209376 0.0100618 -0.001932382 0.209152 0.0100618 -0.001310408 0.209295 0.009880781 -6.49373e-4 0.208784 0.009621858 -5.00504e-4 0.2085559 0.009572148 -0.002069234 0.2089099 0.0100618 -0.001606166 0.208941 0.009880781 -0.001469016 0.209127 0.009880781 -0.001159846 0.208869 0.009733796 -0.001034617 0.209001 0.009733796 -7.63277e-4 0.208684 0.009623944 -0.001808524 0.208526 0.009880781 -0.001719892 0.2087399 0.009880781 -0.002661049 0.208144 0.01027536 -0.002617776 0.208447 0.01027536 -0.00225085 0.208385 0.0100618 -0.001357913 0.208563 0.009733796 -0.002672195 0.208009 0.01027536 -0.002301633 0.2078329 0.0100618 -0.001905858 0.208075 0.009880781 -0.002292931 0.208111 0.0100618 -0.001477062 0.208219 0.009733796 -0.00187081 0.208304 0.009880781 -0.00261712 0.20735 0.01027536 -0.002642393 0.2075009 0.01027536 -0.001504719 0.208038 0.009733796 -0.001316487 0.208183 0.009686291 -0.001427888 0.208394 0.009733796 -0.001247465 0.20833 0.009680747 -0.001179516 0.208476 0.009675323 -0.001268088 0.2087219 0.009733796 -0.001106739 0.2086189 0.009680747 -0.00103271 0.208764 0.009686291 -0.00101161 0.208806 0.00968784 -0.002575278 0.207185 0.01027536 -0.002218604 0.207284 0.0100618 -0.002276718 0.207556 0.0100618 -0.001892328 0.207614 0.009880781 -0.001510381 0.2078559 0.009733796 -0.001913011 0.207844 0.009880781 -0.001092553 0.208 0.009621858 -0.001336216 0.208141 0.00968784 -0.001087844 0.208019 0.009623944 -0.002401947 0.206724 0.01027536 -0.002128183 0.2070209 0.0100618 -0.001844048 0.207388 0.009880781 -0.00149405 0.207674 0.009733796 -0.001096665 0.207868 0.009621858 -0.001048445 0.208 0.009613811 -8.25109e-4 0.207891 0.009572148 -0.002006709 0.206771 0.0100618 -0.001667916 0.206961 0.009880781 -0.001396596 0.207323 0.009733796 -0.001768887 0.2071689 0.009880781 -0.001455962 0.207496 0.009733796 -0.001084804 0.207736 0.009621858 -6.69827e-4 0.207815 0.009545743 -6.67583e-4 0.207799 0.009545743 -0.001057147 0.207606 0.009621858 -0.001542627 0.206767 0.009880781 -0.001678168 0.206323 0.0100618 -0.00203973 0.20617 0.01027536 -0.001947522 0.20607 0.01027536 -0.001217961 0.207006 0.009733796 -0.001316905 0.207159 0.009733796 -0.001014053 0.207481 0.009621858 -6.2403e-4 0.207642 0.009545743 -6.5055e-4 0.207719 0.009545743 -0.001252055 0.205968 0.0100618 -0.00147587 0.206133 0.0100618 -0.001394867 0.2065899 0.009880781 -0.001101255 0.206865 0.009733796 -8.8435e-4 0.207251 0.009621858 -9.56175e-4 0.2073619 0.009621858 -6.56034e-4 0.2074 0.009572148 -0.001040697 0.206294 0.009880781 -0.001226723 0.206431 0.009880781 -9.05531e-4 0.206888 0.00968784 -0.00101 0.205831 0.0100618 -9.68558e-4 0.20674 0.009733796 -6.62842e-4 0.206542 0.009733796 -8.39536e-4 0.20618 0.009880781 -2.44482e-4 0.2052389 0.01027536 -3.29205e-4 0.205246 0.01027536 -2.10647e-4 0.2056069 0.0100618 -4.85497e-4 0.205649 0.0100618 -6.261e-4 0.206091 0.009880781 -1.08908e-4 0.205228 0.01027536 -4.03535e-4 0.2060289 0.009880781 -1.75085e-4 0.205994 0.009880781 5.5918e-5 0.205987 0.009880781 6.72756e-5 0.2055979 0.0100618 -1.38236e-4 0.206395 0.009733796 -3.18605e-4 0.206423 0.009733796 -2.82671e-4 0.206583 0.009686291 -4.94328e-4 0.206472 0.009733796 -4.3045e-4 0.2066529 0.009680747 -8.21691e-4 0.206632 0.009733796 -5.75764e-4 0.2067199 0.009675323 -7.18706e-4 0.206793 0.009680747 -8.64073e-4 0.206867 0.009686291 -2.40526e-4 0.206564 0.00968784 4.41492e-5 0.20639 0.009733796 2.86106e-4 0.206008 0.009880781 3.44217e-4 0.205623 0.0100618 5.50411e-4 0.205283 0.01027536 7.64655e-4 0.205337 0.01027536 7.15226e-4 0.205325 0.01027536 6.16139e-4 0.205681 0.0100618 5.12121e-4 0.2060559 0.009880781 2.2589e-4 0.2064059 0.009733796 -1.00054e-4 0.206852 0.009613811 3.20557e-5 0.206803 0.009621858 7.30669e-4 0.206131 0.009880781 0.001175999 0.205498 0.01027536 0.00137037 0.205603 0.01027536 0.00112915 0.205893 0.0100618 0.0013628 0.206044 0.0100618 9.38562e-4 0.206232 0.009880781 5.76888e-4 0.206503 0.009733796 4.04337e-4 0.206444 0.009733796 1.64013e-4 0.206815 0.009621858 1.00931e-4 0.2072319 0.009545743 8.97168e-6 0.2070749 0.009572148 8.47681e-5 0.20723 0.009545743 1.80663e-4 0.207249 0.009545743 2.9358e-4 0.206843 0.009621858 4.18865e-4 0.2068859 0.009621858 7.41027e-4 0.206583 0.009733796 0.001132726 0.206357 0.009880781 0.001829683 0.205952 0.01027536 0.001729667 0.20586 0.01027536 0.001576602 0.2062219 0.0100618 0.001310408 0.206505 0.009880781 8.94359e-4 0.206682 0.009733796 2.57761e-4 0.207276 0.009545743 0.002177476 0.206347 0.01027536 0.001932382 0.2066479 0.0100618 0.001767396 0.2064239 0.0100618 0.001469016 0.206673 0.009880781 6.49373e-4 0.207016 0.009621858 0.002069234 0.20689 0.0100618 0.001159846 0.2069309 0.009733796 0.00101161 0.2069939 0.00968784 7.63277e-4 0.207116 0.009623944 0.002525091 0.207026 0.01027536 0.002175927 0.207147 0.0100618 0.001606166 0.2068589 0.009880781 0.002613663 0.207336 0.01027536 0.00225085 0.207415 0.0100618 0.001808524 0.207274 0.009880781 0.001719892 0.20706 0.009880781 0.00187081 0.207496 0.009880781 0.001427888 0.207406 0.009733796 0.002301633 0.207967 0.0100618 0.002292931 0.207689 0.0100618 0.001905858 0.207725 0.009880781 0.001477062 0.207581 0.009733796 0.002642393 0.208299 0.01027536 0.002653658 0.208232 0.01027536 0.002672016 0.208012 0.01027536 0.001913011 0.207956 0.009880781 0.001247465 0.2074699 0.009680747 0.001357913 0.207237 0.009733796 0.001179516 0.207324 0.009675323 0.001268088 0.207078 0.009733796 0.001106739 0.207181 0.009680747 0.00261712 0.20845 0.01027536 0.002218604 0.208516 0.0100618 0.002276718 0.208244 0.0100618 0.001892328 0.208186 0.009880781 0.001092553 0.2078 0.009621858 0.001504719 0.207762 0.009733796 0.001087844 0.207781 0.009623944 0.002128183 0.208779 0.0100618 0.002562761 0.208665 0.01027536 0.001510381 0.207944 0.009733796 0.001096665 0.2079319 0.009621858 0.001005411 0.207821 0.009602725 0.00149405 0.208126 0.009733796 0.001768887 0.208631 0.009880781 0.001844048 0.208412 0.009880781 0.002006709 0.209029 0.0100618 0.002401947 0.209076 0.01027536 0.001667916 0.2088389 0.009880781 0.001396596 0.208477 0.009733796 0.001455962 0.208304 0.009733796 6.67583e-4 0.208001 0.009545743 0.001084804 0.208064 0.009621858 8.25109e-4 0.207909 0.009572148 6.69827e-4 0.207985 0.009545743 0.001057147 0.208194 0.009621858 0.001014053 0.208319 0.009621858 0.001855969 0.209263 0.0100618 0.00203973 0.20963 0.01027536 0.001713812 0.2099519 0.01027536 0.00147587 0.209667 0.0100618 0.001727223 0.209942 0.01027536 0.001678168 0.209477 0.0100618 0.001394867 0.20921 0.009880781 0.001542627 0.209033 0.009880781 0.001316905 0.2086409 0.009733796 0.001217961 0.2087939 0.009733796 6.5055e-4 0.208081 0.009545743 0.001453042 0.210143 0.01027536 0.0015527 0.210078 0.01027536 0.001226723 0.209369 0.009880781 5.80237e-4 0.208245 0.009545743 0.001252055 0.209832 0.0100618 9.05531e-4 0.208912 0.00968784 0.179714 0.103398 0.01124995 0.179908 0.103412 0.01124995 0.179768 0.102621 0.00968784 0.180259 0.103436 0.01124995 0.180452 0.103449 0.01124995 0.180135 0.103397 0.01118856 0.180506 0.102673 0.00968784 0.18002 0.103391 0.01119226 0.180138 0.102641 0.009675323 0.179852 0.106743 0.01189994 0.179395 0.106673 0.01189994 0.178956 0.1065289 0.01189994 0.1787469 0.1064299 0.01050347 0.178546 0.106314 0.01189994 0.178178 0.106035 0.01050347 0.178178 0.106035 0.01189994 0.178012 0.105873 0.01050347 0.17786 0.105699 0.01050347 0.17786 0.105699 0.01189994 0.177723 0.105512 0.01050347 0.1776019 0.105315 0.01189994 0.177498 0.105108 0.01050347 0.177411 0.104894 0.01189994 0.1773419 0.104673 0.01050347 0.177291 0.104447 0.01189994 0.177291 0.104447 0.01050347 0.177247 0.103987 0.01189994 0.1772789 0.1035259 0.01189994 0.1773869 0.103076 0.01189994 0.177567 0.10265 0.01189994 0.177468 0.102859 0.01050347 0.177815 0.102259 0.01189994 0.1776829 0.10245 0.01050347 0.1781229 0.101915 0.01189994 0.178484 0.101626 0.01189994 0.1782979 0.101763 0.01050347 0.178484 0.101626 0.01050347 0.178888 0.101401 0.01189994 0.179103 0.101314 0.01050347 0.179324 0.101245 0.01189994 0.179324 0.101245 0.01050347 0.1797789 0.101163 0.01050347 0.1797789 0.101163 0.01189994 0.180241 0.101157 0.01050347 0.180241 0.101157 0.01189994 0.180698 0.101227 0.01189994 0.180471 0.101182 0.01050347 0.181138 0.101371 0.01189994 0.181347 0.10147 0.01050347 0.181547 0.101586 0.01189994 0.181737 0.101718 0.01050347 0.1819159 0.101865 0.01189994 0.1820819 0.1020269 0.01050347 0.182233 0.102201 0.01050347 0.182233 0.102201 0.01189994 0.18237 0.102388 0.01050347 0.182491 0.102585 0.01189994 0.182683 0.103006 0.01189994 0.182596 0.102792 0.01050347 0.182802 0.103453 0.01050347 0.182802 0.103453 0.01189994 0.182846 0.103913 0.01189994 0.182834 0.103682 0.01050347 0.182814 0.104374 0.01189994 0.18277 0.104602 0.01050347 0.182707 0.104824 0.01189994 0.182527 0.10525 0.01050347 0.182411 0.10545 0.01050347 0.182527 0.10525 0.01189994 0.182279 0.105641 0.01189994 0.18197 0.105985 0.01189994 0.181609 0.106274 0.01189994 0.181412 0.106395 0.01050347 0.181205 0.106499 0.01189994 0.18077 0.106655 0.01189994 0.180315 0.106737 0.01189994 0.1796219 0.106718 0.01050347 0.1791909 0.106554 0.01033556 0.178643 0.106225 0.01027536 0.178578 0.106265 0.01033556 0.178614 0.106208 0.01027536 0.178432 0.106082 0.01027536 0.17838 0.106039 0.01027536 0.178261 0.1059409 0.01027536 0.1782169 0.105991 0.01033556 0.178054 0.105833 0.01033556 0.17814 0.105823 0.01027536 0.177928 0.105579 0.01027536 0.177906 0.105662 0.01033556 0.177827 0.105442 0.01027536 0.177772 0.10548 0.01033556 0.177747 0.105312 0.01027536 0.177712 0.105254 0.01027536 0.177612 0.105056 0.01027536 0.177551 0.105084 0.01033556 0.177466 0.104874 0.01033556 0.177398 0.104658 0.01033556 0.177488 0.104722 0.01027536 0.1774629 0.104641 0.01027536 0.177318 0.104212 0.01033556 0.177385 0.104206 0.01027536 0.1773779 0.104087 0.01027536 0.177379 0.1037639 0.01027536 0.177403 0.103545 0.01027536 0.177442 0.103094 0.01033556 0.177501 0.1031309 0.01027536 0.177506 0.103115 0.01027536 0.177522 0.102882 0.01033556 0.1775839 0.102908 0.01027536 0.177619 0.102677 0.01033556 0.177772 0.102546 0.01027536 0.177789 0.102517 0.01027536 0.177915 0.102335 0.01027536 0.177958 0.102283 0.01027536 0.178005 0.10212 0.01033556 0.178555 0.101731 0.01027536 0.178743 0.101615 0.01027536 0.178972 0.101502 0.01027536 0.179145 0.101432 0.01027536 0.179356 0.101366 0.01027536 0.179572 0.101318 0.01027536 0.17956 0.101252 0.01033556 0.179791 0.101288 0.01027536 0.1797839 0.101221 0.01033556 0.17991 0.101281 0.01027536 0.180462 0.10124 0.01033556 0.180552 0.101326 0.01027536 0.180882 0.101409 0.01027536 0.181089 0.101487 0.01027536 0.181165 0.101523 0.01027536 0.181288 0.101581 0.01027536 0.181516 0.101635 0.01033556 0.181661 0.101818 0.01027536 0.1817139 0.101861 0.01027536 0.181702 0.101765 0.01033556 0.181832 0.101959 0.01027536 0.181954 0.102077 0.01027536 0.1822659 0.102458 0.01027536 0.182481 0.1028439 0.01027536 0.182543 0.102816 0.01033556 0.182565 0.103048 0.01027536 0.182695 0.103242 0.01033556 0.1826789 0.103475 0.01027536 0.182681 0.103492 0.01027536 0.182776 0.103688 0.01033556 0.182709 0.103694 0.01027536 0.18269 0.104355 0.01027536 0.182587 0.104785 0.01027536 0.18251 0.104992 0.01027536 0.182572 0.105018 0.01033556 0.182473 0.105069 0.01027536 0.182322 0.105354 0.01027536 0.182305 0.105383 0.01027536 0.182179 0.105565 0.01027536 0.182361 0.105419 0.01033556 0.182232 0.105605 0.01033556 0.18193 0.105942 0.01033556 0.181717 0.106039 0.01027536 0.181676 0.106069 0.01027536 0.1817589 0.106091 0.01033556 0.181576 0.106225 0.01033556 0.1815389 0.106169 0.01027536 0.1813499 0.106285 0.01027536 0.1811529 0.106385 0.01027536 0.180971 0.106531 0.01033556 0.180818 0.106508 0.01027536 0.180522 0.106582 0.01027536 0.180505 0.106584 0.01027536 0.1803089 0.106679 0.01033556 0.180303 0.106612 0.01027536 0.180184 0.106619 0.01027536 0.180082 0.106624 0.01027536 0.179856 0.106685 0.01033556 0.179641 0.106594 0.01027536 0.1796309 0.10666 0.01033556 0.179541 0.1065739 0.01027536 0.179409 0.106616 0.01033556 0.179228 0.106495 0.01027536 0.179399 0.106659 0.0104146 0.178979 0.106475 0.01033556 0.178754 0.106417 0.0104146 0.1787739 0.106378 0.01033556 0.178391 0.106135 0.01033556 0.178188 0.106024 0.0104146 0.178023 0.105863 0.0104146 0.177653 0.105286 0.01033556 0.177615 0.1053079 0.0104146 0.177425 0.104889 0.0104146 0.177349 0.104437 0.01033556 0.177305 0.103986 0.01033556 0.177275 0.104217 0.0104146 0.177312 0.10376 0.01033556 0.177337 0.103534 0.01033556 0.17738 0.103312 0.01033556 0.177401 0.103081 0.0104146 0.177732 0.102481 0.01033556 0.1775799 0.102657 0.0104146 0.177861 0.102295 0.01033556 0.177827 0.102269 0.0104146 0.177973 0.102091 0.0104146 0.178164 0.101958 0.01033556 0.1783339 0.101809 0.01033556 0.178517 0.101675 0.01033556 0.17871 0.101556 0.01033556 0.178689 0.101518 0.0104146 0.178912 0.101454 0.01033556 0.179108 0.101328 0.0104146 0.179122 0.101369 0.01033556 0.179339 0.101302 0.01033556 0.179328 0.10126 0.0104146 0.17978 0.101178 0.0104146 0.180011 0.101209 0.01033556 0.1802369 0.101215 0.01033556 0.180685 0.101284 0.01033556 0.180903 0.101346 0.01033556 0.181115 0.101425 0.01033556 0.181132 0.1013849 0.0104146 0.18132 0.101522 0.01033556 0.18134 0.101483 0.0104146 0.181877 0.101909 0.01033556 0.181906 0.101876 0.0104146 0.182039 0.102067 0.01033556 0.182188 0.1022379 0.01033556 0.182322 0.10242 0.01033556 0.182358 0.102396 0.0104146 0.182478 0.102592 0.0104146 0.18244 0.102614 0.01033556 0.182628 0.103026 0.01033556 0.1827369 0.103231 0.0104146 0.182787 0.103455 0.0104146 0.182745 0.103463 0.01033556 0.182819 0.103683 0.0104146 0.182788 0.103914 0.01033556 0.1827819 0.10414 0.01033556 0.182756 0.104366 0.01033556 0.182799 0.104372 0.0104146 0.182713 0.104588 0.01033556 0.182651 0.104806 0.01033556 0.1827549 0.104598 0.0104146 0.182692 0.1048189 0.0104146 0.182475 0.105223 0.01033556 0.182398 0.105442 0.0104146 0.182267 0.105631 0.0104146 0.182088 0.10578 0.01033556 0.18212 0.105809 0.0104146 0.18196 0.105974 0.0104146 0.181383 0.106344 0.01033556 0.1814039 0.106382 0.0104146 0.181181 0.106446 0.01033556 0.181199 0.106485 0.0104146 0.180986 0.106572 0.0104146 0.180755 0.106598 0.01033556 0.180533 0.106648 0.01033556 0.180541 0.106691 0.0104146 0.180083 0.106735 0.0104146 0.180083 0.106691 0.01033556 0.179853 0.106728 0.0104146 0.179625 0.106703 0.0104146 0.179852 0.106743 0.01050347 0.179395 0.106673 0.01050347 0.179177 0.106596 0.0104146 0.1789619 0.106515 0.0104146 0.179172 0.10661 0.01050347 0.178956 0.1065289 0.01050347 0.178546 0.106314 0.01050347 0.1785539 0.106301 0.0104146 0.1783649 0.1061699 0.0104146 0.178356 0.106182 0.01050347 0.177872 0.105689 0.0104146 0.177735 0.105504 0.0104146 0.1776019 0.105315 0.01050347 0.177511 0.105102 0.0104146 0.177411 0.104894 0.01050347 0.177356 0.104669 0.0104146 0.1773059 0.104445 0.0104146 0.17726 0.104218 0.01050347 0.177262 0.103987 0.0104146 0.177268 0.103757 0.0104146 0.177247 0.103987 0.01050347 0.177294 0.103528 0.0104146 0.177253 0.103756 0.01050347 0.1772789 0.1035259 0.01050347 0.177338 0.103302 0.0104146 0.1773239 0.103298 0.01050347 0.1773869 0.103076 0.01050347 0.177482 0.102865 0.0104146 0.177567 0.10265 0.01050347 0.177695 0.102458 0.0104146 0.177815 0.102259 0.01050347 0.177962 0.102081 0.01050347 0.1781229 0.101915 0.01050347 0.178134 0.101926 0.0104146 0.1783069 0.101775 0.0104146 0.178493 0.101639 0.0104146 0.178682 0.101505 0.01050347 0.178894 0.101415 0.0104146 0.178888 0.101401 0.01050347 0.179552 0.101209 0.0104146 0.179549 0.101195 0.01050347 0.18001 0.1011649 0.0104146 0.18001 0.10115 0.01050347 0.18024 0.101172 0.0104146 0.180469 0.101197 0.0104146 0.1806949 0.101241 0.0104146 0.180698 0.101227 0.01050347 0.180921 0.10129 0.01050347 0.180916 0.101304 0.0104146 0.181138 0.101371 0.01050347 0.1815389 0.101599 0.0104146 0.181547 0.101586 0.01050347 0.181728 0.10173 0.0104146 0.182071 0.102037 0.0104146 0.1819159 0.101865 0.01050347 0.182222 0.1022109 0.0104146 0.182491 0.102585 0.01050347 0.182582 0.102798 0.0104146 0.182669 0.103011 0.0104146 0.182683 0.103006 0.01050347 0.182752 0.103227 0.01050347 0.182831 0.103913 0.0104146 0.182846 0.103913 0.01050347 0.182825 0.104143 0.0104146 0.1828399 0.104144 0.01050347 0.182814 0.104374 0.01050347 0.182707 0.104824 0.01050347 0.182612 0.105035 0.0104146 0.1826249 0.105041 0.01050347 0.1825129 0.105243 0.0104146 0.182279 0.105641 0.01050347 0.182132 0.105819 0.01050347 0.18197 0.105985 0.01050347 0.181795 0.106137 0.01050347 0.181786 0.1061249 0.0104146 0.1816 0.106261 0.0104146 0.181609 0.106274 0.01050347 0.181205 0.106499 0.01050347 0.1809909 0.106586 0.01050347 0.18077 0.106655 0.01050347 0.180766 0.10664 0.0104146 0.180544 0.106706 0.01050347 0.180313 0.1067219 0.0104146 0.180315 0.106737 0.01050347 0.180084 0.10675 0.01050347 0.1827149 0.103813 0.01027536 0.182346 0.103832 0.0100618 0.18169 0.102337 0.0100618 0.1814799 0.101692 0.01027536 0.1812559 0.10199 0.0100618 0.180865 0.101405 0.01027536 0.180669 0.1013489 0.01027536 0.180452 0.101306 0.01027536 0.180207 0.101653 0.0100618 0.178174 0.102043 0.01027536 0.177423 0.103444 0.01027536 0.181919 0.105857 0.01027536 0.182592 0.104769 0.01027536 0.182671 0.104456 0.01027536 0.1827149 0.104136 0.01027536 0.179136 0.103516 0.009602725 0.1787649 0.103537 0.009686291 0.179037 0.104251 0.009613811 0.1789939 0.104248 0.009623944 0.179042 0.104391 0.009621858 0.178996 0.104267 0.009621858 0.179085 0.104254 0.009602725 0.179285 0.104268 0.009572148 0.179466 0.104294 0.009545743 0.179458 0.1042799 0.009545743 0.179609 0.104908 0.009613811 0.179612 0.10486 0.009602725 0.179633 0.105231 0.009686291 0.179587 0.105227 0.00968784 0.180347 0.104959 0.009613811 0.180344 0.1050029 0.009623944 0.180364 0.105 0.009621858 0.180351 0.104912 0.009602725 0.180488 0.104955 0.009621858 0.180365 0.1047109 0.009572148 0.180606 0.104894 0.009621858 0.180391 0.104531 0.009545743 0.180957 0.104384 0.009602725 0.1811 0.103652 0.009623944 0.181056 0.103649 0.009613811 0.181097 0.103633 0.009621858 0.181008 0.103646 0.009602725 0.180628 0.103606 0.009545743 0.1804839 0.1029919 0.009613811 0.180481 0.10304 0.009602725 0.18046 0.102669 0.009686291 0.1797299 0.1029 0.009621858 0.179749 0.102897 0.009623944 0.179746 0.102941 0.009613811 0.179743 0.102988 0.009602725 0.179729 0.103189 0.009572148 0.179635 0.103415 0.009545743 0.1797029 0.1033689 0.009545743 0.179717 0.103361 0.009545743 0.182344 0.10411 0.0100618 0.1819559 0.104083 0.009880781 0.181958 0.103852 0.009880781 0.181535 0.103691 0.009733796 0.182648 0.1045719 0.01027536 0.182308 0.104386 0.0100618 0.1822389 0.104655 0.0100618 0.182415 0.105192 0.01027536 0.182138 0.104914 0.0100618 0.181926 0.104312 0.009880781 0.1814849 0.104413 0.009733796 0.181869 0.1045359 0.009880781 0.182135 0.105617 0.01027536 0.182006 0.105159 0.0100618 0.181675 0.104955 0.009880781 0.181785 0.104751 0.009880781 0.1815299 0.104236 0.009733796 0.181342 0.104201 0.009680747 0.181356 0.104041 0.009675323 0.181554 0.104055 0.009733796 0.181556 0.103872 0.009733796 0.181365 0.103881 0.009680747 0.181376 0.103672 0.00968784 0.182038 0.105735 0.01027536 0.181846 0.105386 0.0100618 0.181333 0.104743 0.009733796 0.181043 0.104409 0.009621858 0.181419 0.104583 0.009733796 0.181324 0.10441 0.00968784 0.18145 0.1057749 0.0100618 0.181884 0.105894 0.01027536 0.1816599 0.105593 0.0100618 0.181542 0.105144 0.009880781 0.18098 0.104526 0.009621858 0.181005 0.1043879 0.009613811 0.181048 0.104391 0.009623944 0.180904 0.104634 0.009621858 0.181228 0.104893 0.009733796 0.181388 0.105316 0.009880781 0.181105 0.105028 0.009733796 0.1812199 0.105931 0.0100618 0.181408 0.10625 0.01027536 0.181122 0.106398 0.01027536 0.181213 0.105467 0.009880781 0.180968 0.105148 0.009733796 0.180815 0.104733 0.009621858 0.1805739 0.104371 0.009545743 0.180757 0.1043699 0.009572148 0.180584 0.104358 0.009545743 0.180715 0.10482 0.009621858 0.180817 0.10525 0.009733796 0.181022 0.105597 0.009880781 0.1809729 0.106058 0.0100618 0.180712 0.106154 0.0100618 0.180948 0.106468 0.01027536 0.180737 0.106534 0.01027536 0.180441 0.106219 0.0100618 0.1808159 0.105702 0.009880781 0.180599 0.105782 0.009880781 0.180458 0.104485 0.009545743 0.1805199 0.104432 0.009545743 0.1801649 0.10625 0.0100618 0.180375 0.105836 0.009880781 0.180654 0.105334 0.009733796 0.180377 0.104539 0.009545743 0.179861 0.106618 0.01027536 0.180306 0.105439 0.009733796 0.180483 0.105397 0.009733796 0.180325 0.105279 0.00968784 0.179611 0.106211 0.0100618 0.1798869 0.106247 0.0100618 0.180145 0.105861 0.009880781 0.179424 0.106551 0.01027536 0.179342 0.106142 0.0100618 0.1799139 0.105859 0.009880781 0.178928 0.106377 0.01027536 0.179005 0.106413 0.01027536 0.179083 0.106041 0.0100618 0.179212 0.106491 0.01027536 0.1796849 0.105829 0.009880781 0.178838 0.10591 0.0100618 0.1788049 0.106319 0.01027536 0.179461 0.105772 0.009880781 0.1792449 0.105688 0.009880781 0.179584 0.1053889 0.009733796 0.1797609 0.105434 0.009733796 0.179796 0.105246 0.009680747 0.179942 0.105457 0.009733796 0.180124 0.105459 0.009733796 0.179956 0.105259 0.009675323 0.1801159 0.105268 0.009680747 0.180279 0.105276 0.009686291 0.17861 0.10575 0.0100618 0.179042 0.105579 0.009880781 0.179414 0.105322 0.009733796 0.179253 0.105236 0.009733796 0.179587 0.104946 0.009621858 0.177958 0.10562 0.01027536 0.178103 0.105787 0.01027536 0.178221 0.105354 0.0100618 0.178404 0.105563 0.0100618 0.178681 0.105291 0.009880781 0.178853 0.105446 0.009880781 0.179104 0.105131 0.009733796 0.179606 0.104952 0.009623944 0.179471 0.104884 0.009621858 0.1793619 0.104807 0.009621858 0.178529 0.105117 0.009880781 0.178065 0.105123 0.0100618 0.177599 0.105025 0.01027536 0.177938 0.104876 0.0100618 0.1784 0.104925 0.009880781 0.178969 0.105009 0.009733796 0.179626 0.10466 0.009572148 0.179638 0.104488 0.009545743 0.179625 0.104478 0.009545743 0.179565 0.104423 0.009545743 0.179177 0.104619 0.009621858 0.179264 0.104719 0.009621858 0.178849 0.104871 0.009733796 0.178746 0.1047199 0.009733796 0.178294 0.1047199 0.009880781 0.177529 0.104852 0.01027536 0.177842 0.104615 0.0100618 0.177412 0.104408 0.01027536 0.177415 0.104425 0.01027536 0.177778 0.104344 0.0100618 0.178663 0.104558 0.009733796 0.179511 0.104362 0.009545743 0.177747 0.104068 0.0100618 0.1786 0.104386 0.009733796 0.178214 0.104503 0.009880781 0.179103 0.104509 0.009621858 0.177373 0.103985 0.01027536 0.1777499 0.10379 0.0100618 0.178161 0.104278 0.009880781 0.178718 0.104228 0.00968784 0.178137 0.103817 0.009880781 0.178135 0.104048 0.009880781 0.177446 0.103328 0.01027536 0.1777859 0.103514 0.0100618 0.177678 0.102708 0.01027536 0.1776199 0.102831 0.01027536 0.177956 0.102986 0.0100618 0.177855 0.103245 0.0100618 0.178167 0.103588 0.009880781 0.1785629 0.103664 0.009733796 0.1780869 0.102741 0.0100618 0.178225 0.103364 0.009880781 0.178247 0.102514 0.0100618 0.178418 0.102945 0.009880781 0.178309 0.1031489 0.009880781 0.178608 0.103487 0.009733796 0.178539 0.103845 0.009733796 0.178751 0.103699 0.009680747 0.178538 0.104028 0.009733796 0.178737 0.103859 0.009675323 0.1787289 0.104019 0.009680747 0.178558 0.104209 0.009733796 0.1787199 0.104182 0.009686291 0.178433 0.102307 0.0100618 0.178055 0.102165 0.01027536 0.178674 0.103317 0.009733796 0.1787689 0.1034899 0.00968784 0.179045 0.103509 0.009623944 0.178417 0.101831 0.01027536 0.178376 0.101861 0.01027536 0.17821 0.102006 0.01027536 0.178551 0.102756 0.009880781 0.178761 0.103157 0.009733796 0.17905 0.103491 0.009621858 0.179089 0.103512 0.009613811 0.179113 0.103374 0.009621858 0.179337 0.10353 0.009572148 0.178866 0.103007 0.009733796 0.178706 0.102584 0.009880781 0.17888 0.102433 0.009880781 0.178643 0.102125 0.0100618 0.1789399 0.101515 0.01027536 0.178685 0.1016499 0.01027536 0.179121 0.101842 0.0100618 0.178873 0.101969 0.0100618 0.179126 0.102752 0.009733796 0.178988 0.102872 0.009733796 0.179278 0.1031669 0.009621858 0.179189 0.103266 0.009621858 0.179509 0.103542 0.009545743 0.1795189 0.103529 0.009545743 0.179378 0.10308 0.009621858 0.179071 0.102303 0.009880781 0.179277 0.102198 0.009880781 0.179382 0.101746 0.0100618 0.179275 0.101392 0.01027536 0.179589 0.101316 0.01027536 0.179652 0.101681 0.0100618 0.179277 0.10265 0.009733796 0.179488 0.103006 0.009621858 0.179574 0.103468 0.009545743 0.17961 0.102503 0.009733796 0.179494 0.102118 0.009880781 0.179439 0.102566 0.009733796 0.179605 0.102945 0.009621858 0.180232 0.101282 0.01027536 0.180011 0.101276 0.01027536 0.179948 0.102039 0.009880781 0.179929 0.1016499 0.0100618 0.179719 0.102064 0.009880781 0.180482 0.101689 0.0100618 0.180409 0.102071 0.009880781 0.18018 0.102041 0.009880781 0.179969 0.102441 0.009733796 0.180633 0.102128 0.009880781 0.180752 0.101758 0.0100618 0.18145 0.101675 0.01027536 0.181011 0.101859 0.0100618 0.180509 0.102511 0.009733796 0.181483 0.10215 0.0100618 0.181052 0.102321 0.009880781 0.180679 0.102578 0.009733796 0.180848 0.102212 0.009880781 0.180298 0.102654 0.009680747 0.180333 0.102466 0.009733796 0.1801519 0.102443 0.009733796 0.1797879 0.102461 0.009733796 0.179978 0.102632 0.009680747 0.1798149 0.1026239 0.009686291 0.18084 0.102664 0.009733796 0.180506 0.102954 0.009621858 0.182166 0.102321 0.01027536 0.182135 0.10228 0.01027536 0.18199 0.102113 0.01027536 0.181241 0.102454 0.009880781 0.180989 0.102769 0.009733796 0.1806229 0.103016 0.009621858 0.180487 0.102948 0.009623944 0.180467 0.10324 0.009572148 0.181412 0.102609 0.009880781 0.181872 0.102546 0.0100618 0.182382 0.102646 0.01027536 0.182346 0.1025879 0.01027536 0.182494 0.102875 0.01027536 0.182155 0.103024 0.0100618 0.181693 0.102975 0.009880781 0.1820279 0.102777 0.0100618 0.181564 0.102783 0.009880781 0.181125 0.102891 0.009733796 0.1807309 0.103093 0.009621858 0.180455 0.103412 0.009545743 0.180468 0.103422 0.009545743 0.180916 0.103281 0.009621858 0.18083 0.103181 0.009621858 0.181245 0.103029 0.009733796 0.1817989 0.10318 0.009880781 0.182251 0.103285 0.0100618 0.18263 0.103259 0.01027536 0.182605 0.103178 0.01027536 0.181347 0.10318 0.009733796 0.18143 0.1033419 0.009733796 0.180582 0.103538 0.009545743 0.180528 0.103477 0.009545743 0.182315 0.103556 0.0100618 0.181932 0.103622 0.009880781 0.181879 0.103397 0.009880781 0.181493 0.103514 0.009733796 0.181051 0.103509 0.009621858 0.180808 0.103632 0.009572148 0.1809909 0.103391 0.009621858 0.180636 0.10362 0.009545743 0.182721 0.103915 0.01027536 0.180599 0.103618 0.01124995 0.180585 0.103811 0.01124995 0.180606 0.103924 0.01119226 0.180561 0.104162 0.01124995 0.1805469 0.104356 0.01124995 0.1813279 0.104363 0.009686291 0.1806 0.104038 0.01118856 0.181373 0.103718 0.009686291 0.1800349 -0.104594 0.01124995 0.180196 -0.104486 0.01124995 0.180304 -0.104448 0.01119226 0.1804699 -0.10524 0.00968784 0.180487 -0.104289 0.01124995 0.180648 -0.104181 0.01124995 0.181084 -0.104826 0.00968784 0.180912 -0.104947 0.009680747 0.1807799 -0.105038 0.009675323 0.1804 -0.104385 0.01118856 0.180509 -0.105215 0.009686291 0.182079 -0.102024 0.01050347 0.182079 -0.102024 0.01189994 0.181735 -0.101716 0.01189994 0.181544 -0.101584 0.01050347 0.181344 -0.101469 0.01189994 0.181344 -0.101469 0.01050347 0.181134 -0.10137 0.01050347 0.180918 -0.101289 0.01189994 0.180918 -0.101289 0.01050347 0.180468 -0.101182 0.01189994 0.180006 -0.10115 0.01050347 0.180006 -0.10115 0.01189994 0.1795459 -0.101195 0.01189994 0.17932 -0.1012459 0.01050347 0.1791 -0.101315 0.01189994 0.178885 -0.101402 0.01050347 0.178679 -0.101507 0.01050347 0.178679 -0.101507 0.01189994 0.1784819 -0.101628 0.01050347 0.178121 -0.101917 0.01050347 0.178295 -0.101765 0.01189994 0.17796 -0.102083 0.01189994 0.177681 -0.102452 0.01189994 0.177467 -0.102862 0.01189994 0.177323 -0.103302 0.01189994 0.177323 -0.103302 0.01050347 0.1772789 -0.103529 0.01050347 0.177253 -0.103759 0.01189994 0.177253 -0.103759 0.01050347 0.17726 -0.104221 0.01050347 0.17726 -0.104221 0.01189994 0.177292 -0.104451 0.01050347 0.177343 -0.104676 0.01189994 0.1774989 -0.105112 0.01189994 0.177412 -0.104897 0.01050347 0.177604 -0.105318 0.01050347 0.177725 -0.105515 0.01189994 0.178014 -0.105876 0.01189994 0.178359 -0.106184 0.01189994 0.17818 -0.106037 0.01050347 0.178359 -0.106184 0.01050347 0.17875 -0.106431 0.01050347 0.178959 -0.10653 0.01050347 0.17875 -0.106431 0.01189994 0.179176 -0.106611 0.01189994 0.179626 -0.106718 0.01189994 0.179626 -0.106718 0.01050347 0.179856 -0.106743 0.01050347 0.180087 -0.10675 0.01050347 0.180087 -0.10675 0.01189994 0.1803179 -0.106737 0.01050347 0.1805469 -0.106705 0.01189994 0.180994 -0.106585 0.01189994 0.181415 -0.106393 0.01050347 0.181415 -0.106393 0.01189994 0.181798 -0.106135 0.01189994 0.182134 -0.105817 0.01189994 0.182281 -0.105638 0.01050347 0.182413 -0.105448 0.01189994 0.182627 -0.105038 0.01189994 0.182771 -0.104598 0.01050347 0.182771 -0.104598 0.01189994 0.182815 -0.104371 0.01050347 0.1828399 -0.1041409 0.01189994 0.182834 -0.103679 0.01189994 0.182834 -0.103679 0.01050347 0.1827509 -0.103224 0.01189994 0.182594 -0.102788 0.01050347 0.182594 -0.102788 0.01189994 0.182368 -0.102385 0.01189994 0.1818299 -0.101957 0.01027536 0.181659 -0.1018159 0.01027536 0.181513 -0.101634 0.01033556 0.181477 -0.1016899 0.01027536 0.181315 -0.101597 0.01027536 0.181317 -0.10152 0.01033556 0.181112 -0.101424 0.01033556 0.181022 -0.101462 0.01027536 0.180666 -0.101348 0.01027536 0.180449 -0.101306 0.01027536 0.180398 -0.1013 0.01027536 0.1800079 -0.101276 0.01027536 0.180007 -0.101209 0.01033556 0.179781 -0.101221 0.01033556 0.179569 -0.101319 0.01027536 0.179336 -0.101302 0.01033556 0.1793529 -0.1013669 0.01027536 0.1791419 -0.101433 0.01027536 0.179126 -0.10144 0.01027536 0.178909 -0.101456 0.01033556 0.178552 -0.101732 0.01027536 0.178514 -0.101677 0.01033556 0.178332 -0.101811 0.01033556 0.178161 -0.10196 0.01033556 0.178003 -0.102122 0.01033556 0.177913 -0.102338 0.01027536 0.177859 -0.102297 0.01033556 0.17773 -0.102484 0.01033556 0.177864 -0.102408 0.01027536 0.177617 -0.10268 0.01033556 0.177441 -0.103097 0.01033556 0.177559 -0.102975 0.01027536 0.177505 -0.103118 0.01027536 0.177459 -0.103282 0.01027536 0.1774449 -0.103331 0.01027536 0.177403 -0.103548 0.01027536 0.177397 -0.1035979 0.01027536 0.177336 -0.103538 0.01033556 0.177312 -0.103763 0.01033556 0.177305 -0.103989 0.01033556 0.177385 -0.104209 0.01027536 0.177318 -0.104216 0.01033556 0.177349 -0.10444 0.01033556 0.17739 -0.104243 0.01027536 0.1774449 -0.104561 0.01027536 0.177399 -0.104661 0.01033556 0.177464 -0.104644 0.01027536 0.177467 -0.104877 0.01033556 0.1775299 -0.104855 0.01027536 0.177536 -0.10487 0.01027536 0.177667 -0.105166 0.01027536 0.177713 -0.105257 0.01027536 0.17796 -0.105623 0.01027536 0.178027 -0.1057 0.01027536 0.178057 -0.105836 0.01033556 0.178252 -0.1059319 0.01027536 0.178219 -0.105993 0.01033556 0.178435 -0.106084 0.01027536 0.178394 -0.106137 0.01033556 0.178504 -0.106132 0.01027536 0.17858 -0.106266 0.01033556 0.178777 -0.10638 0.01033556 0.179008 -0.106414 0.01027536 0.178982 -0.106476 0.01033556 0.179194 -0.106555 0.01033556 0.179412 -0.106617 0.01033556 0.179215 -0.106492 0.01027536 0.179644 -0.106594 0.01027536 0.180086 -0.106691 0.01033556 0.180537 -0.106647 0.01033556 0.180525 -0.106581 0.01027536 0.1809509 -0.106467 0.01027536 0.181156 -0.106383 0.01027536 0.18172 -0.106037 0.01027536 0.181761 -0.106089 0.01033556 0.181796 -0.10597 0.01027536 0.181932 -0.10594 0.01033556 0.182234 -0.105603 0.01033556 0.182363 -0.1054159 0.01033556 0.182306 -0.1053799 0.01027536 0.182476 -0.10522 0.01033556 0.1823999 -0.105218 0.01027536 0.182573 -0.105015 0.01033556 0.182511 -0.104989 0.01027536 0.1825349 -0.104925 0.01027536 0.1826519 -0.104803 0.01033556 0.182635 -0.104618 0.01027536 0.182691 -0.1043519 0.01027536 0.182696 -0.104302 0.01027536 0.182757 -0.104362 0.01033556 0.1827819 -0.104137 0.01033556 0.1827149 -0.1041319 0.01027536 0.182788 -0.103911 0.01033556 0.182709 -0.103691 0.01027536 0.182704 -0.103657 0.01027536 0.182694 -0.1032389 0.01033556 0.182648 -0.103339 0.01027536 0.18263 -0.103256 0.01027536 0.182563 -0.103045 0.01027536 0.182541 -0.102813 0.01033556 0.182557 -0.10303 0.01027536 0.182439 -0.102611 0.01033556 0.182264 -0.102455 0.01027536 0.182133 -0.102277 0.01027536 0.182066 -0.1022 0.01027536 0.1823559 -0.102393 0.0104146 0.182186 -0.102235 0.01033556 0.1820369 -0.102064 0.01033556 0.181874 -0.101907 0.01033556 0.181903 -0.101874 0.0104146 0.181699 -0.101763 0.01033556 0.181725 -0.101728 0.0104146 0.180899 -0.101345 0.01033556 0.181129 -0.101384 0.0104146 0.180913 -0.101303 0.0104146 0.180681 -0.101283 0.01033556 0.180691 -0.101241 0.0104146 0.180459 -0.10124 0.01033556 0.180234 -0.101215 0.01033556 0.180007 -0.1011649 0.0104146 0.179557 -0.101253 0.01033556 0.179105 -0.101329 0.0104146 0.179119 -0.10137 0.01033556 0.178707 -0.101558 0.01033556 0.178891 -0.101416 0.0104146 0.178686 -0.10152 0.0104146 0.17849 -0.1016409 0.0104146 0.177694 -0.10246 0.0104146 0.177579 -0.10266 0.0104146 0.177521 -0.102885 0.01033556 0.17748 -0.102868 0.0104146 0.1773999 -0.103084 0.0104146 0.17738 -0.103315 0.01033556 0.177293 -0.103531 0.0104146 0.177268 -0.10376 0.0104146 0.177262 -0.10399 0.0104146 0.177552 -0.105087 0.01033556 0.177513 -0.105105 0.0104146 0.177655 -0.105289 0.01033556 0.1777729 -0.105482 0.01033556 0.1777369 -0.105507 0.0104146 0.177908 -0.105665 0.01033556 0.177874 -0.105692 0.0104146 0.178557 -0.106303 0.0104146 0.178965 -0.106516 0.0104146 0.1794019 -0.106659 0.0104146 0.179628 -0.106703 0.0104146 0.179634 -0.10666 0.01033556 0.1798599 -0.106685 0.01033556 0.180317 -0.1067219 0.0104146 0.180312 -0.106679 0.01033556 0.180545 -0.10669 0.0104146 0.1807579 -0.106598 0.01033556 0.180769 -0.10664 0.0104146 0.180974 -0.10653 0.01033556 0.1811839 -0.106444 0.01033556 0.180989 -0.106571 0.0104146 0.1812019 -0.106484 0.0104146 0.1813859 -0.106342 0.01033556 0.1815789 -0.106223 0.01033556 0.181789 -0.106123 0.0104146 0.18209 -0.105778 0.01033556 0.182123 -0.105807 0.0104146 0.182269 -0.105629 0.0104146 0.1823999 -0.10544 0.0104146 0.182714 -0.104585 0.01033556 0.182756 -0.104595 0.0104146 0.1827999 -0.104369 0.0104146 0.182825 -0.10414 0.0104146 0.182775 -0.103684 0.01033556 0.182744 -0.10346 0.01033556 0.182787 -0.103452 0.0104146 0.182627 -0.103023 0.01033556 0.1823199 -0.102418 0.01033556 0.182368 -0.102385 0.01050347 0.18222 -0.102208 0.0104146 0.182231 -0.102199 0.01050347 0.182068 -0.102035 0.0104146 0.181913 -0.101863 0.01050347 0.181735 -0.101716 0.01050347 0.181536 -0.101597 0.0104146 0.1813369 -0.101482 0.0104146 0.1806949 -0.101226 0.01050347 0.1804659 -0.101197 0.0104146 0.180468 -0.101182 0.01050347 0.1802369 -0.101172 0.0104146 0.180238 -0.101157 0.01050347 0.1797749 -0.101163 0.01050347 0.179777 -0.101178 0.0104146 0.1795459 -0.101195 0.01050347 0.179549 -0.1012099 0.0104146 0.179324 -0.10126 0.0104146 0.1791 -0.101315 0.01050347 0.178305 -0.101777 0.0104146 0.178295 -0.101765 0.01050347 0.178131 -0.101928 0.0104146 0.177971 -0.102093 0.0104146 0.17796 -0.102083 0.01050347 0.177825 -0.102271 0.0104146 0.1778129 -0.102262 0.01050347 0.177681 -0.102452 0.01050347 0.177565 -0.102653 0.01050347 0.177467 -0.102862 0.01050347 0.177386 -0.103079 0.01050347 0.177337 -0.103305 0.0104146 0.177247 -0.10399 0.01050347 0.177275 -0.10422 0.0104146 0.177307 -0.104448 0.0104146 0.177357 -0.104672 0.0104146 0.177343 -0.104676 0.01050347 0.177426 -0.104892 0.0104146 0.1774989 -0.105112 0.01050347 0.177617 -0.105311 0.0104146 0.177725 -0.105515 0.01050347 0.177862 -0.105701 0.01050347 0.178014 -0.105876 0.01050347 0.178025 -0.105865 0.0104146 0.1781899 -0.106026 0.0104146 0.178368 -0.106172 0.0104146 0.178549 -0.106316 0.01050347 0.178757 -0.106418 0.0104146 0.17918 -0.106597 0.0104146 0.179176 -0.106611 0.01050347 0.179398 -0.106674 0.01050347 0.179857 -0.106728 0.0104146 0.180087 -0.106735 0.0104146 0.1805469 -0.106705 0.01050347 0.180773 -0.106654 0.01050347 0.180994 -0.106585 0.01050347 0.181208 -0.106498 0.01050347 0.181407 -0.10638 0.0104146 0.181603 -0.106259 0.0104146 0.181612 -0.106272 0.01050347 0.181798 -0.106135 0.01050347 0.181973 -0.105983 0.01050347 0.181962 -0.105972 0.0104146 0.182134 -0.105817 0.01050347 0.182413 -0.105448 0.01050347 0.182515 -0.10524 0.0104146 0.182528 -0.105247 0.01050347 0.182613 -0.105032 0.0104146 0.182693 -0.104816 0.0104146 0.182627 -0.105038 0.01050347 0.182708 -0.104821 0.01050347 0.1828399 -0.1041409 0.01050347 0.182846 -0.10391 0.01050347 0.182831 -0.10391 0.0104146 0.182819 -0.10368 0.0104146 0.182802 -0.103449 0.01050347 0.1827509 -0.103224 0.01050347 0.182736 -0.103228 0.0104146 0.182667 -0.103008 0.0104146 0.182682 -0.103003 0.01050347 0.182581 -0.102795 0.0104146 0.1824899 -0.102582 0.01050347 0.1824769 -0.102589 0.0104146 0.181353 -0.106284 0.01027536 0.180967 -0.10646 0.01027536 0.179695 -0.1066 0.01027536 0.178808 -0.10632 0.01027536 0.1787779 -0.106303 0.01027536 0.178501 -0.105657 0.0100618 0.1781049 -0.105789 0.01027536 0.178306 -0.105458 0.0100618 0.177829 -0.105445 0.01027536 0.177996 -0.104997 0.0100618 0.1777639 -0.103647 0.0100618 0.177694 -0.102682 0.01027536 0.178065 -0.102155 0.01027536 0.178207 -0.1020089 0.01027536 0.178539 -0.10221 0.0100618 0.1787599 -0.102041 0.0100618 0.17874 -0.101616 0.01027536 0.1792539 -0.101788 0.0100618 0.179794 -0.101661 0.0100618 0.181286 -0.10158 0.01027536 0.1811389 -0.101923 0.0100618 0.181842 -0.101968 0.01027536 0.181988 -0.102111 0.01027536 0.1819559 -0.102663 0.0100618 0.18238 -0.102643 0.01027536 0.182097 -0.102903 0.0100618 0.18248 -0.102841 0.01027536 0.182648 -0.104569 0.01027536 0.182417 -0.105189 0.01027536 0.18204 -0.105733 0.01027536 0.1820279 -0.105745 0.01027536 0.181886 -0.105891 0.01027536 0.17917 -0.104987 0.00968784 0.179399 -0.104832 0.009623944 0.1791509 -0.103317 0.009621858 0.179048 -0.103047 0.009686291 0.179796 -0.102882 0.009621858 0.179778 -0.102889 0.009623944 0.179802 -0.102926 0.009613811 0.179829 -0.1029649 0.009602725 0.179926 -0.102859 0.009621858 0.180054 -0.103275 0.009545743 0.180038 -0.103275 0.009545743 0.180567 -0.102984 0.009621858 0.1811079 -0.103681 0.009623944 0.181518 -0.103605 0.009733796 0.181071 -0.103706 0.009613811 0.181115 -0.103699 0.009621858 0.181031 -0.103732 0.009602725 0.180865 -0.103845 0.009572148 0.180716 -0.104039 0.009545743 0.1807219 -0.1039569 0.009545743 0.1807219 -0.103941 0.009545743 0.1802909 -0.104974 0.009613811 0.180316 -0.105011 0.009623944 0.180297 -0.105018 0.009621858 0.180392 -0.105421 0.009733796 0.1802639 -0.104935 0.009602725 0.180167 -0.105041 0.009621858 0.1801519 -0.104768 0.009572148 0.180039 -0.104625 0.009545743 0.179475 -0.104781 0.009602725 0.179144 -0.1049489 0.009686291 0.178979 -0.104201 0.009621858 0.178986 -0.104219 0.009623944 0.179022 -0.104194 0.009613811 0.179062 -0.1041679 0.009602725 0.179228 -0.104055 0.009572148 0.179372 -0.103943 0.009545743 0.181554 -0.10569 0.0100618 0.180567 -0.105369 0.009733796 0.181753 -0.105496 0.0100618 0.1813 -0.105397 0.009880781 0.181116 -0.1055369 0.009880781 0.181927 -0.105279 0.0100618 0.182229 -0.105492 0.01027536 0.182181 -0.105562 0.01027536 0.181465 -0.105235 0.009880781 0.180891 -0.105203 0.009733796 0.1810359 -0.105092 0.009733796 0.182588 -0.104782 0.01027536 0.182191 -0.10479 0.0100618 0.182074 -0.105043 0.0100618 0.181731 -0.104858 0.009880781 0.1816099 -0.105055 0.009880781 0.181281 -0.104822 0.009733796 0.181167 -0.104964 0.009733796 0.181046 -0.104853 0.009686291 0.180734 -0.105296 0.009733796 0.180646 -0.105126 0.009680747 0.181829 -0.104648 0.009880781 0.1823289 -0.104253 0.0100618 0.182276 -0.104526 0.0100618 0.181454 -0.104501 0.009733796 0.1813769 -0.104667 0.009733796 0.181012 -0.104471 0.009621858 0.180905 -0.104561 0.009613811 0.180943 -0.104583 0.009621858 0.180929 -0.104597 0.009623944 0.180878 -0.104521 0.009602725 0.180766 -0.104355 0.009572148 0.1819 -0.104429 0.009880781 0.182721 -0.103912 0.01027536 0.1827189 -0.10398 0.01027536 0.182349 -0.1039749 0.0100618 0.181944 -0.104202 0.009880781 0.18151 -0.104328 0.009733796 0.180675 -0.104196 0.009545743 0.181068 -0.10435 0.009621858 0.180669 -0.104212 0.009545743 0.1807 -0.104119 0.009545743 0.181109 -0.104224 0.009621858 0.181558 -0.103967 0.009733796 0.181545 -0.104149 0.009733796 0.18196 -0.103971 0.009880781 0.182335 -0.103698 0.0100618 0.182678 -0.103472 0.01027536 0.182288 -0.103424 0.0100618 0.18191 -0.103513 0.009880781 0.181949 -0.10374 0.009880781 0.181549 -0.103784 0.009733796 0.1811439 -0.103962 0.009621858 0.181134 -0.104094 0.009621858 0.182426 -0.102734 0.01027536 0.1818439 -0.103291 0.009880781 0.182209 -0.103157 0.0100618 0.181137 -0.10383 0.009621858 0.181465 -0.10343 0.009733796 0.1813369 -0.103527 0.00968784 0.181751 -0.103079 0.009880781 0.181634 -0.10288 0.009880781 0.181787 -0.102442 0.0100618 0.181493 -0.102697 0.009880781 0.1813 -0.103105 0.009733796 0.181589 -0.101768 0.01027536 0.181376 -0.10207 0.0100618 0.181593 -0.102243 0.0100618 0.181061 -0.10283 0.009733796 0.1813319 -0.102532 0.009880781 0.1808789 -0.101408 0.01027536 0.180887 -0.101806 0.0100618 0.181086 -0.101486 0.01027536 0.1809549 -0.102265 0.009880781 0.181151 -0.102387 0.009880781 0.18095 -0.102951 0.009686291 0.181189 -0.102961 0.009733796 0.181043 -0.103085 0.009680747 0.181392 -0.103263 0.009733796 0.1811349 -0.103216 0.009675323 0.181222 -0.1033509 0.009680747 0.181311 -0.103488 0.009686291 0.180715 -0.101362 0.01027536 0.180622 -0.101721 0.0100618 0.180745 -0.102168 0.009880781 0.180919 -0.102716 0.009733796 0.180923 -0.102913 0.00968784 0.1803489 -0.101667 0.0100618 0.180764 -0.10262 0.009733796 0.18068 -0.103054 0.009621858 0.180658 -0.103092 0.009613811 0.180694 -0.103068 0.009623944 0.180618 -0.103119 0.009602725 0.180451 -0.103231 0.009572148 0.180598 -0.1025429 0.009733796 0.180525 -0.102097 0.009880781 0.180425 -0.102487 0.009733796 0.180072 -0.101648 0.0100618 0.180076 -0.101278 0.01027536 0.180229 -0.101282 0.01027536 0.179754 -0.101293 0.01027536 0.1797879 -0.101288 0.01027536 0.180068 -0.1020359 0.009880781 0.180298 -0.102053 0.009880781 0.180321 -0.102888 0.009621858 0.180447 -0.1029289 0.009621858 0.180308 -0.103328 0.009545743 0.180293 -0.103321 0.009545743 0.180191 -0.102862 0.009621858 0.180245 -0.102452 0.009733796 0.17952 -0.101708 0.0100618 0.179436 -0.101348 0.01027536 0.179837 -0.102048 0.009880781 0.179609 -0.102087 0.009880781 0.179881 -0.102448 0.009733796 0.180063 -0.102439 0.009733796 0.180059 -0.102853 0.009621858 0.180135 -0.103281 0.009545743 0.180215 -0.103296 0.009545743 0.178831 -0.10157 0.01027536 0.178937 -0.101517 0.01027536 0.178999 -0.101899 0.0100618 0.179701 -0.102479 0.009733796 0.1799409 -0.103132 0.009572148 0.179388 -0.102153 0.009880781 0.179526 -0.102531 0.009733796 0.178297 -0.10193 0.01027536 0.1783739 -0.101863 0.01027536 0.178977 -0.102363 0.009880781 0.179176 -0.102246 0.009880781 0.17834 -0.1024039 0.0100618 0.178793 -0.102503 0.009880781 0.179202 -0.102697 0.009733796 0.177787 -0.10252 0.01027536 0.178053 -0.102167 0.01027536 0.178166 -0.102621 0.0100618 0.178628 -0.102665 0.009880781 0.179057 -0.1028079 0.009733796 0.178927 -0.102936 0.009733796 0.177582 -0.102911 0.01027536 0.177677 -0.102711 0.01027536 0.17802 -0.102857 0.0100618 0.178813 -0.103078 0.009733796 0.178484 -0.102845 0.009880781 0.1791819 -0.102953 0.009680747 0.179313 -0.102862 0.009675323 0.179359 -0.102604 0.009733796 0.179448 -0.102774 0.009680747 0.179584 -0.102685 0.009686291 0.17901 -0.103074 0.00968784 0.178717 -0.103233 0.009733796 0.178362 -0.103042 0.009880781 0.178265 -0.103252 0.009880781 0.1779029 -0.10311 0.0100618 0.177817 -0.103374 0.0100618 0.178194 -0.103471 0.009880781 0.179081 -0.103429 0.009621858 0.179189 -0.103339 0.009613811 0.1791639 -0.103303 0.009623944 0.179215 -0.103379 0.009602725 0.179328 -0.103545 0.009572148 0.17864 -0.103399 0.009733796 0.177373 -0.103988 0.01027536 0.177374 -0.10392 0.01027536 0.1773779 -0.103767 0.01027536 0.177758 -0.104202 0.0100618 0.177744 -0.103925 0.0100618 0.178149 -0.103698 0.009880781 0.178549 -0.103751 0.009733796 0.178584 -0.103572 0.009733796 0.1790249 -0.10355 0.009621858 0.179424 -0.103689 0.009545743 0.179418 -0.103704 0.009545743 0.178984 -0.103676 0.009621858 0.1793929 -0.103781 0.009545743 0.178959 -0.103806 0.009621858 0.1785359 -0.103933 0.009733796 0.178133 -0.103929 0.009880781 0.178144 -0.10416 0.009880781 0.177805 -0.104476 0.0100618 0.177415 -0.104428 0.01027536 0.1778849 -0.104743 0.0100618 0.178183 -0.104387 0.009880781 0.17895 -0.103938 0.009621858 0.179377 -0.103861 0.009545743 0.177613 -0.105059 0.01027536 0.1785759 -0.104295 0.009733796 0.1785449 -0.104116 0.009733796 0.178956 -0.10407 0.009621858 0.179372 -0.103959 0.009545743 0.178342 -0.104821 0.009880781 0.17825 -0.104609 0.009880781 0.178137 -0.105237 0.0100618 0.17846 -0.10502 0.009880781 0.178628 -0.10447 0.009733796 0.1786 -0.105203 0.009880781 0.178264 -0.105943 0.01027536 0.178616 -0.10621 0.01027536 0.178954 -0.1059769 0.0100618 0.178718 -0.10583 0.0100618 0.178762 -0.105368 0.009880781 0.179032 -0.1050699 0.009733796 0.179071 -0.106438 0.01027536 0.178942 -0.105513 0.009880781 0.179139 -0.105635 0.009880781 0.178905 -0.104939 0.009733796 0.17905 -0.104815 0.009680747 0.178794 -0.104795 0.009733796 0.1789579 -0.104684 0.009675323 0.178701 -0.104637 0.009733796 0.178871 -0.104549 0.009680747 0.178782 -0.104412 0.009686291 0.178757 -0.104373 0.00968784 0.179175 -0.105184 0.009733796 0.179413 -0.104846 0.009621858 0.1793299 -0.10528 0.009733796 0.179206 -0.106094 0.0100618 0.179428 -0.106552 0.01027536 0.179378 -0.1065379 0.01027536 0.179471 -0.1061789 0.0100618 0.179348 -0.105732 0.009880781 0.179495 -0.105357 0.009733796 0.179526 -0.104916 0.009621858 0.179436 -0.104808 0.009613811 0.179642 -0.104669 0.009572148 0.179669 -0.105413 0.009733796 0.1795679 -0.105803 0.009880781 0.179795 -0.105847 0.009880781 0.179744 -0.106233 0.0100618 0.179864 -0.106618 0.01027536 0.180085 -0.106624 0.01027536 0.1800169 -0.106622 0.01027536 0.1803399 -0.106607 0.01027536 0.180306 -0.106612 0.01027536 0.180021 -0.106252 0.0100618 0.180299 -0.106239 0.0100618 0.179646 -0.104971 0.009621858 0.179785 -0.1045719 0.009545743 0.1798 -0.104579 0.009545743 0.179772 -0.1050119 0.009621858 0.1798779 -0.104604 0.009545743 0.179902 -0.105038 0.009621858 0.179848 -0.105448 0.009733796 0.1800299 -0.105461 0.009733796 0.1800259 -0.105864 0.009880781 0.180573 -0.106192 0.0100618 0.1807399 -0.106533 0.01027536 0.180657 -0.106552 0.01027536 0.180256 -0.105852 0.009880781 0.179958 -0.104619 0.009545743 0.181262 -0.10633 0.01027536 0.180839 -0.106112 0.0100618 0.1804839 -0.105813 0.009880781 0.180212 -0.105452 0.009733796 0.1800349 -0.105047 0.009621858 0.180056 -0.104625 0.009545743 0.181542 -0.106168 0.01027536 0.181334 -0.105859 0.0100618 0.181094 -0.106001 0.0100618 0.180917 -0.105654 0.009880781 0.180706 -0.105747 0.009880781 0.180059 -0.103306 0.01124995 0.179898 -0.1034139 0.01124995 0.179623 -0.10266 0.00968784 0.17979 -0.103452 0.01119226 0.179606 -0.103611 0.01124995 0.179445 -0.1037189 0.01124995 0.1796939 -0.103515 0.01118856 0.002684056 -0.208697 0.01189994 0.00274074 -0.208473 0.01050347 0.002778708 -0.208245 0.01189994 0.002797484 -0.207783 0.01189994 0.002797484 -0.207783 0.01050347 0.002778232 -0.207552 0.01050347 0.002740025 -0.207324 0.01189994 0.002683103 -0.207099 0.01050347 0.002607822 -0.206881 0.01189994 0.002404451 -0.206465 0.01189994 0.002404451 -0.206465 0.01050347 0.002277731 -0.206272 0.01050347 0.002135515 -0.206089 0.01189994 0.001978695 -0.205919 0.01050347 0.001808345 -0.205762 0.01189994 0.001808345 -0.205762 0.01050347 0.001625597 -0.2056199 0.01050347 0.001431822 -0.205494 0.01189994 0.001228213 -0.205384 0.01050347 0.001016199 -0.205291 0.01050347 0.001016199 -0.205291 0.01189994 5.72949e-4 -0.205159 0.01189994 5.72949e-4 -0.205159 0.01050347 3.44663e-4 -0.205121 0.01050347 1.14022e-4 -0.205102 0.01189994 -1.17398e-4 -0.205102 0.01050347 -3.48016e-4 -0.2051219 0.01189994 -5.76256e-4 -0.20516 0.01050347 -8.0056e-4 -0.205217 0.01189994 -0.001231253 -0.205385 0.01189994 -0.001231253 -0.205385 0.01050347 -0.001628339 -0.205622 0.01189994 -0.001810908 -0.2057639 0.01050347 -0.001981079 -0.2059209 0.01189994 -0.001981079 -0.2059209 0.01050347 -0.002279758 -0.206274 0.01189994 -0.00251621 -0.206672 0.01189994 -0.00251621 -0.206672 0.01050347 -0.002609014 -0.206884 0.01050347 -0.00274074 -0.207327 0.01050347 -0.002684056 -0.207103 0.01189994 -0.002778708 -0.2075549 0.01189994 -0.002797484 -0.208017 0.01189994 -0.002740025 -0.208476 0.01189994 -0.002683103 -0.208701 0.01050347 -0.002607822 -0.208919 0.01189994 -0.002607822 -0.208919 0.01050347 -0.002514719 -0.209131 0.01050347 -0.002404451 -0.209335 0.01189994 -0.002404451 -0.209335 0.01050347 -0.002135515 -0.209711 0.01189994 -0.002135515 -0.209711 0.01050347 -0.001808345 -0.210038 0.01189994 -0.001625597 -0.21018 0.01050347 -0.001431822 -0.210306 0.01189994 -0.001016199 -0.210509 0.01189994 -0.001016199 -0.210509 0.01050347 -5.72949e-4 -0.210641 0.01050347 -5.72949e-4 -0.210641 0.01189994 -1.14022e-4 -0.210698 0.01189994 1.17398e-4 -0.210698 0.01050347 3.48016e-4 -0.210678 0.01189994 5.76256e-4 -0.21064 0.01050347 8.0056e-4 -0.210583 0.01189994 8.0056e-4 -0.210583 0.01050347 0.001019358 -0.210508 0.01050347 0.001231253 -0.210415 0.01189994 0.001628339 -0.210178 0.01189994 0.001810908 -0.210036 0.01050347 0.001981079 -0.209879 0.01189994 0.00213772 -0.209708 0.01050347 0.002279758 -0.209526 0.01189994 0.00251621 -0.209128 0.01189994 0.00251621 -0.209128 0.01050347 0.002609014 -0.208916 0.01050347 0.002683401 -0.208461 0.01033556 0.002720594 -0.2082369 0.01033556 0.002739191 -0.208012 0.01033556 0.002661049 -0.208144 0.01027536 0.002575278 -0.207185 0.01027536 0.002553284 -0.206902 0.01033556 0.002470314 -0.20688 0.01027536 0.002230167 -0.206306 0.01033556 0.002154707 -0.206318 0.01027536 0.002090871 -0.206127 0.01033556 0.001947522 -0.20607 0.01027536 0.001889944 -0.206008 0.01027536 0.001727223 -0.2058579 0.01027536 0.001770496 -0.205807 0.01033556 0.001713812 -0.205848 0.01027536 0.001367568 -0.205602 0.01027536 0.001173138 -0.205497 0.01027536 9.70669e-4 -0.205408 0.01027536 9.95006e-4 -0.205345 0.01033556 7.61562e-4 -0.205336 0.01027536 5.6373e-4 -0.205286 0.01027536 5.47252e-4 -0.205282 0.01027536 5.60973e-4 -0.205217 0.01033556 3.29205e-4 -0.205246 0.01027536 1.08908e-4 -0.205228 0.01027536 1.11639e-4 -0.205161 0.01033556 -1.14944e-4 -0.205161 0.01033556 -3.32407e-4 -0.205246 0.01027536 -3.99475e-4 -0.205258 0.01027536 -5.50411e-4 -0.205283 0.01027536 -9.73676e-4 -0.205409 0.01027536 -7.83827e-4 -0.205273 0.01033556 -9.98088e-4 -0.205347 0.01033556 -0.001205503 -0.205438 0.01033556 -0.001020312 -0.20543 0.01027536 -0.00137037 -0.205603 0.01027536 -0.001594305 -0.2056699 0.01033556 -0.001892209 -0.20601 0.01027536 -0.002093017 -0.206129 0.01033556 -0.002177476 -0.206347 0.01027536 -0.002554476 -0.206905 0.01033556 -0.002525091 -0.207026 0.01027536 -0.002627968 -0.207119 0.01033556 -0.002613663 -0.207336 0.01027536 -0.002683401 -0.207339 0.01033556 -0.002672195 -0.207791 0.01027536 -0.002739012 -0.208015 0.01033556 -0.002672076 -0.207978 0.01027536 -0.002672016 -0.208012 0.01027536 -0.002575278 -0.208615 0.01027536 -0.002562761 -0.208665 0.01027536 -0.002627015 -0.208684 0.01033556 -0.002470314 -0.20892 0.01027536 -0.002354204 -0.209305 0.01033556 -0.002296626 -0.20927 0.01027536 -0.002230167 -0.2094939 0.01033556 -0.002175629 -0.209455 0.01027536 -0.002154707 -0.209482 0.01027536 -0.002090871 -0.209673 0.01033556 -0.001947522 -0.20973 0.01027536 -0.001889944 -0.209792 0.01027536 -0.001770496 -0.209993 0.01033556 -0.001713812 -0.2099519 0.01027536 -0.0015527 -0.210078 0.01027536 -0.001367568 -0.210198 0.01027536 -0.001173138 -0.210303 0.01027536 -9.70669e-4 -0.2103919 0.01027536 -9.95006e-4 -0.210455 0.01033556 -5.6373e-4 -0.210514 0.01027536 -7.80656e-4 -0.210528 0.01033556 -5.60973e-4 -0.210583 0.01033556 -3.37458e-4 -0.2106209 0.01033556 -3.29205e-4 -0.210554 0.01027536 -2.44482e-4 -0.210561 0.01027536 -1.11639e-4 -0.2106389 0.01033556 7.81376e-5 -0.210572 0.01027536 1.12133e-4 -0.210572 0.01027536 1.14944e-4 -0.2106389 0.01033556 3.32407e-4 -0.210554 0.01027536 3.40741e-4 -0.21062 0.01033556 3.99475e-4 -0.210542 0.01027536 9.73676e-4 -0.210391 0.01027536 9.98088e-4 -0.210453 0.01033556 0.001020312 -0.21037 0.01027536 0.001310586 -0.210229 0.01027536 0.00137037 -0.210197 0.01027536 0.001582145 -0.2100549 0.01027536 0.001729667 -0.20994 0.01027536 0.001773059 -0.209991 0.01033556 0.001939654 -0.209837 0.01033556 0.002093017 -0.209671 0.01033556 0.002177476 -0.209453 0.01027536 0.00249201 -0.208871 0.01027536 0.002613663 -0.208464 0.01027536 0.002502679 -0.209122 0.0104146 0.002554476 -0.208895 0.01033556 0.002669632 -0.208693 0.0104146 0.002627968 -0.208681 0.01033556 0.002726018 -0.20847 0.0104146 0.002739012 -0.207785 0.01033556 0.002782464 -0.207783 0.0104146 0.002720177 -0.207559 0.01033556 0.002682745 -0.207336 0.01033556 0.002725303 -0.207327 0.0104146 0.002627015 -0.207116 0.01033556 0.002462148 -0.206694 0.01033556 0.002501189 -0.2066749 0.0104146 0.002354204 -0.206495 0.01033556 0.002391517 -0.2064729 0.0104146 0.001937329 -0.20596 0.01033556 0.001591622 -0.205668 0.01033556 0.001616895 -0.205632 0.0104146 0.001401841 -0.2055439 0.01033556 0.001202523 -0.205436 0.01033556 0.001221597 -0.205397 0.0104146 0.001010775 -0.205305 0.0104146 7.80656e-4 -0.205272 0.01033556 7.93036e-4 -0.2052299 0.0104146 3.37458e-4 -0.205179 0.01033556 3.4281e-4 -0.205136 0.0104146 1.13409e-4 -0.205117 0.0104146 -3.40741e-4 -0.2051799 0.01033556 -5.64211e-4 -0.205217 0.01033556 -0.001224637 -0.205399 0.0104146 -0.001426994 -0.2055079 0.0104146 -0.001404702 -0.205546 0.01033556 -0.001773059 -0.2058089 0.01033556 -0.001801133 -0.205776 0.0104146 -0.001939654 -0.205963 0.01033556 -0.00197041 -0.205932 0.0104146 -0.002126216 -0.206101 0.0104146 -0.002232074 -0.206308 0.01033556 -0.002267479 -0.206283 0.0104146 -0.002355873 -0.206498 0.01033556 -0.002463638 -0.206697 0.01033556 -0.002726018 -0.2073299 0.0104146 -0.002763748 -0.207557 0.0104146 -0.002720594 -0.207563 0.01033556 -0.002739191 -0.207788 0.01033556 -0.002782464 -0.208017 0.0104146 -0.002720177 -0.208241 0.01033556 -0.002682745 -0.208464 0.01033556 -0.002668678 -0.208696 0.0104146 -0.002553284 -0.208898 0.01033556 -0.002462148 -0.209106 0.01033556 -0.002501189 -0.209125 0.0104146 -0.002391517 -0.209327 0.0104146 -0.002265512 -0.20952 0.0104146 -0.001937329 -0.2098399 0.01033556 -0.001968026 -0.20987 0.0104146 -0.001798629 -0.210026 0.0104146 -0.001591622 -0.210132 0.01033556 -0.001616895 -0.210167 0.0104146 -0.001401841 -0.210256 0.01033556 -0.001202523 -0.210364 0.01033556 -0.001221597 -0.210403 0.0104146 -5.6987e-4 -0.210626 0.0104146 1.16767e-4 -0.210682 0.0104146 3.46145e-4 -0.210663 0.0104146 5.64211e-4 -0.210583 0.01033556 7.83827e-4 -0.210527 0.01033556 7.96257e-4 -0.210569 0.0104146 0.001205503 -0.210362 0.01033556 0.001013875 -0.210494 0.0104146 0.001224637 -0.2104009 0.0104146 0.001404702 -0.210254 0.01033556 0.001594305 -0.21013 0.01033556 0.001801133 -0.2100239 0.0104146 0.002232074 -0.209492 0.01033556 0.002355873 -0.209302 0.01033556 0.002463638 -0.209103 0.01033556 0.002595007 -0.208911 0.0104146 0.002684056 -0.208697 0.01050347 0.002763748 -0.208243 0.0104146 0.002778708 -0.208245 0.01050347 0.002782583 -0.2080129 0.0104146 0.002797663 -0.208014 0.01050347 0.00276333 -0.207554 0.0104146 0.002740025 -0.207324 0.01050347 0.002668678 -0.207104 0.0104146 0.002593815 -0.2068859 0.0104146 0.002607822 -0.206881 0.01050347 0.002514719 -0.206669 0.01050347 0.002265512 -0.2062799 0.0104146 0.002124011 -0.206099 0.0104146 0.002135515 -0.206089 0.01050347 0.001968026 -0.2059299 0.0104146 0.001798629 -0.205774 0.0104146 0.001424074 -0.205507 0.0104146 0.001431822 -0.205494 0.01050347 7.97322e-4 -0.205216 0.01050347 5.6987e-4 -0.205174 0.0104146 1.14022e-4 -0.205102 0.01050347 -1.16767e-4 -0.205117 0.0104146 -3.46145e-4 -0.205137 0.0104146 -3.48016e-4 -0.2051219 0.01050347 -5.73159e-4 -0.205175 0.0104146 -7.96257e-4 -0.205231 0.0104146 -8.0056e-4 -0.205217 0.01050347 -0.001013875 -0.2053059 0.0104146 -0.001019358 -0.205292 0.01050347 -0.001434683 -0.205496 0.01050347 -0.001619637 -0.2056339 0.0104146 -0.001628339 -0.205622 0.01050347 -0.00213772 -0.206092 0.01050347 -0.002279758 -0.206274 0.01050347 -0.002393245 -0.206476 0.0104146 -0.002406179 -0.206468 0.01050347 -0.002502679 -0.206678 0.0104146 -0.002595007 -0.206889 0.0104146 -0.002669632 -0.207107 0.0104146 -0.002684056 -0.207103 0.01050347 -0.002778708 -0.2075549 0.01050347 -0.002797663 -0.207786 0.01050347 -0.002782583 -0.207787 0.0104146 -0.002797484 -0.208017 0.01050347 -0.00276333 -0.2082459 0.0104146 -0.002725303 -0.208473 0.0104146 -0.002778232 -0.208248 0.01050347 -0.002740025 -0.208476 0.01050347 -0.002593815 -0.208914 0.0104146 -0.002277731 -0.209528 0.01050347 -0.002124011 -0.209701 0.0104146 -0.001978695 -0.209881 0.01050347 -0.001808345 -0.210038 0.01050347 -0.001424074 -0.2102929 0.0104146 -0.001431822 -0.210306 0.01050347 -0.001228213 -0.210416 0.01050347 -0.001010775 -0.2104949 0.0104146 -7.93036e-4 -0.21057 0.0104146 -7.97322e-4 -0.210584 0.01050347 -3.44663e-4 -0.2106789 0.01050347 -3.4281e-4 -0.210664 0.0104146 -1.14022e-4 -0.210698 0.01050347 -1.13409e-4 -0.210683 0.0104146 3.48016e-4 -0.210678 0.01050347 5.73159e-4 -0.2106249 0.0104146 0.001231253 -0.210415 0.01050347 0.001426994 -0.210292 0.0104146 0.001434683 -0.210304 0.01050347 0.001619637 -0.210166 0.0104146 0.001628339 -0.210178 0.01050347 0.00197041 -0.209868 0.0104146 0.001981079 -0.209879 0.01050347 0.002126216 -0.209699 0.0104146 0.002267479 -0.209517 0.0104146 0.002279758 -0.209526 0.01050347 0.002406179 -0.209332 0.01050347 0.002393245 -0.209324 0.0104146 -0.001453042 -0.210143 0.01027536 -0.00147587 -0.209667 0.0100618 -0.002401947 -0.209076 0.01027536 -0.002563655 -0.207138 0.01027536 -0.00249201 -0.206929 0.01027536 -0.002298295 -0.206532 0.01027536 -0.002242505 -0.206447 0.01027536 -0.002052247 -0.2061859 0.01027536 -0.001767396 -0.2064239 0.0100618 -0.001729667 -0.20586 0.01027536 -0.0013628 -0.206044 0.0100618 -1.12133e-4 -0.205228 0.01027536 4.85497e-4 -0.205649 0.0100618 8.7416e-4 -0.205375 0.01027536 0.00147587 -0.206133 0.0100618 0.00203973 -0.20617 0.01027536 0.002672076 -0.207822 0.01027536 0.002617776 -0.208447 0.01027536 0.00225085 -0.208385 0.0100618 0.002563655 -0.208662 0.01027536 0.002525091 -0.208774 0.01027536 0.002242505 -0.209353 0.01027536 0.0013628 -0.209756 0.0100618 7.15226e-4 -0.210475 0.01027536 6.16139e-4 -0.210119 0.0100618 6.72755e-5 -0.210202 0.0100618 -4.85497e-4 -0.210151 0.0100618 -8.7416e-4 -0.210425 0.01027536 -7.53268e-4 -0.210076 0.0100618 -0.001087844 -0.207781 0.009623944 0.001087844 -0.208019 0.009623944 2.40526e-4 -0.206564 0.00968784 1.19294e-4 -0.206812 0.009623944 1.00054e-4 -0.206852 0.009613811 7.90601e-5 -0.2068949 0.009602725 7.99628e-4 -0.207149 0.009621858 7.84299e-4 -0.207137 0.009623944 0.001101255 -0.206865 0.009733796 7.65059e-4 -0.207176 0.009613811 7.44065e-4 -0.207219 0.009602725 6.2403e-4 -0.207642 0.009545743 5.8841e-4 -0.207569 0.009545743 5.80237e-4 -0.2075549 0.009545743 0.001005411 -0.207979 0.009602725 0.001316487 -0.208183 0.009686291 7.63277e-4 -0.208684 0.009623944 7.51235e-4 -0.2087 0.009621858 7.23861e-4 -0.208665 0.009613811 6.80852e-4 -0.208644 0.009602725 2.57761e-4 -0.208524 0.009545743 3.311e-4 -0.208488 0.009545743 -7.90601e-5 -0.208905 0.009602725 -7.65059e-4 -0.208624 0.009613811 -7.84299e-4 -0.208663 0.009623944 -7.99628e-4 -0.208651 0.009621858 -7.44065e-4 -0.208581 0.009602725 -8.8435e-4 -0.208549 0.009621858 -6.2403e-4 -0.208158 0.009545743 -9.56175e-4 -0.208438 0.009621858 -5.8841e-4 -0.208231 0.009545743 -0.001096665 -0.2079319 0.009621858 -7.23861e-4 -0.207135 0.009613811 -7.63277e-4 -0.207116 0.009623944 -6.49373e-4 -0.207016 0.009621858 -6.80852e-4 -0.207156 0.009602725 -7.51235e-4 -0.2071 0.009621858 -2.57761e-4 -0.207276 0.009545743 -3.311e-4 -0.207312 0.009545743 -3.45223e-4 -0.20732 0.009545743 -7.61562e-4 -0.210464 0.01027536 -6.261e-4 -0.209709 0.009880781 -8.39536e-4 -0.2096199 0.009880781 -5.47252e-4 -0.210518 0.01027536 -1.08908e-4 -0.210572 0.01027536 -2.10647e-4 -0.210193 0.0100618 -1.75085e-4 -0.209806 0.009880781 -3.18605e-4 -0.209377 0.009733796 -4.03535e-4 -0.209771 0.009880781 -4.94328e-4 -0.2093279 0.009733796 5.50411e-4 -0.210517 0.01027536 3.44217e-4 -0.210177 0.0100618 5.5918e-5 -0.2098129 0.009880781 -2.82671e-4 -0.209217 0.009686291 -4.3045e-4 -0.209147 0.009680747 -6.62842e-4 -0.209258 0.009733796 -5.75764e-4 -0.20908 0.009675323 -8.21691e-4 -0.209168 0.009733796 -7.18706e-4 -0.209007 0.009680747 -8.64073e-4 -0.2089329 0.009686291 2.86106e-4 -0.209792 0.009880781 -1.38236e-4 -0.209405 0.009733796 -2.40526e-4 -0.209236 0.00968784 -1.19294e-4 -0.208988 0.009623944 0.001175999 -0.2103019 0.01027536 7.64655e-4 -0.210463 0.01027536 2.2589e-4 -0.209394 0.009733796 3.20557e-5 -0.208997 0.009621858 4.41492e-5 -0.20941 0.009733796 -1.0037e-4 -0.208993 0.009621858 -1.00054e-4 -0.208948 0.009613811 1.64013e-4 -0.208985 0.009621858 5.12121e-4 -0.209744 0.009880781 8.79076e-4 -0.2100279 0.0100618 0.001555323 -0.210076 0.01027536 9.38562e-4 -0.209568 0.009880781 0.00112915 -0.2099069 0.0100618 7.30669e-4 -0.2096689 0.009880781 4.04337e-4 -0.209356 0.009733796 1.00931e-4 -0.208568 0.009545743 8.97167e-6 -0.208725 0.009572148 8.47681e-5 -0.20857 0.009545743 1.80663e-4 -0.208551 0.009545743 4.18865e-4 -0.208914 0.009621858 2.9358e-4 -0.208957 0.009621858 5.76888e-4 -0.209297 0.009733796 7.41027e-4 -0.209217 0.009733796 0.001132726 -0.209443 0.009880781 0.001892209 -0.2097899 0.01027536 0.001829683 -0.209848 0.01027536 0.002052247 -0.209614 0.01027536 0.002041816 -0.209627 0.01027536 0.001767396 -0.209376 0.0100618 0.001576602 -0.209578 0.0100618 5.38042e-4 -0.208856 0.009621858 0.001310408 -0.209295 0.009880781 0.001034617 -0.209001 0.009733796 8.94359e-4 -0.209118 0.009733796 6.49373e-4 -0.208784 0.009621858 5.00504e-4 -0.2085559 0.009572148 3.45223e-4 -0.20848 0.009545743 0.002403378 -0.209073 0.01027536 0.002298295 -0.209268 0.01027536 0.001932382 -0.209152 0.0100618 0.001606166 -0.208941 0.009880781 0.001469016 -0.209127 0.009880781 0.001159846 -0.208869 0.009733796 0.002175927 -0.208653 0.0100618 0.002069234 -0.2089099 0.0100618 0.001719892 -0.2087399 0.009880781 0.001268088 -0.2087219 0.009733796 0.001808524 -0.208526 0.009880781 0.002672195 -0.208009 0.01027536 0.002654075 -0.208229 0.01027536 0.00187081 -0.208304 0.009880781 0.001427888 -0.208394 0.009733796 0.002301633 -0.2078329 0.0100618 0.002292931 -0.208111 0.0100618 0.002642393 -0.2075009 0.01027536 0.002653658 -0.207568 0.01027536 0.002672016 -0.207788 0.01027536 0.001913011 -0.207844 0.009880781 0.001905858 -0.208075 0.009880781 0.001477062 -0.208219 0.009733796 0.001357913 -0.208563 0.009733796 0.001247465 -0.20833 0.009680747 0.001179516 -0.208476 0.009675323 0.001106739 -0.2086189 0.009680747 0.00103271 -0.208764 0.009686291 0.00101161 -0.208806 0.00968784 0.001336216 -0.208141 0.00968784 0.001504719 -0.208038 0.009733796 0.001510381 -0.2078559 0.009733796 0.002276718 -0.207556 0.0100618 0.002490878 -0.206926 0.01027536 0.002562761 -0.207135 0.01027536 0.002218604 -0.207284 0.0100618 0.00261712 -0.20735 0.01027536 0.002128183 -0.2070209 0.0100618 0.001844048 -0.207388 0.009880781 0.00149405 -0.207674 0.009733796 0.001892328 -0.207614 0.009880781 0.001092553 -0.208 0.009621858 0.001096665 -0.207868 0.009621858 0.001048445 -0.208 0.009613811 8.25109e-4 -0.207891 0.009572148 0.001768887 -0.2071689 0.009880781 0.002401947 -0.206724 0.01027536 0.002175629 -0.206345 0.01027536 0.002296626 -0.20653 0.01027536 0.002328991 -0.206589 0.01027536 0.002006709 -0.206771 0.0100618 0.001396596 -0.207323 0.009733796 0.001455962 -0.207496 0.009733796 0.001057147 -0.207606 0.009621858 0.001084804 -0.207736 0.009621858 6.67583e-4 -0.207799 0.009545743 6.69827e-4 -0.207815 0.009545743 6.5055e-4 -0.207719 0.009545743 0.001014053 -0.207481 0.009621858 0.001667916 -0.206961 0.009880781 0.001542627 -0.206767 0.009880781 0.001855969 -0.206537 0.0100618 0.001678168 -0.206323 0.0100618 0.001316905 -0.207159 0.009733796 9.56175e-4 -0.2073619 0.009621858 0.001453042 -0.205657 0.01027536 0.0015527 -0.205722 0.01027536 0.001226723 -0.206431 0.009880781 0.001394867 -0.2065899 0.009880781 0.001217961 -0.207006 0.009733796 8.8435e-4 -0.207251 0.009621858 6.56034e-4 -0.2074 0.009572148 0.00101 -0.205831 0.0100618 0.001252055 -0.205968 0.0100618 0.001040697 -0.206294 0.009880781 7.53268e-4 -0.205724 0.0100618 8.39536e-4 -0.20618 0.009880781 6.62842e-4 -0.206542 0.009733796 2.44482e-4 -0.2052389 0.01027536 2.10647e-4 -0.2056069 0.0100618 4.03535e-4 -0.2060289 0.009880781 6.261e-4 -0.206091 0.009880781 4.94328e-4 -0.206472 0.009733796 -7.81376e-5 -0.205228 0.01027536 1.75085e-4 -0.205994 0.009880781 -3.44217e-4 -0.205623 0.0100618 -6.72755e-5 -0.2055979 0.0100618 1.38236e-4 -0.206395 0.009733796 2.82671e-4 -0.206583 0.009686291 3.18605e-4 -0.206423 0.009733796 4.3045e-4 -0.2066529 0.009680747 5.75764e-4 -0.2067199 0.009675323 8.21691e-4 -0.206632 0.009733796 7.18706e-4 -0.206793 0.009680747 8.64073e-4 -0.206867 0.009686291 9.68558e-4 -0.20674 0.009733796 9.05531e-4 -0.206888 0.00968784 1.0037e-4 -0.206807 0.009621858 -5.5918e-5 -0.205987 0.009880781 -4.41492e-5 -0.20639 0.009733796 -2.86106e-4 -0.206008 0.009880781 -7.64655e-4 -0.205337 0.01027536 -7.15226e-4 -0.205325 0.01027536 -6.16139e-4 -0.205681 0.0100618 -5.12121e-4 -0.2060559 0.009880781 -3.20557e-5 -0.206803 0.009621858 -1.64013e-4 -0.206815 0.009621858 -2.2589e-4 -0.2064059 0.009733796 -4.04337e-4 -0.206444 0.009733796 -7.30669e-4 -0.206131 0.009880781 -8.79076e-4 -0.205772 0.0100618 -0.001175999 -0.205498 0.01027536 -0.001310586 -0.2055709 0.01027536 -0.001582145 -0.205745 0.01027536 -0.001555323 -0.205724 0.01027536 -0.00112915 -0.205893 0.0100618 -5.76888e-4 -0.206503 0.009733796 -8.97167e-6 -0.2070749 0.009572148 -1.00931e-4 -0.2072319 0.009545743 -8.47681e-5 -0.20723 0.009545743 -1.80663e-4 -0.207249 0.009545743 -2.9358e-4 -0.206843 0.009621858 -9.38562e-4 -0.206232 0.009880781 -7.41027e-4 -0.206583 0.009733796 -0.002041816 -0.206173 0.01027536 -0.001829683 -0.205952 0.01027536 -0.001576602 -0.2062219 0.0100618 -0.001132726 -0.206357 0.009880781 -4.18865e-4 -0.2068859 0.009621858 -0.001932382 -0.2066479 0.0100618 -0.001469016 -0.206673 0.009880781 -0.001310408 -0.206505 0.009880781 -8.94359e-4 -0.206682 0.009733796 -5.00504e-4 -0.207244 0.009572148 -5.38042e-4 -0.206944 0.009621858 -0.002403378 -0.206727 0.01027536 -0.001159846 -0.2069309 0.009733796 -0.001034617 -0.206799 0.009733796 -0.002175927 -0.207147 0.0100618 -0.002069234 -0.20689 0.0100618 -0.001606166 -0.2068589 0.009880781 -0.00225085 -0.207415 0.0100618 -0.001719892 -0.20706 0.009880781 -0.002292931 -0.207689 0.0100618 -0.002661049 -0.207656 0.01027536 -0.002654075 -0.207571 0.01027536 -0.002617776 -0.2073529 0.01027536 -0.00187081 -0.207496 0.009880781 -0.001808524 -0.207274 0.009880781 -0.002301633 -0.207967 0.0100618 -0.001905858 -0.207725 0.009880781 -0.001427888 -0.207406 0.009733796 -0.002276718 -0.208244 0.0100618 -0.002642393 -0.208299 0.01027536 -0.002653658 -0.208232 0.01027536 -0.001913011 -0.207956 0.009880781 -0.001477062 -0.207581 0.009733796 -0.001316487 -0.207617 0.009686291 -0.001247465 -0.2074699 0.009680747 -0.001357913 -0.207237 0.009733796 -0.001179516 -0.207324 0.009675323 -0.001106739 -0.207181 0.009680747 -0.001268088 -0.207078 0.009733796 -0.00103271 -0.207036 0.009686291 -0.00101161 -0.2069939 0.00968784 -0.001336216 -0.207659 0.00968784 -0.001504719 -0.207762 0.009733796 -0.001510381 -0.207944 0.009733796 -0.002490878 -0.208874 0.01027536 -0.00261712 -0.20845 0.01027536 -0.002218604 -0.208516 0.0100618 -0.001892328 -0.208186 0.009880781 -0.001092553 -0.2078 0.009621858 -0.001048445 -0.2078 0.009613811 -0.001005411 -0.207821 0.009602725 -0.001084804 -0.208064 0.009621858 -0.00149405 -0.208126 0.009733796 -0.001844048 -0.208412 0.009880781 -0.002128183 -0.208779 0.0100618 -0.002328991 -0.209211 0.01027536 -0.001667916 -0.2088389 0.009880781 -0.002006709 -0.209029 0.0100618 -0.001768887 -0.208631 0.009880781 -0.001455962 -0.208304 0.009733796 -0.001396596 -0.208477 0.009733796 -0.001057147 -0.208194 0.009621858 -8.25109e-4 -0.207909 0.009572148 -6.69827e-4 -0.207985 0.009545743 -6.67583e-4 -0.208001 0.009545743 -0.001014053 -0.208319 0.009621858 -0.001542627 -0.209033 0.009880781 -0.001855969 -0.209263 0.0100618 -0.001727223 -0.209942 0.01027536 -0.00203973 -0.20963 0.01027536 -0.001678168 -0.209477 0.0100618 -0.001217961 -0.2087939 0.009733796 -0.001316905 -0.2086409 0.009733796 -6.5055e-4 -0.208081 0.009545743 -0.001252055 -0.209832 0.0100618 -0.001394867 -0.20921 0.009880781 -0.001101255 -0.208935 0.009733796 -6.56034e-4 -0.208401 0.009572148 -5.80237e-4 -0.208245 0.009545743 -0.00101 -0.209969 0.0100618 -0.001040697 -0.209506 0.009880781 -0.001226723 -0.209369 0.009880781 -9.68558e-4 -0.20906 0.009733796 -9.05531e-4 -0.208912 0.00968784 -0.179706 -0.10351 0.01124995 -0.179708 -0.103485 0.01097637 -0.179714 -0.103398 0.01124995 -0.179768 -0.102621 0.00968784 -0.179716 -0.1033779 0.009744763 -0.179743 -0.102988 0.009602725 -0.179729 -0.103189 0.009572148 -0.179852 -0.106743 0.01189994 -0.179395 -0.106673 0.01189994 -0.178956 -0.1065289 0.01189994 -0.178546 -0.106314 0.01189994 -0.178546 -0.106314 0.01050347 -0.178178 -0.106035 0.01189994 -0.178012 -0.105873 0.01050347 -0.17786 -0.105699 0.01189994 -0.17786 -0.105699 0.01050347 -0.177723 -0.105512 0.01050347 -0.1776019 -0.105315 0.01050347 -0.1776019 -0.105315 0.01189994 -0.177411 -0.104894 0.01050347 -0.177411 -0.104894 0.01189994 -0.177291 -0.104447 0.01189994 -0.177247 -0.103987 0.01189994 -0.1773239 -0.103298 0.01050347 -0.1772789 -0.1035259 0.01189994 -0.1773869 -0.103076 0.01189994 -0.1773869 -0.103076 0.01050347 -0.177567 -0.10265 0.01189994 -0.177567 -0.10265 0.01050347 -0.177815 -0.102259 0.01189994 -0.177962 -0.102081 0.01050347 -0.1781229 -0.101915 0.01189994 -0.1782979 -0.101763 0.01050347 -0.178484 -0.101626 0.01189994 -0.178682 -0.101505 0.01050347 -0.178888 -0.101401 0.01050347 -0.178888 -0.101401 0.01189994 -0.179324 -0.101245 0.01189994 -0.179103 -0.101314 0.01050347 -0.179324 -0.101245 0.01050347 -0.179549 -0.101195 0.01050347 -0.1797789 -0.101163 0.01189994 -0.180241 -0.101157 0.01050347 -0.180241 -0.101157 0.01189994 -0.180698 -0.101227 0.01050347 -0.180698 -0.101227 0.01189994 -0.181138 -0.101371 0.01189994 -0.181547 -0.101586 0.01189994 -0.1819159 -0.101865 0.01189994 -0.182233 -0.102201 0.01189994 -0.18237 -0.102388 0.01050347 -0.182491 -0.102585 0.01050347 -0.182491 -0.102585 0.01189994 -0.182596 -0.102792 0.01050347 -0.182683 -0.103006 0.01189994 -0.182752 -0.103227 0.01050347 -0.182802 -0.103453 0.01189994 -0.182846 -0.103913 0.01189994 -0.182834 -0.103682 0.01050347 -0.1828399 -0.104144 0.01050347 -0.182814 -0.104374 0.01189994 -0.18277 -0.104602 0.01050347 -0.182707 -0.104824 0.01050347 -0.182707 -0.104824 0.01189994 -0.182527 -0.10525 0.01189994 -0.1826249 -0.105041 0.01050347 -0.182279 -0.105641 0.01189994 -0.182132 -0.105819 0.01050347 -0.18197 -0.105985 0.01189994 -0.181609 -0.106274 0.01050347 -0.181609 -0.106274 0.01189994 -0.181205 -0.106499 0.01050347 -0.181205 -0.106499 0.01189994 -0.18077 -0.106655 0.01189994 -0.1809909 -0.106586 0.01050347 -0.18077 -0.106655 0.01050347 -0.180315 -0.106737 0.01189994 -0.180315 -0.106737 0.01050347 -0.1796219 -0.106718 0.01050347 -0.179005 -0.106413 0.01027536 -0.178643 -0.106225 0.01027536 -0.178578 -0.106265 0.01033556 -0.178432 -0.106082 0.01027536 -0.17838 -0.106039 0.01027536 -0.178391 -0.106135 0.01033556 -0.1782169 -0.105991 0.01033556 -0.178261 -0.1059409 0.01027536 -0.178054 -0.105833 0.01033556 -0.17814 -0.105823 0.01027536 -0.177958 -0.10562 0.01027536 -0.177928 -0.105579 0.01027536 -0.177747 -0.105312 0.01027536 -0.177653 -0.105286 0.01033556 -0.177551 -0.105084 0.01033556 -0.177466 -0.104874 0.01033556 -0.177529 -0.104852 0.01027536 -0.1774629 -0.104641 0.01027536 -0.177415 -0.104425 0.01027536 -0.177412 -0.104408 0.01027536 -0.177318 -0.104212 0.01033556 -0.177305 -0.103986 0.01033556 -0.177312 -0.10376 0.01033556 -0.177403 -0.103545 0.01027536 -0.177501 -0.1031309 0.01027536 -0.1775839 -0.102908 0.01027536 -0.1776199 -0.102831 0.01027536 -0.177619 -0.102677 0.01033556 -0.177789 -0.102517 0.01027536 -0.177861 -0.102295 0.01033556 -0.178055 -0.102165 0.01027536 -0.17821 -0.102006 0.01027536 -0.178376 -0.101861 0.01027536 -0.1783339 -0.101809 0.01033556 -0.178417 -0.101831 0.01027536 -0.178517 -0.101675 0.01033556 -0.17871 -0.101556 0.01033556 -0.178972 -0.101502 0.01027536 -0.179339 -0.101302 0.01033556 -0.179275 -0.101392 0.01027536 -0.179572 -0.101318 0.01027536 -0.179589 -0.101316 0.01027536 -0.1797839 -0.101221 0.01033556 -0.180011 -0.101209 0.01033556 -0.17991 -0.101281 0.01027536 -0.180232 -0.101282 0.01027536 -0.1802369 -0.101215 0.01033556 -0.180669 -0.1013489 0.01027536 -0.180685 -0.101284 0.01033556 -0.180865 -0.101405 0.01027536 -0.180903 -0.101346 0.01033556 -0.181115 -0.101425 0.01033556 -0.18132 -0.101522 0.01033556 -0.181288 -0.101581 0.01027536 -0.181516 -0.101635 0.01033556 -0.18145 -0.101675 0.01027536 -0.181702 -0.101765 0.01033556 -0.181877 -0.101909 0.01033556 -0.1817139 -0.101861 0.01027536 -0.181832 -0.101959 0.01027536 -0.181954 -0.102077 0.01027536 -0.182135 -0.10228 0.01027536 -0.182039 -0.102067 0.01033556 -0.182166 -0.102321 0.01027536 -0.182322 -0.10242 0.01033556 -0.1822659 -0.102458 0.01027536 -0.182481 -0.1028439 0.01027536 -0.182543 -0.102816 0.01033556 -0.18263 -0.103259 0.01027536 -0.182695 -0.103242 0.01033556 -0.182788 -0.103914 0.01033556 -0.182709 -0.103694 0.01027536 -0.1827149 -0.104136 0.01027536 -0.1827819 -0.10414 0.01033556 -0.18269 -0.104355 0.01027536 -0.182592 -0.104769 0.01027536 -0.182572 -0.105018 0.01033556 -0.182473 -0.105069 0.01027536 -0.182415 -0.105192 0.01027536 -0.182305 -0.105383 0.01027536 -0.182088 -0.10578 0.01033556 -0.182135 -0.105617 0.01027536 -0.18193 -0.105942 0.01033556 -0.181919 -0.105857 0.01027536 -0.181717 -0.106039 0.01027536 -0.1817589 -0.106091 0.01033556 -0.181576 -0.106225 0.01033556 -0.181676 -0.106069 0.01027536 -0.1811529 -0.106385 0.01027536 -0.181383 -0.106344 0.01033556 -0.181181 -0.106446 0.01033556 -0.180971 -0.106531 0.01033556 -0.181122 -0.106398 0.01027536 -0.180755 -0.106598 0.01033556 -0.180818 -0.106508 0.01027536 -0.180737 -0.106534 0.01027536 -0.180505 -0.106584 0.01027536 -0.180184 -0.106619 0.01027536 -0.179856 -0.106685 0.01033556 -0.1796309 -0.10666 0.01033556 -0.179541 -0.1065739 0.01027536 -0.179228 -0.106495 0.01027536 -0.180083 -0.106735 0.0104146 -0.179853 -0.106728 0.0104146 -0.179625 -0.106703 0.0104146 -0.179409 -0.106616 0.01033556 -0.1791909 -0.106554 0.01033556 -0.178979 -0.106475 0.01033556 -0.1787739 -0.106378 0.01033556 -0.178754 -0.106417 0.0104146 -0.1785539 -0.106301 0.0104146 -0.178188 -0.106024 0.0104146 -0.178023 -0.105863 0.0104146 -0.177906 -0.105662 0.01033556 -0.177772 -0.10548 0.01033556 -0.177615 -0.1053079 0.0104146 -0.177511 -0.105102 0.0104146 -0.177425 -0.104889 0.0104146 -0.177398 -0.104658 0.01033556 -0.177356 -0.104669 0.0104146 -0.177349 -0.104437 0.01033556 -0.177262 -0.103987 0.0104146 -0.177337 -0.103534 0.01033556 -0.177294 -0.103528 0.0104146 -0.177338 -0.103302 0.0104146 -0.17738 -0.103312 0.01033556 -0.177442 -0.103094 0.01033556 -0.177522 -0.102882 0.01033556 -0.177482 -0.102865 0.0104146 -0.177732 -0.102481 0.01033556 -0.178005 -0.10212 0.01033556 -0.178164 -0.101958 0.01033556 -0.178912 -0.101454 0.01033556 -0.178894 -0.101415 0.0104146 -0.179122 -0.101369 0.01033556 -0.179328 -0.10126 0.0104146 -0.17956 -0.101252 0.01033556 -0.17978 -0.101178 0.0104146 -0.180462 -0.10124 0.01033556 -0.180916 -0.101304 0.0104146 -0.181132 -0.1013849 0.0104146 -0.1815389 -0.101599 0.0104146 -0.182188 -0.1022379 0.01033556 -0.18244 -0.102614 0.01033556 -0.182478 -0.102592 0.0104146 -0.182582 -0.102798 0.0104146 -0.182628 -0.103026 0.01033556 -0.182669 -0.103011 0.0104146 -0.182745 -0.103463 0.01033556 -0.182819 -0.103683 0.0104146 -0.182776 -0.103688 0.01033556 -0.182825 -0.104143 0.0104146 -0.182756 -0.104366 0.01033556 -0.182713 -0.104588 0.01033556 -0.182651 -0.104806 0.01033556 -0.182475 -0.105223 0.01033556 -0.182361 -0.105419 0.01033556 -0.1825129 -0.105243 0.0104146 -0.182232 -0.105605 0.01033556 -0.181786 -0.1061249 0.0104146 -0.1814039 -0.106382 0.0104146 -0.180986 -0.106572 0.0104146 -0.180766 -0.10664 0.0104146 -0.180533 -0.106648 0.01033556 -0.1803089 -0.106679 0.01033556 -0.180313 -0.1067219 0.0104146 -0.180083 -0.106691 0.01033556 -0.180084 -0.10675 0.01050347 -0.179852 -0.106743 0.01050347 -0.179399 -0.106659 0.0104146 -0.179395 -0.106673 0.01050347 -0.179177 -0.106596 0.0104146 -0.179172 -0.10661 0.01050347 -0.1789619 -0.106515 0.0104146 -0.178956 -0.1065289 0.01050347 -0.1787469 -0.1064299 0.01050347 -0.1783649 -0.1061699 0.0104146 -0.178356 -0.106182 0.01050347 -0.178178 -0.106035 0.01050347 -0.177872 -0.105689 0.0104146 -0.177735 -0.105504 0.0104146 -0.177498 -0.105108 0.01050347 -0.1773419 -0.104673 0.01050347 -0.1773059 -0.104445 0.0104146 -0.177291 -0.104447 0.01050347 -0.177275 -0.104217 0.0104146 -0.17726 -0.104218 0.01050347 -0.177247 -0.103987 0.01050347 -0.177253 -0.103756 0.01050347 -0.177268 -0.103757 0.0104146 -0.1772789 -0.1035259 0.01050347 -0.177401 -0.103081 0.0104146 -0.177468 -0.102859 0.01050347 -0.1775799 -0.102657 0.0104146 -0.1776829 -0.10245 0.01050347 -0.177695 -0.102458 0.0104146 -0.177815 -0.102259 0.01050347 -0.177827 -0.102269 0.0104146 -0.177973 -0.102091 0.0104146 -0.1781229 -0.101915 0.01050347 -0.178134 -0.101926 0.0104146 -0.1783069 -0.101775 0.0104146 -0.178493 -0.101639 0.0104146 -0.178484 -0.101626 0.01050347 -0.178689 -0.101518 0.0104146 -0.179108 -0.101328 0.0104146 -0.179552 -0.101209 0.0104146 -0.1797789 -0.101163 0.01050347 -0.18001 -0.1011649 0.0104146 -0.18001 -0.10115 0.01050347 -0.18024 -0.101172 0.0104146 -0.180471 -0.101182 0.01050347 -0.180469 -0.101197 0.0104146 -0.1806949 -0.101241 0.0104146 -0.180921 -0.10129 0.01050347 -0.181138 -0.101371 0.01050347 -0.18134 -0.101483 0.0104146 -0.181347 -0.10147 0.01050347 -0.181547 -0.101586 0.01050347 -0.181728 -0.10173 0.0104146 -0.181906 -0.101876 0.0104146 -0.181737 -0.101718 0.01050347 -0.182071 -0.102037 0.0104146 -0.1819159 -0.101865 0.01050347 -0.1820819 -0.1020269 0.01050347 -0.182233 -0.102201 0.01050347 -0.182222 -0.1022109 0.0104146 -0.182358 -0.102396 0.0104146 -0.182683 -0.103006 0.01050347 -0.1827369 -0.103231 0.0104146 -0.182802 -0.103453 0.01050347 -0.182787 -0.103455 0.0104146 -0.182846 -0.103913 0.01050347 -0.182831 -0.103913 0.0104146 -0.182814 -0.104374 0.01050347 -0.182799 -0.104372 0.0104146 -0.1827549 -0.104598 0.0104146 -0.182692 -0.1048189 0.0104146 -0.182612 -0.105035 0.0104146 -0.182527 -0.10525 0.01050347 -0.182411 -0.10545 0.01050347 -0.182398 -0.105442 0.0104146 -0.182279 -0.105641 0.01050347 -0.182267 -0.105631 0.0104146 -0.18212 -0.105809 0.0104146 -0.18196 -0.105974 0.0104146 -0.18197 -0.105985 0.01050347 -0.181795 -0.106137 0.01050347 -0.1816 -0.106261 0.0104146 -0.181412 -0.106395 0.01050347 -0.181199 -0.106485 0.0104146 -0.180544 -0.106706 0.01050347 -0.180541 -0.106691 0.0104146 -0.1827149 -0.103813 0.01027536 -0.18199 -0.102113 0.01027536 -0.1814799 -0.101692 0.01027536 -0.178555 -0.101731 0.01027536 -0.177772 -0.102546 0.01027536 -0.177506 -0.103115 0.01027536 -0.177423 -0.103444 0.01027536 -0.177379 -0.1037639 0.01027536 -0.177373 -0.103985 0.01027536 -0.177747 -0.104068 0.0100618 -0.179212 -0.106491 0.01027536 -0.179424 -0.106551 0.01027536 -0.179641 -0.106594 0.01027536 -0.179861 -0.106618 0.01027536 -0.1798869 -0.106247 0.0100618 -0.180303 -0.106612 0.01027536 -0.182322 -0.105354 0.01027536 -0.182587 -0.104785 0.01027536 -0.182648 -0.1045719 0.01027536 -0.179045 -0.103509 0.009623944 -0.17905 -0.103491 0.009621858 -0.179136 -0.103516 0.009602725 -0.179037 -0.104251 0.009613811 -0.179085 -0.104254 0.009602725 -0.178996 -0.104267 0.009621858 -0.179042 -0.104391 0.009621858 -0.179285 -0.104268 0.009572148 -0.179511 -0.104362 0.009545743 -0.179466 -0.104294 0.009545743 -0.179458 -0.1042799 0.009545743 -0.179587 -0.105227 0.00968784 -0.180364 -0.105 0.009621858 -0.180347 -0.104959 0.009613811 -0.180351 -0.104912 0.009602725 -0.180365 -0.1047109 0.009572148 -0.180391 -0.104531 0.009545743 -0.180606 -0.104894 0.009621858 -0.180377 -0.104539 0.009545743 -0.18098 -0.104526 0.009621858 -0.181056 -0.103649 0.009613811 -0.1811 -0.103652 0.009623944 -0.181097 -0.103633 0.009621858 -0.181008 -0.103646 0.009602725 -0.180582 -0.103538 0.009545743 -0.180628 -0.103606 0.009545743 -0.18046 -0.102669 0.009686291 -0.179746 -0.102941 0.009613811 -0.1797299 -0.1029 0.009621858 -0.1797029 -0.1033689 0.009545743 -0.179717 -0.103361 0.009545743 -0.182671 -0.104456 0.01027536 -0.182308 -0.104386 0.0100618 -0.1819559 -0.104083 0.009880781 -0.181926 -0.104312 0.009880781 -0.181554 -0.104055 0.009733796 -0.182138 -0.104914 0.0100618 -0.18251 -0.104992 0.01027536 -0.1822389 -0.104655 0.0100618 -0.181869 -0.1045359 0.009880781 -0.1815299 -0.104236 0.009733796 -0.182038 -0.105735 0.01027536 -0.182179 -0.105565 0.01027536 -0.182006 -0.105159 0.0100618 -0.181785 -0.104751 0.009880781 -0.1814849 -0.104413 0.009733796 -0.1813279 -0.104363 0.009686291 -0.181342 -0.104201 0.009680747 -0.181356 -0.104041 0.009675323 -0.181556 -0.103872 0.009733796 -0.181365 -0.103881 0.009680747 -0.181373 -0.103718 0.009686291 -0.181376 -0.103672 0.00968784 -0.181419 -0.104583 0.009733796 -0.181333 -0.104743 0.009733796 -0.181675 -0.104955 0.009880781 -0.181846 -0.105386 0.0100618 -0.1816599 -0.105593 0.0100618 -0.181884 -0.105894 0.01027536 -0.181388 -0.105316 0.009880781 -0.181542 -0.105144 0.009880781 -0.181228 -0.104893 0.009733796 -0.181043 -0.104409 0.009621858 -0.180757 -0.1043699 0.009572148 -0.180904 -0.104634 0.009621858 -0.18145 -0.1057749 0.0100618 -0.181213 -0.105467 0.009880781 -0.1812199 -0.105931 0.0100618 -0.1813499 -0.106285 0.01027536 -0.181408 -0.10625 0.01027536 -0.1815389 -0.106169 0.01027536 -0.1809729 -0.106058 0.0100618 -0.181022 -0.105597 0.009880781 -0.180968 -0.105148 0.009733796 -0.181105 -0.105028 0.009733796 -0.180815 -0.104733 0.009621858 -0.1805739 -0.104371 0.009545743 -0.180584 -0.104358 0.009545743 -0.180715 -0.10482 0.009621858 -0.180817 -0.10525 0.009733796 -0.180948 -0.106468 0.01027536 -0.180441 -0.106219 0.0100618 -0.180522 -0.106582 0.01027536 -0.180712 -0.106154 0.0100618 -0.1808159 -0.105702 0.009880781 -0.180654 -0.105334 0.009733796 -0.180458 -0.104485 0.009545743 -0.1805199 -0.104432 0.009545743 -0.1801649 -0.10625 0.0100618 -0.180375 -0.105836 0.009880781 -0.180599 -0.105782 0.009880781 -0.180483 -0.105397 0.009733796 -0.180488 -0.104955 0.009621858 -0.180082 -0.106624 0.01027536 -0.180145 -0.105861 0.009880781 -0.180344 -0.1050029 0.009623944 -0.179611 -0.106211 0.0100618 -0.1799139 -0.105859 0.009880781 -0.180306 -0.105439 0.009733796 -0.1796849 -0.105829 0.009880781 -0.178928 -0.106377 0.01027536 -0.179083 -0.106041 0.0100618 -0.179342 -0.106142 0.0100618 -0.1797609 -0.105434 0.009733796 -0.179942 -0.105457 0.009733796 -0.178838 -0.10591 0.0100618 -0.1788049 -0.106319 0.01027536 -0.179461 -0.105772 0.009880781 -0.178614 -0.106208 0.01027536 -0.17861 -0.10575 0.0100618 -0.1792449 -0.105688 0.009880781 -0.179633 -0.105231 0.009686291 -0.179584 -0.1053889 0.009733796 -0.179796 -0.105246 0.009680747 -0.179956 -0.105259 0.009675323 -0.180124 -0.105459 0.009733796 -0.1801159 -0.105268 0.009680747 -0.180279 -0.105276 0.009686291 -0.180325 -0.105279 0.00968784 -0.178853 -0.105446 0.009880781 -0.179042 -0.105579 0.009880781 -0.179414 -0.105322 0.009733796 -0.178103 -0.105787 0.01027536 -0.178404 -0.105563 0.0100618 -0.179253 -0.105236 0.009733796 -0.179609 -0.104908 0.009613811 -0.179587 -0.104946 0.009621858 -0.179606 -0.104952 0.009623944 -0.179612 -0.10486 0.009602725 -0.179471 -0.104884 0.009621858 -0.179104 -0.105131 0.009733796 -0.178681 -0.105291 0.009880781 -0.178065 -0.105123 0.0100618 -0.178221 -0.105354 0.0100618 -0.177712 -0.105254 0.01027536 -0.177827 -0.105442 0.01027536 -0.177599 -0.105025 0.01027536 -0.177938 -0.104876 0.0100618 -0.177612 -0.105056 0.01027536 -0.1784 -0.104925 0.009880781 -0.178529 -0.105117 0.009880781 -0.178849 -0.104871 0.009733796 -0.178969 -0.105009 0.009733796 -0.179264 -0.104719 0.009621858 -0.179625 -0.104478 0.009545743 -0.1793619 -0.104807 0.009621858 -0.179626 -0.10466 0.009572148 -0.179638 -0.104488 0.009545743 -0.179177 -0.104619 0.009621858 -0.178294 -0.1047199 0.009880781 -0.177842 -0.104615 0.0100618 -0.177488 -0.104722 0.01027536 -0.177778 -0.104344 0.0100618 -0.178214 -0.104503 0.009880781 -0.178663 -0.104558 0.009733796 -0.178746 -0.1047199 0.009733796 -0.179103 -0.104509 0.009621858 -0.179565 -0.104423 0.009545743 -0.1773779 -0.104087 0.01027536 -0.177385 -0.104206 0.01027536 -0.1786 -0.104386 0.009733796 -0.178161 -0.104278 0.009880781 -0.178718 -0.104228 0.00968784 -0.1789939 -0.104248 0.009623944 -0.1777859 -0.103514 0.0100618 -0.1777499 -0.10379 0.0100618 -0.178538 -0.104028 0.009733796 -0.178135 -0.104048 0.009880781 -0.178558 -0.104209 0.009733796 -0.177446 -0.103328 0.01027536 -0.177855 -0.103245 0.0100618 -0.178167 -0.103588 0.009880781 -0.178137 -0.103817 0.009880781 -0.178539 -0.103845 0.009733796 -0.178225 -0.103364 0.009880781 -0.1785629 -0.103664 0.009733796 -0.177678 -0.102708 0.01027536 -0.1780869 -0.102741 0.0100618 -0.177956 -0.102986 0.0100618 -0.177958 -0.102283 0.01027536 -0.177915 -0.102335 0.01027536 -0.178247 -0.102514 0.0100618 -0.178309 -0.1031489 0.009880781 -0.178608 -0.103487 0.009733796 -0.1787649 -0.103537 0.009686291 -0.178751 -0.103699 0.009680747 -0.178737 -0.103859 0.009675323 -0.1787289 -0.104019 0.009680747 -0.1787199 -0.104182 0.009686291 -0.1787689 -0.1034899 0.00968784 -0.178674 -0.103317 0.009733796 -0.178418 -0.102945 0.009880781 -0.178761 -0.103157 0.009733796 -0.178174 -0.102043 0.01027536 -0.178643 -0.102125 0.0100618 -0.178706 -0.102584 0.009880781 -0.178433 -0.102307 0.0100618 -0.178551 -0.102756 0.009880781 -0.179113 -0.103374 0.009621858 -0.179089 -0.103512 0.009613811 -0.179337 -0.10353 0.009572148 -0.178866 -0.103007 0.009733796 -0.17888 -0.102433 0.009880781 -0.178743 -0.101615 0.01027536 -0.178685 -0.1016499 0.01027536 -0.1789399 -0.101515 0.01027536 -0.178873 -0.101969 0.0100618 -0.179071 -0.102303 0.009880781 -0.178988 -0.102872 0.009733796 -0.179278 -0.1031669 0.009621858 -0.179189 -0.103266 0.009621858 -0.1795189 -0.103529 0.009545743 -0.179509 -0.103542 0.009545743 -0.179126 -0.102752 0.009733796 -0.179277 -0.10265 0.009733796 -0.179277 -0.102198 0.009880781 -0.179121 -0.101842 0.0100618 -0.179382 -0.101746 0.0100618 -0.179356 -0.101366 0.01027536 -0.179145 -0.101432 0.01027536 -0.179494 -0.102118 0.009880781 -0.179378 -0.10308 0.009621858 -0.179635 -0.103415 0.009545743 -0.179574 -0.103468 0.009545743 -0.179791 -0.101288 0.01027536 -0.179652 -0.101681 0.0100618 -0.179719 -0.102064 0.009880781 -0.179605 -0.102945 0.009621858 -0.179439 -0.102566 0.009733796 -0.179488 -0.103006 0.009621858 -0.180011 -0.101276 0.01027536 -0.179929 -0.1016499 0.0100618 -0.179948 -0.102039 0.009880781 -0.1797879 -0.102461 0.009733796 -0.17961 -0.102503 0.009733796 -0.179749 -0.102897 0.009623944 -0.180552 -0.101326 0.01027536 -0.180452 -0.101306 0.01027536 -0.180207 -0.101653 0.0100618 -0.18018 -0.102041 0.009880781 -0.180482 -0.101689 0.0100618 -0.180409 -0.102071 0.009880781 -0.181165 -0.101523 0.01027536 -0.181089 -0.101487 0.01027536 -0.180882 -0.101409 0.01027536 -0.180752 -0.101758 0.0100618 -0.180633 -0.102128 0.009880781 -0.181011 -0.101859 0.0100618 -0.180509 -0.102511 0.009733796 -0.181661 -0.101818 0.01027536 -0.181483 -0.10215 0.0100618 -0.1812559 -0.10199 0.0100618 -0.180848 -0.102212 0.009880781 -0.180679 -0.102578 0.009733796 -0.180333 -0.102466 0.009733796 -0.180298 -0.102654 0.009680747 -0.180138 -0.102641 0.009675323 -0.1801519 -0.102443 0.009733796 -0.179969 -0.102441 0.009733796 -0.179978 -0.102632 0.009680747 -0.1798149 -0.1026239 0.009686291 -0.18169 -0.102337 0.0100618 -0.181241 -0.102454 0.009880781 -0.181052 -0.102321 0.009880781 -0.180506 -0.102673 0.00968784 -0.180487 -0.102948 0.009623944 -0.181872 -0.102546 0.0100618 -0.18084 -0.102664 0.009733796 -0.180506 -0.102954 0.009621858 -0.1804839 -0.1029919 0.009613811 -0.180481 -0.10304 0.009602725 -0.1806229 -0.103016 0.009621858 -0.180467 -0.10324 0.009572148 -0.1807309 -0.103093 0.009621858 -0.180989 -0.102769 0.009733796 -0.181412 -0.102609 0.009880781 -0.181564 -0.102783 0.009880781 -0.182382 -0.102646 0.01027536 -0.1820279 -0.102777 0.0100618 -0.182346 -0.1025879 0.01027536 -0.182494 -0.102875 0.01027536 -0.182155 -0.103024 0.0100618 -0.181245 -0.103029 0.009733796 -0.181125 -0.102891 0.009733796 -0.180468 -0.103422 0.009545743 -0.180455 -0.103412 0.009545743 -0.180528 -0.103477 0.009545743 -0.180916 -0.103281 0.009621858 -0.18083 -0.103181 0.009621858 -0.181693 -0.102975 0.009880781 -0.182251 -0.103285 0.0100618 -0.182565 -0.103048 0.01027536 -0.182605 -0.103178 0.01027536 -0.182681 -0.103492 0.01027536 -0.1826789 -0.103475 0.01027536 -0.182315 -0.103556 0.0100618 -0.181879 -0.103397 0.009880781 -0.1817989 -0.10318 0.009880781 -0.181347 -0.10318 0.009733796 -0.182346 -0.103832 0.0100618 -0.18143 -0.1033419 0.009733796 -0.181051 -0.103509 0.009621858 -0.180808 -0.103632 0.009572148 -0.1809909 -0.103391 0.009621858 -0.180636 -0.10362 0.009545743 -0.182344 -0.10411 0.0100618 -0.182721 -0.103915 0.01027536 -0.181958 -0.103852 0.009880781 -0.181932 -0.103622 0.009880781 -0.181535 -0.103691 0.009733796 -0.181493 -0.103514 0.009733796 -0.1805469 -0.104356 0.01124995 -0.180435 -0.104348 0.01124995 -0.18046 -0.10435 0.01097637 -0.181324 -0.10441 0.00968784 -0.180568 -0.104357 0.009744763 -0.180957 -0.104384 0.009602725 -0.181005 -0.1043879 0.009613811 -0.181048 -0.104391 0.009623944 0.157742 -0.09557825 0.007899999 0.157817 -0.09541517 0.01189994 0.157921 -0.09507209 0.007899999 0.157921 -0.09507209 0.01189994 0.157962 -0.09471595 0.01189994 0.157939 -0.0943582 0.01189994 0.157853 -0.09401017 0.01189994 0.157853 -0.09401017 0.007899999 0.157706 -0.09368318 0.007899999 0.157706 -0.09368318 0.01189994 0.157503 -0.09338766 0.01189994 0.157503 -0.09338766 0.007899999 0.156956 -0.09292811 0.007899999 0.15725 -0.09313327 0.01189994 0.156956 -0.09292811 0.01189994 0.15663 -0.09277868 0.01189994 0.156283 -0.09268981 0.007899999 0.156283 -0.09268981 0.01189994 0.155925 -0.09266448 0.007899999 0.155925 -0.09266448 0.01189994 0.155569 -0.0927034 0.007899999 0.155569 -0.0927034 0.01189994 0.155225 -0.09280526 0.01189994 0.154905 -0.09296685 0.007899999 0.154905 -0.09296685 0.01189994 0.154619 -0.0931831 0.007899999 0.154619 -0.0931831 0.01189994 0.154376 -0.09344696 0.01189994 0.154376 -0.09344696 0.007899999 0.154184 -0.09374988 0.01189994 0.1540499 -0.09408217 0.01189994 0.153976 -0.09443318 0.007899999 0.153976 -0.09443318 0.01189994 0.153967 -0.09479171 0.01189994 0.154022 -0.095146 0.01189994 0.154139 -0.09548479 0.007899999 0.154139 -0.09548479 0.01189994 0.1543149 -0.0957973 0.01189994 0.1545439 -0.09607338 0.01189994 0.1548179 -0.09630405 0.01189994 0.15513 -0.09648215 0.01189994 0.155468 -0.09660178 0.01189994 0.155822 -0.09665906 0.007899999 0.155822 -0.09665906 0.01189994 0.15618 -0.09665226 0.01189994 0.156532 -0.09658157 0.007899999 0.156532 -0.09658157 0.01189994 0.156865 -0.09644925 0.01189994 0.157169 -0.09625959 0.01189994 0.1574349 -0.09601855 0.01189994 0.157653 -0.09573405 0.01189994 0.157742 -0.09557825 0.01189994 0.15513 -0.09648215 0.007899999 0.1548179 -0.09630405 0.007899999 0.1545439 -0.09607338 0.007899999 0.155928 -0.09566348 0.007899999 0.15618 -0.09665226 0.007899999 0.155468 -0.09660178 0.007899999 0.1574349 -0.09601855 0.007899999 0.157169 -0.09625959 0.007899999 0.1566219 -0.09541648 0.007899999 0.156414 -0.09555667 0.007899999 0.156865 -0.09644925 0.007899999 0.1561779 -0.09564077 0.007899999 0.1540499 -0.09408217 0.007899999 0.154184 -0.09374988 0.007899999 0.1543149 -0.0957973 0.007899999 0.155101 -0.09517008 0.007899999 0.1550019 -0.0949397 0.007899999 0.154022 -0.095146 0.007899999 0.153967 -0.09479171 0.007899999 0.156903 -0.0950061 0.007899999 0.157817 -0.09541517 0.007899999 0.156852 -0.0951212 0.007899999 0.156788 -0.09522908 0.007899999 0.157653 -0.09573405 0.007899999 0.156755 -0.09405398 0.007899999 0.156951 -0.09451109 0.007899999 0.157939 -0.0943582 0.007899999 0.157962 -0.09471595 0.007899999 0.156958 -0.09476166 0.007899999 0.155872 -0.09366816 0.007899999 0.155215 -0.09400016 0.007899999 0.155404 -0.09383505 0.007899999 0.155225 -0.09280526 0.007899999 0.15663 -0.09277868 0.007899999 0.15725 -0.09313327 0.007899999 0.156788 -0.09522908 0.01189994 0.1566219 -0.09541648 0.01189994 0.156414 -0.09555667 0.01189994 0.1561779 -0.09564077 0.01189994 0.155928 -0.09566348 0.01189994 0.155681 -0.09562337 0.007899999 0.155681 -0.09562337 0.01189994 0.1554509 -0.09552305 0.01189994 0.1554509 -0.09552305 0.007899999 0.1552529 -0.09536868 0.01189994 0.1552529 -0.09536868 0.007899999 0.155101 -0.09517008 0.01189994 0.1550019 -0.0949397 0.01189994 0.154963 -0.09469199 0.007899999 0.154988 -0.09444248 0.007899999 0.154963 -0.09469199 0.01189994 0.154988 -0.09444248 0.01189994 0.155074 -0.09420698 0.007899999 0.155074 -0.09420698 0.01189994 0.155215 -0.09400016 0.01189994 0.155404 -0.09383505 0.01189994 0.155628 -0.09372198 0.007899999 0.155628 -0.09372198 0.01189994 0.155872 -0.09366816 0.01189994 0.156123 -0.09367698 0.007899999 0.156123 -0.09367698 0.01189994 0.156363 -0.09374767 0.007899999 0.156363 -0.09374767 0.01189994 0.156579 -0.09387606 0.01189994 0.156579 -0.09387606 0.007899999 0.156755 -0.09405398 0.01189994 0.156882 -0.09427016 0.007899999 0.156882 -0.09427016 0.01189994 0.156951 -0.09451109 0.01189994 0.156958 -0.09476166 0.01189994 0.156903 -0.0950061 0.01189994 0.156852 -0.0951212 0.01189994 -0.003902316 -0.1843979 0.007899999 -0.003723621 -0.184381 0.01189994 -0.003374397 -0.1843 0.007899999 -0.003374397 -0.1843 0.01189994 -0.00304526 -0.184157 0.01189994 -0.00274676 -0.183959 0.01189994 -0.002488613 -0.18371 0.01189994 -0.002488613 -0.18371 0.007899999 -0.002278983 -0.183419 0.01189994 -0.002124726 -0.183095 0.007899999 -0.002124726 -0.183095 0.01189994 -0.001999974 -0.182392 0.007899999 -0.00203073 -0.182749 0.01189994 -0.001999974 -0.182392 0.01189994 -0.002033531 -0.182035 0.007899999 -0.002033531 -0.182035 0.01189994 -0.002130329 -0.18169 0.01189994 -0.002287149 -0.181367 0.01189994 -0.002499043 -0.181078 0.007899999 -0.002499043 -0.181078 0.01189994 -0.002759218 -0.180831 0.01189994 -0.003059267 -0.180635 0.01189994 -0.003389477 -0.180495 0.01189994 -0.003739416 -0.180417 0.01189994 -0.004452764 -0.180452 0.007899999 -0.00409764 -0.180402 0.01189994 -0.004452764 -0.180452 0.01189994 -0.004793345 -0.180564 0.01189994 -0.004793345 -0.180564 0.007899999 -0.005108416 -0.180735 0.01189994 -0.005622684 -0.181231 0.007899999 -0.005387842 -0.1809599 0.01189994 -0.005622684 -0.181231 0.01189994 -0.005805313 -0.1815389 0.007899999 -0.005805313 -0.1815389 0.01189994 -0.005930006 -0.181876 0.01189994 -0.005992591 -0.182229 0.007899999 -0.005992591 -0.182229 0.01189994 -0.00599122 -0.182587 0.01189994 -0.005925774 -0.18294 0.007899999 -0.005925774 -0.18294 0.01189994 -0.005798459 -0.183275 0.01189994 -0.005613327 -0.183582 0.01189994 -0.005376338 -0.183851 0.01189994 -0.005095124 -0.184074 0.01189994 -0.005095124 -0.184074 0.007899999 -0.004778683 -0.184242 0.007899999 -0.004778683 -0.184242 0.01189994 -0.004437267 -0.184352 0.01189994 -0.004081726 -0.1843979 0.01189994 -0.004081726 -0.1843979 0.007899999 -0.003902316 -0.1843979 0.01189994 -0.003389477 -0.180495 0.007899999 -0.003059267 -0.180635 0.007899999 -0.004295647 -0.181445 0.007899999 -0.004048824 -0.181401 0.007899999 -0.003798902 -0.18142 0.007899999 -0.00409764 -0.180402 0.007899999 -0.003739416 -0.180417 0.007899999 -0.005387842 -0.1809599 0.007899999 -0.004719316 -0.1817049 0.007899999 -0.005108416 -0.180735 0.007899999 -0.00274676 -0.183959 0.007899999 -0.003373384 -0.183179 0.007899999 -0.004437267 -0.184352 0.007899999 -0.004547536 -0.183237 0.007899999 -0.00304526 -0.184157 0.007899999 -0.00382632 -0.183385 0.007899999 -0.003723621 -0.184381 0.007899999 -0.003951132 -0.183399 0.007899999 -0.004076719 -0.1833969 0.007899999 -0.005376338 -0.183851 0.007899999 -0.00473845 -0.1830739 0.007899999 -0.005613327 -0.183582 0.007899999 -0.004882931 -0.182869 0.007899999 -0.00203073 -0.182749 0.007899999 -0.002278983 -0.183419 0.007899999 -0.002759218 -0.180831 0.007899999 -0.003351867 -0.181638 0.007899999 -0.002287149 -0.181367 0.007899999 -0.003065168 -0.182045 0.007899999 -0.002130329 -0.18169 0.007899999 -0.003006219 -0.182289 0.007899999 -0.005798459 -0.183275 0.007899999 -0.00599122 -0.182587 0.007899999 -0.004999876 -0.182386 0.007899999 -0.004965007 -0.182138 0.007899999 -0.005930006 -0.181876 0.007899999 -0.004076719 -0.1833969 0.01189994 -0.00432223 -0.183347 0.007899999 -0.00432223 -0.183347 0.01189994 -0.004547536 -0.183237 0.01189994 -0.00473845 -0.1830739 0.01189994 -0.004882931 -0.182869 0.01189994 -0.004971921 -0.182635 0.01189994 -0.004971921 -0.182635 0.007899999 -0.004999876 -0.182386 0.01189994 -0.004965007 -0.182138 0.01189994 -0.004869461 -0.181906 0.007899999 -0.004869461 -0.181906 0.01189994 -0.004719316 -0.1817049 0.01189994 -0.004523932 -0.1815479 0.007899999 -0.004523932 -0.1815479 0.01189994 -0.004295647 -0.181445 0.01189994 -0.004048824 -0.181401 0.01189994 -0.003798902 -0.18142 0.01189994 -0.003561615 -0.181501 0.007899999 -0.003561615 -0.181501 0.01189994 -0.003351867 -0.181638 0.01189994 -0.003182828 -0.181824 0.007899999 -0.003182828 -0.181824 0.01189994 -0.003065168 -0.182045 0.01189994 -0.003006219 -0.182289 0.01189994 -0.003009676 -0.182539 0.007899999 -0.003009676 -0.182539 0.01189994 -0.00307542 -0.182781 0.01189994 -0.00307542 -0.182781 0.007899999 -0.003199279 -0.182999 0.007899999 -0.003199279 -0.182999 0.01189994 -0.003373384 -0.183179 0.01189994 -0.003586888 -0.183311 0.01189994 -0.003586888 -0.183311 0.007899999 -0.00382632 -0.183385 0.01189994 -0.003951132 -0.183399 0.01189994 -0.16154 -0.08896559 0.01189994 -0.161644 -0.08881926 0.01189994 -0.161644 -0.08881926 0.007899999 -0.16154 -0.08896559 0.007899999 -0.1612949 -0.08922749 0.01189994 -0.161008 -0.08944135 0.01189994 -0.161008 -0.08944135 0.007899999 -0.160686 -0.0896005 0.007899999 -0.160686 -0.0896005 0.01189994 -0.160342 -0.08969968 0.01189994 -0.160342 -0.08969968 0.007899999 -0.159985 -0.0897358 0.01189994 -0.159628 -0.08970755 0.007899999 -0.159628 -0.08970755 0.01189994 -0.159281 -0.089616 0.01189994 -0.158956 -0.089464 0.01189994 -0.158664 -0.0892564 0.007899999 -0.1584129 -0.08899998 0.007899999 -0.158664 -0.0892564 0.01189994 -0.158212 -0.08870285 0.007899999 -0.1584129 -0.08899998 0.01189994 -0.158212 -0.08870285 0.01189994 -0.158068 -0.08837479 0.01189994 -0.157984 -0.0880261 0.007899999 -0.157984 -0.0880261 0.01189994 -0.157964 -0.08766806 0.007899999 -0.157964 -0.08766806 0.01189994 -0.158008 -0.08731228 0.01189994 -0.158115 -0.08697009 0.007899999 -0.158115 -0.08697009 0.01189994 -0.158282 -0.08665245 0.01189994 -0.158502 -0.08636969 0.007899999 -0.158502 -0.08636969 0.01189994 -0.15877 -0.08613085 0.01189994 -0.15877 -0.08613085 0.007899999 -0.159076 -0.08594357 0.01189994 -0.159076 -0.08594357 0.007899999 -0.1594099 -0.08581387 0.007899999 -0.1594099 -0.08581387 0.01189994 -0.159762 -0.08574599 0.01189994 -0.159762 -0.08574599 0.007899999 -0.16012 -0.08574205 0.007899999 -0.16012 -0.08574205 0.01189994 -0.160474 -0.08580219 0.01189994 -0.160811 -0.0859245 0.01189994 -0.161121 -0.08610498 0.01189994 -0.161393 -0.08633798 0.01189994 -0.161393 -0.08633798 0.007899999 -0.16162 -0.0866158 0.007899999 -0.16162 -0.0866158 0.01189994 -0.1617929 -0.08692967 0.01189994 -0.161908 -0.08726948 0.007899999 -0.161908 -0.08726948 0.01189994 -0.16196 -0.08762419 0.01189994 -0.161948 -0.08798259 0.01189994 -0.161872 -0.08833301 0.007899999 -0.1617349 -0.08866417 0.007899999 -0.161872 -0.08833301 0.01189994 -0.1617349 -0.08866417 0.01189994 -0.1589789 -0.08791637 0.007899999 -0.1590549 -0.08815538 0.007899999 -0.158068 -0.08837479 0.007899999 -0.159487 -0.0868563 0.007899999 -0.158282 -0.08665245 0.007899999 -0.158008 -0.08731228 0.007899999 -0.159831 -0.08872705 0.007899999 -0.159985 -0.0897358 0.007899999 -0.160325 -0.08866816 0.007899999 -0.15937 -0.08854079 0.007899999 -0.158956 -0.089464 0.007899999 -0.159588 -0.0886631 0.007899999 -0.159281 -0.089616 0.007899999 -0.161121 -0.08610498 0.007899999 -0.160811 -0.0859245 0.007899999 -0.160218 -0.0867691 0.007899999 -0.160474 -0.08580219 0.007899999 -0.160916 -0.08743345 0.007899999 -0.1617929 -0.08692967 0.007899999 -0.160811 -0.087206 0.007899999 -0.161948 -0.08798259 0.007899999 -0.16196 -0.08762419 0.007899999 -0.160545 -0.08854895 0.007899999 -0.160729 -0.08837866 0.007899999 -0.1612949 -0.08922749 0.007899999 -0.160804 -0.08827757 0.007899999 -0.160865 -0.08816796 0.007899999 -0.160865 -0.08816796 0.01189994 -0.160944 -0.08793008 0.007899999 -0.160944 -0.08793008 0.01189994 -0.160961 -0.0876801 0.007899999 -0.160961 -0.0876801 0.01189994 -0.160916 -0.08743345 0.01189994 -0.160811 -0.087206 0.01189994 -0.1606529 -0.08701169 0.007899999 -0.1606529 -0.08701169 0.01189994 -0.1604509 -0.08686298 0.01189994 -0.1604509 -0.08686298 0.007899999 -0.160218 -0.0867691 0.01189994 -0.15997 -0.0867359 0.01189994 -0.15997 -0.0867359 0.007899999 -0.159721 -0.08676558 0.007899999 -0.159721 -0.08676558 0.01189994 -0.159487 -0.0868563 0.01189994 -0.1592839 -0.08700215 0.007899999 -0.1592839 -0.08700215 0.01189994 -0.159122 -0.0871942 0.007899999 -0.159122 -0.0871942 0.01189994 -0.159014 -0.08742028 0.007899999 -0.158965 -0.08766615 0.007899999 -0.159014 -0.08742028 0.01189994 -0.158965 -0.08766615 0.01189994 -0.1589789 -0.08791637 0.01189994 -0.1590549 -0.08815538 0.01189994 -0.159188 -0.08836787 0.007899999 -0.159188 -0.08836787 0.01189994 -0.15937 -0.08854079 0.01189994 -0.159588 -0.0886631 0.01189994 -0.159831 -0.08872705 0.01189994 -0.160081 -0.0887289 0.01189994 -0.160081 -0.0887289 0.007899999 -0.160325 -0.08866816 0.01189994 -0.160545 -0.08854895 0.01189994 -0.160729 -0.08837866 0.01189994 -0.160804 -0.08827757 0.01189994 -0.157742 0.09557825 0.01189994 -0.157817 0.09541517 0.007899999 -0.157817 0.09541517 0.01189994 -0.157921 0.09507209 0.01189994 -0.157962 0.09471595 0.01189994 -0.157962 0.09471595 0.007899999 -0.157939 0.0943582 0.01189994 -0.157853 0.09401017 0.007899999 -0.157853 0.09401017 0.01189994 -0.157503 0.09338766 0.007899999 -0.157706 0.09368318 0.01189994 -0.157503 0.09338766 0.01189994 -0.15725 0.09313327 0.007899999 -0.15725 0.09313327 0.01189994 -0.156956 0.09292811 0.01189994 -0.15663 0.09277868 0.007899999 -0.15663 0.09277868 0.01189994 -0.156283 0.09268981 0.01189994 -0.155569 0.0927034 0.007899999 -0.155925 0.09266448 0.01189994 -0.155569 0.0927034 0.01189994 -0.155225 0.09280526 0.007899999 -0.155225 0.09280526 0.01189994 -0.154905 0.09296685 0.01189994 -0.154619 0.0931831 0.01189994 -0.154619 0.0931831 0.007899999 -0.154376 0.09344696 0.01189994 -0.154184 0.09374988 0.007899999 -0.154184 0.09374988 0.01189994 -0.1540499 0.09408217 0.01189994 -0.1540499 0.09408217 0.007899999 -0.153976 0.09443318 0.01189994 -0.153967 0.09479171 0.01189994 -0.154022 0.095146 0.007899999 -0.154022 0.095146 0.01189994 -0.154139 0.09548479 0.007899999 -0.154139 0.09548479 0.01189994 -0.1543149 0.0957973 0.01189994 -0.1545439 0.09607338 0.007899999 -0.1545439 0.09607338 0.01189994 -0.1548179 0.09630405 0.01189994 -0.155468 0.09660178 0.007899999 -0.15513 0.09648215 0.01189994 -0.155468 0.09660178 0.01189994 -0.155822 0.09665906 0.01189994 -0.156532 0.09658157 0.007899999 -0.15618 0.09665226 0.01189994 -0.156865 0.09644925 0.007899999 -0.156532 0.09658157 0.01189994 -0.156865 0.09644925 0.01189994 -0.157169 0.09625959 0.01189994 -0.157169 0.09625959 0.007899999 -0.1574349 0.09601855 0.01189994 -0.157653 0.09573405 0.01189994 -0.154963 0.09469199 0.007899999 -0.153976 0.09443318 0.007899999 -0.155074 0.09420698 0.007899999 -0.155215 0.09400016 0.007899999 -0.154376 0.09344696 0.007899999 -0.155404 0.09383505 0.007899999 -0.154905 0.09296685 0.007899999 -0.1550019 0.0949397 0.007899999 -0.153967 0.09479171 0.007899999 -0.1548179 0.09630405 0.007899999 -0.1543149 0.0957973 0.007899999 -0.155872 0.09366816 0.007899999 -0.155925 0.09266448 0.007899999 -0.156283 0.09268981 0.007899999 -0.156414 0.09555667 0.007899999 -0.157706 0.09368318 0.007899999 -0.156951 0.09451109 0.007899999 -0.157939 0.0943582 0.007899999 -0.1561779 0.09564077 0.007899999 -0.155928 0.09566348 0.007899999 -0.15618 0.09665226 0.007899999 -0.155822 0.09665906 0.007899999 -0.15513 0.09648215 0.007899999 -0.156363 0.09374767 0.007899999 -0.156956 0.09292811 0.007899999 -0.156579 0.09387606 0.007899999 -0.156755 0.09405398 0.007899999 -0.157921 0.09507209 0.007899999 -0.156903 0.0950061 0.007899999 -0.156788 0.09522908 0.007899999 -0.157742 0.09557825 0.007899999 -0.157653 0.09573405 0.007899999 -0.1574349 0.09601855 0.007899999 -0.156852 0.0951212 0.007899999 -0.156852 0.0951212 0.01189994 -0.156788 0.09522908 0.01189994 -0.1566219 0.09541648 0.007899999 -0.1566219 0.09541648 0.01189994 -0.156414 0.09555667 0.01189994 -0.1561779 0.09564077 0.01189994 -0.155928 0.09566348 0.01189994 -0.155681 0.09562337 0.007899999 -0.1554509 0.09552305 0.007899999 -0.155681 0.09562337 0.01189994 -0.1554509 0.09552305 0.01189994 -0.1552529 0.09536868 0.007899999 -0.1552529 0.09536868 0.01189994 -0.155101 0.09517008 0.007899999 -0.155101 0.09517008 0.01189994 -0.1550019 0.0949397 0.01189994 -0.154963 0.09469199 0.01189994 -0.154988 0.09444248 0.007899999 -0.154988 0.09444248 0.01189994 -0.155074 0.09420698 0.01189994 -0.155215 0.09400016 0.01189994 -0.155628 0.09372198 0.007899999 -0.155404 0.09383505 0.01189994 -0.155628 0.09372198 0.01189994 -0.155872 0.09366816 0.01189994 -0.156123 0.09367698 0.007899999 -0.156123 0.09367698 0.01189994 -0.156363 0.09374767 0.01189994 -0.156579 0.09387606 0.01189994 -0.156755 0.09405398 0.01189994 -0.156882 0.09427016 0.007899999 -0.156882 0.09427016 0.01189994 -0.156951 0.09451109 0.01189994 -0.156958 0.09476166 0.007899999 -0.156958 0.09476166 0.01189994 -0.156903 0.0950061 0.01189994 0.003902316 0.1843979 0.01189994 0.003902316 0.1843979 0.007899999 0.003723621 0.184381 0.01189994 0.003374397 0.1843 0.01189994 0.003374397 0.1843 0.007899999 0.00304526 0.184157 0.01189994 0.00274676 0.183959 0.007899999 0.00274676 0.183959 0.01189994 0.002488613 0.18371 0.01189994 0.002278983 0.183419 0.01189994 0.002124726 0.183095 0.007899999 0.00203073 0.182749 0.007899999 0.002124726 0.183095 0.01189994 0.00203073 0.182749 0.01189994 0.001999974 0.182392 0.01189994 0.002033531 0.182035 0.01189994 0.002130329 0.18169 0.007899999 0.002130329 0.18169 0.01189994 0.002287149 0.181367 0.01189994 0.002499043 0.181078 0.01189994 0.002759218 0.180831 0.01189994 0.003059267 0.180635 0.007899999 0.003059267 0.180635 0.01189994 0.003389477 0.180495 0.01189994 0.003739416 0.180417 0.01189994 0.00409764 0.180402 0.007899999 0.00409764 0.180402 0.01189994 0.004452764 0.180452 0.01189994 0.004793345 0.180564 0.01189994 0.005108416 0.180735 0.01189994 0.005387842 0.1809599 0.01189994 0.005622684 0.181231 0.007899999 0.005622684 0.181231 0.01189994 0.005805313 0.1815389 0.01189994 0.005930006 0.181876 0.01189994 0.005992591 0.182229 0.01189994 0.00599122 0.182587 0.01189994 0.005925774 0.18294 0.007899999 0.005925774 0.18294 0.01189994 0.005798459 0.183275 0.007899999 0.005613327 0.183582 0.007899999 0.005798459 0.183275 0.01189994 0.005613327 0.183582 0.01189994 0.005376338 0.183851 0.01189994 0.004778683 0.184242 0.007899999 0.005095124 0.184074 0.01189994 0.004778683 0.184242 0.01189994 0.004437267 0.184352 0.01189994 0.004081726 0.1843979 0.007899999 0.004081726 0.1843979 0.01189994 0.004793345 0.180564 0.007899999 0.004452764 0.180452 0.007899999 0.003798902 0.18142 0.007899999 0.003739416 0.180417 0.007899999 0.003389477 0.180495 0.007899999 0.00307542 0.182781 0.007899999 0.002278983 0.183419 0.007899999 0.003199279 0.182999 0.007899999 0.003373384 0.183179 0.007899999 0.002488613 0.18371 0.007899999 0.001999974 0.182392 0.007899999 0.003009676 0.182539 0.007899999 0.002759218 0.180831 0.007899999 0.002499043 0.181078 0.007899999 0.002287149 0.181367 0.007899999 0.003065168 0.182045 0.007899999 0.002033531 0.182035 0.007899999 0.004437267 0.184352 0.007899999 0.00432223 0.183347 0.007899999 0.005095124 0.184074 0.007899999 0.00304526 0.184157 0.007899999 0.003586888 0.183311 0.007899999 0.003723621 0.184381 0.007899999 0.003951132 0.183399 0.007899999 0.004999876 0.182386 0.007899999 0.004965007 0.182138 0.007899999 0.005992591 0.182229 0.007899999 0.005930006 0.181876 0.007899999 0.005376338 0.183851 0.007899999 0.004971921 0.182635 0.007899999 0.00599122 0.182587 0.007899999 0.005805313 0.1815389 0.007899999 0.005387842 0.1809599 0.007899999 0.005108416 0.180735 0.007899999 0.003951132 0.183399 0.01189994 0.004076719 0.1833969 0.007899999 0.004076719 0.1833969 0.01189994 0.00432223 0.183347 0.01189994 0.004547536 0.183237 0.007899999 0.004547536 0.183237 0.01189994 0.00473845 0.1830739 0.007899999 0.00473845 0.1830739 0.01189994 0.004882931 0.182869 0.007899999 0.004882931 0.182869 0.01189994 0.004971921 0.182635 0.01189994 0.004999876 0.182386 0.01189994 0.004965007 0.182138 0.01189994 0.004869461 0.181906 0.007899999 0.004869461 0.181906 0.01189994 0.004719316 0.1817049 0.007899999 0.004523932 0.1815479 0.007899999 0.004719316 0.1817049 0.01189994 0.004523932 0.1815479 0.01189994 0.004295647 0.181445 0.007899999 0.004295647 0.181445 0.01189994 0.004048824 0.181401 0.007899999 0.004048824 0.181401 0.01189994 0.003798902 0.18142 0.01189994 0.003561615 0.181501 0.007899999 0.003561615 0.181501 0.01189994 0.003351867 0.181638 0.007899999 0.003351867 0.181638 0.01189994 0.003182828 0.181824 0.007899999 0.003182828 0.181824 0.01189994 0.003006219 0.182289 0.007899999 0.003065168 0.182045 0.01189994 0.003006219 0.182289 0.01189994 0.003009676 0.182539 0.01189994 0.00307542 0.182781 0.01189994 0.003199279 0.182999 0.01189994 0.003373384 0.183179 0.01189994 0.003586888 0.183311 0.01189994 0.00382632 0.183385 0.007899999 0.00382632 0.183385 0.01189994 0.107304 -0.05561345 0.01189994 0.107304 -0.05561345 0.007899999 0.1071619 -0.0552842 0.007899999 0.1071619 -0.0552842 0.01189994 0.106964 -0.0549854 0.01189994 0.106964 -0.0549854 0.007899999 0.106716 -0.05472677 0.01189994 0.106425 -0.05451667 0.007899999 0.106425 -0.05451667 0.01189994 0.106102 -0.05436176 0.007899999 0.106102 -0.05436176 0.01189994 0.105756 -0.05426716 0.01189994 0.105756 -0.05426716 0.007899999 0.105399 -0.05423587 0.007899999 0.105399 -0.05423587 0.01189994 0.105042 -0.05426889 0.01189994 0.104696 -0.05436497 0.01189994 0.104374 -0.05452126 0.007899999 0.104374 -0.05452126 0.01189994 0.104084 -0.05473268 0.01189994 0.103837 -0.05499249 0.007899999 0.103837 -0.05499249 0.01189994 0.10364 -0.05529218 0.007899999 0.10364 -0.05529218 0.01189994 0.1035 -0.05562216 0.01189994 0.103421 -0.05597186 0.01189994 0.103406 -0.0563302 0.007899999 0.103406 -0.0563302 0.01189994 0.103455 -0.05668538 0.01189994 0.103455 -0.05668538 0.007899999 0.103566 -0.05702608 0.007899999 0.103566 -0.05702608 0.01189994 0.1037369 -0.05734145 0.007899999 0.1037369 -0.05734145 0.01189994 0.103961 -0.0576213 0.007899999 0.104232 -0.05785655 0.007899999 0.103961 -0.0576213 0.01189994 0.104232 -0.05785655 0.01189994 0.10454 -0.05803978 0.01189994 0.104876 -0.05816495 0.01189994 0.105229 -0.05822825 0.01189994 0.105229 -0.05822825 0.007899999 0.105587 -0.05822736 0.01189994 0.10594 -0.05816256 0.007899999 0.10594 -0.05816256 0.01189994 0.106275 -0.05803585 0.007899999 0.106275 -0.05803585 0.01189994 0.1065829 -0.05785125 0.01189994 0.106852 -0.05761468 0.01189994 0.106852 -0.05761468 0.007899999 0.107075 -0.05733388 0.01189994 0.107244 -0.0570178 0.01189994 0.107244 -0.0570178 0.007899999 0.107354 -0.05667644 0.01189994 0.107402 -0.05632108 0.01189994 0.107385 -0.05596286 0.01189994 0.107385 -0.05596286 0.007899999 0.107352 -0.05578637 0.01189994 0.105567 -0.05722248 0.007899999 0.105316 -0.05723208 0.007899999 0.105587 -0.05822736 0.007899999 0.107402 -0.05632108 0.007899999 0.106392 -0.05638569 0.007899999 0.107354 -0.05667644 0.007899999 0.106324 -0.05662679 0.007899999 0.106198 -0.0568434 0.007899999 0.107075 -0.05733388 0.007899999 0.106022 -0.05702185 0.007899999 0.1065829 -0.05785125 0.007899999 0.106378 -0.05601119 0.007899999 0.107352 -0.05578637 0.007899999 0.106398 -0.05613505 0.007899999 0.10606 -0.05548125 0.007899999 0.106716 -0.05472677 0.007899999 0.105042 -0.05426889 0.007899999 0.105615 -0.05525845 0.007899999 0.104889 -0.05537855 0.007899999 0.104084 -0.05473268 0.007899999 0.105118 -0.05527746 0.007899999 0.104696 -0.05436497 0.007899999 0.104516 -0.05669587 0.007899999 0.104429 -0.05646055 0.007899999 0.104876 -0.05816495 0.007899999 0.105071 -0.05717897 0.007899999 0.104847 -0.05706679 0.007899999 0.10454 -0.05803978 0.007899999 0.104658 -0.05690228 0.007899999 0.104404 -0.05621117 0.007899999 0.103421 -0.05597186 0.007899999 0.1035 -0.05562216 0.007899999 0.106398 -0.05613505 0.01189994 0.106378 -0.05601119 0.01189994 0.106342 -0.05589079 0.007899999 0.106392 -0.05638569 0.01189994 0.106324 -0.05662679 0.01189994 0.106198 -0.0568434 0.01189994 0.106022 -0.05702185 0.01189994 0.105807 -0.0571509 0.007899999 0.105807 -0.0571509 0.01189994 0.105567 -0.05722248 0.01189994 0.105316 -0.05723208 0.01189994 0.105071 -0.05717897 0.01189994 0.104847 -0.05706679 0.01189994 0.104658 -0.05690228 0.01189994 0.104516 -0.05669587 0.01189994 0.104429 -0.05646055 0.01189994 0.104404 -0.05621117 0.01189994 0.104441 -0.05596339 0.01189994 0.104441 -0.05596339 0.007899999 0.104539 -0.05573266 0.01189994 0.104539 -0.05573266 0.007899999 0.104692 -0.05553358 0.007899999 0.104692 -0.05553358 0.01189994 0.104889 -0.05537855 0.01189994 0.105118 -0.05527746 0.01189994 0.105365 -0.05523657 0.007899999 0.105365 -0.05523657 0.01189994 0.105615 -0.05525845 0.01189994 0.105851 -0.05534178 0.007899999 0.105851 -0.05534178 0.01189994 0.10606 -0.05548125 0.01189994 0.106227 -0.05566817 0.007899999 0.106227 -0.05566817 0.01189994 0.106342 -0.05589079 0.01189994 0.005363643 -0.120863 0.01189994 0.005363643 -0.120863 0.007899999 0.005489289 -0.120735 0.01189994 0.005703687 -0.120448 0.01189994 0.005703687 -0.120448 0.007899999 0.005863368 -0.120126 0.007899999 0.005863368 -0.120126 0.01189994 0.005963146 -0.119782 0.01189994 0.005999803 -0.1194249 0.007899999 0.005999803 -0.1194249 0.01189994 0.005972206 -0.119068 0.007899999 0.005972206 -0.119068 0.01189994 0.00588119 -0.118721 0.007899999 0.00588119 -0.118721 0.01189994 0.005729734 -0.118396 0.01189994 0.005522668 -0.118103 0.007899999 0.005522668 -0.118103 0.01189994 0.005266666 -0.117852 0.007899999 0.005266666 -0.117852 0.01189994 0.004969954 -0.117651 0.01189994 0.004642069 -0.117506 0.007899999 0.004642069 -0.117506 0.01189994 0.00429356 -0.117422 0.01189994 0.00429356 -0.117422 0.007899999 0.003935575 -0.117401 0.007899999 0.003935575 -0.117401 0.01189994 0.003579676 -0.117445 0.007899999 0.003579676 -0.117445 0.01189994 0.003237307 -0.117551 0.01189994 0.003237307 -0.117551 0.007899999 0.002919435 -0.117717 0.01189994 0.002636313 -0.117937 0.01189994 0.002397 -0.1182039 0.01189994 0.002209186 -0.118509 0.01189994 0.00207895 -0.118844 0.007899999 0.00207895 -0.118844 0.01189994 0.002010464 -0.119195 0.007899999 0.002010464 -0.119195 0.01189994 0.002005934 -0.119554 0.01189994 0.002065479 -0.119908 0.01189994 0.002187192 -0.120245 0.01189994 0.002367138 -0.120555 0.007899999 0.002367138 -0.120555 0.01189994 0.002599596 -0.120828 0.01189994 0.002599596 -0.120828 0.007899999 0.002877116 -0.121055 0.007899999 0.002877116 -0.121055 0.01189994 0.003190636 -0.121229 0.01189994 0.003530204 -0.121344 0.01189994 0.003884911 -0.121397 0.007899999 0.003884911 -0.121397 0.01189994 0.004243254 -0.121385 0.007899999 0.004243254 -0.121385 0.01189994 0.004593849 -0.1213099 0.01189994 0.00492531 -0.121173 0.01189994 0.005227029 -0.120979 0.01189994 0.005227029 -0.120979 0.007899999 0.004252254 -0.118432 0.007899999 0.004484951 -0.118525 0.007899999 0.004969954 -0.117651 0.007899999 0.004687249 -0.118674 0.007899999 0.003754854 -0.118431 0.007899999 0.004003703 -0.1184 0.007899999 0.003530204 -0.121344 0.007899999 0.003628373 -0.120328 0.007899999 0.003190636 -0.121229 0.007899999 0.005729734 -0.118396 0.007899999 0.005963146 -0.119782 0.007899999 0.00492531 -0.121173 0.007899999 0.004364669 -0.120331 0.007899999 0.004593849 -0.1213099 0.007899999 0.003870964 -0.120392 0.007899999 0.002397 -0.1182039 0.007899999 0.00331813 -0.118668 0.007899999 0.002636313 -0.117937 0.007899999 0.003521442 -0.118522 0.007899999 0.002919435 -0.117717 0.007899999 0.002005934 -0.119554 0.007899999 0.002209186 -0.118509 0.007899999 0.002187192 -0.120245 0.007899999 0.002065479 -0.119908 0.007899999 0.005489289 -0.120735 0.007899999 0.004584729 -0.120211 0.007899999 0.004681825 -0.120132 0.01189994 0.004681825 -0.120132 0.007899999 0.004584729 -0.120211 0.01189994 0.004364669 -0.120331 0.01189994 0.004121601 -0.120393 0.01189994 0.004121601 -0.120393 0.007899999 0.003870964 -0.120392 0.01189994 0.003628373 -0.120328 0.01189994 0.003409206 -0.120207 0.007899999 0.003227114 -0.120035 0.007899999 0.003409206 -0.120207 0.01189994 0.003227114 -0.120035 0.01189994 0.0030936 -0.119822 0.01189994 0.0030936 -0.119822 0.007899999 0.003017008 -0.119584 0.007899999 0.003017008 -0.119584 0.01189994 0.003002166 -0.119334 0.007899999 0.003002166 -0.119334 0.01189994 0.003050088 -0.119087 0.007899999 0.003050088 -0.119087 0.01189994 0.003157615 -0.118861 0.007899999 0.003157615 -0.118861 0.01189994 0.00331813 -0.118668 0.01189994 0.003521442 -0.118522 0.01189994 0.003754854 -0.118431 0.01189994 0.004003703 -0.1184 0.01189994 0.004252254 -0.118432 0.01189994 0.004484951 -0.118525 0.01189994 0.004687249 -0.118674 0.01189994 0.004846274 -0.118867 0.01189994 0.004846274 -0.118867 0.007899999 0.004952192 -0.119095 0.01189994 0.004952192 -0.119095 0.007899999 0.004998207 -0.119341 0.007899999 0.004998207 -0.119341 0.01189994 0.004981577 -0.1195909 0.01189994 0.004981577 -0.1195909 0.007899999 0.004903197 -0.1198289 0.007899999 0.004903197 -0.1198289 0.01189994 0.004768133 -0.1200399 0.01189994 0.004768133 -0.1200399 0.007899999 -0.101989 -0.06507658 0.01189994 -0.101815 -0.06512129 0.01189994 -0.101459 -0.06516325 0.01189994 -0.101101 -0.06514108 0.007899999 -0.101101 -0.06514108 0.01189994 -0.100753 -0.06505531 0.01189994 -0.100425 -0.06490868 0.01189994 -0.10013 -0.06470596 0.01189994 -0.10013 -0.06470596 0.007899999 -0.09987479 -0.06445378 0.01189994 -0.09966909 -0.06416016 0.01189994 -0.09942966 -0.06348729 0.007899999 -0.09951907 -0.06383448 0.01189994 -0.09942966 -0.06348729 0.01189994 -0.09940367 -0.0631296 0.007899999 -0.099442 -0.0627731 0.007899999 -0.09940367 -0.0631296 0.01189994 -0.099442 -0.0627731 0.01189994 -0.0997045 -0.06210887 0.007899999 -0.09954327 -0.06242918 0.01189994 -0.0997045 -0.06210887 0.01189994 -0.09992015 -0.06182247 0.01189994 -0.09992015 -0.06182247 0.007899999 -0.100184 -0.06157916 0.007899999 -0.100184 -0.06157916 0.01189994 -0.100486 -0.06138676 0.01189994 -0.100818 -0.06125158 0.007899999 -0.100818 -0.06125158 0.01189994 -0.101169 -0.06117784 0.007899999 -0.101169 -0.06117784 0.01189994 -0.101528 -0.06116795 0.01189994 -0.101882 -0.06122219 0.01189994 -0.102221 -0.0613389 0.01189994 -0.1025339 -0.06151419 0.007899999 -0.1025339 -0.06151419 0.01189994 -0.10281 -0.06174248 0.01189994 -0.103041 -0.06201654 0.01189994 -0.10322 -0.0623275 0.01189994 -0.10334 -0.06266528 0.01189994 -0.103398 -0.06301915 0.007899999 -0.103398 -0.06301915 0.01189994 -0.103392 -0.06337767 0.01189994 -0.103322 -0.06372928 0.01189994 -0.10319 -0.06406277 0.01189994 -0.10319 -0.06406277 0.007899999 -0.1030009 -0.06436735 0.007899999 -0.1030009 -0.06436735 0.01189994 -0.10276 -0.0646333 0.01189994 -0.102476 -0.06485199 0.01189994 -0.102158 -0.06501638 0.01189994 -0.100853 -0.06399905 0.007899999 -0.101078 -0.06410968 0.007899999 -0.100425 -0.06490868 0.007899999 -0.101323 -0.06416088 0.007899999 -0.100519 -0.0636307 0.007899999 -0.09966909 -0.06416016 0.007899999 -0.100663 -0.06383597 0.007899999 -0.09987479 -0.06445378 0.007899999 -0.101814 -0.06407606 0.007899999 -0.102476 -0.06485199 0.007899999 -0.1020269 -0.06394547 0.007899999 -0.10276 -0.0646333 0.007899999 -0.1022019 -0.0637657 0.007899999 -0.09954327 -0.06242918 0.007899999 -0.100404 -0.06314688 0.007899999 -0.09951907 -0.06383448 0.007899999 -0.10334 -0.06266528 0.007899999 -0.10322 -0.0623275 0.007899999 -0.102222 -0.0625903 0.007899999 -0.102327 -0.0635482 0.007899999 -0.103322 -0.06372928 0.007899999 -0.102393 -0.06330651 0.007899999 -0.103392 -0.06337767 0.007899999 -0.100753 -0.06505531 0.007899999 -0.101459 -0.06516325 0.007899999 -0.101696 -0.06412029 0.007899999 -0.101815 -0.06512129 0.007899999 -0.101989 -0.06507658 0.007899999 -0.102158 -0.06501638 0.007899999 -0.101528 -0.06116795 0.007899999 -0.100882 -0.06231069 0.007899999 -0.100486 -0.06138676 0.007899999 -0.100536 -0.06266731 0.007899999 -0.103041 -0.06201654 0.007899999 -0.10281 -0.06174248 0.007899999 -0.1020539 -0.06240469 0.007899999 -0.102221 -0.0613389 0.007899999 -0.101882 -0.06122219 0.007899999 -0.101696 -0.06412029 0.01189994 -0.101814 -0.06407606 0.01189994 -0.1020269 -0.06394547 0.01189994 -0.1022019 -0.0637657 0.01189994 -0.102327 -0.0635482 0.01189994 -0.102393 -0.06330651 0.01189994 -0.102398 -0.06305587 0.007899999 -0.102398 -0.06305587 0.01189994 -0.102339 -0.06281208 0.01189994 -0.102339 -0.06281208 0.007899999 -0.102222 -0.0625903 0.01189994 -0.1020539 -0.06240469 0.01189994 -0.101845 -0.06226664 0.01189994 -0.101845 -0.06226664 0.007899999 -0.101608 -0.06218516 0.007899999 -0.101608 -0.06218516 0.01189994 -0.1013579 -0.06216508 0.007899999 -0.1013579 -0.06216508 0.01189994 -0.101111 -0.06220787 0.007899999 -0.101111 -0.06220787 0.01189994 -0.100882 -0.06231069 0.01189994 -0.100686 -0.06246709 0.007899999 -0.100686 -0.06246709 0.01189994 -0.100536 -0.06266731 0.01189994 -0.100439 -0.06289875 0.007899999 -0.100439 -0.06289875 0.01189994 -0.100404 -0.06314688 0.01189994 -0.100431 -0.06339609 0.01189994 -0.100431 -0.06339609 0.007899999 -0.100519 -0.0636307 0.01189994 -0.100663 -0.06383597 0.01189994 -0.100853 -0.06399905 0.01189994 -0.101078 -0.06410968 0.01189994 -0.101323 -0.06416088 0.01189994 -0.101574 -0.06414949 0.007899999 -0.101574 -0.06414949 0.01189994 -0.107304 0.05561345 0.01189994 -0.107352 0.05578637 0.007899999 -0.107304 0.05561345 0.007899999 -0.1071619 0.0552842 0.01189994 -0.1071619 0.0552842 0.007899999 -0.106964 0.0549854 0.01189994 -0.106716 0.05472677 0.007899999 -0.106716 0.05472677 0.01189994 -0.106425 0.05451667 0.01189994 -0.106102 0.05436176 0.007899999 -0.106102 0.05436176 0.01189994 -0.105756 0.05426716 0.007899999 -0.105756 0.05426716 0.01189994 -0.105399 0.05423587 0.01189994 -0.105042 0.05426889 0.01189994 -0.105042 0.05426889 0.007899999 -0.104696 0.05436497 0.01189994 -0.104374 0.05452126 0.01189994 -0.104084 0.05473268 0.01189994 -0.103837 0.05499249 0.007899999 -0.103837 0.05499249 0.01189994 -0.10364 0.05529218 0.01189994 -0.1035 0.05562216 0.007899999 -0.1035 0.05562216 0.01189994 -0.103421 0.05597186 0.01189994 -0.103406 0.0563302 0.007899999 -0.103406 0.0563302 0.01189994 -0.103455 0.05668538 0.01189994 -0.103566 0.05702608 0.007899999 -0.103566 0.05702608 0.01189994 -0.1037369 0.05734145 0.01189994 -0.1037369 0.05734145 0.007899999 -0.104232 0.05785655 0.007899999 -0.103961 0.0576213 0.01189994 -0.10454 0.05803978 0.007899999 -0.104232 0.05785655 0.01189994 -0.10454 0.05803978 0.01189994 -0.104876 0.05816495 0.007899999 -0.105229 0.05822825 0.007899999 -0.104876 0.05816495 0.01189994 -0.105229 0.05822825 0.01189994 -0.105587 0.05822736 0.007899999 -0.105587 0.05822736 0.01189994 -0.10594 0.05816256 0.01189994 -0.106275 0.05803585 0.01189994 -0.1065829 0.05785125 0.01189994 -0.106852 0.05761468 0.01189994 -0.107075 0.05733388 0.01189994 -0.107244 0.0570178 0.007899999 -0.107244 0.0570178 0.01189994 -0.107354 0.05667644 0.01189994 -0.107402 0.05632108 0.01189994 -0.107385 0.05596286 0.01189994 -0.107352 0.05578637 0.01189994 -0.107402 0.05632108 0.007899999 -0.107354 0.05667644 0.007899999 -0.105399 0.05423587 0.007899999 -0.105615 0.05525845 0.007899999 -0.106425 0.05451667 0.007899999 -0.10606 0.05548125 0.007899999 -0.103421 0.05597186 0.007899999 -0.103961 0.0576213 0.007899999 -0.104658 0.05690228 0.007899999 -0.104516 0.05669587 0.007899999 -0.104429 0.05646055 0.007899999 -0.103455 0.05668538 0.007899999 -0.107075 0.05733388 0.007899999 -0.106852 0.05761468 0.007899999 -0.106227 0.05566817 0.007899999 -0.106964 0.0549854 0.007899999 -0.107385 0.05596286 0.007899999 -0.10364 0.05529218 0.007899999 -0.104539 0.05573266 0.007899999 -0.104692 0.05553358 0.007899999 -0.104084 0.05473268 0.007899999 -0.104889 0.05537855 0.007899999 -0.104374 0.05452126 0.007899999 -0.104696 0.05436497 0.007899999 -0.1065829 0.05785125 0.007899999 -0.106275 0.05803585 0.007899999 -0.10594 0.05816256 0.007899999 -0.105567 0.05722248 0.007899999 -0.105316 0.05723208 0.007899999 -0.106398 0.05613505 0.01189994 -0.106378 0.05601119 0.007899999 -0.106378 0.05601119 0.01189994 -0.106342 0.05589079 0.007899999 -0.106398 0.05613505 0.007899999 -0.106392 0.05638569 0.01189994 -0.106392 0.05638569 0.007899999 -0.106324 0.05662679 0.007899999 -0.106324 0.05662679 0.01189994 -0.106198 0.0568434 0.007899999 -0.106198 0.0568434 0.01189994 -0.106022 0.05702185 0.007899999 -0.105807 0.0571509 0.007899999 -0.106022 0.05702185 0.01189994 -0.105807 0.0571509 0.01189994 -0.105567 0.05722248 0.01189994 -0.105316 0.05723208 0.01189994 -0.105071 0.05717897 0.007899999 -0.105071 0.05717897 0.01189994 -0.104847 0.05706679 0.007899999 -0.104847 0.05706679 0.01189994 -0.104658 0.05690228 0.01189994 -0.104516 0.05669587 0.01189994 -0.104429 0.05646055 0.01189994 -0.104404 0.05621117 0.007899999 -0.104404 0.05621117 0.01189994 -0.104441 0.05596339 0.007899999 -0.104441 0.05596339 0.01189994 -0.104539 0.05573266 0.01189994 -0.104692 0.05553358 0.01189994 -0.104889 0.05537855 0.01189994 -0.105118 0.05527746 0.007899999 -0.105118 0.05527746 0.01189994 -0.105365 0.05523657 0.01189994 -0.105365 0.05523657 0.007899999 -0.105615 0.05525845 0.01189994 -0.105851 0.05534178 0.007899999 -0.105851 0.05534178 0.01189994 -0.10606 0.05548125 0.01189994 -0.106227 0.05566817 0.01189994 -0.106342 0.05589079 0.01189994 -0.005363643 0.120863 0.01189994 -0.005489289 0.120735 0.01189994 -0.005703687 0.120448 0.01189994 -0.005863368 0.120126 0.01189994 -0.005963146 0.119782 0.01189994 -0.005999803 0.1194249 0.01189994 -0.005972206 0.119068 0.007899999 -0.005972206 0.119068 0.01189994 -0.00588119 0.118721 0.007899999 -0.00588119 0.118721 0.01189994 -0.005729734 0.118396 0.007899999 -0.005729734 0.118396 0.01189994 -0.005522668 0.118103 0.01189994 -0.005266666 0.117852 0.007899999 -0.005266666 0.117852 0.01189994 -0.004969954 0.117651 0.01189994 -0.004642069 0.117506 0.007899999 -0.004642069 0.117506 0.01189994 -0.00429356 0.117422 0.01189994 -0.003935575 0.117401 0.01189994 -0.003579676 0.117445 0.007899999 -0.003237307 0.117551 0.007899999 -0.003579676 0.117445 0.01189994 -0.003237307 0.117551 0.01189994 -0.002919435 0.117717 0.01189994 -0.002636313 0.117937 0.01189994 -0.002397 0.1182039 0.01189994 -0.002209186 0.118509 0.007899999 -0.002209186 0.118509 0.01189994 -0.00207895 0.118844 0.007899999 -0.00207895 0.118844 0.01189994 -0.002010464 0.119195 0.01189994 -0.002005934 0.119554 0.007899999 -0.002005934 0.119554 0.01189994 -0.002065479 0.119908 0.01189994 -0.002187192 0.120245 0.01189994 -0.002367138 0.120555 0.007899999 -0.002367138 0.120555 0.01189994 -0.002877116 0.121055 0.007899999 -0.002599596 0.120828 0.01189994 -0.002877116 0.121055 0.01189994 -0.003190636 0.121229 0.007899999 -0.003190636 0.121229 0.01189994 -0.003530204 0.121344 0.01189994 -0.003884911 0.121397 0.01189994 -0.004243254 0.121385 0.007899999 -0.004243254 0.121385 0.01189994 -0.00492531 0.121173 0.007899999 -0.004593849 0.1213099 0.01189994 -0.00492531 0.121173 0.01189994 -0.005227029 0.120979 0.007899999 -0.005227029 0.120979 0.01189994 -0.003521442 0.118522 0.007899999 -0.004003703 0.1184 0.007899999 -0.003935575 0.117401 0.007899999 -0.00429356 0.117422 0.007899999 -0.004252254 0.118432 0.007899999 -0.004484951 0.118525 0.007899999 -0.004687249 0.118674 0.007899999 -0.003530204 0.121344 0.007899999 -0.004998207 0.119341 0.007899999 -0.005999803 0.1194249 0.007899999 -0.004981577 0.1195909 0.007899999 -0.005963146 0.119782 0.007899999 -0.004903197 0.1198289 0.007899999 -0.004969954 0.117651 0.007899999 -0.005522668 0.118103 0.007899999 -0.004952192 0.119095 0.007899999 -0.002397 0.1182039 0.007899999 -0.002636313 0.117937 0.007899999 -0.00331813 0.118668 0.007899999 -0.002919435 0.117717 0.007899999 -0.002010464 0.119195 0.007899999 -0.002599596 0.120828 0.007899999 -0.003227114 0.120035 0.007899999 -0.0030936 0.119822 0.007899999 -0.002187192 0.120245 0.007899999 -0.003017008 0.119584 0.007899999 -0.002065479 0.119908 0.007899999 -0.004584729 0.120211 0.007899999 -0.004593849 0.1213099 0.007899999 -0.004121601 0.120393 0.007899999 -0.003870964 0.120392 0.007899999 -0.003884911 0.121397 0.007899999 -0.005863368 0.120126 0.007899999 -0.005703687 0.120448 0.007899999 -0.004768133 0.1200399 0.007899999 -0.005489289 0.120735 0.007899999 -0.005363643 0.120863 0.007899999 -0.004681825 0.120132 0.01189994 -0.004681825 0.120132 0.007899999 -0.004584729 0.120211 0.01189994 -0.004364669 0.120331 0.01189994 -0.004364669 0.120331 0.007899999 -0.004121601 0.120393 0.01189994 -0.003870964 0.120392 0.01189994 -0.003628373 0.120328 0.007899999 -0.003628373 0.120328 0.01189994 -0.003409206 0.120207 0.007899999 -0.003409206 0.120207 0.01189994 -0.003227114 0.120035 0.01189994 -0.0030936 0.119822 0.01189994 -0.003017008 0.119584 0.01189994 -0.003002166 0.119334 0.007899999 -0.003002166 0.119334 0.01189994 -0.003050088 0.119087 0.007899999 -0.003050088 0.119087 0.01189994 -0.003157615 0.118861 0.01189994 -0.003157615 0.118861 0.007899999 -0.00331813 0.118668 0.01189994 -0.003521442 0.118522 0.01189994 -0.003754854 0.118431 0.007899999 -0.003754854 0.118431 0.01189994 -0.004003703 0.1184 0.01189994 -0.004252254 0.118432 0.01189994 -0.004484951 0.118525 0.01189994 -0.004687249 0.118674 0.01189994 -0.004846274 0.118867 0.007899999 -0.004846274 0.118867 0.01189994 -0.004952192 0.119095 0.01189994 -0.004998207 0.119341 0.01189994 -0.004981577 0.1195909 0.01189994 -0.004903197 0.1198289 0.01189994 -0.004768133 0.1200399 0.01189994 0.009416341 0.217398 0.01889997 0.008770167 0.21459 0.01889997 0.00898987 0.214489 0.01889997 0.009222745 0.214426 0.01889997 0.009462773 0.2143999 0.01889997 0.009703814 0.214414 0.01889997 0.009894907 0.217347 0.01889997 0.01068508 0.21682 0.01889997 0.009939551 0.214466 0.01889997 0.01052218 0.216998 0.01889997 0.01033288 0.217148 0.01889997 0.010122 0.217265 0.01889997 0.00965768 0.217392 0.01889997 0.01037108 0.214679 0.01889997 0.008533418 0.217047 0.01889997 0.008361935 0.216877 0.01889997 0.009177207 0.217365 0.01889997 0.008946418 0.217294 0.01889997 0.008569419 0.214724 0.01889997 0.008729934 0.217187 0.01889997 0.008219897 0.216682 0.01889997 0.008111059 0.216467 0.01889997 0.01081717 0.216618 0.01889997 0.01091527 0.216397 0.01889997 0.01016396 0.214555 0.01889997 0.008049309 0.215519 0.01889997 0.00800687 0.2157559 0.01889997 0.008003115 0.2159979 0.01889997 0.008129298 0.215291 0.01889997 0.008244752 0.215079 0.01889997 0.008038163 0.2162359 0.01889997 0.008392751 0.214888 0.01889997 0.01055568 0.214834 0.01889997 0.01071298 0.215018 0.01889997 0.01083874 0.215224 0.01889997 0.01093 0.215447 0.01889997 0.01098406 0.215682 0.01889997 0.01099979 0.215923 0.01889997 0.01097667 0.2161639 0.01889997 0.00889045 0.215691 0.01024997 0.009047508 0.215577 0.01024997 0.008432269 0.215061 0.008687853 0.009331822 0.2153699 0.01024997 0.00948888 0.215256 0.01024997 0.008859097 0.2147459 0.00868076 0.009211719 0.21542 0.01018857 0.008727788 0.214839 0.008675336 0.009120166 0.215488 0.01019227 0.008469402 0.2150329 0.008686244 0.01189249 0.2144449 0.009503483 0.01209926 0.214859 0.009503483 0.01200449 0.214648 0.01089996 0.01217639 0.215077 0.01089996 0.01223516 0.215301 0.009503483 0.01229649 0.215759 0.009503483 0.01227527 0.215529 0.01089996 0.01229846 0.215991 0.01089996 0.01224535 0.21645 0.01089996 0.01228147 0.216222 0.009503483 0.01219058 0.216675 0.009503483 0.01211738 0.216895 0.01089996 0.01202625 0.2171069 0.009503483 0.01191794 0.217312 0.01089996 0.01179307 0.217507 0.009503483 0.01165258 0.217691 0.009503483 0.01165258 0.217691 0.01089996 0.01149737 0.217862 0.009503483 0.01132857 0.21802 0.01089996 0.01132857 0.21802 0.009503483 0.0111472 0.218164 0.009503483 0.01095455 0.218293 0.009503483 0.01095455 0.218293 0.01089996 0.01075208 0.2184039 0.009503483 0.01054096 0.218499 0.01089996 0.01054096 0.218499 0.009503483 0.01009887 0.218635 0.01089996 0.01009887 0.218635 0.009503483 0.009871006 0.218675 0.009503483 0.009640514 0.2186959 0.01089996 0.00917834 0.218681 0.01089996 0.008724927 0.218591 0.01089996 0.008949756 0.218645 0.009503483 0.008724927 0.218591 0.009503483 0.008292615 0.218426 0.01089996 0.007893264 0.2181929 0.01089996 0.007537722 0.2178969 0.01089996 0.007379472 0.217729 0.009503483 0.007235765 0.2175469 0.009503483 0.007235765 0.2175469 0.01089996 0.007107436 0.217355 0.009503483 0.006995499 0.2171519 0.01089996 0.006823599 0.216723 0.01089996 0.006823599 0.216723 0.009503483 0.006724655 0.216271 0.01089996 0.006764769 0.216499 0.009503483 0.006724655 0.216271 0.009503483 0.006703495 0.216041 0.009503483 0.006701469 0.215809 0.009503483 0.006701469 0.215809 0.01089996 0.006718516 0.215578 0.009503483 0.006754577 0.21535 0.01089996 0.006882548 0.214905 0.01089996 0.006882548 0.214905 0.009503483 0.006973624 0.214693 0.009503483 0.007081985 0.214488 0.01089996 0.007347345 0.214109 0.01089996 0.007347345 0.214109 0.009503483 0.007671415 0.21378 0.009503483 0.007671415 0.21378 0.01089996 0.008247911 0.213396 0.009503483 0.008045375 0.2135069 0.01089996 0.008459031 0.213301 0.01089996 0.008459031 0.213301 0.009503483 0.008901059 0.213165 0.01089996 0.009128928 0.213125 0.009503483 0.009359419 0.213104 0.009503483 0.009359419 0.213104 0.01089996 0.009821593 0.213119 0.01089996 0.009590804 0.213101 0.009503483 0.009821593 0.213119 0.009503483 0.01027506 0.213209 0.01089996 0.01005017 0.213155 0.009503483 0.01049458 0.213283 0.009503483 0.01070725 0.213374 0.009503483 0.01070725 0.213374 0.01089996 0.01110666 0.213607 0.01089996 0.01146215 0.213903 0.01089996 0.01146215 0.213903 0.009503483 0.01176416 0.214253 0.01089996 0.01204496 0.214881 0.009335577 0.01205635 0.2151139 0.009275317 0.01212036 0.215094 0.009335577 0.01207798 0.215196 0.009275317 0.01211249 0.215328 0.009275317 0.012178 0.215314 0.009335577 0.01214486 0.215512 0.009275317 0.01221728 0.215537 0.009335577 0.01217097 0.215766 0.009275317 0.01217168 0.215834 0.009275317 0.01217299 0.215987 0.009275317 0.01215666 0.216207 0.009275317 0.0122233 0.216215 0.009335577 0.01206988 0.2166399 0.009275317 0.011913 0.2170529 0.009275317 0.01189708 0.217083 0.009275317 0.0119735 0.217082 0.009335577 0.01173615 0.2173629 0.009275317 0.01160758 0.217653 0.009335577 0.01145565 0.217821 0.009335577 0.0115447 0.2176229 0.009275317 0.01140779 0.217774 0.009275317 0.01129025 0.217976 0.009335577 0.01132094 0.217856 0.009275317 0.0112465 0.217925 0.009275317 0.01107329 0.2180629 0.009275317 0.01088935 0.218185 0.009275317 0.01080006 0.218235 0.009275317 0.01069587 0.2182919 0.009275317 0.01050978 0.218376 0.009275317 0.01051914 0.218445 0.009335577 0.01049429 0.218383 0.009275317 0.01028585 0.218456 0.009275317 0.01020359 0.218478 0.009275317 0.01008635 0.218578 0.009335577 0.009887814 0.218545 0.009275317 0.009637594 0.218638 0.009335577 0.009411036 0.21864 0.009335577 0.009192764 0.218557 0.009275317 0.008974432 0.218522 0.009275317 0.008924901 0.21851 0.009275317 0.00874114 0.2185339 0.009335577 0.008759677 0.21847 0.009275317 0.00861448 0.2184219 0.009275317 0.008549988 0.2184 0.009275317 0.008346796 0.218313 0.009275317 0.008151471 0.21821 0.009275317 0.008117616 0.218267 0.009335577 0.008036911 0.218136 0.009275317 0.007926881 0.218145 0.009335577 0.007777094 0.217945 0.009275317 0.007625758 0.217808 0.009275317 0.007337272 0.217473 0.009275317 0.007214784 0.217289 0.009275317 0.007107853 0.217096 0.009275317 0.007024228 0.21691 0.009275317 0.007017254 0.216894 0.009275317 0.006943643 0.216686 0.009275317 0.006922006 0.2166039 0.009275317 0.00685501 0.216288 0.009275317 0.00684911 0.2162539 0.009275317 0.00678265 0.2162629 0.009335577 0.006828904 0.2160339 0.009275317 0.006826937 0.215813 0.009275317 0.006759941 0.215811 0.009335577 0.006843268 0.215593 0.009275317 0.00677663 0.2155849 0.009335577 0.00687772 0.2153739 0.009275317 0.006811976 0.2153609 0.009335577 0.006937265 0.214926 0.009335577 0.006999969 0.21495 0.009275317 0.007086932 0.214747 0.009275317 0.007102847 0.214717 0.009275317 0.00713253 0.214518 0.009335577 0.007263839 0.214437 0.009275317 0.007254779 0.214327 0.009335577 0.007309675 0.214365 0.009275317 0.007544338 0.213979 0.009335577 0.007678985 0.213944 0.009275317 0.007887184 0.213683 0.009335577 0.008110582 0.213615 0.009275317 0.008075773 0.213557 0.009335577 0.00819993 0.213565 0.009275317 0.008304059 0.213508 0.009275317 0.008490204 0.213424 0.009275317 0.008480787 0.213355 0.009335577 0.008505702 0.2134169 0.009275317 0.008714139 0.213344 0.009275317 0.00869441 0.21328 0.009335577 0.008796334 0.213322 0.009275317 0.008913576 0.213222 0.009335577 0.009136736 0.213183 0.009335577 0.009588897 0.21316 0.009335577 0.0100255 0.2132779 0.009275317 0.009814858 0.213177 0.009335577 0.01007509 0.21329 0.009275317 0.01024025 0.21333 0.009275317 0.01025885 0.213266 0.009335577 0.01044994 0.2134 0.009275317 0.01047378 0.213337 0.009335577 0.01088225 0.213533 0.009335577 0.01125317 0.213792 0.009335577 0.01121026 0.213844 0.009275317 0.01122289 0.213855 0.009275317 0.0114212 0.213944 0.009335577 0.01157605 0.21411 0.009335577 0.01137417 0.2139919 0.009275317 0.0117169 0.214287 0.009335577 0.01189208 0.214704 0.009275317 0.01184248 0.214476 0.009335577 0.0119521 0.2146739 0.009335577 0.0122205 0.215304 0.009414553 0.01223796 0.215762 0.009335577 0.01223999 0.2159889 0.009335577 0.01218795 0.216439 0.009335577 0.01223057 0.2164469 0.009414553 0.01213437 0.216659 0.009335577 0.01217609 0.216671 0.009414553 0.01206266 0.216874 0.009335577 0.01210325 0.216889 0.009414553 0.01201266 0.217101 0.009414553 0.01186746 0.2172819 0.009335577 0.01174515 0.217473 0.009335577 0.01178079 0.217498 0.009414553 0.01164108 0.217681 0.009414553 0.01111274 0.2181169 0.009335577 0.01092416 0.218243 0.009335577 0.01072585 0.218352 0.009335577 0.01094675 0.21828 0.009414553 0.01074528 0.218391 0.009414553 0.01053535 0.2184849 0.009414553 0.01030558 0.21852 0.009335577 0.009863257 0.218617 0.009335577 0.01009565 0.21862 0.009414553 0.009868979 0.2186599 0.009414553 0.009639799 0.218681 0.009414553 0.009185075 0.218623 0.009335577 0.00896126 0.2185879 0.009335577 0.009180068 0.218667 0.009414553 0.008952677 0.218631 0.009414553 0.0087291 0.218576 0.009414553 0.008526146 0.218463 0.009335577 0.008299112 0.2184129 0.009414553 0.008317887 0.218374 0.009335577 0.007719039 0.218041 0.009414553 0.007746815 0.218008 0.009335577 0.00757879 0.217856 0.009335577 0.007548272 0.217887 0.009414553 0.007423818 0.2176899 0.009335577 0.007247924 0.2175379 0.009414553 0.007283091 0.217513 0.009335577 0.007157444 0.217324 0.009335577 0.007120311 0.217347 0.009414553 0.007047832 0.217126 0.009335577 0.007008969 0.217145 0.009414553 0.006914615 0.216935 0.009414553 0.006955027 0.216919 0.009335577 0.006879508 0.216706 0.009335577 0.006837964 0.216718 0.009414553 0.00682193 0.216486 0.009335577 0.006779491 0.216496 0.009414553 0.006718516 0.21604 0.009414553 0.006761968 0.216038 0.009335577 0.006716489 0.21581 0.009414553 0.006733477 0.21558 0.009414553 0.00686562 0.2151409 0.009335577 0.006823837 0.215129 0.009414553 0.006896615 0.214911 0.009414553 0.007026433 0.214718 0.009335577 0.007392346 0.214147 0.009335577 0.007709622 0.213824 0.009335577 0.00768125 0.213791 0.009414553 0.008274078 0.213448 0.009335577 0.009362339 0.213162 0.009335577 0.009360134 0.213119 0.009414553 0.01004725 0.213169 0.009414553 0.01003867 0.213212 0.009335577 0.01068204 0.2134259 0.009335577 0.01070088 0.213387 0.009414553 0.01090425 0.213495 0.009414553 0.01107305 0.2136549 0.009335577 0.01109808 0.2136189 0.009414553 0.01128095 0.213759 0.009414553 0.01160907 0.214081 0.009414553 0.01162046 0.214071 0.009503483 0.01175206 0.214262 0.009414553 0.01176416 0.214253 0.009503483 0.01187968 0.214453 0.009414553 0.01199096 0.214655 0.009414553 0.01200449 0.214648 0.009503483 0.01208525 0.214865 0.009414553 0.01216197 0.215082 0.009414553 0.01217639 0.215077 0.009503483 0.01226037 0.215531 0.009414553 0.01228135 0.2157599 0.009414553 0.01227527 0.215529 0.009503483 0.0122835 0.21599 0.009414553 0.01226645 0.21622 0.009414553 0.01229846 0.215991 0.009503483 0.01224535 0.21645 0.009503483 0.01211738 0.216895 0.009503483 0.01190495 0.217304 0.009414553 0.01191794 0.217312 0.009503483 0.01148664 0.2178519 0.009414553 0.01131868 0.2180089 0.009414553 0.01113826 0.218152 0.009414553 0.01031827 0.218562 0.009414553 0.01032274 0.218576 0.009503483 0.009640514 0.2186959 0.009503483 0.009409606 0.218683 0.009414553 0.009409129 0.218699 0.009503483 0.00917834 0.218681 0.009503483 0.008510708 0.2185029 0.009414553 0.008505344 0.218517 0.009503483 0.008292615 0.218426 0.009503483 0.008088111 0.218318 0.009503483 0.008095741 0.218305 0.009414553 0.007901906 0.218181 0.009414553 0.007893264 0.2181929 0.009503483 0.007709383 0.218053 0.009503483 0.007390916 0.217719 0.009414553 0.007537722 0.2178969 0.009503483 0.006995499 0.2171519 0.009503483 0.006900668 0.2169409 0.009503483 0.006739556 0.216269 0.009414553 0.006769299 0.215353 0.009414553 0.006754577 0.21535 0.009503483 0.006809353 0.215125 0.009503483 0.006987214 0.214699 0.009414553 0.007094979 0.214496 0.009414553 0.007081985 0.214488 0.009503483 0.007219135 0.214302 0.009414553 0.007206797 0.214293 0.009503483 0.007358908 0.214119 0.009414553 0.007513284 0.213948 0.009414553 0.007502555 0.2139379 0.009503483 0.007852792 0.213636 0.009503483 0.007861614 0.213648 0.009414553 0.008053183 0.2135199 0.009414553 0.008254647 0.213409 0.009414553 0.008045375 0.2135069 0.009503483 0.008464574 0.213315 0.009414553 0.008681654 0.213238 0.009414553 0.008677184 0.2132239 0.009503483 0.008904278 0.21318 0.009414553 0.008901059 0.213165 0.009503483 0.009130954 0.21314 0.009414553 0.009590327 0.213117 0.009414553 0.009819865 0.213133 0.009414553 0.01027506 0.213209 0.009503483 0.01027089 0.2132239 0.009414553 0.01048928 0.213297 0.009414553 0.01091176 0.213482 0.009503483 0.01110666 0.213607 0.009503483 0.01129055 0.213747 0.009503483 0.01145166 0.213913 0.009414553 0.007190406 0.214551 0.009275317 0.007165431 0.2172 0.009275317 0.00748825 0.21702 0.009061753 0.007474601 0.217647 0.009275317 0.007814824 0.217469 0.009061753 0.01062029 0.217912 0.009061753 0.01180946 0.217249 0.009275317 0.01216048 0.216156 0.009275317 0.01198267 0.214906 0.009275317 0.01197576 0.21489 0.009275317 0.01163208 0.21503 0.009061753 0.01166266 0.214327 0.009275317 0.01145559 0.214079 0.009275317 0.01051914 0.213835 0.009061753 0.00999546 0.213651 0.009061753 0.009145617 0.213249 0.009275317 0.008379697 0.213888 0.009061753 0.009030699 0.214626 0.008687853 0.009969294 0.2171739 0.008687853 0.009806692 0.216951 0.008623957 0.00975275 0.216876 0.008602738 0.01040506 0.216515 0.008623957 0.01037925 0.21648 0.008613824 0.01041805 0.2165009 0.008621811 0.0104838 0.216386 0.008621811 0.01035118 0.216441 0.008602738 0.01013696 0.2161239 0.008545756 0.01013135 0.216139 0.008545756 0.01051509 0.215619 0.008613824 0.01047635 0.215647 0.008602738 0.01074725 0.215393 0.008686244 0.01077395 0.215431 0.008687853 0.01007968 0.215021 0.008613824 0.009985625 0.214916 0.008621811 0.01010066 0.214982 0.008621811 0.01004099 0.215049 0.008602738 0.009863495 0.214865 0.008621811 0.009723663 0.215263 0.008545756 0.009247243 0.214924 0.008602738 0.009102106 0.214442 0.008733749 0.00859487 0.215285 0.008623957 0.008581876 0.215299 0.008621811 0.008516132 0.215414 0.008621811 0.008620679 0.2153199 0.008613824 0.008648812 0.215359 0.008602738 0.00884062 0.215755 0.008545756 0.008862912 0.215676 0.008545756 0.008868515 0.215661 0.008545756 0.008523583 0.216153 0.008602738 0.008884787 0.216805 0.008623957 0.008672654 0.217164 0.008733749 0.008899271 0.216818 0.008621811 0.008920252 0.2167789 0.008613824 0.008958935 0.216751 0.008602738 0.00927627 0.2165369 0.008545756 0.009136438 0.216935 0.008621811 0.008145391 0.214038 0.009061753 0.008195698 0.2144989 0.008880794 0.008470237 0.214794 0.008733749 0.008630335 0.213768 0.009061753 0.008374035 0.214352 0.008880794 0.008927881 0.2132869 0.009275317 0.008893668 0.213679 0.009061753 0.008777141 0.214128 0.008880794 0.008764803 0.2145799 0.008733749 0.008568823 0.214228 0.008880794 0.009112119 0.213255 0.009275317 0.009165823 0.213622 0.009061753 0.009586751 0.213227 0.009275317 0.009433686 0.213228 0.009275317 0.009365737 0.213229 0.009275317 0.009442925 0.213598 0.009061753 0.008996009 0.214054 0.008880794 0.008992612 0.214653 0.008686244 0.008929252 0.214501 0.008733749 0.008611023 0.214678 0.008733749 0.008599698 0.214935 0.00868076 0.009211063 0.214842 0.008621811 0.009280741 0.214405 0.008733749 0.009222269 0.214006 0.008880794 0.009807169 0.213243 0.009275317 0.009756326 0.21324 0.009275317 0.009720802 0.213608 0.009061753 0.009452521 0.2139869 0.008880794 0.00921905 0.2148849 0.008613824 0.009193241 0.2148489 0.008623957 0.009340763 0.214814 0.008621811 0.009462535 0.214389 0.008733749 0.009644865 0.2143959 0.008733749 0.009683489 0.213995 0.008880794 0.009911775 0.214031 0.008880794 0.01026284 0.2137269 0.009061753 0.01038545 0.213378 0.009275317 0.01068317 0.213503 0.009275317 0.01065319 0.213487 0.009275317 0.00982511 0.214424 0.008733749 0.009472787 0.214803 0.008621811 0.00936526 0.215086 0.008572161 0.009466946 0.2152259 0.008545756 0.009483218 0.215225 0.008545756 0.009605169 0.214808 0.008621811 0.009736061 0.214829 0.008621811 0.01000064 0.214474 0.008733749 0.0101341 0.214094 0.008880794 0.01084846 0.21359 0.009275317 0.01103454 0.21371 0.009275317 0.01096308 0.2136639 0.009275317 0.01098364 0.214139 0.009061753 0.01076066 0.213973 0.009061753 0.01034718 0.214184 0.008880794 0.01016885 0.214545 0.008733749 0.009645223 0.215241 0.008545756 0.009564697 0.215228 0.008545756 0.01118516 0.214331 0.009061753 0.01073318 0.2144359 0.008880794 0.01054775 0.214298 0.008880794 0.009878754 0.215167 0.008572161 0.009738981 0.215269 0.008545756 0.01152539 0.214153 0.009275317 0.01136195 0.214545 0.009061753 0.01090067 0.214596 0.008880794 0.01033866 0.214832 0.008687853 0.01032727 0.214636 0.008733749 0.01011514 0.214995 0.008623957 0.01183456 0.2146 0.009275317 0.01178514 0.214511 0.009275317 0.01151168 0.21478 0.009061753 0.01117205 0.214969 0.008880794 0.01104766 0.214774 0.008880794 0.01172137 0.215294 0.009061753 0.01127207 0.2151769 0.008880794 0.01134639 0.215396 0.008880794 0.01215076 0.215546 0.009275317 0.01139354 0.215622 0.008880794 0.01177829 0.215566 0.009061753 0.01095777 0.215502 0.008733749 0.01089918 0.215329 0.008733749 0.01082015 0.215165 0.008733749 0.01065355 0.215259 0.00868076 0.01072186 0.215011 0.008733749 0.01060587 0.21487 0.008733749 0.01056134 0.215128 0.008675336 0.01047366 0.214744 0.008733749 0.01046484 0.215 0.00868076 0.01036667 0.214869 0.008686244 0.01180189 0.215843 0.009061753 0.01099509 0.215681 0.008733749 0.01055836 0.215611 0.008621811 0.01055049 0.215593 0.008623957 0.01211017 0.216475 0.009275317 0.01212227 0.216426 0.009275317 0.011792 0.216121 0.009061753 0.01140505 0.216084 0.008880794 0.01141327 0.215853 0.008880794 0.01101058 0.215863 0.008733749 0.01058548 0.215741 0.008621811 0.01059675 0.215873 0.008621811 0.01136904 0.216312 0.008880794 0.01174867 0.216395 0.009061753 0.01199996 0.21685 0.009275317 0.01167255 0.216663 0.009061753 0.01202148 0.216785 0.009275317 0.01100409 0.216045 0.008733749 0.01017498 0.215883 0.008545756 0.01031404 0.2157649 0.008572161 0.01017439 0.215867 0.008545756 0.01017206 0.215965 0.008545756 0.0105921 0.216005 0.008621811 0.01097565 0.216225 0.008733749 0.01130574 0.216534 0.008880794 0.01156479 0.216919 0.009061753 0.01121616 0.216747 0.008880794 0.01155608 0.21761 0.009275317 0.01169025 0.217435 0.009275317 0.01142686 0.2171609 0.009061753 0.01092565 0.216401 0.008733749 0.01053518 0.216264 0.008621811 0.01015937 0.216045 0.008545756 0.01057147 0.216136 0.008621811 0.01126074 0.217384 0.009061753 0.0111016 0.216948 0.008880794 0.01085495 0.216569 0.008733749 0.01076447 0.216727 0.008733749 0.0102331 0.216279 0.008572161 0.01106917 0.217585 0.009061753 0.01096355 0.217133 0.008880794 0.01056766 0.2167389 0.008687853 0.0108546 0.2177619 0.009061753 0.01080429 0.217301 0.008880794 0.01065546 0.216874 0.008733749 0.01036959 0.218032 0.009061753 0.01043117 0.217572 0.008880794 0.01062589 0.2174479 0.008880794 0.01038885 0.217122 0.008733749 0.01007205 0.218513 0.009275317 0.01023519 0.21722 0.008733749 0.01010626 0.2181209 0.009061753 0.01022279 0.217672 0.008880794 0.009413182 0.218573 0.009275317 0.009566247 0.218572 0.009275317 0.009557068 0.2182019 0.009061753 0.009634256 0.218571 0.009275317 0.009854376 0.218551 0.009275317 0.009777665 0.217794 0.008880794 0.00983411 0.218178 0.009061753 0.01000386 0.217746 0.008880794 0.009897828 0.2173579 0.008733749 0.01007068 0.217299 0.008733749 0.01000738 0.2171469 0.008686244 0.0102722 0.216961 0.008675336 0.01052975 0.217006 0.008733749 0.009279131 0.218192 0.009061753 0.009243607 0.21856 0.009275317 0.009004473 0.218149 0.009061753 0.009316444 0.217805 0.008880794 0.009547412 0.217813 0.008880794 0.009719252 0.217395 0.008733749 0.00978887 0.216958 0.008621811 0.009780883 0.216915 0.008613824 0.009659171 0.216986 0.008621811 0.009527146 0.216997 0.008621811 0.009537398 0.217411 0.008733749 0.009088158 0.217769 0.008880794 0.008737087 0.218073 0.009061753 0.008316755 0.218297 0.009275317 0.009355068 0.217404 0.008733749 0.009394764 0.216992 0.008621811 0.009516716 0.216575 0.008545756 0.009634673 0.216714 0.008572161 0.009532988 0.216574 0.008545756 0.009174823 0.2173759 0.008733749 0.008865833 0.217706 0.008880794 0.008999288 0.217326 0.008733749 0.008480727 0.217965 0.009061753 0.007965326 0.2180899 0.009275317 0.008239328 0.217827 0.009061753 0.007789671 0.217956 0.009275317 0.008016228 0.217661 0.009061753 0.008652806 0.217616 0.008880794 0.008831083 0.2172549 0.008733749 0.00935471 0.2165589 0.008545756 0.009263873 0.216971 0.008621811 0.009435236 0.216572 0.008545756 0.007544338 0.217721 0.009275317 0.008266746 0.217364 0.008880794 0.008452117 0.2175019 0.008880794 0.009014308 0.216884 0.008621811 0.009121239 0.216633 0.008572161 0.009260952 0.216531 0.008545756 0.007637977 0.2172549 0.009061753 0.008526265 0.217056 0.008733749 0.00866127 0.2169679 0.008687853 0.007952272 0.2170259 0.008880794 0.008099317 0.217204 0.008880794 0.007367908 0.2167699 0.009061753 0.008278012 0.216789 0.008733749 0.008394062 0.21693 0.008733749 0.007727801 0.216623 0.008880794 0.007827877 0.216831 0.008880794 0.007221698 0.216234 0.009061753 0.006887435 0.216472 0.009275317 0.007278621 0.216506 0.009061753 0.007653594 0.216404 0.008880794 0.008100807 0.216471 0.008733749 0.006828308 0.215966 0.009275317 0.008042216 0.216298 0.008733749 0.00825268 0.216407 0.008686244 0.008179783 0.216635 0.008733749 0.008346378 0.2165409 0.00868076 0.008438587 0.216672 0.008675336 0.008535087 0.2168 0.00868076 0.008633255 0.216931 0.008686244 0.006839513 0.215644 0.009275317 0.007198035 0.215957 0.009061753 0.007207989 0.215679 0.009061753 0.007586658 0.215947 0.008880794 0.007606327 0.2161779 0.008880794 0.008441507 0.216189 0.008621811 0.008225917 0.216369 0.008687853 0.008449435 0.216207 0.008623957 0.00688976 0.2153249 0.009275317 0.007251262 0.215405 0.009061753 0.007989346 0.215937 0.008733749 0.008004903 0.216119 0.008733749 0.008414447 0.216059 0.008621811 0.008484899 0.216181 0.008613824 0.008685886 0.216035 0.008572161 0.007594883 0.215716 0.008880794 0.007630884 0.215488 0.008880794 0.007327437 0.215137 0.009061753 0.006978452 0.2150149 0.009275317 0.006930053 0.21516 0.009275317 0.007694184 0.215266 0.008880794 0.007995843 0.215755 0.008733749 0.00840789 0.215795 0.008621811 0.008403122 0.215927 0.008621811 0.008825004 0.215917 0.008545756 0.0088256 0.215933 0.008545756 0.008827924 0.215835 0.008545756 0.008024275 0.215575 0.008733749 0.007573127 0.214639 0.009061753 0.007435202 0.214881 0.009061753 0.007455289 0.214177 0.009275317 0.007443904 0.21419 0.009275317 0.00778377 0.215053 0.008880794 0.008074223 0.215399 0.008733749 0.008428514 0.215664 0.008621811 0.007592141 0.214026 0.009275317 0.007739126 0.214416 0.009061753 0.00789839 0.214852 0.008880794 0.008144974 0.215231 0.008733749 0.008235454 0.215073 0.008733749 0.008464753 0.2155359 0.008621811 0.008766889 0.215521 0.008572161 0.007926642 0.213737 0.009275317 0.007753431 0.2138749 0.009275317 0.007930815 0.214215 0.009061753 0.008036375 0.214667 0.008880794 0.008344411 0.214926 0.008733749 0.01010948 0.216109 0.01024997 0.009952425 0.216223 0.01024997 0.009879767 0.216312 0.01019227 0.009668111 0.21643 0.01024997 0.009511053 0.216544 0.01024997 0.01014089 0.217054 0.00868076 0.009788215 0.21638 0.01018857 0.01040029 0.216865 0.00868076 0.01053047 0.216767 0.008686244 0.191567 0.09823107 0.01889997 0.191915 0.09823489 0.01889997 0.191915 0.09823489 0.01099997 0.1922529 0.09831899 0.01099997 0.1925629 0.09847867 0.01889997 0.1925629 0.09847867 0.01099997 0.192827 0.09870547 0.01099997 0.193032 0.0989871 0.01099997 0.193167 0.09930837 0.01889997 0.193167 0.09930837 0.01099997 0.1932229 0.09965199 0.01099997 0.1932229 0.09965199 0.01889997 0.193199 0.09999948 0.01099997 0.193199 0.09999948 0.01889997 0.193096 0.100332 0.01099997 0.192918 0.100632 0.01099997 0.192676 0.100882 0.01099997 0.192676 0.100882 0.01889997 0.192383 0.101071 0.01099997 0.192383 0.101071 0.01889997 0.192055 0.101186 0.01099997 0.191708 0.101223 0.01099997 0.192055 0.101186 0.01889997 0.191363 0.101178 0.01099997 0.191708 0.101223 0.01889997 0.191363 0.101178 0.01889997 0.1910369 0.101056 0.01099997 0.1910369 0.101056 0.01889997 0.190748 0.100861 0.01099997 0.190512 0.100605 0.01099997 0.1903409 0.100302 0.01099997 0.190245 0.09996688 0.01099997 0.1903409 0.100302 0.01889997 0.190228 0.09961909 0.01099997 0.190293 0.09927678 0.01099997 0.190293 0.09927678 0.01889997 0.190434 0.09895849 0.01099997 0.190645 0.09868139 0.01099997 0.190645 0.09868139 0.01889997 0.190914 0.09846049 0.01099997 0.190914 0.09846049 0.01889997 0.191227 0.09830766 0.01099997 0.191227 0.09830766 0.01889997 0.191567 0.09823107 0.01099997 0.1922529 0.09831899 0.01889997 0.192827 0.09870547 0.01889997 0.190245 0.09996688 0.01889997 0.193032 0.0989871 0.01889997 0.193096 0.100332 0.01889997 0.192918 0.100632 0.01889997 0.190228 0.09961909 0.01889997 0.190748 0.100861 0.01889997 0.190512 0.100605 0.01889997 0.190434 0.09895849 0.01889997 0.191301 0.09923708 0.01024997 0.191495 0.09921669 0.01024997 0.19122 0.09846258 0.008687853 0.191844 0.09917968 0.01024997 0.192037 0.0991593 0.01024997 0.191715 0.09916245 0.01018857 0.191909 0.09838891 0.008686244 0.191747 0.09840327 0.00868076 0.191587 0.09841746 0.008675336 0.191428 0.09843695 0.00868076 0.191602 0.0991764 0.01019227 0.191893 0.09692776 0.01089996 0.1921229 0.09695118 0.009503483 0.192351 0.09699356 0.01089996 0.192791 0.09713375 0.01089996 0.192574 0.09705448 0.009503483 0.193394 0.09747475 0.009503483 0.193203 0.09734457 0.01089996 0.193574 0.0976203 0.01089996 0.193574 0.0976203 0.009503483 0.193895 0.09795325 0.01089996 0.194157 0.09833461 0.01089996 0.194352 0.0987538 0.01089996 0.194352 0.0987538 0.009503483 0.194476 0.09919935 0.01089996 0.194509 0.09942835 0.009503483 0.194524 0.09965926 0.01089996 0.194524 0.09965926 0.009503483 0.1945199 0.0998907 0.009503483 0.194496 0.100121 0.01089996 0.194496 0.100121 0.009503483 0.194393 0.100572 0.01089996 0.194217 0.1009989 0.009503483 0.194217 0.1009989 0.01089996 0.193973 0.101392 0.009503483 0.193973 0.101392 0.01089996 0.1936669 0.101739 0.01089996 0.193309 0.102032 0.01089996 0.193113 0.102154 0.009503483 0.192694 0.1023499 0.009503483 0.192907 0.102261 0.01089996 0.192474 0.102421 0.009503483 0.192248 0.102473 0.009503483 0.192474 0.102421 0.01089996 0.192019 0.102507 0.01089996 0.191788 0.102522 0.009503483 0.191557 0.102518 0.01089996 0.191099 0.102452 0.01089996 0.191099 0.102452 0.009503483 0.190876 0.102391 0.009503483 0.190659 0.102312 0.01089996 0.190448 0.102215 0.009503483 0.1902469 0.102101 0.01089996 0.190056 0.101971 0.009503483 0.189876 0.1018249 0.01089996 0.1897079 0.101665 0.009503483 0.189555 0.101492 0.01089996 0.189555 0.101492 0.009503483 0.189416 0.101307 0.009503483 0.189293 0.101111 0.01089996 0.189098 0.100692 0.01089996 0.189187 0.100905 0.009503483 0.188974 0.100246 0.01089996 0.188926 0.09978616 0.01089996 0.188926 0.09978616 0.009503483 0.18893 0.09955477 0.009503483 0.188953 0.09932458 0.009503483 0.188996 0.09909707 0.009503483 0.188953 0.09932458 0.01089996 0.1890569 0.09887385 0.009503483 0.1890569 0.09887385 0.01089996 0.189136 0.09865635 0.009503483 0.189233 0.0984463 0.01089996 0.189347 0.09824478 0.009503483 0.189477 0.09805345 0.01089996 0.189782 0.09770619 0.009503483 0.189782 0.09770619 0.01089996 0.190141 0.09741395 0.01089996 0.190141 0.09741395 0.009503483 0.190337 0.09729111 0.009503483 0.190542 0.09718465 0.009503483 0.190542 0.09718465 0.01089996 0.190976 0.09702467 0.01089996 0.19143 0.09693831 0.009503483 0.19143 0.09693831 0.01089996 0.191661 0.09692347 0.009503483 0.1921049 0.09707546 0.009275317 0.192322 0.09711599 0.009275317 0.192337 0.0970506 0.009335577 0.192944 0.09734237 0.009275317 0.1930029 0.09737586 0.009275317 0.193172 0.09739428 0.009335577 0.193277 0.09754687 0.009275317 0.193535 0.09766417 0.009335577 0.193699 0.09782075 0.009335577 0.193798 0.09803265 0.009275317 0.19393 0.09820955 0.009275317 0.19385 0.09799027 0.009335577 0.194048 0.09839689 0.009275317 0.194106 0.09836369 0.009335577 0.19411 0.09851765 0.009275317 0.194149 0.09859317 0.009275317 0.194297 0.09877407 0.009335577 0.194352 0.09922289 0.009275317 0.194418 0.09921038 0.009335577 0.194451 0.09943449 0.009335577 0.194397 0.0997641 0.009275317 0.194374 0.100086 0.009275317 0.194397 0.100335 0.009335577 0.194332 0.10032 0.009275317 0.1943089 0.1004019 0.009275317 0.19426 0.100767 0.009335577 0.194198 0.100741 0.009275317 0.194105 0.100942 0.009275317 0.193996 0.101134 0.009275317 0.1940529 0.10117 0.009335577 0.193901 0.101275 0.009275317 0.193698 0.101526 0.009275317 0.1936269 0.101697 0.009335577 0.193457 0.101847 0.009335577 0.193466 0.10175 0.009275317 0.192883 0.102208 0.009335577 0.192674 0.102295 0.009335577 0.192634 0.102237 0.009275317 0.192324 0.102327 0.009275317 0.192225 0.1023499 0.009275317 0.192006 0.102382 0.009275317 0.192013 0.1024489 0.009335577 0.191787 0.102464 0.009335577 0.191684 0.1023949 0.009275317 0.191565 0.102392 0.009275317 0.19156 0.102459 0.009335577 0.191362 0.102372 0.009275317 0.191335 0.102436 0.009335577 0.191345 0.10237 0.009275317 0.191127 0.10233 0.009275317 0.191045 0.102307 0.009275317 0.190706 0.102196 0.009275317 0.190506 0.102103 0.009275317 0.190446 0.10207 0.009275317 0.190091 0.101924 0.009335577 0.1901299 0.10187 0.009275317 0.1895999 0.101455 0.009335577 0.189344 0.101082 0.009335577 0.189153 0.100671 0.009335577 0.1892099 0.100632 0.009275317 0.189148 0.1004379 0.009275317 0.1889989 0.100011 0.009335577 0.189011 0.09933286 0.009335577 0.189112 0.09889155 0.009335577 0.18914 0.09904319 0.009275317 0.18924 0.09873616 0.009275317 0.18919 0.0986787 0.009335577 0.189345 0.09850347 0.009275317 0.189378 0.09844428 0.009275317 0.189285 0.09847289 0.009335577 0.189453 0.09831106 0.009275317 0.189549 0.09817045 0.009275317 0.1895239 0.09808838 0.009335577 0.1897169 0.09795647 0.009275317 0.190035 0.09764999 0.009275317 0.189992 0.09759807 0.009335577 0.190212 0.09751749 0.009275317 0.190241 0.09749948 0.009275317 0.190399 0.09740006 0.009275317 0.190567 0.09723776 0.009335577 0.1907989 0.09721356 0.009275317 0.190776 0.09715068 0.009335577 0.1912119 0.09702956 0.009335577 0.191444 0.09706318 0.009275317 0.191663 0.096982 0.009335577 0.191889 0.09698617 0.009335577 0.192088 0.09707379 0.009275317 0.191437 0.09699648 0.009335577 0.191662 0.09693849 0.009414553 0.192115 0.09700906 0.009335577 0.192556 0.09711027 0.009335577 0.192769 0.09718787 0.009335577 0.192975 0.09728276 0.009335577 0.192995 0.09724408 0.009414553 0.193195 0.09735739 0.009414553 0.193359 0.09752166 0.009335577 0.193385 0.09748679 0.009414553 0.1935639 0.09763157 0.009414553 0.193883 0.09796279 0.009414553 0.193985 0.09817171 0.009335577 0.194021 0.09814709 0.009414553 0.1942099 0.09856486 0.009335577 0.194249 0.0985465 0.009414553 0.194338 0.09875899 0.009414553 0.194367 0.09898966 0.009335577 0.194461 0.09920215 0.009414553 0.194494 0.0994299 0.009414553 0.1944659 0.09966057 0.009335577 0.194509 0.09965956 0.009414553 0.194461 0.09988719 0.009335577 0.194505 0.09988975 0.009414553 0.194482 0.100119 0.009414553 0.1944389 0.100113 0.009335577 0.194379 0.100567 0.009414553 0.194337 0.100554 0.009335577 0.194165 0.100973 0.009335577 0.19409 0.101193 0.009414553 0.193926 0.101357 0.009335577 0.193816 0.101562 0.009414553 0.193783 0.101533 0.009335577 0.193657 0.101728 0.009414553 0.193301 0.102019 0.009414553 0.193276 0.101983 0.009335577 0.193084 0.102104 0.009335577 0.192901 0.1022469 0.009414553 0.192689 0.102336 0.009414553 0.19247 0.102406 0.009414553 0.192458 0.102364 0.009335577 0.192237 0.102416 0.009335577 0.192018 0.102492 0.009414553 0.191788 0.102507 0.009414553 0.191558 0.102503 0.009414553 0.191112 0.1023949 0.009335577 0.190894 0.102335 0.009335577 0.190681 0.102258 0.009335577 0.190475 0.102163 0.009335577 0.1902779 0.102051 0.009335577 0.190255 0.102088 0.009414553 0.189914 0.101781 0.009335577 0.189751 0.101625 0.009335577 0.189567 0.101483 0.009414553 0.189429 0.101298 0.009414553 0.189464 0.101274 0.009335577 0.189306 0.101103 0.009414553 0.18924 0.100881 0.009335577 0.1892009 0.100899 0.009414553 0.189112 0.100686 0.009414553 0.189083 0.1004559 0.009335577 0.189041 0.100467 0.009414553 0.188989 0.100243 0.009414553 0.189032 0.100235 0.009335577 0.188955 0.1000159 0.009414553 0.188984 0.09978491 0.009335577 0.188941 0.09978586 0.009414553 0.188988 0.09955829 0.009335577 0.188968 0.09932667 0.009414553 0.1890529 0.09911018 0.009335577 0.18915 0.09866207 0.009414553 0.1892459 0.0984531 0.009414553 0.189396 0.09827566 0.009335577 0.189666 0.09791219 0.009335577 0.189823 0.09774839 0.009335577 0.190174 0.09746229 0.009335577 0.190149 0.09742635 0.009414553 0.190366 0.09734189 0.009335577 0.1909919 0.09708106 0.009335577 0.191204 0.09698688 0.009414553 0.1914319 0.09695327 0.009414553 0.191893 0.09692776 0.009503483 0.191892 0.09694278 0.009414553 0.192121 0.09696608 0.009414553 0.192351 0.09699356 0.009503483 0.192347 0.09700816 0.009414553 0.192569 0.0970689 0.009414553 0.192791 0.09713375 0.009503483 0.192786 0.0971477 0.009414553 0.193001 0.09723067 0.009503483 0.193203 0.09734457 0.009503483 0.193731 0.09779059 0.009414553 0.193741 0.09778016 0.009503483 0.193895 0.09795325 0.009503483 0.194034 0.09813857 0.009503483 0.194144 0.09834206 0.009414553 0.194157 0.09833461 0.009503483 0.194263 0.09854018 0.009503483 0.1944079 0.0989781 0.009414553 0.194423 0.0989741 0.009503483 0.194476 0.09919935 0.009503483 0.1944389 0.100345 0.009414553 0.194454 0.100348 0.009503483 0.194393 0.100572 0.009503483 0.1942999 0.100783 0.009414553 0.194314 0.100789 0.009503483 0.194204 0.100992 0.009414553 0.194103 0.1012009 0.009503483 0.193961 0.101383 0.009414553 0.193827 0.101572 0.009503483 0.1936669 0.101739 0.009503483 0.193485 0.101881 0.009414553 0.193494 0.101893 0.009503483 0.193309 0.102032 0.009503483 0.1931059 0.102141 0.009414553 0.192907 0.102261 0.009503483 0.192245 0.102459 0.009414553 0.192019 0.102507 0.009503483 0.191557 0.102518 0.009503483 0.191329 0.102479 0.009414553 0.191327 0.102494 0.009503483 0.191103 0.102437 0.009414553 0.190881 0.1023769 0.009414553 0.190659 0.102312 0.009503483 0.1906639 0.102298 0.009414553 0.190455 0.102201 0.009414553 0.1902469 0.102101 0.009503483 0.190065 0.101959 0.009414553 0.189876 0.1018249 0.009503483 0.189886 0.101814 0.009414553 0.189719 0.101655 0.009414553 0.189293 0.101111 0.009503483 0.189098 0.100692 0.009503483 0.189027 0.100471 0.009503483 0.188974 0.100246 0.009503483 0.1889399 0.100017 0.009503483 0.1889449 0.09955567 0.009414553 0.18901 0.09910047 0.009414553 0.1890709 0.09887838 0.009414553 0.18936 0.09825277 0.009414553 0.189233 0.0984463 0.009503483 0.189489 0.09806245 0.009414553 0.189634 0.09788346 0.009414553 0.189477 0.09805345 0.009503483 0.189622 0.0978735 0.009503483 0.189793 0.0977171 0.009414553 0.189965 0.09756439 0.009414553 0.1899549 0.09755265 0.009503483 0.190344 0.0973041 0.009414553 0.190549 0.09719836 0.009414553 0.190756 0.09709578 0.009503483 0.190761 0.09710985 0.009414553 0.19098 0.09703916 0.009414553 0.190976 0.09702467 0.009503483 0.191202 0.0969721 0.009503483 0.189121 0.100322 0.009275317 0.189481 0.100239 0.009061753 0.1895599 0.100506 0.009061753 0.189402 0.101049 0.009275317 0.1908749 0.101863 0.009061753 0.192241 0.101967 0.009061753 0.1932089 0.1019459 0.009275317 0.19358 0.101649 0.009275317 0.194209 0.100709 0.009275317 0.1943939 0.09988307 0.009275317 0.194027 0.09975838 0.009061753 0.194384 0.09944158 0.009275317 0.194015 0.09948068 0.009061753 0.194329 0.09912347 0.009275317 0.194302 0.0990076 0.009275317 0.194239 0.09881335 0.009275317 0.193651 0.09786731 0.009275317 0.192743 0.09724986 0.009275317 0.189078 0.09934246 0.009275317 0.189055 0.0995624 0.009275317 0.189051 0.09978336 0.009275317 0.189065 0.100004 0.009275317 0.191465 0.100786 0.008623957 0.1906639 0.09944367 0.008621811 0.191985 0.09865957 0.008623957 0.192004 0.09866166 0.008621811 0.192786 0.100002 0.008621811 0.193059 0.09990698 0.008686244 0.192704 0.09922796 0.008621811 0.192667 0.09925109 0.008613824 0.192619 0.09925615 0.008602738 0.192237 0.09928286 0.008545756 0.192248 0.09929537 0.008545756 0.19213 0.09870296 0.008621811 0.191955 0.09838479 0.008687853 0.191249 0.09873735 0.008623957 0.1912299 0.09874349 0.008621811 0.191043 0.098374 0.008733749 0.191253 0.09878098 0.008613824 0.191258 0.09882855 0.008602738 0.191227 0.0992673 0.008545756 0.191285 0.0992105 0.008545756 0.190705 0.0993179 0.008621811 0.190387 0.09949219 0.008687853 0.190263 0.09933841 0.008733749 0.1907399 0.100199 0.008623957 0.190746 0.1002179 0.008621811 0.190783 0.100194 0.008613824 0.190831 0.100189 0.008602738 0.19103 0.100168 0.008572161 0.191269 0.100221 0.008545756 0.191213 0.100163 0.008545756 0.191541 0.101057 0.008686244 0.191494 0.101061 0.008687853 0.192197 0.100664 0.008613824 0.19222 0.100702 0.008621811 0.1923339 0.100635 0.008621811 0.192191 0.100617 0.008602738 0.19217 0.100417 0.008572161 0.192165 0.100235 0.008545756 0.192152 0.1002449 0.008545756 0.1890529 0.09968137 0.009275317 0.189822 0.09992396 0.008880794 0.189076 0.09935939 0.009275317 0.189423 0.09968709 0.009061753 0.189811 0.09969305 0.008880794 0.190222 0.09988158 0.008733749 0.189498 0.09913706 0.009061753 0.189118 0.0991252 0.009275317 0.189444 0.09940975 0.009061753 0.189176 0.09891188 0.009275317 0.189829 0.09946268 0.008880794 0.189252 0.09870415 0.009275317 0.189703 0.09862118 0.009061753 0.189585 0.09887295 0.009061753 0.1899459 0.09901636 0.008880794 0.1898739 0.09923595 0.008880794 0.190228 0.0995174 0.008733749 0.190391 0.0995385 0.008686244 0.190214 0.09969925 0.008733749 0.190405 0.09970098 0.00868076 0.19042 0.09986078 0.008675336 0.190252 0.100062 0.008733749 0.190439 0.10002 0.00868076 0.190304 0.100237 0.008733749 0.190459 0.1001819 0.008686244 0.190465 0.100228 0.008687853 0.1895779 0.09812825 0.009275317 0.18985 0.09838545 0.009061753 0.189752 0.09791958 0.009275317 0.190167 0.09861129 0.008880794 0.190044 0.09880715 0.008880794 0.19032 0.09916508 0.008733749 0.190705 0.09945845 0.008613824 0.190662 0.0994631 0.008623957 0.190753 0.0994535 0.008602738 0.190761 0.09919786 0.008621811 0.190495 0.09884518 0.008733749 0.190398 0.09899985 0.008733749 0.190025 0.09816926 0.009061753 0.189869 0.09779667 0.009275317 0.189984 0.09769511 0.009275317 0.190225 0.09797579 0.009061753 0.190312 0.09843158 0.008880794 0.190609 0.09870326 0.008733749 0.191132 0.0993998 0.008545756 0.190953 0.0994324 0.008572161 0.191124 0.09941416 0.008545756 0.190915 0.09898257 0.008621811 0.190832 0.09908556 0.008621811 0.190478 0.09827065 0.008880794 0.190662 0.098131 0.008880794 0.190446 0.0978077 0.009061753 0.190595 0.09729856 0.009275317 0.190687 0.09766757 0.009061753 0.1905199 0.0973376 0.009275317 0.190816 0.09720838 0.009275317 0.190942 0.09755736 0.009061753 0.1908619 0.09801447 0.008880794 0.190886 0.09846597 0.008733749 0.1907399 0.0985763 0.008733749 0.1910099 0.0988903 0.008621811 0.191175 0.09933066 0.008545756 0.191126 0.09711867 0.009275317 0.1910099 0.09714567 0.009275317 0.191209 0.0974788 0.009061753 0.191116 0.09881025 0.008621811 0.1912789 0.09902817 0.008572161 0.191298 0.09919995 0.008545756 0.1912249 0.09709548 0.009275317 0.191296 0.09785759 0.008880794 0.191211 0.0983017 0.008733749 0.191074 0.09792286 0.008880794 0.191766 0.0970509 0.009275317 0.191761 0.09742039 0.009061753 0.191664 0.09704899 0.009275317 0.191483 0.09743291 0.009061753 0.191524 0.0978195 0.008880794 0.191386 0.09825021 0.008733749 0.1918849 0.09705317 0.009275317 0.1917549 0.09780907 0.008880794 0.1925359 0.09717416 0.009275317 0.192404 0.0971384 0.009275317 0.19231 0.09749585 0.009061753 0.1920379 0.09744149 0.009061753 0.1927109 0.09723818 0.009275317 0.192575 0.09758269 0.009061753 0.192212 0.09787178 0.008880794 0.191985 0.0978266 0.008880794 0.192826 0.09770065 0.009061753 0.192431 0.09794396 0.008880794 0.192109 0.09826135 0.008733749 0.1919299 0.09822565 0.008733749 0.191748 0.09821188 0.008733749 0.191566 0.0982201 0.008733749 0.191266 0.09845685 0.008686244 0.192283 0.09831827 0.008733749 0.193491 0.0977146 0.009275317 0.193319 0.0975756 0.009275317 0.193062 0.09784817 0.009061753 0.193137 0.09745121 0.009275317 0.1935279 0.09774976 0.009275317 0.193278 0.09802305 0.009061753 0.19264 0.09804207 0.008880794 0.191989 0.0987032 0.008613824 0.191994 0.09875077 0.008602738 0.19225 0.09875929 0.008621811 0.192448 0.09839576 0.008733749 0.192602 0.09849256 0.008733749 0.192836 0.09816467 0.008880794 0.193752 0.09798181 0.009275317 0.193948 0.0982384 0.009275317 0.193472 0.09822267 0.009061753 0.1930159 0.09830999 0.008880794 0.192744 0.09860736 0.008733749 0.1920149 0.09895038 0.008572161 0.1920329 0.09912216 0.008545756 0.192048 0.09912985 0.008545756 0.192117 0.09917306 0.008545756 0.192362 0.09882956 0.008621811 0.193177 0.09847599 0.008880794 0.1936399 0.09844416 0.009061753 0.19378 0.09868437 0.009061753 0.194234 0.09879726 0.009275317 0.193433 0.09885966 0.008880794 0.1933169 0.09866011 0.008880794 0.192871 0.09873837 0.008733749 0.19218 0.09922438 0.008545756 0.192465 0.09891289 0.008621811 0.193969 0.09920638 0.009061753 0.19389 0.09893965 0.009061753 0.193074 0.09904128 0.008733749 0.192982 0.09888368 0.008733749 0.192637 0.09911358 0.008621811 0.192557 0.09900796 0.008621811 0.1924189 0.09927725 0.008572161 0.193525 0.09907186 0.008880794 0.193146 0.09920889 0.008733749 0.19271 0.0992465 0.008623957 0.1943989 0.09966206 0.009275317 0.193628 0.09952145 0.008880794 0.19359 0.09929358 0.008880794 0.193639 0.09975236 0.008880794 0.193228 0.09956389 0.008733749 0.1942729 0.100534 0.009275317 0.1943719 0.100103 0.009275317 0.194006 0.100036 0.009061753 0.193621 0.09998285 0.008880794 0.1932359 0.09974616 0.008733749 0.193952 0.100308 0.009061753 0.193747 0.1008239 0.009061753 0.194072 0.101001 0.009275317 0.193865 0.100573 0.009061753 0.193504 0.1004289 0.008880794 0.193576 0.10021 0.008880794 0.193186 0.100107 0.008733749 0.193222 0.09992808 0.008733749 0.193044 0.09974449 0.00868076 0.193197 0.09938389 0.008733749 0.1930299 0.09958475 0.008675336 0.193011 0.09942549 0.00868076 0.192991 0.0992636 0.008686244 0.1929849 0.09921747 0.008687853 0.193599 0.10106 0.009061753 0.193733 0.101489 0.009275317 0.193872 0.101317 0.009275317 0.1934249 0.101276 0.009061753 0.193406 0.100638 0.008880794 0.193283 0.100834 0.008880794 0.1930519 0.100446 0.008733749 0.193129 0.10028 0.008733749 0.192745 0.100128 0.008621811 0.192688 0.100248 0.008621811 0.192955 0.1006 0.008733749 0.193238 0.101928 0.009275317 0.193415 0.101795 0.009275317 0.1930029 0.101638 0.009061753 0.193225 0.10147 0.009061753 0.193138 0.101014 0.008880794 0.192972 0.101175 0.008880794 0.19284 0.100742 0.008733749 0.192318 0.100046 0.008545756 0.1923249 0.100031 0.008545756 0.192618 0.10036 0.008621811 0.192535 0.100463 0.008621811 0.192709 0.1008689 0.008733749 0.193051 0.1020449 0.009275317 0.19265 0.102232 0.009275317 0.192854 0.102147 0.009275317 0.19293 0.102108 0.009275317 0.192763 0.101778 0.009061753 0.192588 0.101431 0.008880794 0.192788 0.101315 0.008880794 0.192223 0.100178 0.008545756 0.192275 0.100115 0.008545756 0.19244 0.1023 0.009275317 0.192508 0.101888 0.009061753 0.192564 0.100979 0.008733749 0.19244 0.100555 0.008621811 0.191967 0.102013 0.009061753 0.192376 0.101523 0.008880794 0.19223 0.100983 0.008687853 0.1924059 0.101071 0.008733749 0.192201 0.100708 0.008623957 0.191689 0.102025 0.009061753 0.191785 0.102396 0.009275317 0.192154 0.101588 0.008880794 0.191926 0.101626 0.008880794 0.191695 0.101636 0.008880794 0.191412 0.102004 0.009061753 0.190738 0.102207 0.009275317 0.190914 0.102271 0.009275317 0.191139 0.10195 0.009061753 0.191465 0.101619 0.008880794 0.190623 0.101745 0.009061753 0.1910189 0.101502 0.008880794 0.191238 0.101574 0.008880794 0.19152 0.10122 0.008733749 0.1917009 0.101234 0.008733749 0.191703 0.101042 0.00868076 0.191884 0.101225 0.008733749 0.192064 0.101195 0.008733749 0.191863 0.101028 0.008675336 0.192022 0.1010079 0.00868076 0.192239 0.101144 0.008733749 0.192184 0.100989 0.008686244 0.191341 0.101184 0.008733749 0.190809 0.1014029 0.008880794 0.190388 0.101597 0.009061753 0.190313 0.101994 0.009275317 0.189959 0.101731 0.009275317 0.190173 0.101899 0.009275317 0.189922 0.101696 0.009275317 0.1911669 0.101127 0.008733749 0.19132 0.100742 0.008621811 0.191446 0.100784 0.008621811 0.191461 0.100742 0.008613824 0.191456 0.100695 0.008602738 0.191002 0.10105 0.008733749 0.190434 0.101135 0.008880794 0.190613 0.101281 0.008880794 0.190171 0.101422 0.009061753 0.18952 0.101236 0.009275317 0.189978 0.101223 0.009061753 0.189652 0.101413 0.009275317 0.189697 0.101464 0.009275317 0.189799 0.1015779 0.009275317 0.189502 0.101207 0.009275317 0.190273 0.10097 0.008880794 0.191088 0.100616 0.008621811 0.190847 0.100953 0.008733749 0.191402 0.100316 0.008545756 0.1912 0.100686 0.008621811 0.191434 0.100495 0.008572161 0.191416 0.100323 0.008545756 0.1913329 0.1002719 0.008545756 0.190705 0.100838 0.008733749 0.18981 0.101001 0.009061753 0.189301 0.100852 0.009275317 0.1893399 0.100928 0.009275317 0.189216 0.100648 0.009275317 0.18967 0.1007609 0.009061753 0.190133 0.100785 0.008880794 0.190578 0.100707 0.008733749 0.190985 0.100533 0.008621811 0.190017 0.1005859 0.008880794 0.189925 0.100374 0.008880794 0.190468 0.100562 0.008733749 0.190812 0.100332 0.008621811 0.190892 0.100437 0.008621811 0.191202 0.10015 0.008545756 0.189098 0.100223 0.009275317 0.189435 0.09996485 0.009061753 0.18986 0.100152 0.008880794 0.190376 0.100404 0.008733749 0.193063 0.09995335 0.008687853 0.192288 0.100035 0.01024997 0.1921769 0.100047 0.01024997 0.192202 0.100044 0.009976387 0.192309 0.100033 0.008744776 0.192497 0.100013 0.008572161 0.192697 0.09999209 0.008602738 0.192744 0.09998697 0.008613824 0.192788 0.09998238 0.008623957 0.181706 -0.115978 0.01024997 0.181718 -0.115948 0.01024997 0.181657 -0.115811 0.008545756 0.181559 -0.116069 0.008545756 0.181695 -0.116008 0.01024997 0.181581 -0.115973 0.008545756 0.182857 -0.116301 0.01024997 0.182778 -0.116124 0.01024997 0.18276 -0.116011 0.01019227 0.182636 -0.115802 0.01024997 0.182557 -0.115625 0.01024997 0.183268 -0.115309 0.008687853 0.1827149 -0.115905 0.01018857 0.1834239 -0.115644 0.008675336 0.183551 -0.115942 0.008686244 0.179888 -0.11772 0.009503483 0.179888 -0.11772 0.01089996 0.180024 -0.117908 0.009503483 0.1801739 -0.118084 0.009503483 0.1801739 -0.118084 0.01089996 0.180516 -0.118395 0.01089996 0.180904 -0.118646 0.01089996 0.180705 -0.118529 0.009503483 0.181113 -0.118747 0.009503483 0.181329 -0.11883 0.01089996 0.181551 -0.118895 0.009503483 0.181778 -0.118941 0.01089996 0.182007 -0.118969 0.009503483 0.18247 -0.1189669 0.009503483 0.1822389 -0.118977 0.01089996 0.182699 -0.118937 0.01089996 0.183147 -0.118821 0.01089996 0.18357 -0.118633 0.009503483 0.18357 -0.118633 0.01089996 0.183768 -0.118514 0.009503483 0.183955 -0.118378 0.01089996 0.184131 -0.118228 0.009503483 0.184294 -0.118064 0.01089996 0.184576 -0.117697 0.01089996 0.184795 -0.117289 0.01089996 0.184795 -0.117289 0.009503483 0.184943 -0.116851 0.009503483 0.184943 -0.116851 0.01089996 0.185016 -0.1163949 0.01089996 0.184989 -0.116625 0.009503483 0.185016 -0.1163949 0.009503483 0.185014 -0.115932 0.01089996 0.184936 -0.115477 0.009503483 0.184869 -0.1152549 0.009503483 0.184936 -0.115477 0.01089996 0.1846809 -0.1148329 0.009503483 0.1847839 -0.11504 0.01089996 0.184561 -0.114634 0.009503483 0.184561 -0.114634 0.01089996 0.184276 -0.114271 0.009503483 0.184276 -0.114271 0.01089996 0.183934 -0.113959 0.01089996 0.1841109 -0.114108 0.009503483 0.1835449 -0.113708 0.01089996 0.183337 -0.113608 0.009503483 0.183121 -0.113525 0.01089996 0.1828989 -0.11346 0.009503483 0.182672 -0.113413 0.01089996 0.182211 -0.113377 0.01089996 0.181751 -0.113418 0.01089996 0.18198 -0.113388 0.009503483 0.181751 -0.113418 0.009503483 0.181524 -0.113466 0.009503483 0.181303 -0.113533 0.01089996 0.18088 -0.113721 0.01089996 0.180682 -0.1138409 0.009503483 0.180494 -0.113976 0.01089996 0.180494 -0.113976 0.009503483 0.1803179 -0.114127 0.009503483 0.1801559 -0.114291 0.01089996 0.179873 -0.114657 0.01089996 0.179655 -0.115065 0.01089996 0.179756 -0.114857 0.009503483 0.179507 -0.115503 0.01089996 0.179433 -0.11596 0.009503483 0.179433 -0.11596 0.01089996 0.179425 -0.116191 0.009503483 0.179436 -0.1164219 0.01089996 0.179436 -0.1164219 0.009503483 0.1794649 -0.116652 0.009503483 0.179514 -0.116878 0.01089996 0.179581 -0.117099 0.009503483 0.179666 -0.117315 0.01089996 0.179666 -0.117315 0.009503483 0.180113 -0.117816 0.009275317 0.18007 -0.1178719 0.009335577 0.180266 -0.117998 0.009275317 0.180217 -0.118044 0.009335577 0.1803269 -0.118058 0.009275317 0.180423 -0.118154 0.009275317 0.180593 -0.118296 0.009275317 0.180552 -0.118349 0.009335577 0.180737 -0.11848 0.009335577 0.1809639 -0.118536 0.009275317 0.1811169 -0.118609 0.009275317 0.181163 -0.118632 0.009275317 0.181369 -0.118711 0.009275317 0.181565 -0.118838 0.009335577 0.181581 -0.118773 0.009275317 0.181798 -0.118817 0.009275317 0.182012 -0.11891 0.009335577 0.182017 -0.118844 0.009275317 0.182051 -0.118845 0.009275317 0.182238 -0.118919 0.009335577 0.182238 -0.118852 0.009275317 0.1824589 -0.118841 0.009275317 0.182678 -0.118813 0.009275317 0.182695 -0.118809 0.009275317 0.1831279 -0.118766 0.009335577 0.183311 -0.118621 0.009275317 0.183338 -0.118682 0.009335577 0.1835089 -0.118523 0.009275317 0.1835409 -0.118582 0.009335577 0.183597 -0.11847 0.009275317 0.183699 -0.118409 0.009275317 0.1838639 -0.11829 0.009275317 0.183919 -0.118332 0.009335577 0.184091 -0.118185 0.009335577 0.1841059 -0.118076 0.009275317 0.184251 -0.118024 0.009335577 0.184642 -0.11747 0.009335577 0.184505 -0.11757 0.009275317 0.184741 -0.1172659 0.009335577 0.184657 -0.117285 0.009275317 0.184679 -0.11724 0.009275317 0.184822 -0.1170549 0.009335577 0.184773 -0.116984 0.009275317 0.184821 -0.116821 0.009275317 0.184886 -0.116837 0.009335577 0.184931 -0.1166149 0.009335577 0.184958 -0.11639 0.009335577 0.1848919 -0.116351 0.009275317 0.184966 -0.116164 0.009335577 0.184893 -0.116028 0.009275317 0.184927 -0.115713 0.009335577 0.184861 -0.115724 0.009275317 0.184879 -0.115491 0.009335577 0.184813 -0.115274 0.009335577 0.184669 -0.115091 0.009275317 0.1847299 -0.115064 0.009335577 0.184518 -0.114805 0.009275317 0.184513 -0.1146669 0.009335577 0.184327 -0.114524 0.009275317 0.184184 -0.114356 0.009275317 0.184123 -0.114296 0.009275317 0.184072 -0.114151 0.009335577 0.183883 -0.114081 0.009275317 0.183898 -0.114006 0.009335577 0.183713 -0.113875 0.009335577 0.183618 -0.113897 0.009275317 0.1835179 -0.1137599 0.009335577 0.183314 -0.113661 0.009335577 0.183287 -0.113723 0.009275317 0.183081 -0.113644 0.009275317 0.182869 -0.113581 0.009275317 0.1827189 -0.113551 0.009275317 0.1826519 -0.113537 0.009275317 0.182399 -0.11351 0.009275317 0.1817719 -0.113541 0.009275317 0.181985 -0.1134459 0.009335577 0.18176 -0.113475 0.009335577 0.1815389 -0.113523 0.009335577 0.181442 -0.113622 0.009275317 0.181322 -0.113589 0.009335577 0.1811389 -0.113733 0.009275317 0.180941 -0.113831 0.009275317 0.180853 -0.113884 0.009275317 0.180404 -0.1142179 0.009275317 0.180199 -0.1143299 0.009335577 0.180128 -0.114519 0.009275317 0.180106 -0.114545 0.009275317 0.1799229 -0.114689 0.009335577 0.179944 -0.114784 0.009275317 0.179709 -0.115088 0.009335577 0.1797699 -0.115115 0.009275317 0.179628 -0.1152999 0.009335577 0.1795639 -0.115517 0.009335577 0.179677 -0.11537 0.009275317 0.179629 -0.115533 0.009275317 0.179598 -0.115683 0.009275317 0.179585 -0.11575 0.009275317 0.1795189 -0.115739 0.009335577 0.1794829 -0.116191 0.009335577 0.179557 -0.116326 0.009275317 0.179589 -0.11663 0.009275317 0.179523 -0.1166419 0.009335577 0.179593 -0.116647 0.009275317 0.17972 -0.117291 0.009335577 0.179879 -0.117462 0.009275317 0.1799319 -0.117549 0.009275317 0.179993 -0.117651 0.009275317 0.17982 -0.117494 0.009335577 0.179937 -0.117688 0.009335577 0.180185 -0.118073 0.009414553 0.180378 -0.118203 0.009335577 0.1803489 -0.118235 0.009414553 0.180932 -0.118595 0.009335577 0.181136 -0.118693 0.009335577 0.181119 -0.118733 0.009414553 0.181347 -0.1187739 0.009335577 0.181334 -0.118816 0.009414553 0.181554 -0.11888 0.009414553 0.181787 -0.118883 0.009335577 0.182008 -0.118954 0.009414553 0.182465 -0.118908 0.009335577 0.182689 -0.118879 0.009335577 0.182911 -0.118832 0.009335577 0.183736 -0.118465 0.009335577 0.183562 -0.11862 0.009414553 0.184121 -0.118217 0.009414553 0.184397 -0.11785 0.009335577 0.184527 -0.117665 0.009335577 0.184863 -0.117069 0.009414553 0.184999 -0.115934 0.009414553 0.184956 -0.115937 0.009335577 0.18497 -0.115705 0.009414553 0.184854 -0.11526 0.009414553 0.18463 -0.114861 0.009335577 0.184549 -0.114643 0.009414553 0.1843799 -0.1144829 0.009335577 0.184233 -0.114311 0.009335577 0.183102 -0.11358 0.009335577 0.183116 -0.113539 0.009414553 0.182885 -0.113516 0.009335577 0.182895 -0.113474 0.009414553 0.1826699 -0.1134279 0.009414553 0.182663 -0.113471 0.009335577 0.182438 -0.113444 0.009335577 0.1824409 -0.113401 0.009414553 0.182211 -0.113436 0.009335577 0.181753 -0.113433 0.009414553 0.181528 -0.113481 0.009414553 0.181308 -0.113548 0.009414553 0.181094 -0.113632 0.009414553 0.181111 -0.113672 0.009335577 0.180908 -0.113773 0.009335577 0.180887 -0.113734 0.009414553 0.1806899 -0.113853 0.009414553 0.180714 -0.11389 0.009335577 0.18053 -0.114022 0.009335577 0.1803579 -0.114169 0.009335577 0.180329 -0.114138 0.009414553 0.1800529 -0.114504 0.009335577 0.179769 -0.114864 0.009414553 0.179807 -0.114884 0.009335577 0.179669 -0.1150709 0.009414553 0.1794919 -0.115964 0.009335577 0.179448 -0.115961 0.009414553 0.179494 -0.116417 0.009335577 0.179451 -0.116421 0.009414553 0.179571 -0.116863 0.009335577 0.179636 -0.11708 0.009335577 0.179782 -0.117515 0.009414553 0.179769 -0.117522 0.009503483 0.179901 -0.117712 0.009414553 0.180036 -0.117899 0.009414553 0.180339 -0.118247 0.009503483 0.180525 -0.118383 0.009414553 0.180516 -0.118395 0.009503483 0.1807129 -0.118516 0.009414553 0.180911 -0.118633 0.009414553 0.180904 -0.118646 0.009503483 0.181329 -0.11883 0.009503483 0.18178 -0.118926 0.009414553 0.181778 -0.118941 0.009503483 0.1822389 -0.118962 0.009414553 0.1822389 -0.118977 0.009503483 0.1824679 -0.118952 0.009414553 0.1826969 -0.118922 0.009414553 0.182699 -0.118937 0.009503483 0.182922 -0.118874 0.009414553 0.1829259 -0.118888 0.009503483 0.183147 -0.118821 0.009503483 0.183142 -0.118807 0.009414553 0.183356 -0.118722 0.009414553 0.183362 -0.118736 0.009503483 0.183759 -0.118501 0.009414553 0.183955 -0.118378 0.009503483 0.183946 -0.118367 0.009414553 0.184283 -0.118053 0.009414553 0.184431 -0.117877 0.009414553 0.184294 -0.118064 0.009503483 0.1844429 -0.117886 0.009503483 0.184576 -0.117697 0.009503483 0.1845639 -0.117689 0.009414553 0.1846939 -0.117498 0.009503483 0.1846809 -0.117491 0.009414553 0.184781 -0.117283 0.009414553 0.184878 -0.1170729 0.009503483 0.1849279 -0.116848 0.009414553 0.184974 -0.116622 0.009414553 0.185001 -0.116394 0.009414553 0.18501 -0.116164 0.009414553 0.185025 -0.116164 0.009503483 0.185014 -0.115932 0.009503483 0.184984 -0.115703 0.009503483 0.184921 -0.11548 0.009414553 0.1847699 -0.115046 0.009414553 0.1847839 -0.11504 0.009503483 0.184668 -0.11484 0.009414553 0.184414 -0.1144559 0.009414553 0.184265 -0.1142809 0.009414553 0.184426 -0.1144469 0.009503483 0.184101 -0.114119 0.009414553 0.183925 -0.113971 0.009414553 0.183934 -0.113959 0.009503483 0.183737 -0.113838 0.009414553 0.183745 -0.113826 0.009503483 0.183538 -0.113721 0.009414553 0.1835449 -0.113708 0.009503483 0.183331 -0.1136209 0.009414553 0.183121 -0.113525 0.009503483 0.182672 -0.113413 0.009503483 0.182442 -0.113386 0.009503483 0.182211 -0.113392 0.009414553 0.182211 -0.113377 0.009503483 0.181981 -0.113403 0.009414553 0.181303 -0.113533 0.009503483 0.181088 -0.113619 0.009503483 0.18088 -0.113721 0.009503483 0.180504 -0.113988 0.009414553 0.180167 -0.114301 0.009414553 0.1801559 -0.114291 0.009503483 0.180007 -0.114468 0.009503483 0.180019 -0.114477 0.009414553 0.179886 -0.114665 0.009414553 0.179873 -0.114657 0.009503483 0.179655 -0.115065 0.009503483 0.1795859 -0.115286 0.009414553 0.179572 -0.115281 0.009503483 0.179522 -0.115507 0.009414553 0.179507 -0.115503 0.009503483 0.179461 -0.11573 0.009503483 0.179476 -0.115732 0.009414553 0.17944 -0.116191 0.009414553 0.17948 -0.116649 0.009414553 0.179529 -0.116874 0.009414553 0.179514 -0.116878 0.009503483 0.1795949 -0.117094 0.009414553 0.1796799 -0.117308 0.009414553 0.1822119 -0.113503 0.009275317 0.183333 -0.113745 0.009275317 0.184457 -0.114704 0.009275317 0.18478 -0.1153939 0.009275317 0.184857 -0.115708 0.009275317 0.184899 -0.116164 0.009275317 0.184343 -0.11781 0.009275317 0.184031 -0.117606 0.009061753 0.1829 -0.1183789 0.009061753 0.180567 -0.118274 0.009275317 0.180122 -0.11783 0.009275317 0.179781 -0.117264 0.009275317 0.179557 -0.116003 0.009275317 0.180572 -0.114075 0.009275317 0.180586 -0.114065 0.009275317 0.180751 -0.113945 0.009275317 0.181043 -0.114201 0.009061753 0.1816099 -0.1158969 0.008545756 0.181356 -0.115134 0.008687853 0.182981 -0.116968 0.008623957 0.182964 -0.116928 0.008613824 0.182305 -0.117269 0.008623957 0.182286 -0.117273 0.008621811 0.182309 -0.117686 0.008733749 0.182186 -0.1170009 0.008572161 0.1820999 -0.116841 0.008545756 0.182116 -0.1168439 0.008545756 0.1811619 -0.117004 0.008686244 0.181129 -0.1162379 0.008621811 0.181133 -0.116257 0.008623957 0.181174 -0.11624 0.008613824 0.181217 -0.1162199 0.008602738 0.1811299 -0.116106 0.008621811 0.1815609 -0.116052 0.008545756 0.181486 -0.115426 0.008613824 0.181506 -0.11547 0.008602738 0.1813639 -0.115497 0.008621811 0.181398 -0.115114 0.008686244 0.182162 -0.115126 0.008613824 0.182182 -0.11517 0.008602738 0.182164 -0.115082 0.008621811 0.182296 -0.115082 0.008621811 0.182263 -0.115353 0.008572161 0.18235 -0.115514 0.008545756 0.182428 -0.115099 0.008621811 0.182976 -0.1154389 0.008613824 0.182906 -0.115317 0.008621811 0.183298 -0.115114 0.008733749 0.18332 -0.116116 0.008621811 0.1837339 -0.116093 0.008733749 0.18332 -0.116249 0.008621811 0.1832759 -0.116115 0.008613824 0.183233 -0.116134 0.008602738 0.182888 -0.116302 0.008545756 0.182891 -0.116286 0.008545756 0.181664 -0.114347 0.008880794 0.181959 -0.11469 0.008733749 0.181448 -0.114428 0.008880794 0.180604 -0.114541 0.009061753 0.180344 -0.114279 0.009275317 0.180813 -0.114358 0.009061753 0.181052 -0.114665 0.008880794 0.181242 -0.114535 0.008880794 0.181611 -0.114796 0.008733749 0.180248 -0.114376 0.009275317 0.180878 -0.114818 0.008880794 0.179867 -0.114916 0.009275317 0.179979 -0.114725 0.009275317 0.18026 -0.114977 0.009061753 0.180724 -0.1149899 0.008880794 0.180419 -0.114749 0.009061753 0.181299 -0.114983 0.008733749 0.181161 -0.115104 0.008733749 0.181546 -0.115045 0.00868076 0.1814489 -0.11488 0.008733749 0.181692 -0.114978 0.008675336 0.181782 -0.114733 0.008733749 0.181839 -0.114915 0.00868076 0.18199 -0.1148509 0.008686244 0.1810399 -0.11524 0.008733749 0.179691 -0.115321 0.009275317 0.18013 -0.115222 0.009061753 0.179793 -0.115069 0.009275317 0.180483 -0.115384 0.008880794 0.180592 -0.11518 0.008880794 0.181453 -0.115398 0.008621811 0.181468 -0.115386 0.008623957 0.181587 -0.115654 0.008572161 0.180935 -0.11539 0.008733749 0.181289 -0.1156049 0.008621811 0.1800299 -0.115482 0.009061753 0.1795589 -0.115969 0.009275317 0.179927 -0.116028 0.009061753 0.179962 -0.115752 0.009061753 0.180344 -0.115824 0.008880794 0.180784 -0.115721 0.008733749 0.1804 -0.115599 0.008880794 0.18085 -0.115551 0.008733749 0.181649 -0.1158249 0.008545756 0.181596 -0.115935 0.008545756 0.181226 -0.115722 0.008621811 0.181179 -0.115846 0.008621811 0.1807399 -0.115898 0.008733749 0.179561 -0.116411 0.009275317 0.1795499 -0.11619 0.009275317 0.179958 -0.116582 0.009061753 0.179926 -0.116306 0.009061753 0.180315 -0.116053 0.008880794 0.180717 -0.116079 0.008733749 0.181147 -0.115974 0.008621811 0.17967 -0.11696 0.009275317 0.180023 -0.116852 0.009061753 0.179636 -0.116846 0.009275317 0.180314 -0.116284 0.008880794 0.181401 -0.116139 0.008572161 0.180121 -0.117112 0.009061753 0.1797 -0.117058 0.009275317 0.180395 -0.116738 0.008880794 0.180341 -0.116513 0.008880794 0.180737 -0.116443 0.008733749 0.180716 -0.116261 0.008733749 0.180249 -0.117359 0.009061753 0.180476 -0.116955 0.008880794 0.1807799 -0.11662 0.008733749 0.180589 -0.117798 0.009061753 0.180406 -0.1175889 0.009061753 0.180928 -0.116953 0.008733749 0.180582 -0.11716 0.008880794 0.180844 -0.116791 0.008733749 0.180796 -0.117983 0.009061753 0.1807129 -0.117351 0.008880794 0.181031 -0.117104 0.008733749 0.180832 -0.118458 0.009275317 0.181025 -0.118142 0.009061753 0.180773 -0.118423 0.009275317 0.181038 -0.117678 0.008880794 0.180865 -0.117524 0.008880794 0.181093 -0.116856 0.00868076 0.181025 -0.11671 0.008675336 0.180963 -0.116563 0.00868076 0.180899 -0.1164129 0.008686244 0.180881 -0.11637 0.008687853 0.181227 -0.11781 0.008880794 0.181287 -0.117362 0.008733749 0.181151 -0.117241 0.008733749 0.181181 -0.1170459 0.008687853 0.181418 -0.118725 0.009275317 0.1815299 -0.118372 0.009061753 0.18127 -0.118273 0.009061753 0.1814309 -0.117919 0.008880794 0.181437 -0.117467 0.008733749 0.181544 -0.117038 0.008621811 0.181445 -0.116949 0.008621811 0.181474 -0.116916 0.008613824 0.181434 -0.116934 0.008623957 0.181518 -0.116896 0.008602738 0.181701 -0.116815 0.008572161 0.181598 -0.117552 0.008733749 0.181647 -0.1180019 0.008880794 0.181731 -0.118804 0.009275317 0.1817989 -0.11844 0.009061753 0.181653 -0.117114 0.008621811 0.18177 -0.1171759 0.008621811 0.181873 -0.116753 0.008545756 0.181859 -0.116745 0.008545756 0.181945 -0.116792 0.008545756 0.181769 -0.117618 0.008733749 0.1818709 -0.118058 0.008880794 0.1820999 -0.118087 0.008880794 0.182075 -0.118475 0.009061753 0.182353 -0.118476 0.009061753 0.182374 -0.118845 0.009275317 0.182629 -0.118444 0.009061753 0.182332 -0.118088 0.008880794 0.181946 -0.117662 0.008733749 0.181894 -0.117223 0.008621811 0.182021 -0.116821 0.008545756 0.183008 -0.118732 0.009275317 0.182894 -0.118767 0.009275317 0.182561 -0.118061 0.008880794 0.1821539 -0.117272 0.008621811 0.1821269 -0.117685 0.008733749 0.182022 -0.117256 0.008621811 0.18316 -0.118281 0.009061753 0.183106 -0.118702 0.009275317 0.183407 -0.118153 0.009061753 0.1830019 -0.117926 0.008880794 0.182786 -0.118007 0.008880794 0.182668 -0.117622 0.008733749 0.183637 -0.117996 0.009061753 0.183207 -0.11782 0.008880794 0.184201 -0.117979 0.009275317 0.1838459 -0.117813 0.009061753 0.184046 -0.118136 0.009275317 0.183878 -0.1182799 0.009275317 0.183398 -0.117689 0.008880794 0.182839 -0.117558 0.008733749 0.1843219 -0.1178359 0.009275317 0.1835719 -0.117537 0.008880794 0.184471 -0.117629 0.009275317 0.183151 -0.117371 0.008733749 0.183051 -0.11724 0.008686244 0.182903 -0.117309 0.00868076 0.183001 -0.117474 0.008733749 0.182758 -0.117377 0.008675336 0.1824899 -0.117665 0.008733749 0.18261 -0.117439 0.00868076 0.18246 -0.117503 0.008686244 0.183094 -0.1172209 0.008687853 0.182997 -0.116957 0.008621811 0.183288 -0.117251 0.008733749 0.1834099 -0.117115 0.008733749 0.183726 -0.117365 0.008880794 0.18419 -0.1173779 0.009061753 0.184583 -0.117439 0.009275317 0.1844199 -0.116872 0.009061753 0.184759 -0.117033 0.009275317 0.18432 -0.117132 0.009061753 0.183858 -0.117175 0.008880794 0.183966 -0.116971 0.008880794 0.1835139 -0.116965 0.008733749 0.183085 -0.116858 0.008621811 0.1829439 -0.116884 0.008602738 0.1828629 -0.116701 0.008572161 0.183161 -0.116749 0.008621811 0.1848649 -0.116605 0.009275317 0.184851 -0.116671 0.009275317 0.184891 -0.116385 0.009275317 0.1844879 -0.116603 0.009061753 0.1841059 -0.116531 0.008880794 0.184049 -0.116755 0.008880794 0.183223 -0.116632 0.008621811 0.1836 -0.116804 0.008733749 0.182801 -0.116529 0.008545756 0.182792 -0.116543 0.008545756 0.182839 -0.116457 0.008545756 0.183665 -0.1166329 0.008733749 0.183271 -0.116509 0.008621811 0.184523 -0.116327 0.009061753 0.184889 -0.115943 0.009275317 0.1845239 -0.116049 0.009061753 0.183733 -0.116275 0.008733749 0.184135 -0.116302 0.008880794 0.18371 -0.116457 0.008733749 0.182869 -0.116381 0.008545756 0.184814 -0.115508 0.009275317 0.184492 -0.115773 0.009061753 0.184426 -0.1155019 0.009061753 0.184109 -0.115841 0.008880794 0.184136 -0.116071 0.008880794 0.1833029 -0.11638 0.008621811 0.183049 -0.116216 0.008572161 0.18475 -0.115296 0.009275317 0.1833159 -0.116097 0.008623957 0.184571 -0.114893 0.009275317 0.184201 -0.114995 0.009061753 0.184329 -0.115242 0.009061753 0.184055 -0.115616 0.008880794 0.184337 -0.114538 0.009275317 0.183974 -0.1154 0.008880794 0.18367 -0.115734 0.008733749 0.183861 -0.114557 0.009061753 0.184044 -0.114766 0.009061753 0.183867 -0.115195 0.008880794 0.184027 -0.114201 0.009275317 0.183737 -0.115004 0.008880794 0.183522 -0.115402 0.008733749 0.183486 -0.113819 0.009275317 0.183677 -0.113931 0.009275317 0.183857 -0.114059 0.009275317 0.183412 -0.1146759 0.008880794 0.1836529 -0.114371 0.009061753 0.183584 -0.11483 0.008880794 0.183288 -0.115351 0.008686244 0.183419 -0.115251 0.008733749 0.183357 -0.115499 0.00868076 0.183606 -0.115563 0.008733749 0.1834869 -0.115792 0.00868076 0.183712 -0.115912 0.008733749 0.183569 -0.115985 0.008687853 0.183425 -0.114212 0.009061753 0.183223 -0.114544 0.008880794 0.183162 -0.114992 0.008733749 0.183004 -0.115405 0.008621811 0.183016 -0.1154209 0.008623957 0.18292 -0.113982 0.009061753 0.183032 -0.113629 0.009275317 0.18318 -0.114082 0.009061753 0.183013 -0.114888 0.008733749 0.182932 -0.115458 0.008602738 0.182851 -0.114802 0.008733749 0.182803 -0.114353 0.008880794 0.183018 -0.114436 0.008880794 0.18265 -0.113914 0.009061753 0.182375 -0.113879 0.009061753 0.182433 -0.113511 0.009275317 0.182579 -0.114296 0.008880794 0.182681 -0.114737 0.008733749 0.182797 -0.115241 0.008621811 0.18268 -0.115179 0.008621811 0.182577 -0.115601 0.008545756 0.182749 -0.11554 0.008572161 0.182591 -0.11561 0.008545756 0.182349 -0.114267 0.008880794 0.181991 -0.113513 0.009275317 0.182076 -0.1135089 0.009275317 0.181755 -0.113545 0.009275317 0.18182 -0.11391 0.009061753 0.182097 -0.113878 0.009061753 0.1825039 -0.114692 0.008733749 0.182429 -0.115534 0.008545756 0.182556 -0.115131 0.008621811 0.182505 -0.115563 0.008545756 0.181556 -0.113588 0.009275317 0.1821179 -0.114266 0.008880794 0.182141 -0.114669 0.008733749 0.182323 -0.114669 0.008733749 0.182334 -0.115511 0.008545756 0.181344 -0.113652 0.009275317 0.18129 -0.114073 0.009061753 0.18155 -0.113976 0.009061753 0.1818889 -0.114293 0.008880794 0.182032 -0.1148329 0.008687853 0.1821449 -0.115086 0.008623957 0.1820549 -0.116707 0.01024997 0.182101 -0.11681 0.01024997 0.182066 -0.11673 0.009976387 0.1821089 -0.116828 0.008744776 0.182417 -0.117521 0.008687853 0.182287 -0.117229 0.008613824 0.182268 -0.1171849 0.008602738 0.180751 -0.116454 0.01889997 0.180854 -0.116786 0.01889997 0.181032 -0.117086 0.01889997 0.181032 -0.117086 0.01099997 0.181273 -0.117337 0.01099997 0.181273 -0.117337 0.01889997 0.1815659 -0.117525 0.01099997 0.1815659 -0.117525 0.01889997 0.181895 -0.117641 0.01889997 0.181895 -0.117641 0.01099997 0.182241 -0.117677 0.01099997 0.182241 -0.117677 0.01889997 0.182587 -0.117633 0.01099997 0.182913 -0.11751 0.01099997 0.182587 -0.117633 0.01889997 0.182913 -0.11751 0.01889997 0.183202 -0.117316 0.01889997 0.183202 -0.117316 0.01099997 0.183438 -0.11706 0.01099997 0.183609 -0.116756 0.01099997 0.183438 -0.11706 0.01889997 0.183609 -0.116756 0.01889997 0.183705 -0.116421 0.01099997 0.183705 -0.116421 0.01889997 0.183721 -0.116074 0.01099997 0.183721 -0.116074 0.01889997 0.183657 -0.115731 0.01099997 0.183516 -0.115413 0.01099997 0.183657 -0.115731 0.01889997 0.183516 -0.115413 0.01889997 0.183305 -0.115136 0.01099997 0.183035 -0.114915 0.01099997 0.183305 -0.115136 0.01889997 0.183035 -0.114915 0.01889997 0.182722 -0.114762 0.01099997 0.182722 -0.114762 0.01889997 0.182383 -0.114686 0.01099997 0.182383 -0.114686 0.01889997 0.182034 -0.114689 0.01099997 0.182034 -0.114689 0.01889997 0.1816959 -0.114773 0.01099997 0.1816959 -0.114773 0.01889997 0.181387 -0.114933 0.01099997 0.181387 -0.114933 0.01889997 0.181123 -0.11516 0.01099997 0.181123 -0.11516 0.01889997 0.180918 -0.115442 0.01099997 0.180783 -0.115763 0.01099997 0.180918 -0.115442 0.01889997 0.180783 -0.115763 0.01889997 0.180727 -0.116107 0.01099997 0.180727 -0.116107 0.01889997 0.180751 -0.116454 0.01099997 0.180854 -0.116786 0.01099997 -0.181583 -0.116234 0.01024997 -0.18168 -0.116066 0.01024997 -0.180931 -0.115804 0.008686244 -0.181856 -0.115761 0.01024997 -0.181953 -0.115593 0.01024997 -0.181766 -0.115855 0.01018857 -0.181171 -0.115383 0.00868076 -0.181711 -0.115955 0.01019227 -0.18101 -0.115661 0.00868076 -0.182279 -0.11685 0.008545756 -0.1823379 -0.116722 0.01024997 -0.1823599 -0.116839 0.008545756 -0.1823689 -0.116714 0.01024997 -0.182399 -0.116705 0.01024997 -0.182769 -0.116064 0.01024997 -0.182867 -0.116121 0.01024997 -0.1827909 -0.116077 0.009976387 -0.182885 -0.116131 0.008744776 -0.1828989 -0.116139 0.008545756 -0.180064 -0.114397 0.01089996 -0.180064 -0.114397 0.009503483 -0.180218 -0.114225 0.009503483 -0.180386 -0.114066 0.01089996 -0.180386 -0.114066 0.009503483 -0.180759 -0.113792 0.01089996 -0.180759 -0.113792 0.009503483 -0.181171 -0.113583 0.009503483 -0.181389 -0.113505 0.009503483 -0.181171 -0.113583 0.01089996 -0.181613 -0.113445 0.009503483 -0.181613 -0.113445 0.01089996 -0.182071 -0.113381 0.01089996 -0.1823019 -0.113378 0.009503483 -0.182533 -0.113394 0.01089996 -0.182987 -0.113483 0.01089996 -0.182762 -0.113429 0.009503483 -0.182987 -0.113483 0.009503483 -0.18342 -0.113645 0.009503483 -0.18342 -0.113645 0.01089996 -0.18382 -0.113876 0.01089996 -0.184177 -0.11417 0.01089996 -0.184481 -0.114519 0.01089996 -0.184723 -0.114913 0.01089996 -0.184897 -0.115341 0.01089996 -0.184957 -0.115565 0.009503483 -0.184998 -0.115793 0.009503483 -0.184998 -0.115793 0.01089996 -0.185021 -0.116023 0.009503483 -0.185024 -0.116254 0.01089996 -0.184973 -0.116714 0.01089996 -0.1848469 -0.117159 0.01089996 -0.18465 -0.117577 0.01089996 -0.184386 -0.117957 0.01089996 -0.184064 -0.118289 0.01089996 -0.184064 -0.118289 0.009503483 -0.183883 -0.1184329 0.009503483 -0.183691 -0.1185629 0.009503483 -0.183691 -0.1185629 0.01089996 -0.183279 -0.118771 0.01089996 -0.183061 -0.11885 0.009503483 -0.182837 -0.118909 0.009503483 -0.182837 -0.118909 0.01089996 -0.182379 -0.118973 0.01089996 -0.182609 -0.118951 0.009503483 -0.182148 -0.1189759 0.009503483 -0.181917 -0.11896 0.01089996 -0.181463 -0.118872 0.009503483 -0.181463 -0.118872 0.01089996 -0.181243 -0.118799 0.009503483 -0.18103 -0.118709 0.01089996 -0.18103 -0.118709 0.009503483 -0.180629 -0.118478 0.009503483 -0.180629 -0.118478 0.01089996 -0.180272 -0.118184 0.01089996 -0.180113 -0.118016 0.009503483 -0.179969 -0.117835 0.01089996 -0.179727 -0.117442 0.009503483 -0.179727 -0.117442 0.01089996 -0.1796309 -0.117231 0.009503483 -0.179553 -0.117013 0.01089996 -0.179553 -0.117013 0.009503483 -0.179493 -0.1167899 0.009503483 -0.179451 -0.116562 0.009503483 -0.179451 -0.116562 0.01089996 -0.1794289 -0.116331 0.009503483 -0.179442 -0.115869 0.009503483 -0.179426 -0.1161 0.01089996 -0.179477 -0.11564 0.01089996 -0.179603 -0.115195 0.01089996 -0.179603 -0.115195 0.009503483 -0.1798 -0.114777 0.01089996 -0.180297 -0.114325 0.009275317 -0.180535 -0.114107 0.009275317 -0.1806409 -0.114022 0.009275317 -0.180987 -0.113731 0.009335577 -0.181079 -0.113763 0.009275317 -0.1811929 -0.113637 0.009335577 -0.181218 -0.113699 0.009275317 -0.181379 -0.113642 0.009275317 -0.18164 -0.113568 0.009275317 -0.181625 -0.113502 0.009335577 -0.181848 -0.113462 0.009335577 -0.181858 -0.113528 0.009275317 -0.182299 -0.113504 0.009275317 -0.1823 -0.1134369 0.009335577 -0.182332 -0.113506 0.009275317 -0.1825259 -0.113452 0.009335577 -0.182519 -0.113519 0.009275317 -0.182654 -0.1135399 0.009275317 -0.182738 -0.113552 0.009275317 -0.182969 -0.113609 0.009275317 -0.183272 -0.113719 0.009275317 -0.183787 -0.113924 0.009335577 -0.183749 -0.113979 0.009275317 -0.183968 -0.1140609 0.009335577 -0.183925 -0.114113 0.009275317 -0.184077 -0.114249 0.009275317 -0.1842949 -0.114487 0.009275317 -0.1843799 -0.114593 0.009275317 -0.184484 -0.114749 0.009275317 -0.184671 -0.114939 0.009335577 -0.184611 -0.11497 0.009275317 -0.18476 -0.115331 0.009275317 -0.184777 -0.115379 0.009275317 -0.1849 -0.115578 0.009335577 -0.184844 -0.115643 0.009275317 -0.1848739 -0.11581 0.009275317 -0.184962 -0.116026 0.009335577 -0.184965 -0.116253 0.009335577 -0.1848829 -0.116471 0.009275317 -0.184916 -0.116703 0.009335577 -0.184798 -0.116905 0.009275317 -0.184792 -0.117139 0.009335577 -0.1847929 -0.116921 0.009275317 -0.184704 -0.117347 0.009335577 -0.184683 -0.117225 0.009275317 -0.184361 -0.117783 0.009275317 -0.184341 -0.11792 0.009335577 -0.184153 -0.1180289 0.009275317 -0.1841419 -0.118042 0.009275317 -0.183915 -0.118247 0.009275317 -0.183848 -0.118386 0.009335577 -0.183625 -0.118456 0.009275317 -0.183432 -0.118564 0.009275317 -0.183463 -0.118623 0.009335577 -0.183371 -0.118592 0.009275317 -0.1832309 -0.118655 0.009275317 -0.183071 -0.118712 0.009275317 -0.183023 -0.11873 0.009275317 -0.18281 -0.118787 0.009275317 -0.18276 -0.118796 0.009275317 -0.1821489 -0.118918 0.009335577 -0.182117 -0.118848 0.009275317 -0.181931 -0.118835 0.009275317 -0.181712 -0.118802 0.009275317 -0.181497 -0.118751 0.009275317 -0.181264 -0.118745 0.009335577 -0.181287 -0.118682 0.009275317 -0.181055 -0.118657 0.009335577 -0.181177 -0.118636 0.009275317 -0.180854 -0.118551 0.009335577 -0.180701 -0.118375 0.009275317 -0.180525 -0.118242 0.009275317 -0.180482 -0.118293 0.009335577 -0.18007 -0.117761 0.009275317 -0.179965 -0.117606 0.009275317 -0.179839 -0.117385 0.009275317 -0.1796849 -0.117209 0.009335577 -0.179747 -0.117184 0.009275317 -0.179606 -0.116712 0.009275317 -0.179488 -0.116328 0.009335577 -0.179576 -0.116545 0.009275317 -0.179534 -0.115652 0.009335577 -0.179651 -0.11545 0.009275317 -0.17972 -0.115239 0.009275317 -0.179767 -0.11513 0.009275317 -0.179909 -0.11484 0.009275317 -0.1800889 -0.114572 0.009275317 -0.180109 -0.114434 0.009335577 -0.1798509 -0.114807 0.009335577 -0.1799719 -0.114615 0.009335577 -0.18026 -0.114266 0.009335577 -0.180396 -0.114077 0.009414553 -0.180424 -0.11411 0.009335577 -0.180601 -0.113968 0.009335577 -0.1807889 -0.113842 0.009335577 -0.180766 -0.1138049 0.009414553 -0.181407 -0.113561 0.009335577 -0.181394 -0.113519 0.009414553 -0.181842 -0.1134189 0.009414553 -0.182074 -0.11344 0.009335577 -0.1823019 -0.113393 0.009414553 -0.1825309 -0.113409 0.009414553 -0.18275 -0.113487 0.009335577 -0.182759 -0.113444 0.009414553 -0.182983 -0.113497 0.009414553 -0.182971 -0.113539 0.009335577 -0.183201 -0.113569 0.009414553 -0.1831859 -0.11361 0.009335577 -0.183395 -0.113698 0.009335577 -0.183596 -0.113803 0.009335577 -0.184137 -0.114212 0.009335577 -0.184167 -0.114181 0.009414553 -0.184292 -0.114377 0.009335577 -0.184325 -0.114348 0.009414553 -0.1844339 -0.114554 0.009335577 -0.18456 -0.114742 0.009335577 -0.184597 -0.114719 0.009414553 -0.184805 -0.115129 0.009414553 -0.184765 -0.115146 0.009335577 -0.184841 -0.115359 0.009335577 -0.1848829 -0.115346 0.009414553 -0.184942 -0.115568 0.009414553 -0.18494 -0.115801 0.009335577 -0.184983 -0.115795 0.009414553 -0.185009 -0.116254 0.009414553 -0.1849499 -0.116479 0.009335577 -0.184863 -0.116923 0.009335577 -0.1849049 -0.116935 0.009414553 -0.184599 -0.117548 0.009335577 -0.184478 -0.117739 0.009335577 -0.18419 -0.118089 0.009335577 -0.184025 -0.118245 0.009335577 -0.183661 -0.118513 0.009335577 -0.183874 -0.118421 0.009414553 -0.183683 -0.11855 0.009414553 -0.183257 -0.118717 0.009335577 -0.183273 -0.118757 0.009414553 -0.183043 -0.118794 0.009335577 -0.182824 -0.118852 0.009335577 -0.182601 -0.118893 0.009335577 -0.182376 -0.118915 0.009335577 -0.182148 -0.118961 0.009414553 -0.181923 -0.118902 0.009335577 -0.181699 -0.118868 0.009335577 -0.181691 -0.118911 0.009414553 -0.181479 -0.118815 0.009335577 -0.1814669 -0.118857 0.009414553 -0.180638 -0.118466 0.009414553 -0.180663 -0.11843 0.009335577 -0.180313 -0.118142 0.009335577 -0.180158 -0.117978 0.009335577 -0.180016 -0.117801 0.009335577 -0.179889 -0.117613 0.009335577 -0.1797789 -0.117415 0.009335577 -0.179608 -0.116996 0.009335577 -0.179567 -0.117009 0.009414553 -0.1795499 -0.116777 0.009335577 -0.179509 -0.116554 0.009335577 -0.179466 -0.11656 0.009414553 -0.179484 -0.116102 0.009335577 -0.179441 -0.116101 0.009414553 -0.1795 -0.115876 0.009335577 -0.179457 -0.115871 0.009414553 -0.179545 -0.115419 0.009414553 -0.179587 -0.115431 0.009335577 -0.179657 -0.115216 0.009335577 -0.179746 -0.115007 0.009335577 -0.179813 -0.114785 0.009414553 -0.1798 -0.114777 0.009503483 -0.179936 -0.11459 0.009414553 -0.179924 -0.114582 0.009503483 -0.180075 -0.114407 0.009414553 -0.180229 -0.114235 0.009414553 -0.180567 -0.113921 0.009503483 -0.180576 -0.113933 0.009414553 -0.180961 -0.113679 0.009503483 -0.180967 -0.113692 0.009414553 -0.181177 -0.113597 0.009414553 -0.181616 -0.11346 0.009414553 -0.18184 -0.113404 0.009503483 -0.182071 -0.113397 0.009414553 -0.182071 -0.113381 0.009503483 -0.182533 -0.113394 0.009503483 -0.183207 -0.113555 0.009503483 -0.183413 -0.113659 0.009414553 -0.1836169 -0.113765 0.009414553 -0.183812 -0.113889 0.009414553 -0.183625 -0.113752 0.009503483 -0.18382 -0.113876 0.009503483 -0.183995 -0.114027 0.009414553 -0.184005 -0.1140159 0.009503483 -0.184177 -0.11417 0.009503483 -0.184336 -0.114338 0.009503483 -0.184469 -0.114528 0.009414553 -0.184481 -0.114519 0.009503483 -0.18461 -0.114711 0.009503483 -0.184723 -0.114913 0.009503483 -0.18471 -0.11492 0.009414553 -0.184819 -0.115124 0.009503483 -0.184897 -0.115341 0.009503483 -0.185006 -0.116024 0.009414553 -0.185024 -0.116254 0.009503483 -0.184993 -0.116484 0.009414553 -0.185008 -0.1164849 0.009503483 -0.184973 -0.116714 0.009503483 -0.184958 -0.116711 0.009414553 -0.1849189 -0.116939 0.009503483 -0.184833 -0.117154 0.009414553 -0.1848469 -0.117159 0.009503483 -0.1847569 -0.117372 0.009503483 -0.184743 -0.117366 0.009414553 -0.184637 -0.11757 0.009414553 -0.18465 -0.117577 0.009503483 -0.184513 -0.1177639 0.009414553 -0.184375 -0.117948 0.009414553 -0.184526 -0.1177729 0.009503483 -0.184386 -0.117957 0.009503483 -0.184221 -0.118119 0.009414553 -0.1842319 -0.11813 0.009503483 -0.184054 -0.118277 0.009414553 -0.183482 -0.1186619 0.009414553 -0.183489 -0.118676 0.009503483 -0.183279 -0.118771 0.009503483 -0.1830559 -0.118835 0.009414553 -0.182834 -0.118895 0.009414553 -0.1826069 -0.118936 0.009414553 -0.1823779 -0.1189579 0.009414553 -0.182379 -0.118973 0.009503483 -0.181919 -0.118945 0.009414553 -0.181917 -0.11896 0.009503483 -0.181688 -0.118925 0.009503483 -0.181248 -0.118785 0.009414553 -0.1810359 -0.118696 0.009414553 -0.180832 -0.118589 0.009414553 -0.1808249 -0.118602 0.009503483 -0.180454 -0.118327 0.009414553 -0.180445 -0.118339 0.009503483 -0.180283 -0.118173 0.009414553 -0.180272 -0.118184 0.009503483 -0.1801249 -0.118006 0.009414553 -0.1799809 -0.1178269 0.009414553 -0.179969 -0.117835 0.009503483 -0.17984 -0.117644 0.009503483 -0.179852 -0.117636 0.009414553 -0.17974 -0.117435 0.009414553 -0.179645 -0.117225 0.009414553 -0.179507 -0.116786 0.009414553 -0.179444 -0.116331 0.009414553 -0.179426 -0.1161 0.009503483 -0.1794919 -0.115643 0.009414553 -0.179477 -0.11564 0.009503483 -0.179617 -0.1152009 0.009414553 -0.179531 -0.115415 0.009503483 -0.179693 -0.114982 0.009503483 -0.179706 -0.114989 0.009414553 -0.181322 -0.118296 0.009061753 -0.181584 -0.118389 0.009061753 -0.184289 -0.117877 0.009275317 -0.184423 -0.117701 0.009275317 -0.1848959 -0.116285 0.009275317 -0.184503 -0.114777 0.009275317 -0.18383 -0.114041 0.009275317 -0.183376 -0.114183 0.009061753 -0.183127 -0.114059 0.009061753 -0.181427 -0.113625 0.009275317 -0.180994 -0.114231 0.009061753 -0.180308 -0.114312 0.009275317 -0.18016 -0.114477 0.009275317 -0.179657 -0.115433 0.009275317 -0.180013 -0.115537 0.009061753 -0.179554 -0.11607 0.009275317 -0.179969 -0.116638 0.009061753 -0.18036 -0.118094 0.009275317 -0.180373 -0.118106 0.009275317 -0.18063 -0.117838 0.009061753 -0.181251 -0.117124 0.008687853 -0.181389 -0.116884 0.008623957 -0.183152 -0.115591 0.008621811 -0.183198 -0.115231 0.008687853 -0.182397 -0.115138 0.008613824 -0.182401 -0.115094 0.008621811 -0.182467 -0.114686 0.008733749 -0.182374 -0.11518 0.008602738 -0.182269 -0.115081 0.008621811 -0.182273 -0.115354 0.008572161 -0.18209 -0.115516 0.008545756 -0.182171 -0.115504 0.008545756 -0.181556 -0.115364 0.008613824 -0.181638 -0.11525 0.008621811 -0.181186 -0.116005 0.008613824 -0.1811479 -0.115983 0.008623957 -0.181142 -0.116001 0.008621811 -0.181227 -0.116029 0.008602738 -0.181401 -0.116129 0.008572161 -0.1815519 -0.116232 0.008545756 -0.181551 -0.116215 0.008545756 -0.181435 -0.116805 0.008602738 -0.182181 -0.117274 0.008621811 -0.182052 -0.117216 0.008613824 -0.182049 -0.11726 0.008621811 -0.182076 -0.117175 0.008602738 -0.182313 -0.117271 0.008621811 -0.182894 -0.116991 0.008613824 -0.183302 -0.116372 0.008623957 -0.183264 -0.1163499 0.008613824 -0.183308 -0.116353 0.008621811 -0.1832219 -0.116326 0.008602738 -0.183049 -0.116226 0.008572161 -0.182898 -0.116123 0.008545756 -0.18062 -0.118313 0.009275317 -0.181074 -0.118171 0.009061753 -0.181268 -0.117835 0.008880794 -0.180842 -0.118018 0.009061753 -0.181075 -0.117707 0.008880794 -0.180155 -0.117867 0.009275317 -0.180208 -0.117934 0.009275317 -0.180441 -0.1176339 0.009061753 -0.180279 -0.117408 0.009061753 -0.181178 -0.117267 0.008733749 -0.180899 -0.117558 0.008880794 -0.17981 -0.117323 0.009275317 -0.179946 -0.117578 0.009275317 -0.180607 -0.1172 0.008880794 -0.1810539 -0.117133 0.008733749 -0.180742 -0.117388 0.008880794 -0.181291 -0.117147 0.008686244 -0.1814309 -0.117231 0.00868076 -0.181317 -0.117385 0.008733749 -0.181469 -0.117486 0.008733749 -0.1816329 -0.117567 0.008733749 -0.181569 -0.117314 0.008675336 -0.181709 -0.117392 0.00868076 -0.181851 -0.117471 0.008686244 -0.181375 -0.1168709 0.008621811 -0.180496 -0.116998 0.008880794 -0.180041 -0.116906 0.009061753 -0.180145 -0.117164 0.009061753 -0.179615 -0.116762 0.009275317 -0.179672 -0.116976 0.009275317 -0.17969 -0.117024 0.009275317 -0.180948 -0.116985 0.008733749 -0.181411 -0.116846 0.008613824 -0.181298 -0.116764 0.008621811 -0.18086 -0.116825 0.008733749 -0.180409 -0.116783 0.008880794 -0.180792 -0.116656 0.008733749 -0.18035 -0.11656 0.008880794 -0.179551 -0.116104 0.009275317 -0.1795549 -0.116325 0.009275317 -0.179561 -0.116392 0.009275317 -0.179924 -0.116085 0.009061753 -0.17993 -0.116363 0.009061753 -0.180317 -0.116331 0.008880794 -0.1807439 -0.116479 0.008733749 -0.181234 -0.116648 0.008621811 -0.1816149 -0.1164669 0.008545756 -0.181536 -0.116631 0.008572161 -0.181622 -0.116481 0.008545756 -0.181584 -0.116391 0.008545756 -0.1811839 -0.116525 0.008621811 -0.180719 -0.116299 0.008733749 -0.180313 -0.1161 0.008880794 -0.179952 -0.115808 0.009061753 -0.179567 -0.115883 0.009275317 -0.1796 -0.115665 0.009275317 -0.179587 -0.115749 0.009275317 -0.1803359 -0.1158699 0.008880794 -0.180715 -0.116116 0.008733749 -0.181131 -0.116266 0.008621811 -0.181563 -0.116312 0.008545756 -0.18115 -0.116397 0.008621811 -0.180387 -0.115645 0.008880794 -0.181129 -0.116133 0.008621811 -0.180231 -0.1150259 0.009061753 -0.1798059 -0.115036 0.009275317 -0.1801069 -0.115275 0.009061753 -0.180909 -0.115845 0.008687853 -0.180733 -0.115935 0.008733749 -0.180027 -0.114653 0.009275317 -0.180384 -0.114794 0.009061753 -0.180567 -0.11522 0.008880794 -0.180464 -0.115427 0.008880794 -0.180773 -0.115757 0.008733749 -0.180564 -0.114582 0.009061753 -0.1806949 -0.115027 0.008880794 -0.180916 -0.115422 0.008733749 -0.180835 -0.115585 0.008733749 -0.180468 -0.11416 0.009275317 -0.180769 -0.114394 0.009061753 -0.180796 -0.113918 0.009275317 -0.180845 -0.1148509 0.008880794 -0.181017 -0.115269 0.008733749 -0.181017 -0.113791 0.009275317 -0.180824 -0.113899 0.009275317 -0.1812379 -0.1140969 0.009061753 -0.181014 -0.114695 0.008880794 -0.1811349 -0.11513 0.008733749 -0.181255 -0.115244 0.008686244 -0.181088 -0.115521 0.008675336 -0.1812019 -0.11456 0.008880794 -0.181269 -0.115007 0.008733749 -0.181279 -0.115204 0.008687853 -0.18169 -0.113558 0.009275317 -0.181619 -0.114362 0.008880794 -0.181496 -0.113993 0.009061753 -0.1814039 -0.114448 0.008880794 -0.181417 -0.1149 0.008733749 -0.181531 -0.115327 0.008621811 -0.181518 -0.115342 0.008623957 -0.1815969 -0.115388 0.008602738 -0.181771 -0.115488 0.008572161 -0.181577 -0.114812 0.008733749 -0.181746 -0.114744 0.008733749 -0.181842 -0.114302 0.008880794 -0.181764 -0.113921 0.009061753 -0.182078 -0.113507 0.009275317 -0.1820099 -0.113513 0.009275317 -0.182071 -0.11427 0.008880794 -0.18204 -0.113882 0.009061753 -0.181923 -0.114697 0.008733749 -0.181877 -0.115137 0.008621811 -0.181755 -0.115186 0.008621811 -0.181935 -0.115567 0.008545756 -0.181921 -0.115574 0.008545756 -0.182011 -0.115537 0.008545756 -0.182103 -0.114671 0.008733749 -0.182318 -0.113876 0.009061753 -0.182953 -0.113604 0.009275317 -0.182594 -0.1139039 0.009061753 -0.182866 -0.113966 0.009061753 -0.1823019 -0.114265 0.008880794 -0.182137 -0.115084 0.008621811 -0.182005 -0.115102 0.008621811 -0.183163 -0.113673 0.009275317 -0.182532 -0.114288 0.008880794 -0.182286 -0.1146669 0.008733749 -0.182187 -0.115503 0.008545756 -0.183562 -0.113861 0.009275317 -0.183366 -0.113759 0.009275317 -0.182757 -0.114339 0.008880794 -0.182558 -0.114861 0.008687853 -0.182419 -0.1151 0.008623957 -0.183182 -0.11452 0.008880794 -0.1829749 -0.114417 0.008880794 -0.183375 -0.114647 0.008880794 -0.1836079 -0.114336 0.009061753 -0.18298 -0.1148689 0.008733749 -0.184242 -0.114421 0.009275317 -0.184009 -0.114721 0.009061753 -0.18409 -0.11426 0.009275317 -0.18382 -0.114517 0.009061753 -0.184171 -0.114947 0.009061753 -0.183551 -0.1147969 0.008880794 -0.183133 -0.114969 0.008733749 -0.184639 -0.115032 0.009275317 -0.1837069 -0.114967 0.008880794 -0.183272 -0.115087 0.008733749 -0.1831589 -0.115207 0.008686244 -0.183019 -0.115123 0.00868076 -0.1828809 -0.115041 0.008675336 -0.182817 -0.114787 0.008733749 -0.182741 -0.114963 0.00868076 -0.1825979 -0.114884 0.008686244 -0.182645 -0.114726 0.008733749 -0.183395 -0.115222 0.008733749 -0.183502 -0.11537 0.008733749 -0.183954 -0.115357 0.008880794 -0.183842 -0.115154 0.008880794 -0.184305 -0.11519 0.009061753 -0.184835 -0.115592 0.009275317 -0.1847029 -0.115171 0.009275317 -0.184409 -0.1154479 0.009061753 -0.1830379 -0.115508 0.008613824 -0.183075 -0.115483 0.008621811 -0.1830599 -0.11547 0.008623957 -0.183014 -0.11555 0.008602738 -0.182914 -0.115723 0.008572161 -0.1835899 -0.115529 0.008733749 -0.183658 -0.115699 0.008733749 -0.18404 -0.115571 0.008880794 -0.184481 -0.115717 0.009061753 -0.18452 -0.115992 0.009061753 -0.184895 -0.11603 0.009275317 -0.184889 -0.115962 0.009275317 -0.184526 -0.11627 0.009061753 -0.184898 -0.116251 0.009275317 -0.1841329 -0.116023 0.008880794 -0.1841 -0.115794 0.008880794 -0.183705 -0.115875 0.008733749 -0.183216 -0.115707 0.008621811 -0.182835 -0.1158879 0.008545756 -0.182828 -0.115873 0.008545756 -0.182865 -0.115963 0.008545756 -0.183266 -0.11583 0.008621811 -0.1833 -0.115958 0.008621811 -0.184137 -0.116254 0.008880794 -0.18485 -0.11669 0.009275317 -0.184498 -0.116547 0.009061753 -0.184863 -0.1166059 0.009275317 -0.184437 -0.116818 0.009061753 -0.183731 -0.116056 0.008733749 -0.182886 -0.116042 0.008545756 -0.184343 -0.11708 0.009061753 -0.1847299 -0.117115 0.009275317 -0.184114 -0.116484 0.008880794 -0.1833209 -0.116221 0.008621811 -0.183735 -0.1162379 0.008733749 -0.183318 -0.116089 0.008621811 -0.184541 -0.117514 0.009275317 -0.184644 -0.117319 0.009275317 -0.184219 -0.117329 0.009061753 -0.184063 -0.11671 0.008880794 -0.1837159 -0.11642 0.008733749 -0.183986 -0.116927 0.008880794 -0.183615 -0.11677 0.008733749 -0.183676 -0.116598 0.008733749 -0.1840659 -0.117561 0.009061753 -0.183755 -0.117327 0.008880794 -0.1838819 -0.117134 0.008880794 -0.183981 -0.118194 0.009275317 -0.183886 -0.117772 0.009061753 -0.183654 -0.118437 0.009275317 -0.183809 -0.118332 0.009275317 -0.183681 -0.117961 0.009061753 -0.183605 -0.117503 0.008880794 -0.183435 -0.11766 0.008880794 -0.183212 -0.1182579 0.009061753 -0.183456 -0.118123 0.009061753 -0.183248 -0.117795 0.008880794 -0.183181 -0.117348 0.008733749 -0.1831949 -0.117111 0.008686244 -0.183315 -0.117224 0.008733749 -0.1834329 -0.117085 0.008733749 -0.183279 -0.116971 0.00868076 -0.183534 -0.116933 0.008733749 -0.183362 -0.116834 0.008675336 -0.183439 -0.116693 0.00868076 -0.183519 -0.116551 0.008686244 -0.1835409 -0.11651 0.008687853 -0.183045 -0.117906 0.008880794 -0.183033 -0.117454 0.008733749 -0.183171 -0.117151 0.008687853 -0.182932 -0.117013 0.008623957 -0.182592 -0.118826 0.009275317 -0.182685 -0.1184329 0.009061753 -0.182954 -0.1183609 0.009061753 -0.182873 -0.117542 0.008733749 -0.182811 -0.117105 0.008621811 -0.182919 -0.117027 0.008621811 -0.182852 -0.116967 0.008602738 -0.182695 -0.117168 0.008621811 -0.182703 -0.117611 0.008733749 -0.182831 -0.1179929 0.008880794 -0.18241 -0.118472 0.009061753 -0.182372 -0.118848 0.009275317 -0.18244 -0.118841 0.009275317 -0.182151 -0.118851 0.009275317 -0.182132 -0.118478 0.009061753 -0.182608 -0.118052 0.008880794 -0.1826789 -0.116866 0.008572161 -0.182514 -0.116787 0.008545756 -0.182529 -0.11678 0.008545756 -0.182439 -0.116818 0.008545756 -0.182572 -0.117218 0.008621811 -0.182399 -0.116828 0.008545756 -0.182444 -0.117252 0.008621811 -0.182527 -0.117658 0.008733749 -0.182379 -0.118085 0.008880794 -0.181856 -0.11845 0.009061753 -0.181796 -0.118815 0.009275317 -0.181481 -0.118745 0.009275317 -0.181918 -0.118066 0.008880794 -0.182148 -0.11809 0.008880794 -0.182164 -0.117687 0.008733749 -0.182346 -0.117683 0.008733749 -0.181692 -0.118016 0.008880794 -0.181982 -0.117669 0.008733749 -0.182177 -0.1170009 0.008572161 -0.182263 -0.116851 0.008545756 -0.1808879 -0.118493 0.009275317 -0.181084 -0.118596 0.009275317 -0.181475 -0.117938 0.008880794 -0.181804 -0.117629 0.008733749 -0.181892 -0.117494 0.008687853 -0.18203 -0.117254 0.008623957 -0.181134 -0.115148 0.01099997 -0.180926 -0.115427 0.01889997 -0.181134 -0.115148 0.01889997 -0.181401 -0.114924 0.01099997 -0.181401 -0.114924 0.01889997 -0.181712 -0.114768 0.01099997 -0.181712 -0.114768 0.01889997 -0.182051 -0.114687 0.01889997 -0.182051 -0.114687 0.01099997 -0.182399 -0.114687 0.01099997 -0.182399 -0.114687 0.01889997 -0.182738 -0.114768 0.01099997 -0.183049 -0.114924 0.01099997 -0.182738 -0.114768 0.01889997 -0.183049 -0.114924 0.01889997 -0.1833159 -0.115148 0.01889997 -0.1833159 -0.115148 0.01099997 -0.183524 -0.115427 0.01099997 -0.1836619 -0.115747 0.01099997 -0.183524 -0.115427 0.01889997 -0.183722 -0.1160899 0.01099997 -0.1836619 -0.115747 0.01889997 -0.183722 -0.1160899 0.01889997 -0.183702 -0.116438 0.01099997 -0.183702 -0.116438 0.01889997 -0.183602 -0.116771 0.01099997 -0.183602 -0.116771 0.01889997 -0.183428 -0.1170729 0.01099997 -0.183189 -0.117326 0.01099997 -0.183428 -0.1170729 0.01889997 -0.182898 -0.117518 0.01099997 -0.183189 -0.117326 0.01889997 -0.182898 -0.117518 0.01889997 -0.1825709 -0.117637 0.01099997 -0.1825709 -0.117637 0.01889997 -0.182225 -0.117677 0.01099997 -0.182225 -0.117677 0.01889997 -0.181879 -0.117637 0.01099997 -0.181879 -0.117637 0.01889997 -0.1815519 -0.117518 0.01099997 -0.1815519 -0.117518 0.01889997 -0.181261 -0.117326 0.01099997 -0.181022 -0.1170729 0.01099997 -0.181261 -0.117326 0.01889997 -0.181022 -0.1170729 0.01889997 -0.180848 -0.116771 0.01099997 -0.180848 -0.116771 0.01889997 -0.180748 -0.116438 0.01099997 -0.180748 -0.116438 0.01889997 -0.180727 -0.1160899 0.01099997 -0.180788 -0.115747 0.01099997 -0.180727 -0.1160899 0.01889997 -0.180788 -0.115747 0.01889997 -0.180926 -0.115427 0.01099997 -0.191668 0.09908086 0.01024997 -0.191612 0.09917825 0.01024997 -0.1916249 0.09915637 0.009976387 -0.191919 0.0986458 0.008623957 -0.191678 0.09906309 0.008744776 -0.191687 0.09904867 0.008545756 -0.1922529 0.09954828 0.01024997 -0.192309 0.09945088 0.01024997 -0.192265 0.0995264 0.009976387 -0.192319 0.09943306 0.008744776 -0.192414 0.09926897 0.008572161 -0.189193 0.09852778 0.009503483 -0.189103 0.09874099 0.01089996 -0.188977 0.099186 0.01089996 -0.188926 0.09964555 0.01089996 -0.188951 0.100107 0.01089996 -0.188993 0.100335 0.009503483 -0.1890529 0.1005589 0.009503483 -0.1890529 0.1005589 0.01089996 -0.189227 0.100987 0.01089996 -0.1893399 0.101189 0.009503483 -0.189469 0.101381 0.009503483 -0.189469 0.101381 0.01089996 -0.189772 0.10173 0.01089996 -0.190129 0.102024 0.01089996 -0.190325 0.1021479 0.009503483 -0.19053 0.102255 0.01089996 -0.190963 0.102417 0.01089996 -0.191417 0.102506 0.01089996 -0.191648 0.102522 0.009503483 -0.191879 0.102519 0.009503483 -0.191879 0.102519 0.01089996 -0.192337 0.102455 0.01089996 -0.192337 0.102455 0.009503483 -0.192561 0.1023949 0.009503483 -0.192779 0.102317 0.01089996 -0.193191 0.102108 0.01089996 -0.193383 0.101979 0.009503483 -0.1935639 0.1018339 0.01089996 -0.193732 0.101675 0.009503483 -0.193886 0.101503 0.01089996 -0.19415 0.101123 0.009503483 -0.19415 0.101123 0.01089996 -0.194257 0.100918 0.009503483 -0.194347 0.100705 0.01089996 -0.194419 0.100485 0.009503483 -0.194473 0.10026 0.01089996 -0.194524 0.09979987 0.01089996 -0.194508 0.100031 0.009503483 -0.194498 0.09933817 0.01089996 -0.1944569 0.09911048 0.009503483 -0.194397 0.0988869 0.01089996 -0.194397 0.0988869 0.009503483 -0.194319 0.09866911 0.009503483 -0.194223 0.09845846 0.009503483 -0.19411 0.09825646 0.009503483 -0.194223 0.09845846 0.01089996 -0.193981 0.09806448 0.01089996 -0.193677 0.09771579 0.01089996 -0.193677 0.09771579 0.009503483 -0.19332 0.09742176 0.01089996 -0.193125 0.0972979 0.009503483 -0.19292 0.09719055 0.01089996 -0.192487 0.09702837 0.01089996 -0.1922619 0.09697467 0.009503483 -0.1920329 0.0969398 0.009503483 -0.1920329 0.0969398 0.01089996 -0.191802 0.09692376 0.009503483 -0.1915709 0.09692698 0.009503483 -0.1915709 0.09692698 0.01089996 -0.1911129 0.09699046 0.01089996 -0.190671 0.09712857 0.01089996 -0.190259 0.09733736 0.01089996 -0.190259 0.09733736 0.009503483 -0.1900669 0.09746658 0.009503483 -0.189886 0.0976113 0.009503483 -0.189718 0.09777027 0.009503483 -0.189886 0.0976113 0.01089996 -0.189564 0.0979427 0.01089996 -0.189564 0.0979427 0.009503483 -0.1893 0.0983228 0.01089996 -0.189157 0.09897887 0.009275317 -0.189 0.0994212 0.009335577 -0.189067 0.09942847 0.009275317 -0.188984 0.09964716 0.009335577 -0.188988 0.09987378 0.009335577 -0.189061 0.09993779 0.009275317 -0.189076 0.10009 0.009275317 -0.189172 0.100521 0.009275317 -0.189108 0.100541 0.009335577 -0.18931 0.100868 0.009275317 -0.189339 0.10093 0.009275317 -0.189446 0.101123 0.009275317 -0.189279 0.100961 0.009335577 -0.189389 0.101158 0.009335577 -0.189516 0.101346 0.009335577 -0.18957 0.101307 0.009275317 -0.189655 0.101413 0.009275317 -0.1897079 0.101479 0.009275317 -0.189658 0.101523 0.009335577 -0.189873 0.101651 0.009275317 -0.190025 0.101787 0.009275317 -0.190354 0.102097 0.009335577 -0.190677 0.102181 0.009275317 -0.190997 0.102296 0.009275317 -0.190979 0.102361 0.009335577 -0.191199 0.1024129 0.009335577 -0.191431 0.102381 0.009275317 -0.191649 0.102463 0.009335577 -0.191872 0.102393 0.009275317 -0.192101 0.102438 0.009335577 -0.192324 0.102398 0.009335577 -0.19226 0.102342 0.009275317 -0.19231 0.102332 0.009275317 -0.192523 0.102275 0.009275317 -0.192757 0.102263 0.009335577 -0.192871 0.102137 0.009275317 -0.192932 0.102109 0.009275317 -0.193161 0.102058 0.009335577 -0.193125 0.102001 0.009275317 -0.193415 0.101793 0.009275317 -0.193642 0.101588 0.009275317 -0.193653 0.101575 0.009275317 -0.193861 0.101328 0.009275317 -0.1939229 0.101247 0.009275317 -0.194041 0.10106 0.009275317 -0.193978 0.101285 0.009335577 -0.194144 0.100864 0.009275317 -0.194183 0.1007699 0.009275317 -0.194292 0.100684 0.009335577 -0.1943629 0.100469 0.009335577 -0.194416 0.100248 0.009335577 -0.19445 0.100024 0.009335577 -0.194465 0.09979826 0.009335577 -0.194398 0.09979647 0.009275317 -0.194395 0.0995754 0.009275317 -0.194389 0.09950768 0.009275317 -0.19444 0.09934616 0.009335577 -0.1944 0.09912317 0.009335577 -0.194277 0.09892439 0.009275317 -0.19426 0.09887635 0.009275317 -0.194203 0.09871625 0.009275317 -0.194139 0.09857708 0.009275317 -0.194003 0.09832215 0.009275317 -0.193934 0.09809917 0.009335577 -0.193984 0.09829396 0.009275317 -0.19388 0.09813886 0.009275317 -0.193792 0.09792226 0.009335577 -0.193795 0.09803265 0.009275317 -0.193742 0.09796625 0.009275317 -0.193287 0.09746986 0.009335577 -0.193249 0.097525 0.009275317 -0.193096 0.09734857 0.009335577 -0.193062 0.09740656 0.009275317 -0.192772 0.0972644 0.009275317 -0.192686 0.09715527 0.009335577 -0.192469 0.09715455 0.009275317 -0.192471 0.0970847 0.009335577 -0.192238 0.09709787 0.009275317 -0.192026 0.09699785 0.009335577 -0.191799 0.09704935 0.009275317 -0.191574 0.09698545 0.009335577 -0.191358 0.09707367 0.009275317 -0.19119 0.09710395 0.009275317 -0.1911399 0.09711307 0.009275317 -0.190927 0.09717029 0.009275317 -0.190907 0.09710627 0.009335577 -0.190487 0.09727668 0.009335577 -0.190517 0.09733647 0.009275317 -0.190289 0.09738719 0.009335577 -0.1902959 0.09746336 0.009275317 -0.190101 0.09751379 0.009335577 -0.189797 0.09787058 0.009275317 -0.18976 0.0978111 0.009335577 -0.189609 0.0979799 0.009335577 -0.18966 0.09802258 0.009275317 -0.189527 0.09819889 0.009275317 -0.189472 0.09816056 0.009335577 -0.189351 0.09835195 0.009335577 -0.189409 0.09838557 0.009275317 -0.189436 0.09813588 0.009414553 -0.1893129 0.09833025 0.009414553 -0.1892459 0.09855276 0.009335577 -0.189157 0.09876149 0.009335577 -0.189087 0.09897679 0.009335577 -0.189034 0.0991972 0.009335577 -0.189009 0.100099 0.009335577 -0.189007 0.100332 0.009414553 -0.18905 0.100322 0.009335577 -0.189067 0.100554 0.009414553 -0.189185 0.100754 0.009335577 -0.189145 0.100771 0.009414553 -0.18924 0.10098 0.009414553 -0.189352 0.101181 0.009414553 -0.189813 0.101688 0.009335577 -0.189954 0.101873 0.009414553 -0.1899819 0.101839 0.009335577 -0.190163 0.101976 0.009335577 -0.190138 0.102011 0.009414553 -0.190555 0.1022019 0.009335577 -0.190764 0.10229 0.009335577 -0.190967 0.102403 0.009414553 -0.191191 0.102456 0.009414553 -0.1914229 0.102448 0.009335577 -0.1918759 0.10246 0.009335577 -0.191648 0.102507 0.009414553 -0.192107 0.102481 0.009414553 -0.192543 0.102339 0.009335577 -0.1923339 0.1024399 0.009414553 -0.192556 0.102381 0.009414553 -0.192963 0.102169 0.009335577 -0.193348 0.101932 0.009335577 -0.193525 0.10179 0.009335577 -0.19369 0.101634 0.009335577 -0.1937209 0.101665 0.009414553 -0.193841 0.101466 0.009335577 -0.193875 0.101493 0.009414553 -0.194099 0.101093 0.009335577 -0.194204 0.100893 0.009335577 -0.194333 0.100699 0.009414553 -0.194405 0.100481 0.009414553 -0.194462 0.0995717 0.009335577 -0.194442 0.0991137 0.009414553 -0.194341 0.09890437 0.009335577 -0.194383 0.09889137 0.009414553 -0.194265 0.0986911 0.009335577 -0.194171 0.09848487 0.009335577 -0.19406 0.0982871 0.009335577 -0.193637 0.09775769 0.009335577 -0.193495 0.09757298 0.009414553 -0.193468 0.09760659 0.009335577 -0.193117 0.0973109 0.009414553 -0.1929129 0.0972042 0.009414553 -0.1928949 0.09724348 0.009335577 -0.192701 0.09711456 0.009414553 -0.19225 0.09703207 0.009335577 -0.1917999 0.0969823 0.009335577 -0.191348 0.09700727 0.009335577 -0.191125 0.09704756 0.009335577 -0.190693 0.09718281 0.009335577 -0.190677 0.09714245 0.009414553 -0.189924 0.09765535 0.009335577 -0.189575 0.0979523 0.009414553 -0.1893 0.0983228 0.009503483 -0.189206 0.09853416 0.009414553 -0.189117 0.09874618 0.009414553 -0.189045 0.09896498 0.009414553 -0.189103 0.09874099 0.009503483 -0.188992 0.09918886 0.009414553 -0.189031 0.09896087 0.009503483 -0.188977 0.099186 0.009503483 -0.188957 0.09941637 0.009414553 -0.188942 0.0994147 0.009503483 -0.188941 0.09964597 0.009414553 -0.188926 0.09964555 0.009503483 -0.188929 0.09987699 0.009503483 -0.188944 0.09987616 0.009414553 -0.188951 0.100107 0.009503483 -0.188966 0.100105 0.009414553 -0.189131 0.100776 0.009503483 -0.189227 0.100987 0.009503483 -0.189481 0.101372 0.009414553 -0.189625 0.101552 0.009414553 -0.189613 0.101562 0.009503483 -0.189772 0.10173 0.009503483 -0.189783 0.101719 0.009414553 -0.189945 0.101884 0.009503483 -0.190129 0.102024 0.009503483 -0.1903319 0.102135 0.009414553 -0.19053 0.102255 0.009503483 -0.190536 0.102241 0.009414553 -0.190748 0.102331 0.009414553 -0.190743 0.102345 0.009503483 -0.190963 0.102417 0.009503483 -0.191188 0.102471 0.009503483 -0.191419 0.102491 0.009414553 -0.191417 0.102506 0.009503483 -0.191878 0.102503 0.009414553 -0.192109 0.102496 0.009503483 -0.192779 0.102317 0.009503483 -0.192773 0.102303 0.009414553 -0.192989 0.102221 0.009503483 -0.192982 0.102208 0.009414553 -0.193183 0.102095 0.009414553 -0.193191 0.102108 0.009503483 -0.193374 0.101967 0.009414553 -0.193554 0.101823 0.009414553 -0.1935639 0.1018339 0.009503483 -0.1940129 0.10131 0.009414553 -0.193886 0.101503 0.009503483 -0.1940259 0.101318 0.009503483 -0.194137 0.101115 0.009414553 -0.194243 0.100911 0.009414553 -0.194347 0.100705 0.009503483 -0.194458 0.100257 0.009414553 -0.194473 0.10026 0.009503483 -0.1944929 0.100029 0.009414553 -0.194509 0.09979945 0.009414553 -0.194524 0.09979987 0.009503483 -0.194521 0.09956848 0.009503483 -0.194506 0.09956926 0.009414553 -0.194483 0.0993402 0.009414553 -0.194498 0.09933817 0.009503483 -0.194305 0.09867477 0.009414553 -0.1942099 0.09846526 0.009414553 -0.194097 0.09826439 0.009414553 -0.193969 0.09807336 0.009414553 -0.193981 0.09806448 0.009503483 -0.193836 0.09788388 0.009503483 -0.193825 0.09789365 0.009414553 -0.1936669 0.09772658 0.009414553 -0.193505 0.09756135 0.009503483 -0.19332 0.09742176 0.009503483 -0.193312 0.0974341 0.009414553 -0.19292 0.09719055 0.009503483 -0.192707 0.09710049 0.009503483 -0.192483 0.09704285 0.009414553 -0.192487 0.09702837 0.009503483 -0.192259 0.09698945 0.009414553 -0.192031 0.0969547 0.009414553 -0.191802 0.0969389 0.009414553 -0.1915709 0.096942 0.009414553 -0.1913419 0.09696418 0.009414553 -0.191116 0.09700518 0.009414553 -0.19134 0.09694927 0.009503483 -0.1911129 0.09699046 0.009503483 -0.190894 0.09706479 0.009414553 -0.190889 0.09705036 0.009503483 -0.190671 0.09712857 0.009503483 -0.190467 0.09723788 0.009414553 -0.190461 0.09722435 0.009503483 -0.190266 0.09735018 0.009414553 -0.1900759 0.09747868 0.009414553 -0.189896 0.09762257 0.009414553 -0.189729 0.09778076 0.009414553 -0.189424 0.0981273 0.009503483 -0.1933299 0.09758645 0.009275317 -0.193577 0.09779435 0.009275317 -0.194344 0.09918808 0.009275317 -0.194396 0.09983038 0.009275317 -0.194298 0.10045 0.009275317 -0.192731 0.102201 0.009275317 -0.192454 0.101907 0.009061753 -0.191617 0.102394 0.009275317 -0.191084 0.101934 0.009061753 -0.190584 0.102141 0.009275317 -0.190388 0.102039 0.009275317 -0.190574 0.101717 0.009061753 -0.190201 0.101921 0.009275317 -0.189115 0.100308 0.009275317 -0.189054 0.09961509 0.009275317 -0.189151 0.09899497 0.009275317 -0.189513 0.09908211 0.009061753 -0.189306 0.09858137 0.009275317 -0.192453 0.09714925 0.009275317 -0.191901 0.09863978 0.008621811 -0.191549 0.1008059 0.008621811 -0.1913509 0.101016 0.008686244 -0.191392 0.101039 0.008687853 -0.1909109 0.100392 0.008613824 -0.190889 0.10043 0.008623957 -0.1908749 0.100417 0.008621811 -0.190798 0.100309 0.008621811 -0.190935 0.10035 0.008602738 -0.191036 0.100176 0.008572161 -0.191084 0.0999366 0.008545756 -0.191115 0.100012 0.008545756 -0.190734 0.100193 0.008621811 -0.1902329 0.09948039 0.008733749 -0.191056 0.09890925 0.008613824 -0.191031 0.0988729 0.008621811 -0.191097 0.09893316 0.008602738 -0.191138 0.09879547 0.008621811 -0.191271 0.09903347 0.008572161 -0.191435 0.0991128 0.008545756 -0.191255 0.09873145 0.008621811 -0.192058 0.09840637 0.008687853 -0.192538 0.0990538 0.008613824 -0.192575 0.09902888 0.008621811 -0.1928949 0.0987671 0.008733749 -0.192514 0.09909516 0.008602738 -0.192335 0.0994333 0.008545756 -0.192764 0.09989535 0.008613824 -0.192722 0.09987139 0.008602738 -0.193019 0.100096 0.008686244 -0.193041 0.100055 0.008687853 -0.192394 0.100536 0.008613824 -0.1924189 0.100573 0.008621811 -0.192681 0.100893 0.008733749 -0.1923519 0.100512 0.008602738 -0.1919389 0.100363 0.008545756 -0.192014 0.100333 0.008545756 -0.1920289 0.100326 0.008545756 -0.192866 0.0973041 0.009275317 -0.192876 0.09772861 0.009061753 -0.192627 0.09760439 0.009061753 -0.192663 0.09721809 0.009275317 -0.192475 0.09796196 0.008880794 -0.192682 0.09806525 0.008880794 -0.192019 0.09706455 0.009275317 -0.192154 0.09708505 0.009275317 -0.192366 0.09751105 0.009061753 -0.192257 0.09788435 0.008880794 -0.192317 0.09833258 0.008733749 -0.191832 0.09705168 0.009275317 -0.192094 0.09744995 0.009061753 -0.192032 0.09783369 0.008880794 -0.19151 0.09705895 0.009275317 -0.191578 0.09705239 0.009275317 -0.1918179 0.097422 0.009061753 -0.19154 0.0974276 0.009061753 -0.191967 0.09823119 0.008733749 -0.192098 0.09842896 0.008686244 -0.192145 0.09827131 0.008733749 -0.192241 0.09850817 0.00868076 -0.192381 0.09858596 0.008675336 -0.19248 0.09841406 0.008733749 -0.192519 0.09866857 0.00868076 -0.192633 0.09851467 0.008733749 -0.192772 0.09863299 0.008733749 -0.192659 0.09875249 0.008686244 -0.191802 0.09781038 0.008880794 -0.191264 0.0974667 0.009061753 -0.190879 0.09718745 0.009275317 -0.190996 0.09753859 0.009061753 -0.1913419 0.09784758 0.008880794 -0.1915709 0.09781509 0.008880794 -0.191786 0.09821289 0.008733749 -0.191603 0.09821659 0.008733749 -0.191898 0.09868377 0.008613824 -0.191874 0.09872519 0.008602738 -0.1917729 0.098899 0.008572161 -0.191769 0.09862649 0.008621811 -0.1907179 0.09724485 0.009275317 -0.190738 0.09764248 0.009061753 -0.1905789 0.09730827 0.009275317 -0.190324 0.09744435 0.009275317 -0.190494 0.09777659 0.009061753 -0.190904 0.09799367 0.008880794 -0.191119 0.09790736 0.008880794 -0.1914229 0.09824216 0.008733749 -0.191637 0.09862917 0.008621811 -0.191671 0.0990498 0.008545756 -0.19159 0.09906119 0.008545756 -0.191505 0.09864777 0.008621811 -0.191377 0.0986821 0.008621811 -0.1910769 0.09835755 0.008733749 -0.191246 0.09828937 0.008733749 -0.190702 0.09810519 0.008880794 -0.189968 0.09770596 0.009275317 -0.1902689 0.09793907 0.009061753 -0.190035 0.09765279 0.009275317 -0.190141 0.09756779 0.009275317 -0.189808 0.09785789 0.009275317 -0.190064 0.09812766 0.009061753 -0.190514 0.09824019 0.008880794 -0.190917 0.09844559 0.008733749 -0.191511 0.09908229 0.008545756 -0.189589 0.09811747 0.009275317 -0.190769 0.09855228 0.008733749 -0.191421 0.0991199 0.008545756 -0.189884 0.09833949 0.009061753 -0.190345 0.09839695 0.008880794 -0.190195 0.09857296 0.008880794 -0.190779 0.09874916 0.008687853 -0.191018 0.09888726 0.008623957 -0.189267 0.09867537 0.009275317 -0.189731 0.09857136 0.009061753 -0.190635 0.09867596 0.008733749 -0.18922 0.09878498 0.009275317 -0.189607 0.0988202 0.009061753 -0.1899639 0.09897255 0.008880794 -0.1900669 0.09876579 0.008880794 -0.190517 0.09881496 0.008733749 -0.189087 0.09929406 0.009275317 -0.1891 0.09920996 0.009275317 -0.189887 0.09919029 0.008880794 -0.190335 0.09913051 0.008733749 -0.189424 0.09962999 0.009061753 -0.1894519 0.09935337 0.009061753 -0.189055 0.09987008 0.009275317 -0.189051 0.09964907 0.009275317 -0.1894299 0.09990799 0.009061753 -0.189836 0.09941565 0.008880794 -0.190273 0.09930241 0.008733749 -0.1904309 0.09934926 0.008686244 -0.19051 0.09920668 0.00868076 -0.190416 0.09896719 0.008733749 -0.1905879 0.09906649 0.008675336 -0.190671 0.09892886 0.00868076 -0.190755 0.09878909 0.008686244 -0.189106 0.100257 0.009275317 -0.189817 0.09987676 0.008880794 -0.189813 0.09964567 0.008880794 -0.18919 0.100569 0.009275317 -0.189541 0.100452 0.009061753 -0.189469 0.100183 0.009061753 -0.18985 0.100106 0.008880794 -0.190219 0.09984439 0.008733749 -0.190215 0.09966188 0.008733749 -0.1906419 0.09954679 0.008621811 -0.190648 0.09952819 0.008623957 -0.190629 0.09967857 0.008621811 -0.190631 0.09981095 0.008621811 -0.190244 0.1000249 0.008733749 -0.189909 0.100329 0.008880794 -0.189247 0.100729 0.009275317 -0.189465 0.101151 0.009275317 -0.1896449 0.10071 0.009061753 -0.189996 0.100543 0.008880794 -0.19065 0.0999422 0.008621811 -0.191052 0.0997771 0.008545756 -0.191063 0.0998578 0.008545756 -0.190684 0.1000699 0.008621811 -0.190292 0.100201 0.008733749 -0.19036 0.100371 0.008733749 -0.190107 0.100746 0.008880794 -0.189779 0.100953 0.009061753 -0.18986 0.10164 0.009275317 -0.189941 0.101179 0.009061753 -0.19012 0.101859 0.009275317 -0.190342 0.101564 0.009061753 -0.1901299 0.101383 0.009061753 -0.1902419 0.100933 0.008880794 -0.190448 0.10053 0.008733749 -0.1911219 0.100027 0.008545756 -0.190575 0.101253 0.008880794 -0.190399 0.101103 0.008880794 -0.190554 0.100678 0.008733749 -0.190678 0.100813 0.008733749 -0.190768 0.10138 0.008880794 -0.1908169 0.100931 0.008733749 -0.190981 0.102291 0.009275317 -0.190787 0.102227 0.009275317 -0.190822 0.101841 0.009061753 -0.191296 0.10236 0.009275317 -0.1912119 0.102348 0.009275317 -0.191192 0.101561 0.008880794 -0.190975 0.101483 0.008880794 -0.190969 0.101031 0.008733749 -0.191632 0.102024 0.009061753 -0.191356 0.101996 0.009061753 -0.1914179 0.101612 0.008880794 -0.192092 0.102372 0.009275317 -0.19194 0.102387 0.009275317 -0.191651 0.102396 0.009275317 -0.191648 0.101635 0.008880794 -0.191304 0.1011739 0.008733749 -0.191209 0.100937 0.00868076 -0.191133 0.101113 0.008733749 -0.191069 0.100859 0.008675336 -0.190931 0.100777 0.00868076 -0.190791 0.100693 0.008686244 -0.190751 0.100669 0.008687853 -0.191482 0.101214 0.008733749 -0.191879 0.10163 0.008880794 -0.19191 0.1020179 0.009061753 -0.192185 0.101979 0.009061753 -0.192571 0.102258 0.009275317 -0.192108 0.101598 0.008880794 -0.191664 0.101233 0.008733749 -0.191552 0.100762 0.008613824 -0.1915299 0.1008 0.008623957 -0.191576 0.10072 0.008602738 -0.191677 0.100547 0.008572161 -0.1918129 0.100816 0.008621811 -0.191681 0.100819 0.008621811 -0.192027 0.101203 0.008733749 -0.191846 0.101229 0.008733749 -0.193154 0.1019819 0.009275317 -0.192712 0.101803 0.009061753 -0.1925449 0.101452 0.008880794 -0.192331 0.101538 0.008880794 -0.191944 0.100798 0.008621811 -0.191779 0.100396 0.008545756 -0.191763 0.100397 0.008545756 -0.19186 0.1003839 0.008545756 -0.192203 0.1011559 0.008733749 -0.192072 0.100763 0.008621811 -0.192373 0.101088 0.008733749 -0.192956 0.101669 0.009061753 -0.193481 0.10174 0.009275317 -0.193309 0.101878 0.009275317 -0.193181 0.101506 0.009061753 -0.192748 0.1013399 0.008880794 -0.192533 0.101 0.008733749 -0.193566 0.101106 0.009061753 -0.193789 0.101423 0.009275317 -0.193386 0.101318 0.009061753 -0.192935 0.101205 0.008880794 -0.192311 0.10065 0.008621811 -0.1921949 0.100714 0.008621811 -0.192179 0.100412 0.008572161 -0.193105 0.101049 0.008880794 -0.192671 0.100696 0.008687853 -0.192432 0.100558 0.008623957 -0.193843 0.100625 0.009061753 -0.193719 0.100874 0.009061753 -0.193255 0.100873 0.008880794 -0.192933 0.1006309 0.008733749 -0.194293 0.100467 0.009275317 -0.193937 0.100363 0.009061753 -0.19423 0.100661 0.009275317 -0.193382 0.10068 0.008880794 -0.1943629 0.100151 0.009275317 -0.19435 0.100235 0.009275317 -0.193486 0.100473 0.008880794 -0.1930339 0.100478 0.008733749 -0.194383 0.100017 0.009275317 -0.193998 0.100092 0.009061753 -0.193614 0.10003 0.008880794 -0.193176 0.100143 0.008733749 -0.193563 0.100255 0.008880794 -0.193637 0.09979981 0.008880794 -0.1940259 0.09981548 0.009061753 -0.1931149 0.100315 0.008733749 -0.192939 0.100239 0.00868076 -0.192862 0.100379 0.008675336 -0.192779 0.100517 0.00868076 -0.192815 0.1007699 0.008733749 -0.192695 0.100656 0.008686244 -0.194374 0.09935539 0.009275317 -0.19402 0.09953749 0.009061753 -0.193633 0.09956878 0.008880794 -0.193216 0.09996515 0.008733749 -0.194335 0.0991379 0.009275317 -0.193981 0.09926217 0.009061753 -0.1935999 0.0993399 0.008880794 -0.193231 0.0996012 0.008733749 -0.193235 0.09978359 0.008733749 -0.192808 0.09989875 0.008621811 -0.192802 0.09991729 0.008623957 -0.192821 0.09976691 0.008621811 -0.192818 0.09963446 0.008621811 -0.193909 0.09899359 0.009061753 -0.19354 0.09911668 0.008880794 -0.194111 0.09851515 0.009275317 -0.193671 0.09849208 0.009061753 -0.193805 0.09873557 0.009061753 -0.193454 0.09890228 0.008880794 -0.193158 0.09924417 0.008733749 -0.1932049 0.09942048 0.008733749 -0.1928 0.09950327 0.008621811 -0.192549 0.09977108 0.008572161 -0.192399 0.09968465 0.008545756 -0.192398 0.09966838 0.008545756 -0.192386 0.09958767 0.008545756 -0.192766 0.0993753 0.008621811 -0.19309 0.09907495 0.008733749 -0.19332 0.09806209 0.009061753 -0.19359 0.09780579 0.009275317 -0.193509 0.09826648 0.009061753 -0.193342 0.09869986 0.008880794 -0.192716 0.0992524 0.008621811 -0.192365 0.099509 0.008545756 -0.1934249 0.09765827 0.009275317 -0.193108 0.09788185 0.009061753 -0.193207 0.09851229 0.008880794 -0.193002 0.0989151 0.008733749 -0.192652 0.09913641 0.008621811 -0.192328 0.09941869 0.008545756 -0.192875 0.09819269 0.008880794 -0.193051 0.09834247 0.008880794 -0.192698 0.0987764 0.008687853 -0.19256 0.09901577 0.008623957 -0.191083 0.09977936 0.01024997 -0.1911799 0.09983569 0.01024997 -0.190409 0.09938997 0.008687853 -0.191159 0.09982299 0.009976387 -0.191065 0.09976917 0.008744776 -0.191051 0.09976077 0.008545756 -0.190901 0.0996744 0.008572161 -0.1907269 0.09957408 0.008602738 -0.190686 0.09955006 0.008613824 -0.190426 0.09897279 0.01099997 -0.190426 0.09897279 0.01889997 -0.190288 0.09929257 0.01889997 -0.190288 0.09929257 0.01099997 -0.190227 0.09963548 0.01099997 -0.190248 0.09998315 0.01099997 -0.190348 0.100317 0.01099997 -0.190348 0.100317 0.01889997 -0.190522 0.100618 0.01889997 -0.190522 0.100618 0.01099997 -0.190761 0.100872 0.01099997 -0.191052 0.101063 0.01099997 -0.191379 0.101182 0.01099997 -0.191052 0.101063 0.01889997 -0.191725 0.101223 0.01889997 -0.191725 0.101223 0.01099997 -0.192071 0.101182 0.01099997 -0.192398 0.101063 0.01889997 -0.192398 0.101063 0.01099997 -0.192689 0.100872 0.01099997 -0.192689 0.100872 0.01889997 -0.192928 0.100618 0.01889997 -0.192928 0.100618 0.01099997 -0.193102 0.100317 0.01099997 -0.193202 0.09998315 0.01099997 -0.193202 0.09998315 0.01889997 -0.193222 0.09963548 0.01099997 -0.193162 0.09929257 0.01099997 -0.193024 0.09897279 0.01099997 -0.193162 0.09929257 0.01889997 -0.193024 0.09897279 0.01889997 -0.192816 0.09869337 0.01099997 -0.192816 0.09869337 0.01889997 -0.192549 0.09846949 0.01099997 -0.192238 0.09831315 0.01099997 -0.192549 0.09846949 0.01889997 -0.192238 0.09831315 0.01889997 -0.191899 0.09823286 0.01099997 -0.191551 0.09823286 0.01099997 -0.191551 0.09823286 0.01889997 -0.1912119 0.09831315 0.01099997 -0.190901 0.09846949 0.01099997 -0.190901 0.09846949 0.01889997 -0.190634 0.09869337 0.01099997 -0.193222 0.09963548 0.01889997 -0.191899 0.09823286 0.01889997 -0.1912119 0.09831315 0.01889997 -0.190761 0.100872 0.01889997 -0.191379 0.101182 0.01889997 -0.192071 0.101182 0.01889997 -0.193102 0.100317 0.01889997 -0.190248 0.09998315 0.01889997 -0.190227 0.09963548 0.01889997 -0.190634 0.09869337 0.01889997 -0.008698284 0.217168 0.01889997 -0.01030164 0.217168 0.01889997 -0.01008796 0.21728 0.01889997 -0.01049464 0.217023 0.01889997 -0.0106619 0.216849 0.01889997 -0.009024977 0.214477 0.01889997 -0.008912026 0.21728 0.01889997 -0.009141027 0.217356 0.01889997 -0.009379267 0.217395 0.01889997 -0.009620666 0.217395 0.01889997 -0.009858965 0.217356 0.01889997 -0.01079899 0.21665 0.01889997 -0.01073449 0.215048 0.01889997 -0.01058179 0.214861 0.01889997 -0.01040107 0.2147009 0.01889997 -0.0101971 0.214572 0.01889997 -0.009974956 0.214477 0.01889997 -0.009740591 0.214419 0.01889997 -0.009499967 0.2143999 0.01889997 -0.009259343 0.214419 0.01889997 -0.008505284 0.217023 0.01889997 -0.00880289 0.214572 0.01889997 -0.008598864 0.2147009 0.01889997 -0.008338034 0.216849 0.01889997 -0.008418142 0.214861 0.01889997 -0.008200943 0.21665 0.01889997 -0.008097469 0.216432 0.01889997 -0.01090246 0.216432 0.01889997 -0.01096969 0.2161999 0.01889997 -0.01085519 0.215257 0.01889997 -0.01094079 0.215483 0.01889997 -0.01099878 0.21596 0.01889997 -0.01098906 0.215719 0.01889997 -0.008059203 0.215483 0.01889997 -0.008010923 0.215719 0.01889997 -0.008144795 0.215257 0.01889997 -0.008265495 0.215048 0.01889997 -0.008001208 0.21596 0.01889997 -0.008030295 0.2161999 0.01889997 -0.009869992 0.217064 0.008654952 -0.009869992 0.216858 0.008607208 -0.01045745 0.21553 0.008607208 -0.01006478 0.21553 0.008545756 -0.01002269 0.2154729 0.008545756 -0.009130001 0.215335 0.008545756 -0.008542418 0.21553 0.008607208 -0.008553683 0.2154999 0.008606612 -0.008145928 0.216134 0.008692502 -0.008935213 0.21627 0.008545756 -0.008542418 0.21627 0.008607208 -0.00856173 0.21627 0.008602738 -0.008553683 0.2163 0.008606612 -0.008607268 0.21627 0.008595764 -0.008187413 0.2159 0.008675336 -0.008188664 0.215975 0.008677899 -0.008229494 0.21553 0.008679568 -0.008193612 0.21553 0.008687853 -0.008191227 0.215672 0.008683025 -0.008188664 0.215825 0.008677899 -0.00856173 0.21553 0.008602738 -0.008607268 0.21553 0.008595764 -0.008818387 0.21553 0.008563578 -0.009130001 0.214594 0.008687853 -0.009130001 0.214942 0.008607208 -0.009130001 0.214946 0.008606374 -0.009613335 0.2145889 0.008679151 -0.01007086 0.21465 0.008692502 -0.00992465 0.2145929 0.008692502 -0.009869992 0.214594 0.008687853 -0.009772896 0.2145529 0.008692502 -0.009766936 0.214592 0.008684337 -0.01012724 0.215086 0.008606612 -0.01003044 0.21502 0.008606612 -0.009869992 0.215061 0.008587658 -0.009869992 0.214962 0.008602738 -0.0104382 0.21553 0.008602738 -0.01028609 0.21553 0.008579552 -0.01008009 0.21553 0.00854808 -0.01080626 0.21627 0.008687853 -0.0105586 0.21627 0.008630573 -0.01073318 0.216506 0.008692502 -0.01008009 0.21627 0.00854808 -0.01036417 0.216455 0.008606612 -0.01028609 0.21627 0.008579552 -0.009869992 0.2164649 0.008545756 -0.01003044 0.21678 0.008606612 -0.009926736 0.216834 0.008606612 -0.009869992 0.216838 0.008602738 -0.009869992 0.2167389 0.008587658 -0.009869992 0.21653 0.008555769 -0.009462416 0.217212 0.008676588 -0.009304404 0.21726 0.008692502 -0.009310066 0.217209 0.008681774 -0.00915569 0.217207 0.008686959 -0.009130001 0.217206 0.008687853 -0.009150624 0.217229 0.008692502 -0.009130001 0.216858 0.008607208 -0.009130001 0.2164649 0.008545756 -0.009020566 0.216809 0.008606612 -0.009130001 0.216634 0.008571505 -0.009127259 0.216857 0.008606612 -0.009130001 0.216838 0.008602738 -0.009130001 0.216854 0.008606374 -0.009869992 0.215335 0.008545756 -0.009869992 0.21527 0.008555769 -0.009912252 0.2153649 0.008545756 -0.009970545 0.215416 0.008545756 -0.01036417 0.215345 0.008606612 -0.009130001 0.214962 0.008602738 -0.009020566 0.214991 0.008606612 -0.009130001 0.215166 0.008571505 -0.008920133 0.215052 0.008606612 -0.008827209 0.215124 0.008606612 -0.009118854 0.2153429 0.008545756 -0.009057819 0.21539 0.008545756 -0.008743107 0.215205 0.008606612 -0.009002566 0.215443 0.008545756 -0.00895375 0.215503 0.008545756 -0.008935213 0.21553 0.008545756 -0.009118854 0.216457 0.008545756 -0.008920133 0.2167479 0.008606612 -0.009057819 0.21641 0.008545756 -0.008827209 0.2166759 0.008606612 -0.009002566 0.2163569 0.008545756 -0.008743107 0.2165949 0.008606612 -0.00895375 0.216297 0.008545756 -0.008818387 0.21627 0.008563578 -0.01006478 0.21627 0.008545756 -0.01002269 0.216327 0.008545756 -0.01021599 0.216637 0.008606612 -0.009970545 0.2163839 0.008545756 -0.01012724 0.216714 0.008606612 -0.009912252 0.216435 0.008545756 -0.009869992 0.214942 0.008607208 -0.009926736 0.2149659 0.008606612 -0.009869992 0.214736 0.008654952 -0.01020956 0.214723 0.008692502 -0.01021599 0.2151629 0.008606612 -0.01029527 0.21525 0.008606612 -0.01065599 0.215157 0.008692502 -0.01042187 0.215447 0.008606612 -0.0105586 0.21553 0.008630573 -0.01080626 0.21553 0.008687853 -0.01083844 0.215589 0.008692502 -0.01080739 0.2155939 0.008685648 -0.01080995 0.215748 0.008680462 -0.01086515 0.215743 0.008692502 -0.01087415 0.2159 0.008692502 -0.01086515 0.216057 0.008692502 -0.01081258 0.2159 0.008675336 -0.01080995 0.2160519 0.008680462 -0.01080739 0.216206 0.008685648 -0.00860548 0.215395 0.008606612 -0.008303403 0.215224 0.008692502 -0.008668839 0.215296 0.008606612 -0.008388221 0.215092 0.008692502 -0.008487522 0.214971 0.008692502 -0.008600056 0.214861 0.008692502 -0.008724331 0.214766 0.008692502 -0.00885868 0.214685 0.008692502 -0.009127259 0.214943 0.008606612 -0.009001374 0.214619 0.008692502 -0.009150624 0.2145709 0.008692502 -0.00915569 0.2145929 0.008686959 -0.009310066 0.214591 0.008681774 -0.009462416 0.214588 0.008676588 -0.009499967 0.214587 0.008675336 -0.00885868 0.217115 0.008692502 -0.008600056 0.216939 0.008692502 -0.008668839 0.216504 0.008606612 -0.00860548 0.216405 0.008606612 -0.008229494 0.21627 0.008679568 -0.008193612 0.21627 0.008687853 -0.008191227 0.216128 0.008683025 -0.0104382 0.21627 0.008602738 -0.01042187 0.2163529 0.008606612 -0.01045745 0.21627 0.008607208 -0.01029527 0.2165499 0.008606612 -0.01065599 0.216643 0.008692502 -0.009869992 0.217206 0.008687853 -0.009766936 0.217208 0.008684337 -0.009613335 0.217211 0.008679151 -0.009499967 0.217213 0.008675336 -0.01083844 0.216211 0.008692502 -0.01116949 0.216288 0.00880295 -0.01079428 0.2163619 0.008692502 -0.01111435 0.216476 0.00880295 -0.01056379 0.2167699 0.008692502 -0.01082688 0.216985 0.00880295 -0.01069456 0.2171289 0.00880295 -0.01045769 0.216885 0.008692502 -0.01033908 0.216988 0.008692502 -0.01054668 0.217257 0.00880295 -0.01020956 0.217077 0.008692502 -0.01007086 0.21715 0.008692502 -0.010212 0.217459 0.00880295 -0.00992465 0.217207 0.008692502 -0.009772896 0.217247 0.008692502 -0.009617567 0.217269 0.008692502 -0.009460747 0.217274 0.008692502 -0.009646654 0.217608 0.00880295 -0.009451031 0.217613 0.00880295 -0.009064197 0.217558 0.00880295 -0.009001374 0.217181 0.008692502 -0.008700072 0.217416 0.00880295 -0.008724331 0.217034 0.008692502 -0.008532464 0.217315 0.00880295 -0.008377492 0.217195 0.00880295 -0.008487522 0.216829 0.008692502 -0.008237123 0.217059 0.00880295 -0.008388221 0.216708 0.008692502 -0.008303403 0.216576 0.008692502 -0.008234143 0.216435 0.008692502 -0.008007466 0.2167429 0.00880295 -0.008181452 0.216287 0.008692502 -0.007855355 0.216383 0.00880295 -0.007811009 0.216192 0.00880295 -0.008128046 0.215978 0.008692502 -0.008128046 0.215822 0.008692502 -0.008145928 0.2156659 0.008692502 -0.007788717 0.215802 0.00880295 -0.007811009 0.215608 0.00880295 -0.007855355 0.215417 0.00880295 -0.008181452 0.215513 0.008692502 -0.008234143 0.2153649 0.008692502 -0.008007466 0.215057 0.00880295 -0.008532464 0.214485 0.00880295 -0.008700072 0.214384 0.00880295 -0.008878111 0.214303 0.00880295 -0.009064197 0.214242 0.00880295 -0.009304404 0.21454 0.008692502 -0.009460747 0.2145259 0.008692502 -0.009617567 0.214531 0.008692502 -0.009451031 0.214187 0.00880295 -0.01002967 0.2142699 0.00880295 -0.010212 0.214341 0.00880295 -0.01033908 0.214812 0.008692502 -0.01038509 0.214432 0.00880295 -0.01054668 0.214543 0.00880295 -0.01045769 0.214915 0.008692502 -0.01069456 0.214671 0.00880295 -0.01056379 0.21503 0.008692502 -0.01082688 0.214815 0.00880295 -0.01094198 0.214973 0.00880295 -0.01073318 0.215294 0.008692502 -0.01079428 0.215438 0.008692502 -0.01116949 0.215512 0.00880295 -0.01120287 0.215705 0.00880295 -0.01121407 0.2159 0.00880295 -0.01153177 0.2161329 0.008937358 -0.01133525 0.216802 0.008937358 -0.01103818 0.216656 0.00880295 -0.01094198 0.216827 0.00880295 -0.01122045 0.217006 0.008937358 -0.01038509 0.217368 0.00880295 -0.0105561 0.217651 0.008937358 -0.01002967 0.21753 0.00880295 -0.01013195 0.217845 0.008937358 -0.009840369 0.21758 0.00880295 -0.009906113 0.217904 0.008937358 -0.009256005 0.217597 0.00880295 -0.009208917 0.2179239 0.008937358 -0.008878111 0.217497 0.00880295 -0.008545577 0.217709 0.008937358 -0.008345603 0.217588 0.008937358 -0.00816065 0.217446 0.008937358 -0.007993221 0.217283 0.008937358 -0.008113265 0.216908 0.00880295 -0.007921099 0.216567 0.00880295 -0.007616102 0.216696 0.008937358 -0.007537662 0.216476 0.008937358 -0.007484734 0.216249 0.008937358 -0.007788717 0.2159979 0.00880295 -0.00745815 0.2157829 0.008937358 -0.007484734 0.215551 0.008937358 -0.007537662 0.215324 0.008937358 -0.007921099 0.215233 0.00880295 -0.007616102 0.215104 0.008937358 -0.008113265 0.214893 0.00880295 -0.007845401 0.214698 0.008937358 -0.008237123 0.214741 0.00880295 -0.007993221 0.2145169 0.008937358 -0.00816065 0.214354 0.008937358 -0.008377492 0.214605 0.00880295 -0.008345603 0.214212 0.008937358 -0.008545577 0.214091 0.008937358 -0.009256005 0.214203 0.00880295 -0.009208917 0.213876 0.008937358 -0.009646654 0.214192 0.00880295 -0.009674966 0.213862 0.008937358 -0.009840369 0.2142199 0.00880295 -0.009906113 0.213896 0.008937358 -0.0105561 0.2141489 0.008937358 -0.01074886 0.21428 0.008937358 -0.0110833 0.214605 0.008937358 -0.01122045 0.214794 0.008937358 -0.01103818 0.215144 0.00880295 -0.01111435 0.215324 0.00880295 -0.01153177 0.215667 0.008937358 -0.01120287 0.216095 0.00880295 -0.01149195 0.216363 0.008937358 -0.01142615 0.216587 0.008937358 -0.01172828 0.216695 0.009095132 -0.01162308 0.216944 0.009095132 -0.0110833 0.217195 0.008937358 -0.01149028 0.217179 0.009095132 -0.01092535 0.2173669 0.008937358 -0.01074886 0.2175199 0.008937358 -0.01094466 0.217774 0.009095132 -0.01072168 0.217926 0.009095132 -0.01034957 0.21776 0.008937358 -0.01048278 0.218052 0.009095132 -0.009674966 0.217938 0.008937358 -0.009702444 0.218257 0.009095132 -0.009441554 0.217944 0.008937358 -0.008980035 0.217878 0.008937358 -0.008898556 0.218188 0.009095132 -0.008757948 0.217806 0.008937358 -0.00864166 0.218105 0.009095132 -0.00839591 0.217992 0.009095132 -0.008164584 0.217853 0.009095132 -0.007845401 0.217102 0.008937358 -0.007719159 0.216906 0.008937358 -0.007439911 0.217063 0.009095132 -0.007229983 0.216567 0.009095132 -0.007168769 0.216303 0.009095132 -0.00745815 0.216017 0.008937358 -0.007138013 0.216035 0.009095132 -0.007168769 0.215497 0.009095132 -0.007229983 0.215233 0.009095132 -0.007320761 0.2149789 0.009095132 -0.007719159 0.2148939 0.008937358 -0.007950663 0.214112 0.009095132 -0.008164584 0.2139469 0.009095132 -0.008757948 0.213994 0.008937358 -0.008980035 0.213922 0.008937358 -0.00864166 0.213695 0.009095132 -0.008898556 0.213612 0.009095132 -0.009441554 0.213856 0.008937358 -0.01013195 0.213955 0.008937358 -0.01023107 0.2136499 0.009095132 -0.01034957 0.21404 0.008937358 -0.01072168 0.213874 0.009095132 -0.01094466 0.214026 0.009095132 -0.01092535 0.214433 0.008937358 -0.01133149 0.214402 0.009095132 -0.01133525 0.214998 0.008937358 -0.01142615 0.215213 0.008937358 -0.01172828 0.2151049 0.009095132 -0.01149195 0.2154369 0.008937358 -0.01186579 0.2159 0.009095132 -0.01154518 0.2159 0.008937358 -0.009119331 0.213253 0.009275317 -0.009423613 0.213227 0.009275317 -0.009432435 0.213535 0.009095132 -0.009702444 0.2135429 0.009095132 -0.009499967 0.213226 0.009275317 -0.009728848 0.213235 0.009275317 -0.00996983 0.213581 0.009095132 -0.0100311 0.213279 0.009275317 -0.01032638 0.213356 0.009275317 -0.01048278 0.213748 0.009095132 -0.01061099 0.213467 0.009275317 -0.01088106 0.2136099 0.009275317 -0.01113307 0.213782 0.009275317 -0.01114875 0.214203 0.009095132 -0.01136386 0.213982 0.009275317 -0.01157039 0.2142069 0.009275317 -0.01149028 0.214621 0.009095132 -0.01174986 0.2144539 0.009275317 -0.01162308 0.214856 0.009095132 -0.01189994 0.21472 0.009275317 -0.01201885 0.215001 0.009275317 -0.0118044 0.215364 0.009095132 -0.01185035 0.2156299 0.009095132 -0.01210486 0.215294 0.009275317 -0.01215696 0.215595 0.009275317 -0.01185035 0.21617 0.009095132 -0.01217436 0.2159 0.009275317 -0.01215696 0.216205 0.009275317 -0.01210486 0.216506 0.009275317 -0.0118044 0.216436 0.009095132 -0.01201885 0.216799 0.009275317 -0.01189994 0.2170799 0.009275317 -0.01174986 0.217346 0.009275317 -0.01157039 0.217593 0.009275317 -0.01133149 0.217398 0.009095132 -0.01114875 0.217597 0.009095132 -0.01136386 0.217818 0.009275317 -0.01113307 0.2180179 0.009275317 -0.01088106 0.21819 0.009275317 -0.01023107 0.21815 0.009095132 -0.01061099 0.218333 0.009275317 -0.01032638 0.218444 0.009275317 -0.00996983 0.218219 0.009095132 -0.0100311 0.2185209 0.009275317 -0.009728848 0.218565 0.009275317 -0.009432435 0.2182649 0.009095132 -0.00916326 0.218242 0.009095132 -0.009423613 0.218573 0.009275317 -0.009119331 0.218547 0.009275317 -0.008820056 0.218487 0.009275317 -0.008529663 0.218392 0.009275317 -0.008251905 0.2182649 0.009275317 -0.007990419 0.2181079 0.009275317 -0.007950663 0.217688 0.009095132 -0.007748603 0.217921 0.009275317 -0.007756948 0.2175 0.009095132 -0.007529616 0.217708 0.009275317 -0.007585942 0.2172909 0.009095132 -0.007336318 0.217472 0.009275317 -0.007171213 0.217215 0.009275317 -0.007036507 0.2169409 0.009275317 -0.007320761 0.216821 0.009095132 -0.006933867 0.216653 0.009275317 -0.006864726 0.216356 0.009275317 -0.006829917 0.216053 0.009275317 -0.007138013 0.2157649 0.009095132 -0.006829917 0.2157469 0.009275317 -0.006864726 0.215444 0.009275317 -0.006933867 0.215147 0.009275317 -0.007036507 0.214859 0.009275317 -0.007171213 0.214585 0.009275317 -0.007439911 0.2147369 0.009095132 -0.007585942 0.214509 0.009095132 -0.007756948 0.2143 0.009095132 -0.007336318 0.214328 0.009275317 -0.007529616 0.214092 0.009275317 -0.007748603 0.213879 0.009275317 -0.007990419 0.213692 0.009275317 -0.00839591 0.213808 0.009095132 -0.008251905 0.213535 0.009275317 -0.008529663 0.2134079 0.009275317 -0.008820056 0.213313 0.009275317 -0.00916326 0.213558 0.009095132 -0.00996083 0.213138 0.01089996 -0.009039103 0.213138 0.009503483 -0.009499967 0.2131 0.01089996 -0.009039103 0.213138 0.01089996 -0.008590817 0.213252 0.009503483 -0.008167326 0.213437 0.009503483 -0.008590817 0.213252 0.01089996 -0.008167326 0.213437 0.01089996 -0.007780194 0.21369 0.009503483 -0.007780194 0.21369 0.01089996 -0.007439911 0.214004 0.01089996 -0.007439911 0.214004 0.009503483 -0.007155895 0.2143689 0.01089996 -0.007155895 0.2143689 0.009503483 -0.006935775 0.214775 0.009503483 -0.006935775 0.214775 0.01089996 -0.006785631 0.215213 0.009503483 -0.006785631 0.215213 0.01089996 -0.006709516 0.215669 0.01089996 -0.006709516 0.215669 0.009503483 -0.006709516 0.216131 0.009503483 -0.006709516 0.216131 0.01089996 -0.006785631 0.216587 0.009503483 -0.006785631 0.216587 0.01089996 -0.006935775 0.217025 0.009503483 -0.006935775 0.217025 0.01089996 -0.007155895 0.217431 0.009503483 -0.007155895 0.217431 0.01089996 -0.007439911 0.217796 0.009503483 -0.007439911 0.217796 0.01089996 -0.007780194 0.21811 0.009503483 -0.007780194 0.21811 0.01089996 -0.008167326 0.218363 0.01089996 -0.008167326 0.218363 0.009503483 -0.008590817 0.2185479 0.009503483 -0.008590817 0.2185479 0.01089996 -0.009039103 0.218662 0.01089996 -0.009039103 0.218662 0.009503483 -0.009499967 0.2186999 0.009503483 -0.009499967 0.2186999 0.01089996 -0.00996083 0.218662 0.009503483 -0.01040917 0.2185479 0.009503483 -0.00996083 0.218662 0.01089996 -0.01040917 0.2185479 0.01089996 -0.01083266 0.218363 0.009503483 -0.01083266 0.218363 0.01089996 -0.01121979 0.21811 0.009503483 -0.01121979 0.21811 0.01089996 -0.01155996 0.217796 0.01089996 -0.01155996 0.217796 0.009503483 -0.01184409 0.217431 0.009503483 -0.01184409 0.217431 0.01089996 -0.01206415 0.217025 0.01089996 -0.01206415 0.217025 0.009503483 -0.0122143 0.216587 0.009503483 -0.0122143 0.216587 0.01089996 -0.01229035 0.216131 0.009503483 -0.01229035 0.216131 0.01089996 -0.01229035 0.215669 0.009503483 -0.01229035 0.215669 0.01089996 -0.0122143 0.215213 0.01089996 -0.0122143 0.215213 0.009503483 -0.01206415 0.214775 0.009503483 -0.01206415 0.214775 0.01089996 -0.01184409 0.2143689 0.01089996 -0.01184409 0.2143689 0.009503483 -0.01155996 0.214004 0.009503483 -0.01155996 0.214004 0.01089996 -0.01121979 0.21369 0.01089996 -0.01121979 0.21369 0.009503483 -0.01083266 0.213437 0.009503483 -0.01083266 0.213437 0.01089996 -0.01040917 0.213252 0.01089996 -0.01040917 0.213252 0.009503483 -0.00996083 0.213138 0.009503483 -0.009499967 0.2131 0.009503483 0.180788 0.115747 0.01889997 0.180926 0.115427 0.01099997 0.180926 0.115427 0.01889997 0.181134 0.115148 0.01889997 0.181134 0.115148 0.01099997 0.181401 0.114924 0.01889997 0.181401 0.114924 0.01099997 0.181712 0.114768 0.01099997 0.182051 0.114687 0.01099997 0.182399 0.114687 0.01099997 0.182738 0.114768 0.01889997 0.182738 0.114768 0.01099997 0.183049 0.114924 0.01099997 0.1833159 0.115148 0.01099997 0.183524 0.115427 0.01099997 0.1836619 0.115747 0.01099997 0.183722 0.1160899 0.01099997 0.183722 0.1160899 0.01889997 0.183702 0.116438 0.01099997 0.183602 0.116771 0.01099997 0.183428 0.1170729 0.01099997 0.183189 0.117326 0.01099997 0.183428 0.1170729 0.01889997 0.183189 0.117326 0.01889997 0.182898 0.117518 0.01099997 0.1825709 0.117637 0.01889997 0.1825709 0.117637 0.01099997 0.182225 0.117677 0.01099997 0.182225 0.117677 0.01889997 0.181879 0.117637 0.01889997 0.181879 0.117637 0.01099997 0.1815519 0.117518 0.01099997 0.1815519 0.117518 0.01889997 0.181261 0.117326 0.01099997 0.181022 0.1170729 0.01099997 0.181022 0.1170729 0.01889997 0.180848 0.116771 0.01889997 0.180848 0.116771 0.01099997 0.180748 0.116438 0.01099997 0.180727 0.1160899 0.01099997 0.180748 0.116438 0.01889997 0.180727 0.1160899 0.01889997 0.180788 0.115747 0.01099997 0.183524 0.115427 0.01889997 0.1836619 0.115747 0.01889997 0.183049 0.114924 0.01889997 0.182399 0.114687 0.01889997 0.183702 0.116438 0.01889997 0.183602 0.116771 0.01889997 0.1833159 0.115148 0.01889997 0.181712 0.114768 0.01889997 0.182051 0.114687 0.01889997 0.182898 0.117518 0.01889997 0.181261 0.117326 0.01889997 0.181583 0.116234 0.01024997 0.180909 0.115845 0.008687853 0.18168 0.116066 0.01024997 0.181711 0.115955 0.01019227 0.181856 0.115761 0.01024997 0.181953 0.115593 0.01024997 0.181766 0.115855 0.01018857 0.181088 0.115521 0.008675336 0.180931 0.115804 0.008686244 0.182282 0.116819 0.01024997 0.182113 0.116722 0.01024997 0.181892 0.117494 0.008687853 0.181809 0.116546 0.01024997 0.181641 0.1164489 0.01024997 0.1814309 0.117231 0.00868076 0.181903 0.116636 0.01018857 0.182003 0.116691 0.01019227 0.180064 0.114397 0.01089996 0.1798 0.114777 0.01089996 0.180064 0.114397 0.009503483 0.180386 0.114066 0.01089996 0.180567 0.113921 0.009503483 0.180759 0.113792 0.009503483 0.180759 0.113792 0.01089996 0.180961 0.113679 0.009503483 0.181171 0.113583 0.01089996 0.181171 0.113583 0.009503483 0.181613 0.113445 0.01089996 0.181613 0.113445 0.009503483 0.182071 0.113381 0.01089996 0.182071 0.113381 0.009503483 0.1823019 0.113378 0.009503483 0.182533 0.113394 0.01089996 0.182762 0.113429 0.009503483 0.182987 0.113483 0.009503483 0.182987 0.113483 0.01089996 0.183207 0.113555 0.009503483 0.18342 0.113645 0.01089996 0.18382 0.113876 0.01089996 0.18382 0.113876 0.009503483 0.184005 0.1140159 0.009503483 0.184177 0.11417 0.01089996 0.184481 0.114519 0.01089996 0.184481 0.114519 0.009503483 0.18461 0.114711 0.009503483 0.184819 0.115124 0.009503483 0.184723 0.114913 0.01089996 0.184897 0.115341 0.01089996 0.184897 0.115341 0.009503483 0.184998 0.115793 0.009503483 0.184998 0.115793 0.01089996 0.185024 0.116254 0.01089996 0.185008 0.1164849 0.009503483 0.184973 0.116714 0.01089996 0.184973 0.116714 0.009503483 0.1849189 0.116939 0.009503483 0.1848469 0.117159 0.009503483 0.1848469 0.117159 0.01089996 0.18465 0.117577 0.01089996 0.184386 0.117957 0.01089996 0.1842319 0.11813 0.009503483 0.184064 0.118289 0.009503483 0.183883 0.1184329 0.009503483 0.184064 0.118289 0.01089996 0.183489 0.118676 0.009503483 0.183691 0.1185629 0.01089996 0.183279 0.118771 0.01089996 0.182837 0.118909 0.01089996 0.182837 0.118909 0.009503483 0.182379 0.118973 0.01089996 0.181917 0.11896 0.01089996 0.181917 0.11896 0.009503483 0.181688 0.118925 0.009503483 0.181463 0.118872 0.01089996 0.18103 0.118709 0.009503483 0.18103 0.118709 0.01089996 0.180629 0.118478 0.01089996 0.180113 0.118016 0.009503483 0.180272 0.118184 0.01089996 0.179969 0.117835 0.01089996 0.17984 0.117644 0.009503483 0.179727 0.117442 0.01089996 0.179553 0.117013 0.01089996 0.179493 0.1167899 0.009503483 0.179451 0.116562 0.009503483 0.179451 0.116562 0.01089996 0.179442 0.115869 0.009503483 0.179426 0.1161 0.01089996 0.179477 0.11564 0.009503483 0.179477 0.11564 0.01089996 0.179603 0.115195 0.01089996 0.1798 0.114777 0.009503483 0.179924 0.114582 0.009503483 0.180297 0.114325 0.009275317 0.18026 0.114266 0.009335577 0.180109 0.114434 0.009335577 0.180601 0.113968 0.009335577 0.180796 0.113918 0.009275317 0.1807889 0.113842 0.009335577 0.180987 0.113731 0.009335577 0.181379 0.113642 0.009275317 0.18164 0.113568 0.009275317 0.18169 0.113558 0.009275317 0.181848 0.113462 0.009335577 0.181858 0.113528 0.009275317 0.1820099 0.113513 0.009275317 0.182078 0.113507 0.009275317 0.182332 0.113506 0.009275317 0.1825259 0.113452 0.009335577 0.18275 0.113487 0.009335577 0.182738 0.113552 0.009275317 0.182953 0.113604 0.009275317 0.183163 0.113673 0.009275317 0.183749 0.113979 0.009275317 0.183787 0.113924 0.009335577 0.18383 0.114041 0.009275317 0.183925 0.114113 0.009275317 0.183968 0.1140609 0.009335577 0.184242 0.114421 0.009275317 0.1844339 0.114554 0.009335577 0.184484 0.114749 0.009275317 0.18456 0.114742 0.009335577 0.184639 0.115032 0.009275317 0.18476 0.115331 0.009275317 0.184841 0.115359 0.009335577 0.184835 0.115592 0.009275317 0.184844 0.115643 0.009275317 0.184962 0.116026 0.009335577 0.184889 0.115962 0.009275317 0.184898 0.116251 0.009275317 0.1848829 0.116471 0.009275317 0.1849499 0.116479 0.009335577 0.184916 0.116703 0.009335577 0.18485 0.11669 0.009275317 0.184798 0.116905 0.009275317 0.184704 0.117347 0.009335577 0.184541 0.117514 0.009275317 0.184423 0.117701 0.009275317 0.184478 0.117739 0.009335577 0.184361 0.117783 0.009275317 0.184341 0.11792 0.009335577 0.184153 0.1180289 0.009275317 0.1841419 0.118042 0.009275317 0.183981 0.118194 0.009275317 0.183915 0.118247 0.009275317 0.183809 0.118332 0.009275317 0.183848 0.118386 0.009335577 0.183654 0.118437 0.009275317 0.183432 0.118564 0.009275317 0.183661 0.118513 0.009335577 0.183463 0.118623 0.009335577 0.1832309 0.118655 0.009275317 0.182824 0.118852 0.009335577 0.182601 0.118893 0.009335577 0.182376 0.118915 0.009335577 0.182117 0.118848 0.009275317 0.181931 0.118835 0.009275317 0.181699 0.118868 0.009335577 0.181796 0.118815 0.009275317 0.181264 0.118745 0.009335577 0.181177 0.118636 0.009275317 0.181084 0.118596 0.009275317 0.180663 0.11843 0.009335577 0.180701 0.118375 0.009275317 0.180525 0.118242 0.009275317 0.180373 0.118106 0.009275317 0.180482 0.118293 0.009335577 0.180313 0.118142 0.009335577 0.18036 0.118094 0.009275317 0.180208 0.117934 0.009275317 0.180158 0.117978 0.009335577 0.180155 0.117867 0.009275317 0.179889 0.117613 0.009335577 0.17981 0.117323 0.009275317 0.1796849 0.117209 0.009335577 0.17969 0.117024 0.009275317 0.179608 0.116996 0.009335577 0.179615 0.116762 0.009275317 0.179606 0.116712 0.009275317 0.179509 0.116554 0.009335577 0.179551 0.116104 0.009275317 0.179484 0.116102 0.009335577 0.179567 0.115883 0.009275317 0.179587 0.115749 0.009275317 0.1796 0.115665 0.009275317 0.179657 0.115216 0.009335577 0.17972 0.115239 0.009275317 0.179767 0.11513 0.009275317 0.179746 0.115007 0.009335577 0.1799719 0.114615 0.009335577 0.1800889 0.114572 0.009275317 0.18016 0.114477 0.009275317 0.1798509 0.114807 0.009335577 0.179936 0.11459 0.009414553 0.180424 0.11411 0.009335577 0.180967 0.113692 0.009414553 0.181177 0.113597 0.009414553 0.1811929 0.113637 0.009335577 0.181407 0.113561 0.009335577 0.181616 0.11346 0.009414553 0.181625 0.113502 0.009335577 0.182074 0.11344 0.009335577 0.182071 0.113397 0.009414553 0.1823 0.1134369 0.009335577 0.1825309 0.113409 0.009414553 0.182759 0.113444 0.009414553 0.182971 0.113539 0.009335577 0.182983 0.113497 0.009414553 0.1831859 0.11361 0.009335577 0.183201 0.113569 0.009414553 0.183413 0.113659 0.009414553 0.183395 0.113698 0.009335577 0.183596 0.113803 0.009335577 0.183995 0.114027 0.009414553 0.184137 0.114212 0.009335577 0.184167 0.114181 0.009414553 0.184325 0.114348 0.009414553 0.184292 0.114377 0.009335577 0.184469 0.114528 0.009414553 0.184671 0.114939 0.009335577 0.184597 0.114719 0.009414553 0.18471 0.11492 0.009414553 0.184805 0.115129 0.009414553 0.184765 0.115146 0.009335577 0.1848829 0.115346 0.009414553 0.1849 0.115578 0.009335577 0.184942 0.115568 0.009414553 0.18494 0.115801 0.009335577 0.184983 0.115795 0.009414553 0.184965 0.116253 0.009335577 0.185006 0.116024 0.009414553 0.184958 0.116711 0.009414553 0.1849049 0.116935 0.009414553 0.184863 0.116923 0.009335577 0.184792 0.117139 0.009335577 0.184833 0.117154 0.009414553 0.184599 0.117548 0.009335577 0.18419 0.118089 0.009335577 0.184375 0.117948 0.009414553 0.184025 0.118245 0.009335577 0.183874 0.118421 0.009414553 0.183683 0.11855 0.009414553 0.183257 0.118717 0.009335577 0.183043 0.118794 0.009335577 0.1830559 0.118835 0.009414553 0.182834 0.118895 0.009414553 0.1826069 0.118936 0.009414553 0.1821489 0.118918 0.009335577 0.182148 0.118961 0.009414553 0.181919 0.118945 0.009414553 0.181923 0.118902 0.009335577 0.181691 0.118911 0.009414553 0.181479 0.118815 0.009335577 0.1814669 0.118857 0.009414553 0.181055 0.118657 0.009335577 0.1810359 0.118696 0.009414553 0.180854 0.118551 0.009335577 0.180638 0.118466 0.009414553 0.180283 0.118173 0.009414553 0.1801249 0.118006 0.009414553 0.1799809 0.1178269 0.009414553 0.180016 0.117801 0.009335577 0.179852 0.117636 0.009414553 0.1797789 0.117415 0.009335577 0.17974 0.117435 0.009414553 0.179567 0.117009 0.009414553 0.1795499 0.116777 0.009335577 0.179466 0.11656 0.009414553 0.179488 0.116328 0.009335577 0.179444 0.116331 0.009414553 0.1795 0.115876 0.009335577 0.179534 0.115652 0.009335577 0.1794919 0.115643 0.009414553 0.179587 0.115431 0.009335577 0.179545 0.115419 0.009414553 0.179693 0.114982 0.009503483 0.180075 0.114407 0.009414553 0.180218 0.114225 0.009503483 0.180229 0.114235 0.009414553 0.180396 0.114077 0.009414553 0.180386 0.114066 0.009503483 0.180576 0.113933 0.009414553 0.180766 0.1138049 0.009414553 0.181389 0.113505 0.009503483 0.181394 0.113519 0.009414553 0.18184 0.113404 0.009503483 0.181842 0.1134189 0.009414553 0.1823019 0.113393 0.009414553 0.182533 0.113394 0.009503483 0.18342 0.113645 0.009503483 0.1836169 0.113765 0.009414553 0.183812 0.113889 0.009414553 0.183625 0.113752 0.009503483 0.184177 0.11417 0.009503483 0.184336 0.114338 0.009503483 0.184723 0.114913 0.009503483 0.184957 0.115565 0.009503483 0.185021 0.116023 0.009503483 0.185009 0.116254 0.009414553 0.184993 0.116484 0.009414553 0.185024 0.116254 0.009503483 0.184743 0.117366 0.009414553 0.1847569 0.117372 0.009503483 0.184637 0.11757 0.009414553 0.184513 0.1177639 0.009414553 0.18465 0.117577 0.009503483 0.184526 0.1177729 0.009503483 0.184386 0.117957 0.009503483 0.184221 0.118119 0.009414553 0.184054 0.118277 0.009414553 0.183691 0.1185629 0.009503483 0.183482 0.1186619 0.009414553 0.183273 0.118757 0.009414553 0.183279 0.118771 0.009503483 0.183061 0.11885 0.009503483 0.182609 0.118951 0.009503483 0.182379 0.118973 0.009503483 0.1823779 0.1189579 0.009414553 0.182148 0.1189759 0.009503483 0.181463 0.118872 0.009503483 0.181243 0.118799 0.009503483 0.181248 0.118785 0.009414553 0.180832 0.118589 0.009414553 0.1808249 0.118602 0.009503483 0.180629 0.118478 0.009503483 0.180445 0.118339 0.009503483 0.180454 0.118327 0.009414553 0.180272 0.118184 0.009503483 0.179969 0.117835 0.009503483 0.179727 0.117442 0.009503483 0.1796309 0.117231 0.009503483 0.179645 0.117225 0.009414553 0.179553 0.117013 0.009503483 0.179507 0.116786 0.009414553 0.1794289 0.116331 0.009503483 0.179441 0.116101 0.009414553 0.179457 0.115871 0.009414553 0.179426 0.1161 0.009503483 0.179531 0.115415 0.009503483 0.179603 0.115195 0.009503483 0.179617 0.1152009 0.009414553 0.179706 0.114989 0.009414553 0.179813 0.114785 0.009414553 0.181481 0.118745 0.009275317 0.183023 0.11873 0.009275317 0.182954 0.1183609 0.009061753 0.184644 0.117319 0.009275317 0.184683 0.117225 0.009275317 0.1847299 0.117115 0.009275317 0.1847929 0.116921 0.009275317 0.184437 0.116818 0.009061753 0.183562 0.113861 0.009275317 0.183272 0.113719 0.009275317 0.182866 0.113966 0.009061753 0.180308 0.114312 0.009275317 0.179657 0.115433 0.009275317 0.179554 0.11607 0.009275317 0.179946 0.117578 0.009275317 0.179965 0.117606 0.009275317 0.18062 0.118313 0.009275317 0.183014 0.11555 0.008602738 0.183198 0.115231 0.008687853 0.182397 0.115138 0.008613824 0.182401 0.115094 0.008621811 0.182374 0.11518 0.008602738 0.182273 0.115354 0.008572161 0.182171 0.115504 0.008545756 0.182187 0.115503 0.008545756 0.1815969 0.115388 0.008602738 0.181638 0.11525 0.008621811 0.181279 0.115204 0.008687853 0.181186 0.116005 0.008613824 0.1811479 0.115983 0.008623957 0.181227 0.116029 0.008602738 0.181142 0.116001 0.008621811 0.181563 0.116312 0.008545756 0.1815519 0.116232 0.008545756 0.181131 0.116266 0.008621811 0.181291 0.117147 0.008686244 0.18203 0.117254 0.008623957 0.182052 0.117216 0.008613824 0.182049 0.11726 0.008621811 0.182181 0.117274 0.008621811 0.182076 0.117175 0.008602738 0.182177 0.1170009 0.008572161 0.1823599 0.116839 0.008545756 0.182279 0.11685 0.008545756 0.182313 0.117271 0.008621811 0.183171 0.117151 0.008687853 0.183181 0.117348 0.008733749 0.183302 0.116372 0.008623957 0.183308 0.116353 0.008621811 0.183264 0.1163499 0.008613824 0.1832219 0.116326 0.008602738 0.183049 0.116226 0.008572161 0.182886 0.116042 0.008545756 0.182898 0.116123 0.008545756 0.181074 0.118171 0.009061753 0.1816329 0.117567 0.008733749 0.18063 0.117838 0.009061753 0.180842 0.118018 0.009061753 0.181469 0.117486 0.008733749 0.181268 0.117835 0.008880794 0.180441 0.1176339 0.009061753 0.181317 0.117385 0.008733749 0.181075 0.117707 0.008880794 0.18007 0.117761 0.009275317 0.180279 0.117408 0.009061753 0.180899 0.117558 0.008880794 0.181178 0.117267 0.008733749 0.179747 0.117184 0.009275317 0.179839 0.117385 0.009275317 0.180742 0.117388 0.008880794 0.181569 0.117314 0.008675336 0.181709 0.117392 0.00868076 0.181851 0.117471 0.008686244 0.180145 0.117164 0.009061753 0.180496 0.116998 0.008880794 0.180607 0.1172 0.008880794 0.1810539 0.117133 0.008733749 0.181375 0.1168709 0.008621811 0.181251 0.117124 0.008687853 0.181389 0.116884 0.008623957 0.179969 0.116638 0.009061753 0.179672 0.116976 0.009275317 0.180041 0.116906 0.009061753 0.180409 0.116783 0.008880794 0.18086 0.116825 0.008733749 0.180948 0.116985 0.008733749 0.181411 0.116846 0.008613824 0.181435 0.116805 0.008602738 0.181298 0.116764 0.008621811 0.181536 0.116631 0.008572161 0.181234 0.116648 0.008621811 0.18035 0.11656 0.008880794 0.179576 0.116545 0.009275317 0.1795549 0.116325 0.009275317 0.179561 0.116392 0.009275317 0.179924 0.116085 0.009061753 0.17993 0.116363 0.009061753 0.180317 0.116331 0.008880794 0.1807439 0.116479 0.008733749 0.180792 0.116656 0.008733749 0.1816149 0.1164669 0.008545756 0.181622 0.116481 0.008545756 0.1811839 0.116525 0.008621811 0.181584 0.116391 0.008545756 0.18115 0.116397 0.008621811 0.180719 0.116299 0.008733749 0.180313 0.1161 0.008880794 0.179651 0.11545 0.009275317 0.180013 0.115537 0.009061753 0.179952 0.115808 0.009061753 0.1803359 0.1158699 0.008880794 0.180715 0.116116 0.008733749 0.180733 0.115935 0.008733749 0.181129 0.116133 0.008621811 0.181401 0.116129 0.008572161 0.181551 0.116215 0.008545756 0.179909 0.11484 0.009275317 0.1798059 0.115036 0.009275317 0.180231 0.1150259 0.009061753 0.180464 0.115427 0.008880794 0.1801069 0.115275 0.009061753 0.180387 0.115645 0.008880794 0.180773 0.115757 0.008733749 0.180027 0.114653 0.009275317 0.180384 0.114794 0.009061753 0.180564 0.114582 0.009061753 0.1806949 0.115027 0.008880794 0.180567 0.11522 0.008880794 0.180835 0.115585 0.008733749 0.180535 0.114107 0.009275317 0.180468 0.11416 0.009275317 0.180769 0.114394 0.009061753 0.180916 0.115422 0.008733749 0.1806409 0.114022 0.009275317 0.180845 0.1148509 0.008880794 0.181218 0.113699 0.009275317 0.181079 0.113763 0.009275317 0.181017 0.113791 0.009275317 0.180824 0.113899 0.009275317 0.1812379 0.1140969 0.009061753 0.180994 0.114231 0.009061753 0.181014 0.114695 0.008880794 0.1811349 0.11513 0.008733749 0.181255 0.115244 0.008686244 0.181017 0.115269 0.008733749 0.181171 0.115383 0.00868076 0.18101 0.115661 0.00868076 0.181496 0.113993 0.009061753 0.181417 0.1149 0.008733749 0.1812019 0.11456 0.008880794 0.181269 0.115007 0.008733749 0.181531 0.115327 0.008621811 0.181518 0.115342 0.008623957 0.181764 0.113921 0.009061753 0.181427 0.113625 0.009275317 0.1814039 0.114448 0.008880794 0.181556 0.115364 0.008613824 0.181755 0.115186 0.008621811 0.181577 0.114812 0.008733749 0.181619 0.114362 0.008880794 0.18204 0.113882 0.009061753 0.182299 0.113504 0.009275317 0.182318 0.113876 0.009061753 0.181842 0.114302 0.008880794 0.181746 0.114744 0.008733749 0.181771 0.115488 0.008572161 0.181921 0.115574 0.008545756 0.181935 0.115567 0.008545756 0.182011 0.115537 0.008545756 0.182005 0.115102 0.008621811 0.181877 0.115137 0.008621811 0.181923 0.114697 0.008733749 0.182071 0.11427 0.008880794 0.1823019 0.114265 0.008880794 0.182594 0.1139039 0.009061753 0.182654 0.1135399 0.009275317 0.182519 0.113519 0.009275317 0.182969 0.113609 0.009275317 0.182103 0.114671 0.008733749 0.182137 0.115084 0.008621811 0.18209 0.115516 0.008545756 0.183127 0.114059 0.009061753 0.182757 0.114339 0.008880794 0.182532 0.114288 0.008880794 0.182286 0.1146669 0.008733749 0.182269 0.115081 0.008621811 0.183366 0.113759 0.009275317 0.182467 0.114686 0.008733749 0.182419 0.1151 0.008623957 0.183182 0.11452 0.008880794 0.183376 0.114183 0.009061753 0.1829749 0.114417 0.008880794 0.182645 0.114726 0.008733749 0.184077 0.114249 0.009275317 0.1836079 0.114336 0.009061753 0.1843799 0.114593 0.009275317 0.1842949 0.114487 0.009275317 0.18409 0.11426 0.009275317 0.18382 0.114517 0.009061753 0.183551 0.1147969 0.008880794 0.183375 0.114647 0.008880794 0.184171 0.114947 0.009061753 0.184009 0.114721 0.009061753 0.183133 0.114969 0.008733749 0.184611 0.11497 0.009275317 0.184503 0.114777 0.009275317 0.183842 0.115154 0.008880794 0.1837069 0.114967 0.008880794 0.183395 0.115222 0.008733749 0.1831589 0.115207 0.008686244 0.183272 0.115087 0.008733749 0.183019 0.115123 0.00868076 0.18298 0.1148689 0.008733749 0.182741 0.114963 0.00868076 0.182817 0.114787 0.008733749 0.1825979 0.114884 0.008686244 0.1847029 0.115171 0.009275317 0.184305 0.11519 0.009061753 0.183502 0.11537 0.008733749 0.183075 0.115483 0.008621811 0.1830599 0.11547 0.008623957 0.1848739 0.11581 0.009275317 0.184777 0.115379 0.009275317 0.184409 0.1154479 0.009061753 0.183954 0.115357 0.008880794 0.183152 0.115591 0.008621811 0.1830379 0.115508 0.008613824 0.183216 0.115707 0.008621811 0.1835899 0.115529 0.008733749 0.18404 0.115571 0.008880794 0.18452 0.115992 0.009061753 0.184481 0.115717 0.009061753 0.184895 0.11603 0.009275317 0.1848959 0.116285 0.009275317 0.184526 0.11627 0.009061753 0.1841 0.115794 0.008880794 0.183705 0.115875 0.008733749 0.183658 0.115699 0.008733749 0.183266 0.11583 0.008621811 0.182835 0.1158879 0.008545756 0.182914 0.115723 0.008572161 0.182828 0.115873 0.008545756 0.182865 0.115963 0.008545756 0.1833 0.115958 0.008621811 0.183731 0.116056 0.008733749 0.1841329 0.116023 0.008880794 0.184863 0.1166059 0.009275317 0.184498 0.116547 0.009061753 0.184137 0.116254 0.008880794 0.183735 0.1162379 0.008733749 0.183318 0.116089 0.008621811 0.184114 0.116484 0.008880794 0.1833209 0.116221 0.008621811 0.1828989 0.116139 0.008545756 0.184219 0.117329 0.009061753 0.184343 0.11708 0.009061753 0.183986 0.116927 0.008880794 0.184063 0.11671 0.008880794 0.183676 0.116598 0.008733749 0.1837159 0.11642 0.008733749 0.1835409 0.11651 0.008687853 0.184289 0.117877 0.009275317 0.1840659 0.117561 0.009061753 0.183886 0.117772 0.009061753 0.183755 0.117327 0.008880794 0.183534 0.116933 0.008733749 0.1838819 0.117134 0.008880794 0.183615 0.11677 0.008733749 0.183681 0.117961 0.009061753 0.183605 0.117503 0.008880794 0.183315 0.117224 0.008733749 0.1834329 0.117085 0.008733749 0.183371 0.118592 0.009275317 0.183212 0.1182579 0.009061753 0.183625 0.118456 0.009275317 0.183248 0.117795 0.008880794 0.183456 0.118123 0.009061753 0.183435 0.11766 0.008880794 0.1831949 0.117111 0.008686244 0.183279 0.116971 0.00868076 0.183362 0.116834 0.008675336 0.183439 0.116693 0.00868076 0.183519 0.116551 0.008686244 0.183071 0.118712 0.009275317 0.183033 0.117454 0.008733749 0.182919 0.117027 0.008621811 0.182932 0.117013 0.008623957 0.182592 0.118826 0.009275317 0.182685 0.1184329 0.009061753 0.18276 0.118796 0.009275317 0.18281 0.118787 0.009275317 0.182831 0.1179929 0.008880794 0.182873 0.117542 0.008733749 0.183045 0.117906 0.008880794 0.182811 0.117105 0.008621811 0.182894 0.116991 0.008613824 0.182852 0.116967 0.008602738 0.182372 0.118848 0.009275317 0.18241 0.118472 0.009061753 0.18244 0.118841 0.009275317 0.182151 0.118851 0.009275317 0.182132 0.118478 0.009061753 0.182379 0.118085 0.008880794 0.182608 0.118052 0.008880794 0.182527 0.117658 0.008733749 0.182703 0.117611 0.008733749 0.182695 0.117168 0.008621811 0.182514 0.116787 0.008545756 0.1826789 0.116866 0.008572161 0.182529 0.11678 0.008545756 0.182439 0.116818 0.008545756 0.182572 0.117218 0.008621811 0.182346 0.117683 0.008733749 0.182148 0.11809 0.008880794 0.181497 0.118751 0.009275317 0.181712 0.118802 0.009275317 0.181856 0.11845 0.009061753 0.182444 0.117252 0.008621811 0.181322 0.118296 0.009061753 0.181287 0.118682 0.009275317 0.181692 0.118016 0.008880794 0.181584 0.118389 0.009061753 0.181918 0.118066 0.008880794 0.182164 0.117687 0.008733749 0.181982 0.117669 0.008733749 0.182263 0.116851 0.008545756 0.1808879 0.118493 0.009275317 0.181475 0.117938 0.008880794 0.181804 0.117629 0.008733749 0.182168 0.115535 0.01024997 0.182336 0.115633 0.01024997 0.182558 0.114861 0.008687853 0.182641 0.115808 0.01024997 0.1828089 0.115905 0.01024997 0.182547 0.115719 0.01018857 0.1828809 0.115041 0.008675336 0.182447 0.115663 0.01019227 0.19049 -0.100575 0.01889997 0.19037 -0.1003659 0.01889997 0.190226 -0.09966236 0.01889997 0.190236 -0.09990358 0.01889997 0.190284 -0.10014 0.01889997 0.190563 -0.09877407 0.01889997 0.190643 -0.100762 0.01889997 0.190824 -0.100922 0.01889997 0.19308 -0.1003659 0.01889997 0.192959 -0.100575 0.01889997 0.193166 -0.10014 0.01889997 0.1932139 -0.09990358 0.01889997 0.193224 -0.09966236 0.01889997 0.193195 -0.09942269 0.01889997 0.193127 -0.09919089 0.01889997 0.193024 -0.09897279 0.01889997 0.190322 -0.09919089 0.01889997 0.192887 -0.09877407 0.01889997 0.190255 -0.09942269 0.01889997 0.1927199 -0.09859997 0.01889997 0.1925269 -0.09845495 0.01889997 0.192313 -0.09834277 0.01889997 0.1910279 -0.101051 0.01889997 0.19125 -0.101146 0.01889997 0.191484 -0.101203 0.01889997 0.191725 -0.101223 0.01889997 0.1919659 -0.101203 0.01889997 0.192084 -0.0982663 0.01889997 0.191846 -0.09822756 0.01889997 0.190426 -0.09897279 0.01889997 0.191604 -0.09822756 0.01889997 0.1922 -0.101146 0.01889997 0.192422 -0.101051 0.01889997 0.192807 -0.100762 0.01889997 0.1926259 -0.100922 0.01889997 0.191366 -0.0982663 0.01889997 0.191137 -0.09834277 0.01889997 0.190923 -0.09845495 0.01889997 0.19073 -0.09859997 0.01889997 0.191197 -0.0998972 0.01024997 0.191188 -0.09986668 0.01024997 0.191084 -0.0999366 0.008545756 0.1911799 -0.09983569 0.01024997 0.191997 -0.100307 0.01024997 0.192094 -0.100139 0.01024997 0.192671 -0.100696 0.008687853 0.192174 -0.100057 0.01019227 0.19227 -0.09983426 0.01024997 0.192367 -0.09966605 0.01024997 0.193041 -0.100055 0.008687853 0.192233 -0.09995889 0.01018857 0.192695 -0.100656 0.008686244 0.1893 -0.0983228 0.01089996 0.189193 -0.09852778 0.009503483 0.189103 -0.09874099 0.01089996 0.188977 -0.099186 0.01089996 0.188977 -0.099186 0.009503483 0.188926 -0.09964555 0.01089996 0.188951 -0.100107 0.01089996 0.188993 -0.100335 0.009503483 0.1890529 -0.1005589 0.01089996 0.189131 -0.100776 0.009503483 0.189227 -0.100987 0.01089996 0.189469 -0.101381 0.01089996 0.189772 -0.10173 0.009503483 0.189772 -0.10173 0.01089996 0.189945 -0.101884 0.009503483 0.190129 -0.102024 0.01089996 0.19053 -0.102255 0.01089996 0.190743 -0.102345 0.009503483 0.190963 -0.102417 0.01089996 0.191417 -0.102506 0.01089996 0.191417 -0.102506 0.009503483 0.191648 -0.102522 0.009503483 0.191879 -0.102519 0.01089996 0.192109 -0.102496 0.009503483 0.192337 -0.102455 0.01089996 0.192779 -0.102317 0.009503483 0.192779 -0.102317 0.01089996 0.193191 -0.102108 0.01089996 0.193191 -0.102108 0.009503483 0.1935639 -0.1018339 0.009503483 0.1935639 -0.1018339 0.01089996 0.193886 -0.101503 0.009503483 0.193886 -0.101503 0.01089996 0.19415 -0.101123 0.01089996 0.1940259 -0.101318 0.009503483 0.19415 -0.101123 0.009503483 0.194257 -0.100918 0.009503483 0.194347 -0.100705 0.01089996 0.194419 -0.100485 0.009503483 0.194473 -0.10026 0.009503483 0.194473 -0.10026 0.01089996 0.194508 -0.100031 0.009503483 0.194524 -0.09979987 0.009503483 0.194524 -0.09979987 0.01089996 0.194498 -0.09933817 0.01089996 0.194498 -0.09933817 0.009503483 0.1944569 -0.09911048 0.009503483 0.194397 -0.0988869 0.01089996 0.194397 -0.0988869 0.009503483 0.194319 -0.09866911 0.009503483 0.194223 -0.09845846 0.01089996 0.194223 -0.09845846 0.009503483 0.193981 -0.09806448 0.01089996 0.19411 -0.09825646 0.009503483 0.193981 -0.09806448 0.009503483 0.193677 -0.09771579 0.01089996 0.193505 -0.09756135 0.009503483 0.19332 -0.09742176 0.01089996 0.19332 -0.09742176 0.009503483 0.19292 -0.09719055 0.01089996 0.192487 -0.09702837 0.01089996 0.1922619 -0.09697467 0.009503483 0.1920329 -0.0969398 0.01089996 0.1920329 -0.0969398 0.009503483 0.1915709 -0.09692698 0.01089996 0.191802 -0.09692376 0.009503483 0.1915709 -0.09692698 0.009503483 0.1911129 -0.09699046 0.01089996 0.190671 -0.09712857 0.01089996 0.190889 -0.09705036 0.009503483 0.190461 -0.09722435 0.009503483 0.190259 -0.09733736 0.009503483 0.1900669 -0.09746658 0.009503483 0.190259 -0.09733736 0.01089996 0.189886 -0.0976113 0.01089996 0.189886 -0.0976113 0.009503483 0.189564 -0.0979427 0.009503483 0.189564 -0.0979427 0.01089996 0.189151 -0.09899497 0.009275317 0.189087 -0.09897679 0.009335577 0.189034 -0.0991972 0.009335577 0.1891 -0.09920996 0.009275317 0.189067 -0.09942847 0.009275317 0.188984 -0.09964716 0.009335577 0.189055 -0.09987008 0.009275317 0.189009 -0.100099 0.009335577 0.189061 -0.09993779 0.009275317 0.189108 -0.100541 0.009335577 0.18931 -0.100868 0.009275317 0.189446 -0.101123 0.009275317 0.189389 -0.101158 0.009335577 0.189516 -0.101346 0.009335577 0.1897079 -0.101479 0.009275317 0.190163 -0.101976 0.009335577 0.190025 -0.101787 0.009275317 0.190354 -0.102097 0.009335577 0.190555 -0.1022019 0.009335577 0.190677 -0.102181 0.009275317 0.190764 -0.10229 0.009335577 0.1912119 -0.102348 0.009275317 0.191199 -0.1024129 0.009335577 0.191431 -0.102381 0.009275317 0.1914229 -0.102448 0.009335577 0.191617 -0.102394 0.009275317 0.191651 -0.102396 0.009275317 0.191872 -0.102393 0.009275317 0.1918759 -0.10246 0.009335577 0.19194 -0.102387 0.009275317 0.19226 -0.102342 0.009275317 0.19231 -0.102332 0.009275317 0.192757 -0.102263 0.009335577 0.192871 -0.102137 0.009275317 0.192963 -0.102169 0.009335577 0.192932 -0.102109 0.009275317 0.193125 -0.102001 0.009275317 0.193161 -0.102058 0.009335577 0.193415 -0.101793 0.009275317 0.193481 -0.10174 0.009275317 0.193789 -0.101423 0.009275317 0.194041 -0.10106 0.009275317 0.194099 -0.101093 0.009335577 0.194144 -0.100864 0.009275317 0.19423 -0.100661 0.009275317 0.194292 -0.100684 0.009335577 0.194293 -0.100467 0.009275317 0.194416 -0.100248 0.009335577 0.19435 -0.100235 0.009275317 0.1943629 -0.100151 0.009275317 0.19445 -0.100024 0.009335577 0.194383 -0.100017 0.009275317 0.194396 -0.09983038 0.009275317 0.194398 -0.09979647 0.009275317 0.194389 -0.09950768 0.009275317 0.194374 -0.09935539 0.009275317 0.194335 -0.0991379 0.009275317 0.1944 -0.09912317 0.009335577 0.194277 -0.09892439 0.009275317 0.194341 -0.09890437 0.009335577 0.194203 -0.09871625 0.009275317 0.194171 -0.09848487 0.009335577 0.194139 -0.09857708 0.009275317 0.194111 -0.09851515 0.009275317 0.194003 -0.09832215 0.009275317 0.19406 -0.0982871 0.009335577 0.193984 -0.09829396 0.009275317 0.193934 -0.09809917 0.009335577 0.19388 -0.09813886 0.009275317 0.193795 -0.09803265 0.009275317 0.193742 -0.09796625 0.009275317 0.193792 -0.09792226 0.009335577 0.19359 -0.09780579 0.009275317 0.193637 -0.09775769 0.009335577 0.193287 -0.09746986 0.009335577 0.1933299 -0.09758645 0.009275317 0.193096 -0.09734857 0.009335577 0.193062 -0.09740656 0.009275317 0.1928949 -0.09724348 0.009335577 0.192866 -0.0973041 0.009275317 0.192663 -0.09721809 0.009275317 0.192453 -0.09714925 0.009275317 0.192238 -0.09709787 0.009275317 0.192154 -0.09708505 0.009275317 0.191832 -0.09705168 0.009275317 0.192026 -0.09699785 0.009335577 0.191574 -0.09698545 0.009335577 0.19151 -0.09705895 0.009275317 0.191348 -0.09700727 0.009335577 0.19119 -0.09710395 0.009275317 0.191125 -0.09704756 0.009335577 0.190907 -0.09710627 0.009335577 0.190927 -0.09717029 0.009275317 0.190879 -0.09718745 0.009275317 0.1907179 -0.09724485 0.009275317 0.190517 -0.09733647 0.009275317 0.190289 -0.09738719 0.009335577 0.189924 -0.09765535 0.009335577 0.189968 -0.09770596 0.009275317 0.18976 -0.0978111 0.009335577 0.189808 -0.09785789 0.009275317 0.189797 -0.09787058 0.009275317 0.189472 -0.09816056 0.009335577 0.189589 -0.09811747 0.009275317 0.189409 -0.09838557 0.009275317 0.189306 -0.09858137 0.009275317 0.189157 -0.09876149 0.009335577 0.18922 -0.09878498 0.009275317 0.189436 -0.09813588 0.009414553 0.189351 -0.09835195 0.009335577 0.1892459 -0.09855276 0.009335577 0.189206 -0.09853416 0.009414553 0.189117 -0.09874618 0.009414553 0.188992 -0.09918886 0.009414553 0.189 -0.0994212 0.009335577 0.188988 -0.09987378 0.009335577 0.188966 -0.100105 0.009414553 0.18905 -0.100322 0.009335577 0.189185 -0.100754 0.009335577 0.189067 -0.100554 0.009414553 0.189279 -0.100961 0.009335577 0.18924 -0.10098 0.009414553 0.189352 -0.101181 0.009414553 0.189658 -0.101523 0.009335577 0.189813 -0.101688 0.009335577 0.1899819 -0.101839 0.009335577 0.190979 -0.102361 0.009335577 0.191419 -0.102491 0.009414553 0.191649 -0.102463 0.009335577 0.191648 -0.102507 0.009414553 0.191878 -0.102503 0.009414553 0.192101 -0.102438 0.009335577 0.192107 -0.102481 0.009414553 0.1923339 -0.1024399 0.009414553 0.192324 -0.102398 0.009335577 0.192556 -0.102381 0.009414553 0.192543 -0.102339 0.009335577 0.192773 -0.102303 0.009414553 0.192982 -0.102208 0.009414553 0.193348 -0.101932 0.009335577 0.193525 -0.10179 0.009335577 0.19369 -0.101634 0.009335577 0.193841 -0.101466 0.009335577 0.193875 -0.101493 0.009414553 0.193978 -0.101285 0.009335577 0.1940129 -0.10131 0.009414553 0.194137 -0.101115 0.009414553 0.194204 -0.100893 0.009335577 0.1943629 -0.100469 0.009335577 0.194333 -0.100699 0.009414553 0.194465 -0.09979826 0.009335577 0.194462 -0.0995717 0.009335577 0.19444 -0.09934616 0.009335577 0.194483 -0.0993402 0.009414553 0.194442 -0.0991137 0.009414553 0.194305 -0.09867477 0.009414553 0.194265 -0.0986911 0.009335577 0.194097 -0.09826439 0.009414553 0.193969 -0.09807336 0.009414553 0.1936669 -0.09772658 0.009414553 0.193468 -0.09760659 0.009335577 0.193495 -0.09757298 0.009414553 0.193117 -0.0973109 0.009414553 0.1929129 -0.0972042 0.009414553 0.192686 -0.09715527 0.009335577 0.192701 -0.09711456 0.009414553 0.192471 -0.0970847 0.009335577 0.192259 -0.09698945 0.009414553 0.19225 -0.09703207 0.009335577 0.1917999 -0.0969823 0.009335577 0.1915709 -0.096942 0.009414553 0.190894 -0.09706479 0.009414553 0.190693 -0.09718281 0.009335577 0.190487 -0.09727668 0.009335577 0.190101 -0.09751379 0.009335577 0.1900759 -0.09747868 0.009414553 0.189609 -0.0979799 0.009335577 0.189424 -0.0981273 0.009503483 0.1893 -0.0983228 0.009503483 0.1893129 -0.09833025 0.009414553 0.189103 -0.09874099 0.009503483 0.189045 -0.09896498 0.009414553 0.189031 -0.09896087 0.009503483 0.188957 -0.09941637 0.009414553 0.188942 -0.0994147 0.009503483 0.188941 -0.09964597 0.009414553 0.188926 -0.09964555 0.009503483 0.188944 -0.09987616 0.009414553 0.188929 -0.09987699 0.009503483 0.188951 -0.100107 0.009503483 0.189007 -0.100332 0.009414553 0.1890529 -0.1005589 0.009503483 0.189145 -0.100771 0.009414553 0.189227 -0.100987 0.009503483 0.1893399 -0.101189 0.009503483 0.189481 -0.101372 0.009414553 0.189469 -0.101381 0.009503483 0.189625 -0.101552 0.009414553 0.189613 -0.101562 0.009503483 0.189783 -0.101719 0.009414553 0.189954 -0.101873 0.009414553 0.190138 -0.102011 0.009414553 0.190129 -0.102024 0.009503483 0.1903319 -0.102135 0.009414553 0.190325 -0.1021479 0.009503483 0.19053 -0.102255 0.009503483 0.190536 -0.102241 0.009414553 0.190748 -0.102331 0.009414553 0.190967 -0.102403 0.009414553 0.191191 -0.102456 0.009414553 0.190963 -0.102417 0.009503483 0.191188 -0.102471 0.009503483 0.191879 -0.102519 0.009503483 0.192337 -0.102455 0.009503483 0.192561 -0.1023949 0.009503483 0.192989 -0.102221 0.009503483 0.193183 -0.102095 0.009414553 0.193374 -0.101967 0.009414553 0.193383 -0.101979 0.009503483 0.193554 -0.101823 0.009414553 0.1937209 -0.101665 0.009414553 0.193732 -0.101675 0.009503483 0.194243 -0.100911 0.009414553 0.194347 -0.100705 0.009503483 0.194405 -0.100481 0.009414553 0.194458 -0.100257 0.009414553 0.1944929 -0.100029 0.009414553 0.194509 -0.09979945 0.009414553 0.194521 -0.09956848 0.009503483 0.194506 -0.09956926 0.009414553 0.194383 -0.09889137 0.009414553 0.1942099 -0.09846526 0.009414553 0.193825 -0.09789365 0.009414553 0.193836 -0.09788388 0.009503483 0.193677 -0.09771579 0.009503483 0.193312 -0.0974341 0.009414553 0.193125 -0.0972979 0.009503483 0.19292 -0.09719055 0.009503483 0.192483 -0.09704285 0.009414553 0.192707 -0.09710049 0.009503483 0.192487 -0.09702837 0.009503483 0.192031 -0.0969547 0.009414553 0.191802 -0.0969389 0.009414553 0.1913419 -0.09696418 0.009414553 0.19134 -0.09694927 0.009503483 0.1911129 -0.09699046 0.009503483 0.191116 -0.09700518 0.009414553 0.190677 -0.09714245 0.009414553 0.190671 -0.09712857 0.009503483 0.190467 -0.09723788 0.009414553 0.190266 -0.09735018 0.009414553 0.189896 -0.09762257 0.009414553 0.189718 -0.09777027 0.009503483 0.189729 -0.09778076 0.009414553 0.189575 -0.0979523 0.009414553 0.19332 -0.09806209 0.009061753 0.193671 -0.09849208 0.009061753 0.19426 -0.09887635 0.009275317 0.194298 -0.10045 0.009275317 0.194183 -0.1007699 0.009275317 0.193719 -0.100874 0.009061753 0.1939229 -0.101247 0.009275317 0.193861 -0.101328 0.009275317 0.192731 -0.102201 0.009275317 0.190981 -0.102291 0.009275317 0.190388 -0.102039 0.009275317 0.190574 -0.101717 0.009061753 0.189873 -0.101651 0.009275317 0.18919 -0.100569 0.009275317 0.189054 -0.09961509 0.009275317 0.189157 -0.09897887 0.009275317 0.189267 -0.09867537 0.009275317 0.189731 -0.09857136 0.009061753 0.1902959 -0.09746336 0.009275317 0.192772 -0.0972644 0.009275317 0.192876 -0.09772861 0.009061753 0.192802 -0.09991729 0.008623957 0.191919 -0.0986458 0.008623957 0.191901 -0.09863978 0.008621811 0.190648 -0.09952819 0.008623957 0.1915299 -0.1008 0.008623957 0.191549 -0.1008059 0.008621811 0.1909109 -0.100392 0.008613824 0.190889 -0.10043 0.008623957 0.1908749 -0.100417 0.008621811 0.190935 -0.10035 0.008602738 0.191036 -0.100176 0.008572161 0.191115 -0.100012 0.008545756 0.190734 -0.100193 0.008621811 0.1911219 -0.100027 0.008545756 0.1902329 -0.09948039 0.008733749 0.191056 -0.09890925 0.008613824 0.190769 -0.09855228 0.008733749 0.191031 -0.0988729 0.008621811 0.191097 -0.09893316 0.008602738 0.191435 -0.0991128 0.008545756 0.191874 -0.09872519 0.008602738 0.192058 -0.09840637 0.008687853 0.192538 -0.0990538 0.008613824 0.19256 -0.09901577 0.008623957 0.1928949 -0.0987671 0.008733749 0.192514 -0.09909516 0.008602738 0.192575 -0.09902888 0.008621811 0.192652 -0.09913641 0.008621811 0.192414 -0.09926897 0.008572161 0.192365 -0.099509 0.008545756 0.192335 -0.0994333 0.008545756 0.192722 -0.09987139 0.008602738 0.192394 -0.100536 0.008613824 0.1923519 -0.100512 0.008602738 0.1924189 -0.100573 0.008621811 0.192179 -0.100412 0.008572161 0.192014 -0.100333 0.008545756 0.1920289 -0.100326 0.008545756 0.192627 -0.09760439 0.009061753 0.192682 -0.09806525 0.008880794 0.192469 -0.09715455 0.009275317 0.19248 -0.09841406 0.008733749 0.192366 -0.09751105 0.009061753 0.192475 -0.09796196 0.008880794 0.192019 -0.09706455 0.009275317 0.192094 -0.09744995 0.009061753 0.192257 -0.09788435 0.008880794 0.191358 -0.09707367 0.009275317 0.19154 -0.0974276 0.009061753 0.191578 -0.09705239 0.009275317 0.191799 -0.09704935 0.009275317 0.191802 -0.09781038 0.008880794 0.1918179 -0.097422 0.009061753 0.191967 -0.09823119 0.008733749 0.192032 -0.09783369 0.008880794 0.192145 -0.09827131 0.008733749 0.192098 -0.09842896 0.008686244 0.192241 -0.09850817 0.00868076 0.192317 -0.09833258 0.008733749 0.192381 -0.09858596 0.008675336 0.192633 -0.09851467 0.008733749 0.192519 -0.09866857 0.00868076 0.192659 -0.09875249 0.008686244 0.192698 -0.0987764 0.008687853 0.191786 -0.09821289 0.008733749 0.1915709 -0.09781509 0.008880794 0.191264 -0.0974667 0.009061753 0.1911399 -0.09711307 0.009275317 0.191603 -0.09821659 0.008733749 0.191898 -0.09868377 0.008613824 0.191769 -0.09862649 0.008621811 0.1917729 -0.098899 0.008572161 0.1914229 -0.09824216 0.008733749 0.1913419 -0.09784758 0.008880794 0.190996 -0.09753859 0.009061753 0.190324 -0.09744435 0.009275317 0.1905789 -0.09730827 0.009275317 0.190494 -0.09777659 0.009061753 0.190738 -0.09764248 0.009061753 0.190904 -0.09799367 0.008880794 0.191119 -0.09790736 0.008880794 0.191505 -0.09864777 0.008621811 0.191637 -0.09862917 0.008621811 0.191671 -0.0990498 0.008545756 0.191687 -0.09904867 0.008545756 0.191377 -0.0986821 0.008621811 0.191246 -0.09828937 0.008733749 0.190702 -0.09810519 0.008880794 0.1902689 -0.09793907 0.009061753 0.190035 -0.09765279 0.009275317 0.190141 -0.09756779 0.009275317 0.190514 -0.09824019 0.008880794 0.1910769 -0.09835755 0.008733749 0.191511 -0.09908229 0.008545756 0.19159 -0.09906119 0.008545756 0.18966 -0.09802258 0.009275317 0.189884 -0.09833949 0.009061753 0.190064 -0.09812766 0.009061753 0.190345 -0.09839695 0.008880794 0.190917 -0.09844559 0.008733749 0.191138 -0.09879547 0.008621811 0.191255 -0.09873145 0.008621811 0.191421 -0.0991199 0.008545756 0.189527 -0.09819889 0.009275317 0.190635 -0.09867596 0.008733749 0.189607 -0.0988202 0.009061753 0.190195 -0.09857296 0.008880794 0.190517 -0.09881496 0.008733749 0.189513 -0.09908211 0.009061753 0.1899639 -0.09897255 0.008880794 0.1900669 -0.09876579 0.008880794 0.189087 -0.09929406 0.009275317 0.190416 -0.09896719 0.008733749 0.1894519 -0.09935337 0.009061753 0.189424 -0.09962999 0.009061753 0.189887 -0.09919029 0.008880794 0.189836 -0.09941565 0.008880794 0.190273 -0.09930241 0.008733749 0.189051 -0.09964907 0.009275317 0.189813 -0.09964567 0.008880794 0.1904309 -0.09934926 0.008686244 0.190335 -0.09913051 0.008733749 0.19051 -0.09920668 0.00868076 0.1905879 -0.09906649 0.008675336 0.190671 -0.09892886 0.00868076 0.190755 -0.09878909 0.008686244 0.190409 -0.09938997 0.008687853 0.189817 -0.09987676 0.008880794 0.1894299 -0.09990799 0.009061753 0.189076 -0.10009 0.009275317 0.189172 -0.100521 0.009275317 0.189469 -0.100183 0.009061753 0.189115 -0.100308 0.009275317 0.189106 -0.100257 0.009275317 0.190215 -0.09966188 0.008733749 0.190629 -0.09967857 0.008621811 0.190686 -0.09955006 0.008613824 0.1906419 -0.09954679 0.008621811 0.1907269 -0.09957408 0.008602738 0.190901 -0.0996744 0.008572161 0.190219 -0.09984439 0.008733749 0.18985 -0.100106 0.008880794 0.190244 -0.1000249 0.008733749 0.189541 -0.100452 0.009061753 0.189247 -0.100729 0.009275317 0.189339 -0.10093 0.009275317 0.189465 -0.101151 0.009275317 0.189779 -0.100953 0.009061753 0.1896449 -0.10071 0.009061753 0.189909 -0.100329 0.008880794 0.190631 -0.09981095 0.008621811 0.191052 -0.0997771 0.008545756 0.191051 -0.09976077 0.008545756 0.191063 -0.0998578 0.008545756 0.191074 -0.0998972 0.008545756 0.19065 -0.0999422 0.008621811 0.190292 -0.100201 0.008733749 0.19036 -0.100371 0.008733749 0.189996 -0.100543 0.008880794 0.18986 -0.10164 0.009275317 0.189941 -0.101179 0.009061753 0.189655 -0.101413 0.009275317 0.18957 -0.101307 0.009275317 0.1901299 -0.101383 0.009061753 0.190107 -0.100746 0.008880794 0.190684 -0.1000699 0.008621811 0.19012 -0.101859 0.009275317 0.190399 -0.101103 0.008880794 0.1902419 -0.100933 0.008880794 0.190448 -0.10053 0.008733749 0.190798 -0.100309 0.008621811 0.190201 -0.101921 0.009275317 0.190342 -0.101564 0.009061753 0.190678 -0.100813 0.008733749 0.190751 -0.100669 0.008687853 0.190554 -0.100678 0.008733749 0.190584 -0.102141 0.009275317 0.190575 -0.101253 0.008880794 0.190787 -0.102227 0.009275317 0.191084 -0.101934 0.009061753 0.190822 -0.101841 0.009061753 0.190768 -0.10138 0.008880794 0.191296 -0.10236 0.009275317 0.190997 -0.102296 0.009275317 0.190975 -0.101483 0.008880794 0.191356 -0.101996 0.009061753 0.191304 -0.1011739 0.008733749 0.191192 -0.101561 0.008880794 0.191632 -0.102024 0.009061753 0.1914179 -0.101612 0.008880794 0.191648 -0.101635 0.008880794 0.1913509 -0.101016 0.008686244 0.191209 -0.100937 0.00868076 0.191133 -0.101113 0.008733749 0.190969 -0.101031 0.008733749 0.191069 -0.100859 0.008675336 0.1908169 -0.100931 0.008733749 0.190931 -0.100777 0.00868076 0.190791 -0.100693 0.008686244 0.191392 -0.101039 0.008687853 0.191482 -0.101214 0.008733749 0.191879 -0.10163 0.008880794 0.19191 -0.1020179 0.009061753 0.192185 -0.101979 0.009061753 0.192092 -0.102372 0.009275317 0.192571 -0.102258 0.009275317 0.192523 -0.102275 0.009275317 0.191664 -0.101233 0.008733749 0.191681 -0.100819 0.008621811 0.191552 -0.100762 0.008613824 0.191576 -0.10072 0.008602738 0.191677 -0.100547 0.008572161 0.191846 -0.101229 0.008733749 0.192108 -0.101598 0.008880794 0.192454 -0.101907 0.009061753 0.193154 -0.1019819 0.009275317 0.192956 -0.101669 0.009061753 0.192712 -0.101803 0.009061753 0.192331 -0.101538 0.008880794 0.192027 -0.101203 0.008733749 0.1918129 -0.100816 0.008621811 0.191779 -0.100396 0.008545756 0.191763 -0.100397 0.008545756 0.19186 -0.1003839 0.008545756 0.191944 -0.100798 0.008621811 0.192072 -0.100763 0.008621811 0.192203 -0.1011559 0.008733749 0.1925449 -0.101452 0.008880794 0.192748 -0.1013399 0.008880794 0.193309 -0.101878 0.009275317 0.193653 -0.101575 0.009275317 0.193386 -0.101318 0.009061753 0.193642 -0.101588 0.009275317 0.193181 -0.101506 0.009061753 0.192373 -0.101088 0.008733749 0.1919389 -0.100363 0.008545756 0.193105 -0.101049 0.008880794 0.192681 -0.100893 0.008733749 0.192935 -0.101205 0.008880794 0.192533 -0.101 0.008733749 0.192311 -0.10065 0.008621811 0.1921949 -0.100714 0.008621811 0.193566 -0.101106 0.009061753 0.192815 -0.1007699 0.008733749 0.192432 -0.100558 0.008623957 0.193843 -0.100625 0.009061753 0.193255 -0.100873 0.008880794 0.193382 -0.10068 0.008880794 0.192933 -0.1006309 0.008733749 0.193486 -0.100473 0.008880794 0.1930339 -0.100478 0.008733749 0.193998 -0.100092 0.009061753 0.193937 -0.100363 0.009061753 0.193563 -0.100255 0.008880794 0.193614 -0.10003 0.008880794 0.193176 -0.100143 0.008733749 0.194395 -0.0995754 0.009275317 0.1940259 -0.09981548 0.009061753 0.1931149 -0.100315 0.008733749 0.193019 -0.100096 0.008686244 0.192939 -0.100239 0.00868076 0.192862 -0.100379 0.008675336 0.192779 -0.100517 0.00868076 0.192808 -0.09989875 0.008621811 0.193216 -0.09996515 0.008733749 0.193637 -0.09979981 0.008880794 0.193235 -0.09978359 0.008733749 0.193633 -0.09956878 0.008880794 0.19402 -0.09953749 0.009061753 0.193981 -0.09926217 0.009061753 0.194344 -0.09918808 0.009275317 0.1935999 -0.0993399 0.008880794 0.192821 -0.09976691 0.008621811 0.192764 -0.09989535 0.008613824 0.193231 -0.0996012 0.008733749 0.19354 -0.09911668 0.008880794 0.193909 -0.09899359 0.009061753 0.193805 -0.09873557 0.009061753 0.193454 -0.09890228 0.008880794 0.1932049 -0.09942048 0.008733749 0.192818 -0.09963446 0.008621811 0.192398 -0.09966838 0.008545756 0.192549 -0.09977108 0.008572161 0.192399 -0.09968465 0.008545756 0.1928 -0.09950327 0.008621811 0.192766 -0.0993753 0.008621811 0.193158 -0.09924417 0.008733749 0.193577 -0.09779435 0.009275317 0.193509 -0.09826648 0.009061753 0.193342 -0.09869986 0.008880794 0.192716 -0.0992524 0.008621811 0.19309 -0.09907495 0.008733749 0.192386 -0.09958767 0.008545756 0.1934249 -0.09765827 0.009275317 0.193108 -0.09788185 0.009061753 0.193207 -0.09851229 0.008880794 0.193051 -0.09834247 0.008880794 0.193002 -0.0989151 0.008733749 0.192328 -0.09941869 0.008545756 0.193249 -0.097525 0.009275317 0.192875 -0.09819269 0.008880794 0.192772 -0.09863299 0.008733749 0.19155 -0.09919476 0.01024997 0.191529 -0.09918218 0.009976387 0.191453 -0.09913855 0.01024997 0.191435 -0.0991283 0.008744776 0.190779 -0.09874916 0.008687853 0.191018 -0.09888726 0.008623957 0.191271 -0.09903347 0.008572161 -0.0258404 -0.02077329 0.023 -0.02549999 -0.02074998 0.002999961 -0.0258404 -0.02077329 0.002999961 -0.02649599 -0.02095699 0.002999961 -0.02649599 -0.02095699 0.023 -0.02707767 -0.02131068 0.002999961 -0.02707767 -0.02131068 0.023 -0.02754235 -0.02180826 0.002999961 -0.02754235 -0.02180826 0.023 -0.02785569 -0.02241277 0.023 -0.02785569 -0.02241277 0.002999961 -0.02799415 -0.02307939 0.023 -0.02799415 -0.02307939 0.002999961 -0.02794766 -0.02375859 0.023 -0.02794766 -0.02375859 0.002999961 -0.02771967 -0.02440017 0.002999961 -0.02771967 -0.02440017 0.023 -0.02732706 -0.0249564 0.002999961 -0.02679896 -0.02538597 0.002999961 -0.02732706 -0.0249564 0.023 -0.02679896 -0.02538597 0.023 -0.02617448 -0.02565729 0.002999961 -0.02617448 -0.02565729 0.023 -0.02549999 -0.02574998 0.023 -0.02549999 -0.02574998 0.002999961 -0.02482545 -0.02565729 0.023 -0.02482545 -0.02565729 0.002999961 -0.02420097 -0.02538597 0.002999961 -0.02420097 -0.02538597 0.023 -0.02367287 -0.0249564 0.002999961 -0.02328026 -0.02440017 0.002999961 -0.02367287 -0.0249564 0.023 -0.02328026 -0.02440017 0.023 -0.02305227 -0.02375859 0.002999961 -0.02305227 -0.02375859 0.023 -0.02300578 -0.02307939 0.023 -0.02300578 -0.02307939 0.002999961 -0.0231443 -0.02241277 0.002999961 -0.0231443 -0.02241277 0.023 -0.02345758 -0.02180826 0.023 -0.02345758 -0.02180826 0.002999961 -0.02392226 -0.02131068 0.002999961 -0.024504 -0.02095699 0.002999961 -0.02392226 -0.02131068 0.023 -0.024504 -0.02095699 0.023 -0.02515959 -0.02077329 0.002999961 -0.02515959 -0.02077329 0.023 -0.02549999 -0.02074998 0.023 0.02515959 0.02572667 0.023 0.02549999 0.02574998 0.002999961 0.02515959 0.02572667 0.002999961 0.024504 0.02554297 0.002999961 0.024504 0.02554297 0.023 0.02392226 0.02518928 0.002999961 0.02392226 0.02518928 0.023 0.02345758 0.0246917 0.023 0.02345758 0.0246917 0.002999961 0.0231443 0.02408719 0.002999961 0.0231443 0.02408719 0.023 0.02300578 0.02342057 0.023 0.02300578 0.02342057 0.002999961 0.02305227 0.02274137 0.002999961 0.02328026 0.02209979 0.002999961 0.02305227 0.02274137 0.023 0.02328026 0.02209979 0.023 0.02367287 0.02154356 0.023 0.02367287 0.02154356 0.002999961 0.02420097 0.02111399 0.002999961 0.02420097 0.02111399 0.023 0.02482545 0.02084267 0.023 0.02482545 0.02084267 0.002999961 0.02549999 0.02074998 0.002999961 0.02549999 0.02074998 0.023 0.02617448 0.02084267 0.023 0.02617448 0.02084267 0.002999961 0.02679896 0.02111399 0.002999961 0.02732706 0.02154356 0.002999961 0.02679896 0.02111399 0.023 0.02732706 0.02154356 0.023 0.02771967 0.02209979 0.002999961 0.02771967 0.02209979 0.023 0.02794766 0.02274137 0.023 0.02794766 0.02274137 0.002999961 0.02799415 0.02342057 0.002999961 0.02785569 0.02408719 0.002999961 0.02799415 0.02342057 0.023 0.02785569 0.02408719 0.023 0.02754235 0.0246917 0.002999961 0.02754235 0.0246917 0.023 0.02707767 0.02518928 0.023 0.02707767 0.02518928 0.002999961 0.02649599 0.02554297 0.002999961 0.02649599 0.02554297 0.023 0.0258404 0.02572667 0.002999961 0.0258404 0.02572667 0.023 0.02549999 0.02574998 0.023 0.02515959 -0.02077329 0.023 0.02549999 -0.02074998 0.002999961 0.02549999 -0.02074998 0.023 0.02515959 -0.02077329 0.002999961 0.024504 -0.02095699 0.002999961 0.024504 -0.02095699 0.023 0.02392226 -0.02131068 0.002999961 0.02392226 -0.02131068 0.023 0.02345758 -0.02180826 0.002999961 0.0231443 -0.02241277 0.002999961 0.02345758 -0.02180826 0.023 0.02300578 -0.02307939 0.002999961 0.0231443 -0.02241277 0.023 0.02300578 -0.02307939 0.023 0.02305227 -0.02375859 0.023 0.02305227 -0.02375859 0.002999961 0.02328026 -0.02440017 0.002999961 0.02367287 -0.0249564 0.002999961 0.02328026 -0.02440017 0.023 0.02420097 -0.02538597 0.002999961 0.02367287 -0.0249564 0.023 0.02482545 -0.02565729 0.002999961 0.02420097 -0.02538597 0.023 0.02482545 -0.02565729 0.023 0.02549999 -0.02574998 0.002999961 0.02549999 -0.02574998 0.023 0.02617448 -0.02565729 0.002999961 0.02617448 -0.02565729 0.023 0.02679896 -0.02538597 0.002999961 0.02679896 -0.02538597 0.023 0.02732706 -0.0249564 0.023 0.02732706 -0.0249564 0.002999961 0.02771967 -0.02440017 0.002999961 0.02771967 -0.02440017 0.023 0.02794766 -0.02375859 0.023 0.02794766 -0.02375859 0.002999961 0.02799415 -0.02307939 0.002999961 0.02799415 -0.02307939 0.023 0.02785569 -0.02241277 0.002999961 0.02785569 -0.02241277 0.023 0.02754235 -0.02180826 0.002999961 0.02754235 -0.02180826 0.023 0.02707767 -0.02131068 0.002999961 0.02707767 -0.02131068 0.023 0.02649599 -0.02095699 0.002999961 0.02649599 -0.02095699 0.023 0.0258404 -0.02077329 0.002999961 0.0258404 -0.02077329 0.023 -0.02593386 0.02415096 0.002999961 -0.02549999 0.02224999 0.002999961 -0.02506607 0.02234899 0.002999961 -0.02471816 0.02262645 0.002999961 -0.02328026 0.02209979 0.002999961 -0.02420097 0.02111399 0.002999961 -0.02482545 0.02084267 0.002999961 -0.02471816 0.02387344 0.002999961 -0.02628177 0.02387344 0.002999961 -0.02649599 0.02554297 0.002999961 -0.02549999 0.02074998 0.002999961 -0.02593386 0.02234899 0.002999961 -0.02679896 0.02111399 0.002999961 -0.02549999 0.02424997 0.002999961 -0.02506607 0.02415096 0.002999961 -0.024504 0.02554297 0.002999961 -0.02392226 0.02518928 0.002999961 -0.02647489 0.02302747 0.002999961 -0.02799415 0.02342057 0.002999961 -0.02647489 0.02347248 0.002999961 -0.02785569 0.02408719 0.002999961 -0.02754235 0.0246917 0.002999961 -0.0245251 0.02347248 0.002999961 -0.0245251 0.02302747 0.002999961 -0.02305227 0.02274137 0.002999961 -0.02628177 0.02262645 0.002999961 -0.02794766 0.02274137 0.002999961 -0.02549999 0.02574998 0.023 -0.02549999 0.02574998 0.002999961 -0.0258404 0.02572667 0.002999961 -0.0258404 0.02572667 0.023 -0.02649599 0.02554297 0.023 -0.02707767 0.02518928 0.002999961 -0.02707767 0.02518928 0.023 -0.02754235 0.0246917 0.023 -0.02785569 0.02408719 0.023 -0.02799415 0.02342057 0.023 -0.02794766 0.02274137 0.023 -0.02771967 0.02209979 0.002999961 -0.02771967 0.02209979 0.023 -0.02732706 0.02154356 0.002999961 -0.02732706 0.02154356 0.023 -0.02679896 0.02111399 0.023 -0.02617448 0.02084267 0.002999961 -0.02617448 0.02084267 0.023 -0.02549999 0.02074998 0.023 -0.02482545 0.02084267 0.023 -0.02420097 0.02111399 0.023 -0.02367287 0.02154356 0.023 -0.02367287 0.02154356 0.002999961 -0.02328026 0.02209979 0.023 -0.02300578 0.02342057 0.002999961 -0.02305227 0.02274137 0.023 -0.02300578 0.02342057 0.023 -0.0231443 0.02408719 0.002999961 -0.0231443 0.02408719 0.023 -0.02345758 0.0246917 0.002999961 -0.02345758 0.0246917 0.023 -0.02392226 0.02518928 0.023 -0.024504 0.02554297 0.023 -0.02515959 0.02572667 0.002999961 -0.02515959 0.02572667 0.023 -0.01943778 0.07833486 0.01069998 -0.01923549 0.07834517 0.003699958 -0.01923549 0.07834517 0.01069998 -0.01943778 0.07833486 0.003699958 -0.01983416 0.0782535 0.003699958 -0.01983416 0.0782535 0.01069998 -0.02020609 0.07809388 0.01069998 -0.02053827 0.07786267 0.003699958 -0.02053827 0.07786267 0.01069998 -0.0208171 0.07756936 0.003699958 -0.0208171 0.07756936 0.01069998 -0.02103108 0.07722598 0.01069998 -0.02117168 0.07684648 0.003699958 -0.02117168 0.07684648 0.01069998 -0.0212329 0.07644647 0.003699958 -0.0212329 0.07644647 0.01069998 -0.02121239 0.07604229 0.01069998 -0.02111095 0.07565057 0.01069998 -0.02093279 0.07528728 0.01069998 -0.02093279 0.07528728 0.003699958 -0.02068507 0.07496726 0.003699958 -0.02068507 0.07496726 0.01069998 -0.02037799 0.07470369 0.003699958 -0.02037799 0.07470369 0.01069998 -0.02002418 0.07450729 0.003699958 -0.02002418 0.07450729 0.01069998 -0.01963806 0.07438606 0.003699958 -0.01963806 0.07438606 0.01069998 -0.01923549 0.07434517 0.01069998 -0.01883286 0.07438606 0.01069998 -0.01883286 0.07438606 0.003699958 -0.0184468 0.07450729 0.003699958 -0.0184468 0.07450729 0.01069998 -0.01809298 0.07470369 0.01069998 -0.01778584 0.07496726 0.003699958 -0.01778584 0.07496726 0.01069998 -0.01753818 0.07528728 0.01069998 -0.01735997 0.07565057 0.01069998 -0.01725858 0.07604229 0.003699958 -0.01725858 0.07604229 0.01069998 -0.01723808 0.07644647 0.01069998 -0.01729935 0.07684648 0.01069998 -0.01729935 0.07684648 0.003699958 -0.0174399 0.07722598 0.01069998 -0.017654 0.07756936 0.01069998 -0.01793277 0.07786267 0.003699958 -0.01793277 0.07786267 0.01069998 -0.01826488 0.07809388 0.01069998 -0.01826488 0.07809388 0.003699958 -0.01903319 0.07833486 0.003699958 -0.01863676 0.0782535 0.01069998 -0.01903319 0.07833486 0.01069998 -0.0189538 0.07538568 0.003699958 -0.01923549 0.07534515 0.003699958 -0.01923549 0.07434517 0.003699958 -0.0197761 0.07718646 0.003699958 -0.02020609 0.07809388 0.003699958 -0.01951718 0.07730466 0.003699958 -0.02014505 0.07592976 0.003699958 -0.02111095 0.07565057 0.003699958 -0.02022528 0.07620286 0.003699958 -0.02022528 0.07648748 0.003699958 -0.01951718 0.07538568 0.003699958 -0.0197761 0.07550388 0.003699958 -0.01999127 0.07569026 0.003699958 -0.01832586 0.07676059 0.003699958 -0.01824569 0.07648748 0.003699958 -0.01723808 0.07644647 0.003699958 -0.01824569 0.07620286 0.003699958 -0.01832586 0.07592976 0.003699958 -0.01847976 0.07700008 0.003699958 -0.017654 0.07756936 0.003699958 -0.0174399 0.07722598 0.003699958 -0.01923549 0.07734519 0.003699958 -0.0189538 0.07730466 0.003699958 -0.01863676 0.0782535 0.003699958 -0.01869487 0.07718646 0.003699958 -0.02121239 0.07604229 0.003699958 -0.02014505 0.07676059 0.003699958 -0.01999127 0.07700008 0.003699958 -0.02103108 0.07722598 0.003699958 -0.01735997 0.07565057 0.003699958 -0.01753818 0.07528728 0.003699958 -0.01847976 0.07569026 0.003699958 -0.01869487 0.07550388 0.003699958 -0.01809298 0.07470369 0.003699958 0.01902657 0.07833486 0.01069998 0.01922887 0.07834517 0.01069998 0.01922887 0.07834517 0.003699958 0.01902657 0.07833486 0.003699958 0.0186302 0.0782535 0.003699958 0.0186302 0.0782535 0.01069998 0.01825827 0.07809388 0.01069998 0.01792609 0.07786267 0.01069998 0.01764726 0.07756936 0.003699958 0.01764726 0.07756936 0.01069998 0.01743328 0.07722598 0.003699958 0.01743328 0.07722598 0.01069998 0.01729267 0.07684648 0.01069998 0.01723146 0.07644647 0.01069998 0.01725196 0.07604229 0.01069998 0.01735335 0.07565057 0.01069998 0.01753157 0.07528728 0.01069998 0.01753157 0.07528728 0.003699958 0.01777929 0.07496726 0.003699958 0.01808637 0.07470369 0.003699958 0.01777929 0.07496726 0.01069998 0.01808637 0.07470369 0.01069998 0.01844018 0.07450729 0.01069998 0.0188263 0.07438606 0.003699958 0.0188263 0.07438606 0.01069998 0.01922887 0.07434517 0.01069998 0.0196315 0.07438606 0.01069998 0.02001756 0.07450729 0.01069998 0.02037137 0.07470369 0.01069998 0.02067846 0.07496726 0.01069998 0.02092617 0.07528728 0.01069998 0.02120578 0.07604229 0.003699958 0.02110439 0.07565057 0.01069998 0.02120578 0.07604229 0.01069998 0.02122628 0.07644647 0.01069998 0.02116495 0.07684648 0.01069998 0.02102446 0.07722598 0.003699958 0.02102446 0.07722598 0.01069998 0.02081036 0.07756936 0.003699958 0.02081036 0.07756936 0.01069998 0.02053159 0.07786267 0.01069998 0.02019947 0.07809388 0.01069998 0.02019947 0.07809388 0.003699958 0.0198276 0.0782535 0.01069998 0.01943117 0.07833486 0.003699958 0.01943117 0.07833486 0.01069998 0.01976948 0.07550388 0.003699958 0.02001756 0.07450729 0.003699958 0.0196315 0.07438606 0.003699958 0.01951056 0.07538568 0.003699958 0.01922887 0.07534515 0.003699958 0.01922887 0.07434517 0.003699958 0.01894718 0.07730466 0.003699958 0.01792609 0.07786267 0.003699958 0.01868826 0.07718646 0.003699958 0.01825827 0.07809388 0.003699958 0.01847308 0.07569026 0.003699958 0.01831924 0.07592976 0.003699958 0.01735335 0.07565057 0.003699958 0.01823908 0.07620286 0.003699958 0.01894718 0.07538568 0.003699958 0.01844018 0.07450729 0.003699958 0.01868826 0.07550388 0.003699958 0.02021867 0.07648748 0.003699958 0.02122628 0.07644647 0.003699958 0.02021867 0.07620286 0.003699958 0.0199846 0.07700008 0.003699958 0.0201385 0.07676059 0.003699958 0.02116495 0.07684648 0.003699958 0.01922887 0.07734519 0.003699958 0.01951056 0.07730466 0.003699958 0.01976948 0.07718646 0.003699958 0.0198276 0.0782535 0.003699958 0.02053159 0.07786267 0.003699958 0.01725196 0.07604229 0.003699958 0.01723146 0.07644647 0.003699958 0.01823908 0.07648748 0.003699958 0.01729267 0.07684648 0.003699958 0.01831924 0.07676059 0.003699958 0.01847308 0.07700008 0.003699958 0.02110439 0.07565057 0.003699958 0.0201385 0.07592976 0.003699958 0.0199846 0.07569026 0.003699958 0.02092617 0.07528728 0.003699958 0.02067846 0.07496726 0.003699958 0.02037137 0.07470369 0.003699958 -0.03334176 -0.07050645 0.002268791 -0.0326581 -0.06696987 0.002190828 -0.03366148 -0.07041329 0.002190828 -0.03291136 -0.0668962 0.001973152 -0.03391468 -0.07033956 0.001973152 -0.03404879 -0.07030045 0.001661002 -0.03303259 -0.06686079 0.001319289 -0.03271889 -0.06971496 -0.002437889 -0.03278577 -0.06982719 -0.002449989 -0.03247219 -0.06644356 6.18371e-4 -0.03219085 -0.06895875 -0.001995384 -0.03236097 -0.06636077 0.001961529 -0.0322414 -0.06687206 0.002245604 -0.03213959 -0.06668478 0.002139091 -0.03203177 -0.06648635 0.002026319 -0.03188109 -0.06624805 0.001624763 -0.03213155 -0.06614106 0.001026272 -0.0318259 -0.06621879 0.001110732 -0.03186404 -0.06623899 0.001466035 -0.03256958 -0.06677019 0.002178549 -0.03267097 -0.06636065 0.001781821 -0.03252387 -0.06616669 0.001415193 -0.03219896 -0.06612819 0.001539826 -0.03218537 -0.06640255 5.76967e-4 -0.03304547 -0.06685709 0.001661002 -0.03284376 -0.06672078 0.001966476 -0.03271955 -0.0663836 9.81571e-4 -0.03244966 -0.06619966 9.80327e-4 -0.0330041 -0.06673467 0.001655519 -0.03289085 -0.066486 0.001528203 -0.03297066 -0.06670808 0.001258671 -0.03292566 -0.06665277 0.001158297 -0.03278505 -0.06635528 0.001278042 -0.03271478 -0.06655937 7.33953e-4 -0.02034574 -0.07367968 0.01069998 -0.01985347 -0.07307177 0.01069998 -0.01919746 -0.07264578 0.01069998 -0.01919746 -0.07264578 0.005699992 -0.01844197 -0.07244336 0.01069998 -0.01766085 -0.07248425 0.005699992 -0.01766085 -0.07248425 0.01069998 -0.01693069 -0.07276457 0.01069998 -0.02209579 -0.0767107 0.01069998 -0.02152299 -0.07231718 7.54407e-4 -0.02171009 -0.07219076 7.81957e-4 -0.02227497 -0.07361978 0.002050399 -0.02191126 -0.07208645 7.63908e-4 -0.02266258 -0.0733878 0.002058625 -0.02231025 -0.07197809 6.16046e-4 -0.02232205 -0.07197725 6.09969e-4 -0.02307957 -0.07328945 0.001915454 -0.02268338 -0.07203269 3.44622e-4 -0.02539569 -0.0765264 -0.005745708 -0.02681249 -0.0699805 1.12406e-5 -0.03172737 -0.07519316 -0.005015909 -0.0314483 -0.07551139 -0.005173861 -0.03135305 -0.07575088 -0.005359351 -0.03106075 -0.07574337 -0.005182087 -0.03064376 -0.07584166 -0.005038917 -0.03047907 -0.07672679 -0.00583297 -0.03028237 -0.07578629 -0.004773616 -0.02833586 -0.07012045 0.002050399 -0.0287016 -0.07003885 0.001920223 -0.02199596 -0.07393795 0.001892447 -0.02241408 -0.07332217 0.002268791 -0.02794128 -0.07034015 0.002058625 -0.02764755 -0.07065218 0.001915454 -0.02751475 -0.07099276 0.001650094 -0.02344095 -0.07334488 0.001650094 -0.02367299 -0.07354259 0.001316726 -0.02757006 -0.07129257 0.001316726 -0.02538746 -0.07901066 -0.005173861 -0.02578204 -0.07879096 -0.005182087 -0.02607578 -0.07847899 -0.005038917 -0.02820348 -0.07828277 -0.006076335 -0.02620846 -0.07813841 -0.004773616 -0.02615326 -0.07783859 -0.004440188 -0.03005039 -0.07558858 -0.004440188 -0.03424298 -0.07085216 0.004949986 -0.03073638 -0.07287681 0.004949986 -0.02043026 -0.07882696 0.003018796 -0.0247671 -0.07632321 0.005924999 -0.02829736 -0.07428491 0.006553947 -0.0288763 -0.0739507 0.006289839 -0.0294311 -0.07363039 0.005924999 -0.03073638 -0.07287681 0.01069998 -0.02331948 -0.07715886 0.004282474 -0.02346175 -0.07707679 0.004949986 -0.02346175 -0.07707679 0.01069998 -0.0212385 -0.07262587 5.8694e-4 -0.02800869 -0.0700922 0.002268791 -0.0289039 -0.07038927 0.002268791 -0.02875095 -0.07003796 0.001892447 -0.02971005 -0.0707708 0.002268791 -0.03300839 -0.08381885 1.24825e-4 -0.03180187 -0.08451539 1.24825e-4 -0.02941 -0.07758617 -0.006076335 -0.02692466 -0.07877886 -0.00583297 -0.02366834 -0.07776319 -0.005986452 -0.02258539 -0.07754069 0.002787828 -0.02249735 -0.07748347 0.002596795 -0.02248358 -0.07746869 0.002569258 -0.02239358 -0.07732838 0.002407014 -0.02226996 -0.07692879 0.002269208 -0.02055728 -0.07466471 -0.001066863 -0.02076679 -0.07363426 -1.52939e-4 -0.02226555 -0.07690137 0.002268791 -0.02217209 -0.0760684 0.002268791 -0.02215099 -0.07513499 0.002268791 -0.02202147 -0.07389569 0.001920223 -0.02222377 -0.07424598 0.002268791 -0.02375906 -0.07690507 0.004914522 -0.02512276 -0.0811792 0.007353782 -0.0229516 -0.07737129 0.003553032 -0.02268207 -0.07752686 0.003018796 -0.02590078 -0.07566857 0.006553947 -0.0253219 -0.07600277 0.006289839 -0.02424377 -0.07662528 0.005464494 -0.02975285 -0.076806 0.009062349 -0.02709907 -0.0749768 0.006767451 -0.02649575 -0.07532495 0.006713926 -0.02735626 -0.07818967 0.009062349 -0.02770227 -0.07462847 0.006713926 -0.02995437 -0.07332819 0.005464494 -0.03104215 -0.07642078 0.008701384 -0.0308786 -0.07279455 0.004282474 -0.03229999 -0.07627159 0.00812143 -0.03043907 -0.07304835 0.004914522 -0.02910268 -0.0688216 -1.52939e-4 -0.03009968 -0.06915539 -0.001066863 -0.03050798 -0.07125556 0.002268791 -0.03118258 -0.07175308 0.002268791 -0.03135579 -0.07191258 0.002303242 -0.03156405 -0.07222348 0.002566337 -0.03445565 -0.07670021 0.006439805 -0.03157919 -0.07233536 0.002756416 -0.03153508 -0.07241368 0.002968192 -0.03151607 -0.07242655 0.003018796 -0.03126698 -0.07257038 0.003576874 -0.03148978 -0.07207959 0.002408802 -0.03088128 -0.06970995 -0.002077937 -0.03576129 -0.0780006 0.004375159 -0.03558349 -0.08094376 0.001520216 -0.03096979 -0.07388097 -0.00632143 -0.02564245 -0.07904797 -0.005359351 -0.02497237 -0.07909315 -0.005015909 -0.0225833 -0.07754737 -0.005139946 -0.02168786 -0.07710015 -0.004170835 -0.02064687 -0.07561886 -0.002077937 -0.02500289 -0.08316367 0.005428731 -0.02232116 -0.07714438 0.002307653 -0.03345865 -0.07636636 0.007353782 -0.02637809 -0.0791136 0.008701384 -0.02561998 -0.08012831 0.00812143 -0.02491325 -0.08220946 0.006439805 -0.02477586 -0.08394807 0.004772067 -0.02507317 -0.08440178 0.004143536 -0.02538657 -0.08399039 0.004375159 -0.02997595 -0.0855084 1.86371e-4 -0.0292409 -0.08528059 8.41862e-4 -0.03495156 -0.08198356 8.41862e-4 -0.0353477 -0.082053 5.42217e-4 -0.03407746 -0.08295947 3.68211e-4 -0.03478127 -0.0827341 1.86371e-4 -0.03601735 -0.07155978 0.01069998 -0.02850174 -0.0774064 0.009184837 -0.02910298 -0.08565837 5.42217e-4 -0.02802437 -0.08530795 0.001520216 -0.02825927 -0.08570349 9.86431e-4 -0.02693927 -0.0850923 0.002366781 -0.02604389 -0.08464497 0.003335833 -0.02608019 -0.08521169 0.002745211 -0.03338319 -0.08395707 -2.31592e-4 -0.03052306 -0.0850116 3.68211e-4 -0.03173428 -0.08490908 -2.31592e-4 -0.03085935 -0.08525675 -7.34334e-5 -0.03599959 -0.07889705 0.003335833 -0.03603005 -0.07745045 0.004772067 -0.03523725 -0.07725477 0.005428731 -0.03593927 -0.07989609 0.002366781 -0.03637695 -0.0799089 0.002099931 -0.03580856 -0.0813449 9.86431e-4 -0.0184434 -0.08098471 0.01028966 -0.01968067 -0.0809918 0.01069998 -0.02457326 -0.08407056 0.00472331 -0.02443528 -0.08412027 0.004667997 -0.02433806 -0.08415526 0.004629075 -0.01940929 -0.08109658 0.01069998 -0.02431857 -0.08415919 0.00461924 -0.02409195 -0.08417499 0.004485845 -0.01843857 -0.0809763 0.01069998 -0.02388799 -0.08413225 0.004329562 -0.02399188 -0.08416867 0.004418492 -0.01876628 -0.08108538 0.01069998 -0.01909238 -0.08112728 0.01069998 -0.02379888 -0.08410096 0.004253208 -0.02379268 -0.0840972 0.00424689 -0.01841849 -0.08094155 0.01015084 -0.02375435 -0.0840736 0.00420767 -0.01844185 -0.08098208 0.01066267 -0.01575577 -0.0763297 0.01069998 -0.01617389 -0.07705366 0.0062505 -0.01595544 -0.07667535 0.006026685 -0.01575577 -0.0763297 0.005913555 -0.01547545 -0.07559937 0.01069998 -0.01543456 -0.07481825 0.01069998 -0.01547545 -0.07559937 0.005733489 -0.01558756 -0.0759772 0.005816817 -0.01563698 -0.07406276 0.01069998 -0.01563698 -0.07406276 0.005699992 -0.01606297 -0.07340675 0.01069998 -0.01606297 -0.07340675 0.005699992 -0.01667088 -0.0729146 0.01069998 -0.0154252 -0.07522636 0.005699992 -0.01543456 -0.07481825 0.005699992 -0.01882886 -0.07703799 0.005699992 -0.01985347 -0.07307177 0.005699992 -0.01922887 -0.07554519 0.005699992 -0.02034574 -0.07367968 0.005699992 -0.01962888 -0.07565236 0.005699992 -0.01693069 -0.07276457 0.005699992 -0.01667088 -0.0729146 0.005699992 -0.01853609 -0.07674515 0.005699992 -0.01842886 -0.0763452 0.005699992 -0.01853609 -0.07594519 0.005699992 -0.01844197 -0.07244336 0.005699992 -0.01882886 -0.07565236 0.005699992 -0.01992166 -0.07594519 0.005699992 -0.02209579 -0.0767107 0.005699992 -0.02002888 -0.0763452 0.005699992 -0.02224826 -0.07691138 0.005699992 -0.01992166 -0.07674515 0.005699992 -0.01962888 -0.07703799 0.005699992 -0.01922887 -0.07714515 0.005699992 -0.02241235 -0.07704627 0.00567311 -0.01920646 -0.07901936 0.005635261 -0.02287727 -0.0772072 0.005436599 -0.02264189 -0.07715815 0.005577623 -0.02260047 -0.07713866 0.005595386 -0.02243715 -0.07706207 0.005665421 -0.02345758 -0.07707905 0.004954099 -0.02335649 -0.07712948 0.005051672 -0.01995515 -0.07910126 0.004949986 -0.0197677 -0.07914716 0.005229532 -0.0232166 -0.0771777 0.005176901 -0.0230326 -0.07720148 0.005321919 -0.0196712 -0.07913666 0.005318045 -0.02296137 -0.07721066 0.005378007 -0.01950579 -0.0791189 0.005469858 -0.01889306 -0.07884836 0.005699992 -0.01871997 -0.0790143 0.005739331 -0.01859098 -0.07918626 0.005850911 -0.01856499 -0.07916265 0.005853235 -0.01847416 -0.07930779 0.006027936 -0.01844435 -0.07927811 0.006029844 -0.01891565 -0.07886338 0.005699574 -0.01874357 -0.07903265 0.005737483 -0.01891398 -0.07943886 0.005737185 -0.01928776 -0.07904636 0.005590379 -0.0190404 -0.07922548 0.005644023 -0.01922094 -0.07960927 0.005485892 -0.01919418 -0.07986909 0.005609869 -0.01884317 -0.07963287 0.005903065 -0.01925384 -0.080087 0.005790293 -0.01933026 -0.07934617 0.005436778 -0.01947146 -0.0799815 0.005202651 -0.01972049 -0.07932317 0.004860758 -0.01956695 -0.07937735 0.005158782 -0.01960748 -0.07963037 0.004789292 -0.01963877 -0.07996165 0.004749894 -0.01946204 -0.07967269 0.005149304 -0.01980787 -0.08025079 0.00475049 -0.01952534 -0.0768156 -0.002293407 -0.01934146 -0.07637751 -0.001995384 -0.01989299 -0.07749545 -0.002377688 -0.01985728 -0.07743358 -0.002421975 -0.01707047 -0.07585775 9.06117e-4 -0.01981675 -0.07736319 -0.002445101 -0.02002328 -0.07916998 0.001478075 -0.02029126 -0.07962656 0.001920759 -0.01883655 -0.0797832 0.006121098 -0.01840555 -0.07938438 0.006249666 -0.01837086 -0.07934838 0.0062505 -0.01958405 -0.07864797 0.001319289 -0.01959335 -0.0802499 0.005309581 -0.018377 -0.08086967 0.01004719 -0.0203315 -0.07992118 0.002553641 -0.0202831 -0.07997649 0.002819299 -0.01702529 -0.07596307 0.001288115 -0.01710367 -0.07605737 0.001319289 -0.01722425 -0.07476317 8.10153e-4 -0.01703095 -0.0749942 7.47413e-4 -0.01713037 -0.07509458 5.76967e-4 -0.01713156 -0.07469046 0.001334249 -0.01689118 -0.07491075 0.001244306 -0.01714706 -0.07473015 0.001461088 -0.0171898 -0.07483977 0.001812219 -0.01691776 -0.07505577 0.001735985 -0.01721936 -0.0748918 0.001867949 -0.01762586 -0.07555741 0.002268791 -0.01739066 -0.07518738 0.0021559 -0.0170992 -0.07537758 0.002082705 -0.01702255 -0.07536339 6.18371e-4 -0.01692628 -0.0752834 7.53114e-4 -0.01677578 -0.07521796 0.001162648 -0.01738536 -0.0757876 0.002190828 -0.01719486 -0.07596999 0.001973152 -0.01700156 -0.07563149 7.33953e-4 -0.01692777 -0.0755822 8.26295e-4 -0.01680874 -0.07554978 0.001105904 -0.01677775 -0.07534575 0.001585304 -0.0169335 -0.07562536 0.001886546 -0.01709395 -0.07606655 0.001661002 -0.0170353 -0.07584035 9.54643e-4 -0.01698356 -0.07583868 0.001085638 -0.01680099 -0.07564455 0.001394033 -0.01698237 -0.07588505 0.001205146 -0.01690685 -0.07583647 0.001600086 -0.0323385 -0.06706309 0.002268791 -0.01736629 -0.07514905 0.002144157 -0.03197056 -0.06638967 0.00186336 -0.01718646 -0.07473355 0.001023888 -0.02211177 -0.07201337 7.05472e-4 -0.02689647 -0.06933015 6.16046e-4 -0.02764856 -0.06879299 7.36893e-4 -0.02736049 -0.06892836 7.82215e-4 -0.03183829 -0.06625717 0.001025855 -0.02709889 -0.06911009 7.37178e-4 -0.02793949 -0.06872808 6.16046e-4 -0.0279935 -0.06872588 5.8694e-4 -0.02126729 -0.07258015 6.16046e-4 -0.0210306 -0.07644557 -0.003131508 -0.01922988 -0.07598048 -0.00161916 -0.01730865 -0.07486575 6.16046e-4 -0.0253182 -0.07716685 -0.006344437 -0.03158324 -0.07235127 -0.005139946 -0.02988618 -0.07452946 -0.006344437 -0.0295248 -0.07447415 -0.006079137 -0.02929276 -0.07427638 -0.005745708 -0.02502459 -0.07747888 -0.006487607 -0.02462989 -0.07769846 -0.006479382 -0.0318982 -0.06644248 6.16046e-4 -0.03252398 -0.06937956 -0.002699077 -0.03140527 -0.07045567 -0.003131508 -0.03164356 -0.0713523 -0.004170835 -0.03304058 -0.07143539 -0.005065023 -0.03282916 -0.0726118 -0.006124734 -0.025451 -0.07682615 -0.006079137 -0.03030318 -0.07443118 -0.006487607 -0.03069078 -0.07419925 -0.006479382 -0.03231275 -0.07381725 -0.007036685 -0.03122746 -0.07339888 -0.005986452 -0.02675789 -0.06967586 3.49106e-4 -0.02291536 -0.07223045 1.12406e-5 -0.0242148 -0.07778096 -0.00632143 -0.02218586 -0.07875669 -0.006124734 -0.02106136 -0.07835155 -0.005065023 -0.02809858 -0.07803648 -0.008299946 -0.02935075 -0.07728147 -0.008297324 -0.02721709 -0.07832676 -0.008281886 -0.03050345 -0.07615458 -0.008202791 -0.02641659 -0.07851439 -0.008204162 -0.03048139 -0.07617968 -0.008209049 -0.03085088 -0.07576155 -0.008104443 -0.02888876 -0.0856859 -8.93084e-4 -0.03345406 -0.08378696 -0.001633703 -0.02994149 -0.07675385 -0.008281886 -0.03119158 -0.07537597 -0.007952749 -0.03444117 -0.08298259 -0.001398086 -0.03190296 -0.06866365 -0.00161916 -0.03247839 -0.06933718 -0.002293407 -0.03284758 -0.06993359 -0.002421975 -0.03267967 -0.06964927 -0.002430856 -0.01953929 -0.07687628 -0.002699077 -0.01973408 -0.07721698 -0.00244522 -0.01969498 -0.07714599 -0.002430856 -0.02539855 -0.07872056 -0.007952749 -0.02952265 -0.08557695 -0.001151442 -0.02590149 -0.07861858 -0.008104085 -0.02924919 -0.07737225 -0.008299946 -0.0292232 -0.07739228 -0.008299946 -0.02797216 -0.07808649 -0.008299767 -0.03054207 -0.08528667 -0.001451253 -0.02645355 -0.07850569 -0.008207738 -0.03036129 -0.08533817 -0.001398086 -0.03293728 -0.07034146 -0.003905594 -0.03690844 -0.07911598 0.001056432 -0.0367884 -0.07950216 7.38038e-4 -0.03572076 -0.08158999 -7.40891e-4 -0.03151476 -0.07499718 -0.007759511 -0.02851539 -0.08574998 -7.40891e-4 -0.0249089 -0.0788111 -0.007759511 -0.0234881 -0.07891219 -0.007036685 -0.02577894 -0.0855416 0.001056432 -0.02016568 -0.07771509 -0.003905594 -0.02502757 -0.08523458 0.001801013 -0.02503937 -0.08523941 0.001789331 -0.02476757 -0.08395409 0.004770755 -0.02472728 -0.08456397 0.004064619 -0.02427417 -0.08416819 0.004596889 -0.02404797 -0.08417665 0.004459083 -0.03660088 -0.07643938 0.004033029 -0.0368669 -0.07712286 0.003670096 -0.03656858 -0.07697159 0.004485845 -0.03647148 -0.07712596 0.004596889 -0.03656858 -0.07697159 0.004485845 -0.03634947 -0.07724159 0.004667997 -0.03679585 -0.0774312 0.003898382 -0.03642839 -0.0771749 0.004629075 -0.03627425 -0.07793486 0.004143536 -0.03664946 -0.07662856 0.00420767 -0.03678995 -0.07683825 0.003414452 -0.03689634 -0.07723808 0.002950906 -0.0369786 -0.07754695 0.002592682 -0.03701835 -0.07831168 0.001801013 -0.03709286 -0.07858139 0.002072989 -0.03701657 -0.07832437 0.001789331 -0.03672969 -0.08019536 6.61584e-4 -0.03665149 -0.07994228 3.75128e-4 -0.03628486 -0.08070576 -1.79576e-4 -0.03633499 -0.08101755 6.4245e-5 -0.03625267 -0.08077299 -2.28336e-4 -0.03547859 -0.08188128 -8.93084e-4 -0.03506726 -0.08237576 -0.001151442 -0.03430628 -0.08311349 -0.001451253 -0.03356474 -0.08400106 -0.001326858 -0.03320068 -0.08394998 -0.001650512 -0.03264927 -0.08458995 -0.001387536 -0.03252917 -0.08438199 -0.001694977 -0.0318194 -0.08474749 -0.001650512 -0.03155148 -0.08488547 -0.001633703 -0.03068238 -0.08548557 -0.001146256 -0.0277127 -0.08599567 6.4245e-5 -0.02754187 -0.08580207 -2.28336e-4 -0.02746766 -0.08579647 -1.79576e-4 -0.02680319 -0.08592647 6.61584e-4 -0.02662318 -0.0857321 3.75128e-4 -0.02617347 -0.08563059 7.38038e-4 -0.02596759 -0.08573788 0.001335978 -0.02522385 -0.08543395 0.002072989 -0.02358615 -0.08389216 0.003986716 -0.02361476 -0.08393687 0.004033029 -0.02386569 -0.0843001 0.003414452 -0.02407366 -0.08450895 0.003670096 -0.02458798 -0.08502137 0.002856671 -0.02415877 -0.0845921 0.002950906 -0.02438515 -0.08481776 0.002592682 -0.02437627 -0.0846017 0.003898382 -0.02702605 -0.08597767 9.7774e-4 -0.02790886 -0.08604496 3.97844e-4 -0.02867627 -0.08594417 -4.43108e-4 -0.02884435 -0.08599489 -9.46945e-5 -0.02967339 -0.08577287 -8.49532e-4 -0.03168147 -0.08508837 -0.001326858 -0.03270137 -0.08468025 -0.00101155 -0.03440827 -0.08333438 -0.001146256 -0.03516155 -0.08260416 -8.49532e-4 -0.0358085 -0.08182638 -4.43108e-4 -0.03514039 -0.08275246 -4.89252e-4 -0.0369842 -0.07937735 0.001335978 -0.03701525 -0.07884711 0.002347946 -0.03705346 -0.07782435 0.002856671 -0.02487546 -0.0850991 0.003108739 -0.02549278 -0.08549958 0.002347946 -0.02579349 -0.08542156 0.00258398 -0.02621489 -0.08579468 0.001632452 -0.02810084 -0.08594238 7.21672e-4 -0.02981239 -0.0858286 -4.89252e-4 -0.02899426 -0.08589458 2.51305e-4 -0.03079187 -0.08554965 -7.7732e-4 -0.0308541 -0.08546936 -4.00591e-4 -0.03176188 -0.08516418 -9.52683e-4 -0.03178036 -0.08510118 -5.68061e-4 -0.03359019 -0.08410859 -9.52683e-4 -0.03267765 -0.08463907 -6.24288e-4 -0.03430849 -0.08347499 -4.00591e-4 -0.0344091 -0.08346128 -7.7732e-4 -0.03576838 -0.08199739 -9.46945e-5 -0.03560656 -0.08207696 2.51305e-4 -0.03627949 -0.08121216 3.97844e-4 -0.03609466 -0.08132719 7.21672e-4 -0.03666269 -0.08041399 9.7774e-4 -0.03690975 -0.07961988 0.001632452 -0.03669649 -0.07980656 0.001900732 -0.03679728 -0.07906848 0.00258398 -0.03697705 -0.0781123 0.003108739 -0.025204 -0.08503907 0.003310501 -0.02552348 -0.08485037 0.00343132 -0.02648305 -0.08570325 0.001900732 -0.02673137 -0.0854777 0.002099931 -0.0272578 -0.08587819 0.00127542 -0.02746295 -0.08564287 0.001509428 -0.02991867 -0.08573579 -1.25492e-4 -0.03258156 -0.08447277 -2.84693e-4 -0.03352636 -0.08409315 -5.68061e-4 -0.03412169 -0.08337336 -7.34334e-5 -0.03500688 -0.08279806 -1.25492e-4 -0.03646057 -0.08056485 0.00127542 -0.03615415 -0.08062499 0.001509428 -0.0364722 -0.07921189 0.002745211 -0.03676074 -0.07836675 0.003310501 -0.03643769 -0.07854908 0.00343132 -0.03658777 -0.07771629 0.004064619 -0.03623747 -0.07733631 0.00472331 -0.03603947 -0.07744628 0.004770755 -0.03662508 -0.07047629 0.01069998 -0.03663778 -0.07049828 0.01046127 -0.03661304 -0.07688188 0.004418492 -0.03665095 -0.07668077 0.004253208 -0.03656005 -0.07080006 0.01069998 -0.03659194 -0.07693439 0.004459083 -0.03634238 -0.0712561 0.01069998 -0.03634947 -0.07724159 0.004667997 -0.03665077 -0.07667356 0.00424689 -0.03657644 -0.07639217 0.003986716 -0.03110235 -0.07151067 0.01069998 -0.02965956 -0.06555676 0.01069998 -0.03026747 -0.0650646 0.005699992 -0.02923357 -0.06621277 0.01069998 -0.02965956 -0.06555676 0.005699992 -0.02903115 -0.06696826 0.01069998 -0.02903115 -0.06696826 0.005699992 -0.0290721 -0.06774938 0.01069998 -0.02935236 -0.06847965 0.01069998 -0.02935236 -0.06847965 0.005699992 -0.03026747 -0.0650646 0.01069998 -0.03052729 -0.06491458 0.01069998 -0.03404319 -0.06600427 0.005965054 -0.03524905 -0.0696038 0.0062505 -0.03436034 -0.06655371 0.0062505 -0.03510427 -0.069646 0.005965054 -0.03485769 -0.06971788 0.005769431 -0.03394228 -0.06582969 0.005913555 -0.03455495 -0.06980609 0.005699992 -0.03315216 -0.06499165 0.005699992 -0.03119987 -0.07174307 0.005699992 -0.03221929 -0.06964516 0.005699992 -0.03261929 -0.06953799 0.005699992 -0.03291207 -0.06924515 0.005699992 -0.03181928 -0.06953799 0.005699992 -0.03110235 -0.07151067 0.005699992 -0.0315265 -0.06924515 0.005699992 -0.03141927 -0.06884515 0.005699992 -0.0290721 -0.06774938 0.005699992 -0.03221929 -0.06804519 0.005699992 -0.03261929 -0.06815236 0.005699992 -0.03279405 -0.06479579 0.005699992 -0.03291207 -0.0684452 0.005699992 -0.0330193 -0.06884515 0.005699992 -0.0315265 -0.0684452 0.005699992 -0.02923357 -0.06621277 0.005699992 -0.03125745 -0.06463426 0.005699992 -0.03052729 -0.06491458 0.005699992 -0.03181928 -0.06815236 0.005699992 -0.03125745 -0.06463426 0.01069998 -0.03203856 -0.06459337 0.01069998 -0.03203856 -0.06459337 0.005699992 -0.03279405 -0.06479579 0.01069998 -0.03345006 -0.06522178 0.01069998 -0.03345006 -0.06522178 0.005733489 -0.03358608 -0.06535398 0.005769431 -0.03394228 -0.06582969 0.01069998 -0.03423446 -0.06633555 0.006099522 -0.0366196 -0.07046675 0.01021599 -0.03656357 -0.07036966 0.01004719 -0.03436827 -0.07114988 0.001618146 -0.0328834 -0.06999546 -0.002377688 -0.03411829 -0.07056337 0.001342952 -0.03403586 -0.07030415 0.001319289 -0.03531205 -0.07129949 0.00475049 -0.03462594 -0.07151228 0.002147614 -0.03540349 -0.0702902 0.006091713 -0.03544706 -0.07087635 0.00564903 -0.03537058 -0.07123827 0.005016088 -0.03287637 -0.06673228 9.06117e-4 -0.03301578 -0.06680876 0.001313507 -0.03289026 -0.06665796 0.001029789 -0.03376787 -0.07112646 0.003018796 -0.0340774 -0.07103425 0.002929508 -0.03455245 -0.07075995 0.004860758 -0.03439986 -0.07108998 0.002858102 -0.03467118 -0.07128268 0.002818703 -0.03487497 -0.07081568 0.004789292 -0.03514629 -0.07100838 0.004749894 -0.03483694 -0.07157379 0.002819299 2.66172e-4 0.0818603 0.00939995 4.16767e-4 0.08180516 0.00939995 -3.4258e-4 0.07996416 0.00939995 -1.88037e-4 0.07992136 0.00939995 -5.16209e-5 0.08189517 0.00939995 -2.86238e-5 0.0799039 0.00939995 1.08683e-4 0.08189058 0.00939995 -6.39104e-4 0.08166456 0.00939995 -5.08183e-4 0.08175718 0.00939995 -3.641e-4 0.08182758 0.00939995 -2.10588e-4 0.08187395 0.00939995 5.56568e-4 0.08172661 0.00939995 6.81954e-4 0.08162659 0.00939995 5.7551e-4 0.08008646 0.00939995 -7.3821e-4 0.08023059 0.00939995 -8.36025e-4 0.08035767 0.00939995 8.03505e-4 0.08031058 0.00939995 6.98553e-4 0.08018928 0.00939995 4.3756e-4 0.08000469 0.00939995 2.88279e-4 0.0799461 0.00939995 7.89678e-4 0.0815078 0.00939995 1.31531e-4 0.07991218 0.00939995 -9.12188e-4 0.08049875 0.00939995 -9.64725e-4 0.08065038 0.00939995 -9.92276e-4 0.08080828 0.00939995 9.85376e-4 0.08075147 0.00939995 9.96434e-4 0.08091145 0.00939995 8.7695e-4 0.08137327 0.00939995 9.41509e-4 0.08122646 0.00939995 9.81684e-4 0.08107119 0.00939995 8.87646e-4 0.08044707 0.00939995 9.48798e-4 0.08059537 0.00939995 -7.53472e-4 0.08155208 0.00939995 -8.48326e-4 0.0814228 0.00939995 -4.88251e-4 0.08003127 0.00939995 -6.21276e-4 0.08012086 0.00939995 -9.94128e-4 0.08096867 0.00939995 -9.70233e-4 0.08112728 0.00939995 -9.21209e-4 0.08127999 0.00939995 3.07288e-4 0.07968837 0.01729995 -3.68884e-6 0.07964998 0.01729995 -3.14434e-4 0.07969015 0.01729995 -3.68884e-6 0.07964998 0.009653449 -3.14434e-4 0.07969015 0.009653449 -6.05422e-4 0.07980638 0.01729995 -8.58369e-4 0.07999128 0.01729995 -6.05422e-4 0.07980638 0.009653449 -8.58369e-4 0.07999128 0.009653449 -0.001057326 0.08023327 0.01729995 -0.001057326 0.08023327 0.009653449 -0.001189947 0.08051717 0.009653449 -0.001189947 0.08051717 0.01729995 -0.001247704 0.0808252 0.01729995 -0.001247704 0.0808252 0.009653449 -0.00122714 0.08113789 0.01729995 -0.00122714 0.08113789 0.009653449 -0.001129448 0.08143556 0.009653449 -0.001129448 0.08143556 0.01729995 -9.60786e-4 0.0816996 0.01729995 -9.60786e-4 0.0816996 0.009653449 -7.31744e-4 0.08191341 0.01729995 -7.31744e-4 0.08191341 0.009653449 -4.56724e-4 0.08206355 0.009653449 -4.56724e-4 0.08206355 0.01729995 -1.53006e-4 0.08214056 0.01729995 -1.53006e-4 0.08214056 0.009653449 1.60326e-4 0.08213967 0.009653449 1.60326e-4 0.08213967 0.01729995 4.63583e-4 0.08206087 0.01729995 4.63583e-4 0.08206087 0.009653449 7.37713e-4 0.08190906 0.01729995 7.37713e-4 0.08190906 0.009653449 9.65489e-4 0.08169388 0.01729995 9.65489e-4 0.08169388 0.009653449 0.001132547 0.08142888 0.01729995 0.001132547 0.08142888 0.009653449 0.001228511 0.08113056 0.01729995 0.001228511 0.08113056 0.009653449 0.001247286 0.08081775 0.009653449 0.001247286 0.08081775 0.01729995 0.001187622 0.08051019 0.009653449 0.001187622 0.08051019 0.01729995 0.001053392 0.08022707 0.01729995 0.001053392 0.08022707 0.009653449 8.52991e-4 0.07998627 0.01729995 5.98957e-4 0.07980281 0.01729995 8.52991e-4 0.07998627 0.009653449 5.98957e-4 0.07980281 0.009653449 4.56724e-4 0.07973641 0.01729995 3.07288e-4 0.07968837 0.009653449 -0.0693497 0.04114735 0.00939995 -0.06924706 0.04102414 0.00939995 -0.0710358 0.04024088 0.00939995 -0.07078695 0.0411331 0.00939995 -0.0692833 0.03982746 0.00939995 -0.06939315 0.0397107 0.00939995 -0.07066798 0.04124057 0.00939995 -0.07053339 0.04132765 0.00939995 -0.0703864 0.04139196 0.00939995 -0.07023108 0.0414319 0.00939995 -0.07007139 0.04144644 0.00939995 -0.06991136 0.04143506 0.00939995 -0.06916546 0.04088616 0.00939995 -0.06919348 0.03996038 0.00939995 -0.06910705 0.04073679 0.00939995 -0.06907349 0.04057997 0.00939995 -0.06906539 0.04041975 0.00939995 -0.06908315 0.04026037 0.00939995 -0.06912618 0.04010599 0.00939995 -0.070827 0.03981208 0.00939995 -0.07091939 0.03994315 0.00939995 -0.06966167 0.03953719 0.00939995 -0.0709896 0.04008728 0.00939995 -0.07105666 0.04039984 0.00939995 -0.07105177 0.04056018 0.00939995 -0.06975537 0.04139828 0.00939995 -0.06960719 0.04133689 0.00939995 -0.06947076 0.04125255 0.00939995 -0.06952047 0.03961306 0.00939995 -0.0708872 0.04100787 0.00939995 -0.070966 0.04086816 0.00939995 -0.07102125 0.04071766 0.00939995 -0.06981331 0.03948485 0.00939995 -0.06997126 0.03945755 0.00939995 -0.07013165 0.03945595 0.00939995 -0.07029026 0.03948009 0.00939995 -0.07071477 0.03969746 0.00939995 -0.07044285 0.03952938 0.00939995 -0.0705856 0.03960245 0.00939995 -0.0692088 -0.04096567 0.00939995 -0.07050645 -0.03955835 0.00939995 -0.07004117 -0.03945368 0.00939995 -0.07076597 -0.03974515 0.00939995 -0.07064378 -0.03964138 0.00939995 -0.06941586 -0.04120916 0.00939995 -0.06930249 -0.04109579 0.00939995 -0.07100015 -0.04078435 0.00939995 -0.0710417 -0.04062938 0.00939995 -0.07105779 -0.04046988 0.00939995 -0.0693289 -0.03977447 0.00939995 -0.07035768 -0.03949856 0.00939995 -0.06944668 -0.03966569 0.00939995 -0.06988155 -0.03946989 0.00939995 -0.07020127 -0.0394634 0.00939995 -0.06972676 -0.03951138 0.00939995 -0.06958049 -0.03957718 0.00939995 -0.06922996 -0.03990066 0.00939995 -0.07086986 -0.0398674 0.00939995 -0.06915265 -0.04004114 0.00939995 -0.06909888 -0.0401923 0.00939995 -0.06906998 -0.04034996 0.00939995 -0.06906676 -0.04051035 0.00939995 -0.06908929 -0.04066908 0.00939995 -0.06913709 -0.04082214 0.00939995 -0.0695461 -0.04130285 0.00939995 -0.06968957 -0.0413745 0.00939995 -0.07061105 -0.04128116 0.00939995 -0.0707373 -0.04118227 0.00939995 -0.07047057 -0.04135859 0.00939995 -0.07084596 -0.04106438 0.00939995 -0.07104796 -0.04030978 0.00939995 -0.07101279 -0.04015338 0.00939995 -0.07095289 -0.04000455 0.00939995 -0.06984269 -0.04142218 0.00939995 -0.07000148 -0.04144465 0.00939995 -0.07093435 -0.04093056 0.00939995 -0.07016175 -0.04144138 0.00939995 -0.07031947 -0.04141247 0.00939995 0.06906777 0.04037469 0.00939995 0.06906861 0.04053497 0.00939995 0.06909507 0.04069316 0.00939995 0.06931877 0.04111438 0.00939995 0.06955897 0.03958946 0.00939995 0.06942749 0.03968119 0.00939995 0.06931227 0.03979289 0.00939995 0.0692166 0.03992146 0.00939995 0.06914275 0.04006385 0.00939995 0.06909281 0.04021626 0.00939995 0.07018637 0.04143857 0.00939995 0.06986689 0.04142725 0.00939995 0.07002615 0.04144585 0.00939995 0.06956738 0.04131537 0.00939995 0.0706315 0.04126727 0.00939995 0.06971269 0.0413835 0.00939995 0.07049298 0.04134815 0.00939995 0.07034337 0.04140579 0.00939995 0.07086098 0.04104465 0.00939995 0.07094609 0.04090875 0.00939995 0.0710082 0.04076087 0.00939995 0.07048416 0.03954756 0.00939995 0.07033395 0.03949147 0.00939995 0.07017666 0.03946018 0.00939995 0.0707553 0.04116529 0.00939995 0.069435 0.04122495 0.00939995 0.06914657 0.04084509 0.00939995 0.06922179 0.04098665 0.00939995 0.07104426 0.04028528 0.00939995 0.07105785 0.04044508 0.00939995 0.07104575 0.04060494 0.00939995 0.0709415 0.03998255 0.00939995 0.0708552 0.03984749 0.00939995 0.0710051 0.04012978 0.00939995 0.0707482 0.03972798 0.00939995 0.07062345 0.03962707 0.00939995 0.0700165 0.03945446 0.00939995 0.06985735 0.03947454 0.00939995 0.06970345 0.03951996 0.00939995 0.06926655 -0.03948527 0.009653449 0.06912207 -0.03962528 0.009653449 0.06942778 -0.03968089 0.00939995 0.06931257 -0.03979259 0.00939995 0.06900197 -0.03978669 0.009653449 0.06921678 -0.03992116 0.00939995 0.06890928 -0.03996515 0.009653449 0.0688464 -0.0401563 0.009653449 0.06914299 -0.0400635 0.00939995 0.06881505 -0.04035496 0.009653449 0.06906777 -0.04037427 0.00939995 0.068816 -0.04055619 0.009653449 0.06884908 -0.04075455 0.009653449 0.06891369 -0.04094505 0.009653449 0.06922155 -0.04098635 0.00939995 0.06900799 -0.04112279 0.009653449 0.06912946 -0.04128307 0.009653449 0.06927525 -0.04142177 0.009653449 0.0694347 -0.04122465 0.00939995 0.06944125 -0.04153525 0.009653449 0.06962347 -0.04162067 0.009653449 0.06971228 -0.04138326 0.00939995 0.06981688 -0.04167586 0.009653449 0.07001668 -0.04169917 0.009653449 0.0700258 -0.04144585 0.00939995 0.07021766 -0.04169017 0.009653449 0.07018595 -0.04143869 0.00939995 0.0704146 -0.0416491 0.009653449 0.07060235 -0.04157686 0.009653449 0.07034295 -0.04140585 0.00939995 0.07049268 -0.04134839 0.00939995 0.0707761 -0.04147547 0.009653449 0.07093137 -0.04134756 0.009653449 0.0706312 -0.04126757 0.00939995 0.07106405 -0.0411964 0.009653449 0.070755 -0.04116559 0.00939995 0.07117086 -0.04102587 0.009653449 0.07124888 -0.04084044 0.009653449 0.07100808 -0.04076129 0.00939995 0.07129615 -0.040645 0.009653449 0.07104575 -0.04060536 0.00939995 0.07131135 -0.04044437 0.009653449 0.07105785 -0.04044544 0.00939995 0.07129436 -0.04024386 0.009653449 0.07124525 -0.04004877 0.009653449 0.07100516 -0.04013019 0.00939995 0.07116568 -0.03986406 0.009653449 0.07105737 -0.03969454 0.009653449 0.07092326 -0.03954458 0.009653449 0.0707485 -0.03972816 0.00939995 0.07076686 -0.0394181 0.009653449 0.07048457 -0.0395478 0.00939995 0.07059216 -0.03931826 0.009653449 0.07040375 -0.03924775 0.009653449 0.07020646 -0.03920835 0.009653449 0.07017707 -0.03946018 0.00939995 0.07000547 -0.03920125 0.009653449 0.06980586 -0.03922635 0.009653449 0.06961297 -0.03928315 0.009653449 0.0694316 -0.03937029 0.009653449 0.06955927 -0.03958928 0.00939995 0.06909281 -0.04021584 0.00939995 0.06914645 -0.04084467 0.00939995 0.06909495 -0.04069274 0.00939995 0.06906861 -0.04053455 0.00939995 0.07104426 -0.04028564 0.00939995 0.07085537 -0.03984779 0.00939995 0.07094168 -0.03998285 0.00939995 0.0708608 -0.04104506 0.00939995 0.07094585 -0.04090905 0.00939995 0.06985765 -0.03947448 0.00939995 0.07062375 -0.03962737 0.00939995 0.06970387 -0.0395199 0.00939995 0.06931847 -0.04111409 0.00939995 0.06956708 -0.04131519 0.00939995 0.07001686 -0.03945446 0.00939995 0.07033437 -0.03949159 0.00939995 0.06986647 -0.04142719 0.00939995 0.08646708 0.03820598 0.01029998 0.08651387 0.03805255 0.01029998 0.08523786 0.03689014 0.01029998 0.0850895 0.03695106 0.01029998 0.08653539 0.03789365 0.01029998 0.08653116 0.03773325 0.01029998 0.08472818 0.03726238 0.01029998 0.0846461 0.03740006 0.01029998 0.08458709 0.03754925 0.01029998 0.08644646 0.0374251 0.01029998 0.0865013 0.03757578 0.01029998 0.08626848 0.0371595 0.01029998 0.08495277 0.03703486 0.01029998 0.0863682 0.03728508 0.01029998 0.08483129 0.03713959 0.01029998 0.08455288 0.03770589 0.01029998 0.08576536 0.03881049 0.01029998 0.08591818 0.03876179 0.01029998 0.08606117 0.03868925 0.01029998 0.08619076 0.03859466 0.01029998 0.08630347 0.03848057 0.01029998 0.08639639 0.03834986 0.01029998 0.0853942 0.03685396 0.01029998 0.08467048 0.03832596 0.01029998 0.08475977 0.03845918 0.01029998 0.0849961 0.03867447 0.01029998 0.08486926 0.03857636 0.01029998 0.08460378 0.03818017 0.01029998 0.08513706 0.03875094 0.01029998 0.08454418 0.03786605 0.01029998 0.08456128 0.03802549 0.01029998 0.08560675 0.03883397 0.01029998 0.08544635 0.03883177 0.01029998 0.08528846 0.03880387 0.01029998 0.08601558 0.03696388 0.01029998 0.08586895 0.03689897 0.01029998 0.08614999 0.03705149 0.01029998 0.0857138 0.03685849 0.01029998 0.08555418 0.03684329 0.01029998 0.0869168 0.03605985 0.02254998 0.0869168 0.03605985 0.02029997 0.08660507 0.03585755 0.02254998 0.08660507 0.03585755 0.02029997 0.08626425 0.03570938 0.02029997 0.08626425 0.03570938 0.02254998 0.08590376 0.03561925 0.02254998 0.08590376 0.03561925 0.02029997 0.08553338 0.03558975 0.02254998 0.08516305 0.03562158 0.02254998 0.08553338 0.03558975 0.02029997 0.08516305 0.03562158 0.02029997 0.08480316 0.03571385 0.02029997 0.08480316 0.03571385 0.02254998 0.08446335 0.03586429 0.02254998 0.08446335 0.03586429 0.02029997 0.08415287 0.03606849 0.02254998 0.08415287 0.03606849 0.02029997 0.0838803 0.03632098 0.02029997 0.0838803 0.03632098 0.02254998 0.08365285 0.03661495 0.02254998 0.08365285 0.03661495 0.02029997 0.08347707 0.0369423 0.02254998 0.08347707 0.0369423 0.02029997 0.08335745 0.03729414 0.02254998 0.08335745 0.03729414 0.02029997 0.08329749 0.03766089 0.02254998 0.08329856 0.03803247 0.02254998 0.08329749 0.03766089 0.02029997 0.08329856 0.03803247 0.02029997 0.08336091 0.03839886 0.02254998 0.08336091 0.03839886 0.02029997 0.08348268 0.03874987 0.02029997 0.08348268 0.03874987 0.02254998 0.0836606 0.03907614 0.02029997 0.0836606 0.03907614 0.02254998 0.08388966 0.03936874 0.02029997 0.08388966 0.03936874 0.02254998 0.0841639 0.03961956 0.02029997 0.0841639 0.03961956 0.02254998 0.08447557 0.03982186 0.02254998 0.08447557 0.03982186 0.02029997 0.08481639 0.03997009 0.02029997 0.08481639 0.03997009 0.02254998 0.08517688 0.04006016 0.02029997 0.08517688 0.04006016 0.02254998 0.08554726 0.04008966 0.02029997 0.08554726 0.04008966 0.02254998 0.08591759 0.04005789 0.02029997 0.08591759 0.04005789 0.02254998 0.08627748 0.03996556 0.02254998 0.08627748 0.03996556 0.02029997 0.08661741 0.03981518 0.02029997 0.08661741 0.03981518 0.02254998 0.08692777 0.03961098 0.02029997 0.08692777 0.03961098 0.02254998 0.08720046 0.03935849 0.02029997 0.08720046 0.03935849 0.02254998 0.08742779 0.03906446 0.02254998 0.08742779 0.03906446 0.02029997 0.08760356 0.03873717 0.02254998 0.08772319 0.03838527 0.02254998 0.08760356 0.03873717 0.02029997 0.08772319 0.03838527 0.02029997 0.08778315 0.03801858 0.02254998 0.08778315 0.03801858 0.02029997 0.08778208 0.03764694 0.02254998 0.08771979 0.03728055 0.02254998 0.08778208 0.03764694 0.02029997 0.08771979 0.03728055 0.02029997 0.08759796 0.03692948 0.02254998 0.08759796 0.03692948 0.02029997 0.08742016 0.03660327 0.02254998 0.08742016 0.03660327 0.02029997 0.08719098 0.03631067 0.02029997 0.08719098 0.03631067 0.02254998 0.008761286 0.09283208 0.02019995 0.008749961 0.09300237 0.02019995 0.008796989 0.0933395 0.02019995 0.008933186 0.09365147 0.02019995 0.008933186 0.09365147 0.01055347 0.009148538 0.09391516 0.02019995 0.009427011 0.09411096 0.02019995 0.009148538 0.09391516 0.01055347 0.009747982 0.09422427 0.01055347 0.009747982 0.09422427 0.02019995 0.01008766 0.09424686 0.02019995 0.01042079 0.094177 0.01055347 0.01042079 0.094177 0.02019995 0.01072275 0.09401977 0.02019995 0.01072275 0.09401977 0.01055347 0.01097106 0.09378695 0.02019995 0.01114749 0.09349578 0.02019995 0.01123869 0.09316778 0.02019995 0.01114749 0.09349578 0.01055347 0.01123869 0.09316778 0.01055347 0.01123797 0.09282737 0.01055347 0.01123797 0.09282737 0.02019995 0.01114559 0.09249979 0.02019995 0.01096808 0.09220927 0.02019995 0.01114559 0.09249979 0.01055347 0.01096808 0.09220927 0.01055347 0.01071888 0.09197735 0.01055347 0.01071888 0.09197735 0.02019995 0.01041638 0.09182137 0.02019995 0.0100829 0.09175276 0.02019995 0.009743332 0.0917766 0.02019995 0.0100829 0.09175276 0.01055347 0.009743332 0.0917766 0.01055347 0.009422779 0.09189116 0.02019995 0.009145021 0.0920881 0.02019995 0.009145021 0.0920881 0.01055347 0.008930683 0.09235256 0.02019995 0.008795678 0.09266495 0.02019995 0.008795678 0.09266495 0.01055347 0.0109148 0.09339529 0.01029998 0.01097106 0.09378695 0.01055347 0.01008766 0.09424686 0.01055347 0.01006984 0.09399396 0.01029998 0.009799063 0.09397596 0.01029998 0.009427011 0.09411096 0.01055347 0.00954318 0.0938856 0.01029998 0.009321212 0.09372955 0.01029998 0.008796989 0.0933395 0.01055347 0.008749961 0.09300237 0.01055347 0.009039938 0.09273296 0.01029998 0.008930683 0.09235256 0.01055347 0.009318411 0.09227299 0.01029998 0.009422779 0.09189116 0.01055347 0.01006609 0.09200567 0.01029998 0.01041638 0.09182137 0.01055347 0.01033186 0.09206038 0.01029998 0.01091319 0.09260129 0.01029998 0.009795367 0.09202468 0.01029998 0.0103355 0.09393829 0.01029998 0.01057618 0.093813 0.01029998 0.01057308 0.09218478 0.01029998 0.009539842 0.09211605 0.01029998 0.009147584 0.09248387 0.01029998 0.00900346 0.0930019 0.01029998 0.009040951 0.09327065 0.01029998 0.009149551 0.09351938 0.01029998 0.01098746 0.0931338 0.01029998 0.01098698 0.09286236 0.01029998 0.01077419 0.09362739 0.01029998 0.01077175 0.09236967 0.01029998 0.01222956 0.09330207 0.02254998 0.01222956 0.09330207 0.02029997 0.01224887 0.09293097 0.02254998 0.01224887 0.09293097 0.02029997 0.01220685 0.09256178 0.02254998 0.009381055 0.09083676 0.02029997 0.009033441 0.09096819 0.02029997 0.008712172 0.09115499 0.02254998 0.008712172 0.09115499 0.02029997 0.00842607 0.09139209 0.02254998 0.00842607 0.09139209 0.02029997 0.008182883 0.09167307 0.02254998 0.008182883 0.09167307 0.02029997 0.007989287 0.09199029 0.02254998 0.007989287 0.09199029 0.02029997 0.007850468 0.09233498 0.02254998 0.007850468 0.09233498 0.02029997 0.007770359 0.09269785 0.02254998 0.007751047 0.09306895 0.02254998 0.007770359 0.09269785 0.02029997 0.007751047 0.09306895 0.02029997 0.007793068 0.0934382 0.02029997 0.007793068 0.0934382 0.02254998 0.00789529 0.09379547 0.02254998 0.00789529 0.09379547 0.02029997 0.008054912 0.09413099 0.02254998 0.008054912 0.09413099 0.02029997 0.008267581 0.09443581 0.02254998 0.008267581 0.09443581 0.02029997 0.008527576 0.09470129 0.02029997 0.008527576 0.09470129 0.02254998 0.008827686 0.09492045 0.02254998 0.008827686 0.09492045 0.02029997 0.009159743 0.09508717 0.02029997 0.009159743 0.09508717 0.02254998 0.009514749 0.09519708 0.02254998 0.009514749 0.09519708 0.02029997 0.009882986 0.09524697 0.02254998 0.009882986 0.09524697 0.02029997 0.0102545 0.09523558 0.02254998 0.0102545 0.09523558 0.02029997 0.01061886 0.09516316 0.02254998 0.01061886 0.09516316 0.02029997 0.01096659 0.09503179 0.02254998 0.01096659 0.09503179 0.02029997 0.01128774 0.09484499 0.02029997 0.01128774 0.09484499 0.02254998 0.01157385 0.09460788 0.02254998 0.01157385 0.09460788 0.02029997 0.01181709 0.09432685 0.02254998 0.01181709 0.09432685 0.02029997 0.01201069 0.09400969 0.02029997 0.01201069 0.09400969 0.02254998 0.01214945 0.093665 0.02029997 0.01214945 0.093665 0.02254998 -0.08614999 -0.03705149 0.01029998 -0.08653539 -0.03789365 0.01029998 -0.08601558 -0.03696388 0.01029998 -0.08586895 -0.03689897 0.01029998 -0.0857138 -0.03685849 0.01029998 -0.08458709 -0.03754925 0.01029998 -0.08646708 -0.03820598 0.01029998 -0.08591818 -0.03876179 0.01029998 -0.08606117 -0.03868925 0.01029998 -0.08619076 -0.03859466 0.01029998 -0.08576536 -0.03881049 0.01029998 -0.08630347 -0.03848057 0.01029998 -0.0853942 -0.03685396 0.01029998 -0.08651387 -0.03805255 0.01029998 -0.08513706 -0.03875094 0.01029998 -0.08528846 -0.03880387 0.01029998 -0.08544635 -0.03883177 0.01029998 -0.08560675 -0.03883397 0.01029998 -0.08639639 -0.03834986 0.01029998 -0.08653116 -0.03773325 0.01029998 -0.0865013 -0.03757578 0.01029998 -0.08644646 -0.0374251 0.01029998 -0.08483129 -0.03713959 0.01029998 -0.08456128 -0.03802549 0.01029998 -0.08460378 -0.03818017 0.01029998 -0.0863682 -0.03728508 0.01029998 -0.0849961 -0.03867447 0.01029998 -0.08626848 -0.0371595 0.01029998 -0.08495277 -0.03703486 0.01029998 -0.0850895 -0.03695106 0.01029998 -0.08555418 -0.03684329 0.01029998 -0.08455288 -0.03770589 0.01029998 -0.08454418 -0.03786605 0.01029998 -0.08467048 -0.03832596 0.01029998 -0.08475977 -0.03845918 0.01029998 -0.08486926 -0.03857636 0.01029998 -0.08472818 -0.03726238 0.01029998 -0.08523786 -0.03689014 0.01029998 -0.0846461 -0.03740006 0.01029998 0.07468718 -0.05724215 0.02029997 0.07435619 -0.05707335 0.02254998 0.0740574 -0.0568524 0.02254998 0.07435619 -0.05707335 0.02029997 0.07379907 -0.05658519 0.02254998 0.0740574 -0.0568524 0.02029997 0.07379907 -0.05658519 0.02029997 0.07358831 -0.05627918 0.02254998 0.07343077 -0.05594265 0.02254998 0.07358831 -0.05627918 0.02029997 0.07343077 -0.05594265 0.02029997 0.07333076 -0.05558478 0.02254998 0.07333076 -0.05558478 0.02029997 0.073291 -0.05521529 0.02254998 0.073291 -0.05521529 0.02029997 0.07331269 -0.05484426 0.02254998 0.07331269 -0.05484426 0.02029997 0.07339495 -0.05448186 0.02254998 0.07339495 -0.05448186 0.02029997 0.07353585 -0.05413806 0.02029997 0.07353585 -0.05413806 0.02254998 0.07373148 -0.0538221 0.02254998 0.07373148 -0.0538221 0.02029997 0.07397645 -0.05354255 0.02029997 0.07397645 -0.05354255 0.02254998 0.07426398 -0.05330729 0.02029997 0.07426398 -0.05330729 0.02254998 0.07458639 -0.05312246 0.02254998 0.07458639 -0.05312246 0.02029997 0.07493478 -0.05299329 0.02029997 0.07493478 -0.05299329 0.02254998 0.07529979 -0.0529232 0.02254998 0.07529979 -0.0529232 0.02029997 0.07567125 -0.05291408 0.02029997 0.07567125 -0.05291408 0.02254998 0.07603919 -0.05296617 0.02254998 0.07603919 -0.05296617 0.02029997 0.07639348 -0.05307829 0.02254998 0.07639348 -0.05307829 0.02029997 0.07672458 -0.05324709 0.02029997 0.07672458 -0.05324709 0.02254998 0.07702326 -0.05346804 0.02254998 0.07702326 -0.05346804 0.02029997 0.07728159 -0.05373525 0.02254998 0.07728159 -0.05373525 0.02029997 0.07749235 -0.05404126 0.02029997 0.07749235 -0.05404126 0.02254998 0.07764995 -0.05437785 0.02029997 0.07764995 -0.05437785 0.02254998 0.07774996 -0.05473577 0.02254998 0.07774996 -0.05473577 0.02029997 0.07778966 -0.05510514 0.02254998 0.07778966 -0.05510514 0.02029997 0.07776808 -0.05547618 0.02254998 0.07776808 -0.05547618 0.02029997 0.07768565 -0.05583858 0.02254998 0.07768565 -0.05583858 0.02029997 0.0775448 -0.05618238 0.02254998 0.0775448 -0.05618238 0.02029997 0.07734918 -0.05649834 0.02254998 0.07734918 -0.05649834 0.02029997 0.07710427 -0.05677789 0.02029997 0.07710427 -0.05677789 0.02254998 0.07681667 -0.05701315 0.02029997 0.07681667 -0.05701315 0.02254998 0.07649427 -0.05719798 0.02254998 0.07649427 -0.05719798 0.02029997 0.07614588 -0.05732715 0.02254998 0.07614588 -0.05732715 0.02029997 0.07578086 -0.05739736 0.02254998 0.07578086 -0.05739736 0.02029997 0.07540935 -0.05740636 0.02254998 0.07540935 -0.05740636 0.02029997 0.07504147 -0.05735427 0.02254998 0.07504147 -0.05735427 0.02029997 0.07468718 -0.05724215 0.02254998 -0.008781492 0.09327888 0.02019995 -0.008754849 0.09311038 0.02019995 -0.00877124 0.09277039 0.02019995 -0.008754849 0.09311038 0.01055347 -0.008878767 0.0924474 0.02019995 -0.009069442 0.09216541 0.02019995 -0.008878767 0.0924474 0.01055347 -0.00932914 0.09194529 0.02019995 -0.009638547 0.09180337 0.02019995 -0.009974777 0.09175026 0.02019995 -0.01031285 0.09178978 0.02019995 -0.01031285 0.09178978 0.01055347 -0.01062774 0.09191906 0.02019995 -0.01089614 0.09212857 0.02019995 -0.01062774 0.09191906 0.01055347 -0.01109808 0.09240269 0.02019995 -0.01109808 0.09240269 0.01055347 -0.01121848 0.0927211 0.02019995 -0.01124858 0.09306019 0.01055347 -0.01124858 0.09306019 0.02019995 -0.011186 0.09339475 0.01055347 -0.011186 0.09339475 0.02019995 -0.0110355 0.09370011 0.02019995 -0.0110355 0.09370011 0.01055347 -0.01080816 0.0939536 0.02019995 -0.01080816 0.0939536 0.01055347 -0.01052099 0.09413629 0.02019995 -0.01019507 0.0942347 0.02019995 -0.009854733 0.09424149 0.02019995 -0.01019507 0.0942347 0.01055347 -0.009854733 0.09424149 0.01055347 -0.009525179 0.09415626 0.02019995 -0.009230792 0.09398525 0.02019995 -0.009230792 0.09398525 0.01055347 -0.008993506 0.09374129 0.02019995 -0.008830785 0.0934422 0.02019995 -0.01089614 0.09212857 0.01055347 -0.0108754 0.09252375 0.01029998 -0.01071435 0.0923053 0.01029998 -0.009974777 0.09175026 0.01055347 -0.009979903 0.0920037 0.01029998 -0.009638547 0.09180337 0.01055347 -0.00932914 0.09194529 0.01055347 -0.009711861 0.09204608 0.01029998 -0.009069442 0.09216541 0.01055347 -0.009465157 0.09215921 0.01029998 -0.00877124 0.09277039 0.01055347 -0.009020447 0.09281688 0.01029998 -0.008830785 0.0934422 0.01055347 -0.008993506 0.09374129 0.01055347 -0.009067893 0.09335249 0.01029998 -0.009386777 0.09378546 0.01029998 -0.009621441 0.09392178 0.01029998 -0.009525179 0.09415626 0.01055347 -0.009884178 0.09398978 0.01029998 -0.01015549 0.0939843 0.01029998 -0.01052099 0.09413629 0.01055347 -0.01041525 0.0939058 0.01029998 -0.01064425 0.09376019 0.01029998 -0.01082545 0.09355819 0.01029998 -0.01094549 0.0933147 0.01029998 -0.01121848 0.0927211 0.01055347 -0.01050049 0.09213829 0.01029998 -0.009197592 0.09359085 0.01029998 -0.009007334 0.09308797 0.01029998 -0.01024949 0.09203517 0.01029998 -0.01097136 0.09277766 0.01029998 -0.01099526 0.09304797 0.01029998 -0.009106159 0.09255939 0.01029998 -0.009258151 0.09233456 0.01029998 -0.01219326 0.092498 0.02254998 -0.01219326 0.092498 0.02029997 -0.01224595 0.09286576 0.02029997 -0.01224595 0.09286576 0.02254998 -0.01223737 0.09323728 0.02254998 -0.01223737 0.09323728 0.02029997 -0.01216787 0.09360235 0.02029997 -0.01216787 0.09360235 0.02254998 -0.01203918 0.09395098 0.02254998 -0.01203918 0.09395098 0.02029997 -0.01185476 0.09427356 0.02254998 -0.01161986 0.09456145 0.02254998 -0.01185476 0.09427356 0.02029997 -0.01161986 0.09456145 0.02029997 -0.01134079 0.0948069 0.02254998 -0.01134079 0.0948069 0.02029997 -0.01102507 0.09500288 0.02254998 -0.01102507 0.09500288 0.02029997 -0.01068139 0.09514427 0.02254998 -0.01031917 0.09522718 0.02254998 -0.01068139 0.09514427 0.02029997 -0.01031917 0.09522718 0.02029997 -0.009948253 0.09524935 0.02029997 -0.009948253 0.09524935 0.02254998 -0.009578704 0.09521019 0.02254998 -0.009578704 0.09521019 0.02029997 -0.009220659 0.09511065 0.02254998 -0.009220659 0.09511065 0.02029997 -0.008883893 0.09495365 0.02254998 -0.008883893 0.09495365 0.02029997 -0.008577525 0.09474331 0.02254998 -0.008310019 0.0944854 0.02254998 -0.008577525 0.09474331 0.02029997 -0.008310019 0.0944854 0.02029997 -0.008088529 0.09418696 0.02254998 -0.008088529 0.09418696 0.02029997 -0.007919251 0.09385615 0.02254998 -0.007919251 0.09385615 0.02029997 -0.007806718 0.09350198 0.02254998 -0.007806718 0.09350198 0.02029997 -0.007753968 0.09313416 0.02029997 -0.007753968 0.09313416 0.02254998 -0.007762491 0.0927627 0.02029997 -0.007762491 0.0927627 0.02254998 -0.007832109 0.09239757 0.02254998 -0.007832109 0.09239757 0.02029997 -0.007960796 0.092049 0.02254998 -0.007960796 0.092049 0.02029997 -0.008145153 0.09172636 0.02254998 -0.008145153 0.09172636 0.02029997 -0.008380055 0.09143835 0.02254998 -0.008380055 0.09143835 0.02029997 -0.008659183 0.09119307 0.02029997 -0.008659183 0.09119307 0.02254998 -0.008974909 0.09099709 0.02029997 -0.008974909 0.09099709 0.02254998 -0.00931853 0.09085565 0.02029997 -0.00931853 0.09085565 0.02254998 -0.009680747 0.0907728 0.02254998 -0.009680747 0.0907728 0.02029997 -0.01005166 0.09075057 0.02254998 -0.01005166 0.09075057 0.02029997 -0.01042127 0.09078979 0.02029997 -0.01042127 0.09078979 0.02254998 -0.01077926 0.09088927 0.02254998 -0.01077926 0.09088927 0.02029997 -0.01111608 0.09104627 0.02254998 -0.01111608 0.09104627 0.02029997 -0.01142239 0.09125667 0.02254998 -0.01142239 0.09125667 0.02029997 -0.01168996 0.09151458 0.02029997 -0.01168996 0.09151458 0.02254998 -0.01191139 0.09181296 0.02029997 -0.01191139 0.09181296 0.02254998 -0.01208066 0.09214377 0.02029997 -0.01208066 0.09214377 0.02254998 -0.08470708 0.03729319 0.01029998 -0.08456897 0.03806209 0.01029998 -0.08461719 0.03821498 0.01029998 -0.08649069 0.03753995 0.01029998 -0.08652645 0.0376963 0.01029998 -0.08492308 0.03705745 0.01029998 -0.08505648 0.03696858 0.01029998 -0.08520257 0.03690224 0.01029998 -0.0865367 0.03785628 0.01029998 -0.0865212 0.0380159 0.01029998 -0.0864802 0.03817099 0.01029998 -0.08641487 0.0383175 0.01029998 -0.0848056 0.03716659 0.01029998 -0.08632689 0.03845155 0.01029998 -0.08621859 0.03856974 0.01029998 -0.08609271 0.03866916 0.01029998 -0.08595246 0.03874695 0.01029998 -0.0858016 0.03880137 0.01029998 -0.08517146 0.03876549 0.01029998 -0.08502775 0.03869426 0.01029998 -0.08489739 0.03860098 0.01029998 -0.0853573 0.03686016 0.01029998 -0.08551681 0.03684347 0.01029998 -0.0856769 0.03685259 0.01029998 -0.08643031 0.03739136 0.01029998 -0.085644 0.03883075 0.01029998 -0.08548367 0.03883457 0.01029998 -0.08532476 0.03881269 0.01029998 -0.08454591 0.03790336 0.01029998 -0.08454859 0.03774297 0.01029998 -0.08463019 0.03743398 0.01029998 -0.0845769 0.03758519 0.01029998 -0.08478355 0.03848797 0.01029998 -0.08468937 0.03835827 0.01029998 -0.08583348 0.03688728 0.01029998 -0.0859825 0.03694665 0.01029998 -0.08634686 0.03725439 0.01029998 -0.08611994 0.03702914 0.01029998 -0.08624249 0.03713268 0.01029998 0.01018309 -0.09397947 0.01029998 0.009863436 -0.0939871 0.01029998 0.009706854 -0.09395235 0.01029998 0.01036876 -0.09207427 0.01029998 0.01021546 -0.09202706 0.01029998 0.01051247 -0.09214538 0.01029998 0.01064294 -0.09223866 0.01029998 0.01002359 -0.09399616 0.01029998 0.01075679 -0.09235167 0.01029998 0.01096338 -0.0932545 0.01029998 0.01005667 -0.09200507 0.01029998 0.01092308 -0.09262466 0.01029998 0.01097136 -0.09277766 0.01029998 0.01099175 -0.09309667 0.01029998 0.01099449 -0.09293639 0.01029998 0.01091009 -0.09340578 0.01029998 0.01083326 -0.0935465 0.01029998 0.01085096 -0.09248149 0.01029998 0.01073479 -0.09367311 0.01029998 0.01061725 -0.0937823 0.01029998 0.009896337 -0.09200888 0.01029998 0.009557843 -0.09389311 0.01029998 0.009420335 -0.09381055 0.01029998 0.009297788 -0.09370708 0.01029998 0.0104838 -0.09387117 0.01029998 0.01033776 -0.09393745 0.01029998 0.00919348 -0.09358525 0.01029998 0.009738683 -0.09203839 0.01029998 0.009110033 -0.0934484 0.01029998 0.009049654 -0.0932998 0.01029998 0.009013831 -0.09314346 0.01029998 0.009003639 -0.09298336 0.01029998 0.009019196 -0.0928238 0.01029998 0.009060144 -0.09266877 0.01029998 0.009125471 -0.09252226 0.01029998 0.009213387 -0.09238815 0.01029998 0.009321749 -0.09226989 0.01029998 0.009587824 -0.09209269 0.01029998 0.009447634 -0.09217059 0.01029998 0.01219326 -0.092498 0.02029997 0.01224595 -0.09286576 0.02254998 0.01224595 -0.09286576 0.02029997 0.01223737 -0.09323728 0.02254998 0.01223737 -0.09323728 0.02029997 0.01216787 -0.09360235 0.02029997 0.01216787 -0.09360235 0.02254998 0.01203918 -0.09395098 0.02254998 0.01203918 -0.09395098 0.02029997 0.01185476 -0.09427356 0.02029997 0.01185476 -0.09427356 0.02254998 0.01161986 -0.09456145 0.02254998 0.01161986 -0.09456145 0.02029997 0.01134079 -0.0948069 0.02254998 0.01134079 -0.0948069 0.02029997 0.01102507 -0.09500288 0.02029997 0.01102507 -0.09500288 0.02254998 0.01068139 -0.09514427 0.02029997 0.01068139 -0.09514427 0.02254998 0.01031917 -0.09522718 0.02254998 0.009948253 -0.09524935 0.02254998 0.01031917 -0.09522718 0.02029997 0.009578704 -0.09521019 0.02254998 0.009948253 -0.09524935 0.02029997 0.009578704 -0.09521019 0.02029997 0.009220659 -0.09511065 0.02254998 0.009220659 -0.09511065 0.02029997 0.008883893 -0.09495365 0.02254998 0.008883893 -0.09495365 0.02029997 0.008577525 -0.09474331 0.02254998 0.008310019 -0.0944854 0.02254998 0.008577525 -0.09474331 0.02029997 0.008310019 -0.0944854 0.02029997 0.008088529 -0.09418696 0.02254998 0.008088529 -0.09418696 0.02029997 0.007919251 -0.09385615 0.02029997 0.007919251 -0.09385615 0.02254998 0.007806718 -0.09350198 0.02254998 0.007806718 -0.09350198 0.02029997 0.007753968 -0.09313416 0.02254998 0.007762491 -0.0927627 0.02254998 0.007753968 -0.09313416 0.02029997 0.007762491 -0.0927627 0.02029997 0.007832109 -0.09239757 0.02254998 0.007832109 -0.09239757 0.02029997 0.007960796 -0.092049 0.02254998 0.007960796 -0.092049 0.02029997 0.008145153 -0.09172636 0.02029997 0.008145153 -0.09172636 0.02254998 0.008380055 -0.09143835 0.02254998 0.008380055 -0.09143835 0.02029997 0.008659183 -0.09119307 0.02029997 0.008659183 -0.09119307 0.02254998 0.008974909 -0.09099709 0.02029997 0.008974909 -0.09099709 0.02254998 0.00931853 -0.09085565 0.02029997 0.00931853 -0.09085565 0.02254998 0.009680747 -0.0907728 0.02254998 0.01005166 -0.09075057 0.02254998 0.009680747 -0.0907728 0.02029997 0.01005166 -0.09075057 0.02029997 0.01042127 -0.09078979 0.02029997 0.01042127 -0.09078979 0.02254998 0.01077926 -0.09088927 0.02254998 0.01077926 -0.09088927 0.02029997 0.01111608 -0.09104627 0.02254998 0.01111608 -0.09104627 0.02029997 0.01142239 -0.09125667 0.02029997 0.01142239 -0.09125667 0.02254998 0.01168996 -0.09151458 0.02254998 0.01168996 -0.09151458 0.02029997 0.01191139 -0.09181296 0.02254998 0.01191139 -0.09181296 0.02029997 0.01208066 -0.09214377 0.02254998 0.01208066 -0.09214377 0.02029997 0.01219326 -0.092498 0.02254998 0.08517146 -0.03876549 0.01029998 0.08532476 -0.03881269 0.01029998 0.08551681 -0.03684347 0.01029998 0.0856769 -0.03685259 0.01029998 0.0859825 -0.03694665 0.01029998 0.08611994 -0.03702914 0.01029998 0.08502775 -0.03869426 0.01029998 0.08489739 -0.03860098 0.01029998 0.08583348 -0.03688728 0.01029998 0.08609271 -0.03866916 0.01029998 0.08595246 -0.03874695 0.01029998 0.08456897 -0.03806209 0.01029998 0.08470708 -0.03729319 0.01029998 0.08454591 -0.03790336 0.01029998 0.08463019 -0.03743398 0.01029998 0.08454859 -0.03774297 0.01029998 0.0845769 -0.03758519 0.01029998 0.08461719 -0.03821498 0.01029998 0.08505648 -0.03696858 0.01029998 0.08492308 -0.03705745 0.01029998 0.0848056 -0.03716659 0.01029998 0.08468937 -0.03835827 0.01029998 0.08478355 -0.03848797 0.01029998 0.08520257 -0.03690224 0.01029998 0.0853573 -0.03686016 0.01029998 0.0864802 -0.03817099 0.01029998 0.08641487 -0.0383175 0.01029998 0.0858016 -0.03880137 0.01029998 0.085644 -0.03883075 0.01029998 0.08548367 -0.03883457 0.01029998 0.08643031 -0.03739136 0.01029998 0.08649069 -0.03753995 0.01029998 0.08634686 -0.03725439 0.01029998 0.08652645 -0.0376963 0.01029998 0.0865367 -0.03785628 0.01029998 0.0865212 -0.0380159 0.01029998 0.08624249 -0.03713268 0.01029998 0.08632689 -0.03845155 0.01029998 0.08621859 -0.03856974 0.01029998 0.08583921 -0.03560966 0.02029997 0.0862022 -0.03568929 0.02029997 0.08654719 -0.03582757 0.02254998 0.08654719 -0.03582757 0.02029997 0.08686459 -0.03602069 0.02029997 0.08686459 -0.03602069 0.02254998 0.08714598 -0.03626346 0.02254998 0.08714598 -0.03626346 0.02029997 0.0873835 -0.03654927 0.02254998 0.0873835 -0.03654927 0.02029997 0.08757078 -0.03687018 0.02254998 0.08757078 -0.03687018 0.02029997 0.08770269 -0.03721755 0.02029997 0.08770269 -0.03721755 0.02254998 0.08777558 -0.03758198 0.02254998 0.08777558 -0.03758198 0.02029997 0.0877875 -0.03795337 0.02254998 0.0877875 -0.03795337 0.02029997 0.08773809 -0.03832179 0.02254998 0.08773809 -0.03832179 0.02029997 0.08762878 -0.03867685 0.02254998 0.08762878 -0.03867685 0.02029997 0.08746248 -0.03900927 0.02254998 0.08746248 -0.03900927 0.02029997 0.08724379 -0.03930968 0.02029997 0.08724379 -0.03930968 0.02254998 0.08697855 -0.03956997 0.02254998 0.08697855 -0.03956997 0.02029997 0.08667415 -0.03978317 0.02254998 0.08667415 -0.03978317 0.02029997 0.08633887 -0.03994327 0.02029997 0.08633887 -0.03994327 0.02254998 0.08598178 -0.04004597 0.02254998 0.08598178 -0.04004597 0.02029997 0.08561259 -0.04008859 0.02029997 0.08561259 -0.04008859 0.02254998 0.08524149 -0.04006975 0.02029997 0.08524149 -0.04006975 0.02254998 0.0848785 -0.03999018 0.02254998 0.0848785 -0.03999018 0.02029997 0.08453357 -0.0398519 0.02254998 0.08453357 -0.0398519 0.02029997 0.08421605 -0.03965878 0.02254998 0.08421605 -0.03965878 0.02029997 0.08393478 -0.03941595 0.02254998 0.08393478 -0.03941595 0.02029997 0.08369719 -0.03913015 0.02029997 0.08369719 -0.03913015 0.02254998 0.08350998 -0.03880929 0.02029997 0.08350998 -0.03880929 0.02254998 0.08337807 -0.0384618 0.02254998 0.08337807 -0.0384618 0.02029997 0.08330518 -0.0380975 0.02254998 0.08330518 -0.0380975 0.02029997 0.08329319 -0.03772598 0.02254998 0.08329319 -0.03772598 0.02029997 0.08334261 -0.03735768 0.02254998 0.08334261 -0.03735768 0.02029997 0.08345186 -0.03700256 0.02254998 0.08345186 -0.03700256 0.02029997 0.08361816 -0.03667014 0.02029997 0.08361816 -0.03667014 0.02254998 0.08383685 -0.0363698 0.02254998 0.08410209 -0.03610944 0.02254998 0.08383685 -0.0363698 0.02029997 0.08410209 -0.03610944 0.02029997 0.08440649 -0.0358963 0.02254998 0.08474177 -0.0357362 0.02254998 0.08440649 -0.0358963 0.02029997 0.08474177 -0.0357362 0.02029997 0.08509898 -0.0356335 0.02254998 0.08546805 -0.03559088 0.02254998 0.08509898 -0.0356335 0.02029997 0.08546805 -0.03559088 0.02029997 0.08583921 -0.03560966 0.02254998 0.0862022 -0.03568929 0.02254998 -0.02672445 -0.02246427 -0.001699984 -0.02672445 -0.02246427 -0.002999961 -0.02607816 -0.02213048 -0.001699984 -0.02543175 -0.0217967 -0.001699984 -0.02481949 -0.02218949 -0.001699984 -0.02420729 -0.02258235 -0.001699984 -0.02424138 -0.02330905 -0.001699984 -0.02427548 -0.02403569 -0.001699984 -0.02734398 -0.0216369 -0.002999961 -0.02716696 -0.02504539 -0.002999961 -0.02736765 -0.0248357 -0.002999961 -0.02612829 -0.02088189 -0.002999961 -0.02584379 -0.02082419 -0.002999961 -0.0267927 -0.02391755 -0.002999961 -0.02788555 -0.02380788 -0.002999961 -0.02375465 -0.02496945 -0.002999961 -0.02356356 -0.02475094 -0.002999961 -0.02427548 -0.02403569 -0.002999961 -0.02354168 -0.02177774 -0.002999961 -0.02640396 -0.02097284 -0.002999961 -0.02555447 -0.02080059 -0.002999961 -0.02543175 -0.0217967 -0.002999961 -0.02643746 -0.02551347 -0.002999961 -0.02316218 -0.02398276 -0.002999961 -0.02339965 -0.02451139 -0.002999961 -0.02691358 -0.02124887 -0.002999961 -0.02793484 -0.02352178 -0.002999961 -0.02556818 -0.02470326 -0.002999961 -0.02446269 -0.0254696 -0.002999961 -0.02559065 -0.0256983 -0.002999961 -0.02338129 -0.02201968 -0.002999961 -0.02469819 -0.02093487 -0.002999961 -0.02442997 -0.02104598 -0.002999961 -0.02420729 -0.02258235 -0.002999961 -0.02394229 -0.02135896 -0.002999961 -0.02305328 -0.0231229 -0.002999961 -0.02442735 -0.02071779 0 -0.02487134 -0.0205751 -0.002699971 -0.02487069 -0.02057296 0 -0.02533239 -0.02050918 -0.002699971 -0.02533215 -0.02050507 0 -0.02579849 -0.02051627 0 -0.02669018 -0.02077609 -0.002699971 -0.0262562 -0.02060598 0 -0.02669215 -0.02077186 0 -0.02680987 -0.020832 -0.002699971 -0.02708667 -0.0210039 -0.002699971 -0.02709388 -0.02100896 0 -0.02744966 -0.02131056 0 -0.02774786 -0.02166908 -0.002699971 -0.02774935 -0.02166795 0 -0.02756989 -0.02143937 -0.002699971 -0.0277695 -0.02169686 -0.002699971 -0.0279805 -0.02207255 -0.002699971 -0.02798438 -0.02207088 0 -0.02793717 -0.02197617 -0.002699971 -0.0281682 -0.02258437 -0.002699971 -0.02814787 -0.02250766 0 -0.02823525 -0.02296584 0 -0.02824395 -0.02343219 0 -0.02824985 -0.02322965 -0.002699971 -0.02823227 -0.02296608 -0.002699971 -0.02822816 -0.02290457 -0.002699971 -0.02817779 -0.02387619 -0.002699971 -0.02817368 -0.02389329 0 -0.02817267 -0.02389305 -0.002699971 -0.02808487 -0.02418845 -0.002699971 -0.02780538 -0.02474659 -0.002699971 -0.02780658 -0.02474725 0 -0.02802646 -0.02433586 0 -0.02779209 -0.02476936 -0.002699971 -0.02759629 -0.02502977 -0.002699971 -0.02752035 -0.02511554 0 -0.02737104 -0.02526527 -0.002699971 -0.02717608 -0.0254302 0 -0.02751719 -0.02511245 -0.002699971 -0.02711957 -0.0254724 -0.002699971 -0.02655225 -0.02579069 -0.002699971 -0.02678209 -0.02567917 -0.002699971 -0.02678346 -0.02568209 0 -0.0262444 -0.02589726 -0.002699971 -0.02592605 -0.02596676 -0.002699971 -0.02635395 -0.025864 0 -0.02589994 -0.02597075 0 -0.02543437 -0.02599918 0 -0.02495336 -0.02594506 -0.002699971 -0.02497065 -0.02594858 0 -0.0245223 -0.02582025 0 -0.02410185 -0.02561807 0 -0.02433568 -0.02574139 -0.002699971 -0.02404916 -0.02558618 -0.002699971 -0.02339285 -0.02501708 0 -0.02372175 -0.02534776 0 -0.02339607 -0.02501428 -0.002699971 -0.02312457 -0.02463555 0 -0.02312618 -0.02463465 -0.002699971 -0.02299159 -0.02437704 -0.002699971 -0.02292907 -0.02421247 -0.002699971 -0.0229246 -0.02421414 0 -0.0228759 -0.02407246 -0.002699971 -0.02279865 -0.02376508 0 -0.02275609 -0.02343314 -0.002699971 -0.02278137 -0.02283567 0 -0.02275049 -0.02330106 0 -0.02278989 -0.02278345 -0.002699971 -0.02286398 -0.0224663 -0.002699971 -0.0229752 -0.02215999 -0.002699971 -0.02289044 -0.02238219 0 -0.02289408 -0.02238345 -0.002699971 -0.02307826 -0.02195549 -0.002699971 -0.02312189 -0.02186906 -0.002699971 -0.02307468 -0.0219537 0 -0.02332866 -0.02156245 0 -0.02364826 -0.0212233 -0.002699971 -0.0236451 -0.02121978 0 -0.02401489 -0.02093547 0 -0.02401489 -0.02093547 -0.002699971 -0.02275508 -0.02330106 -0.002699971 -0.02464306 -0.02584755 -0.002792656 -0.02802205 -0.02433395 -0.002699971 -0.0280711 -0.02418345 -0.002792656 -0.02744615 -0.02131396 -0.002699971 -0.02733129 -0.02121818 -0.002792656 -0.02429896 -0.02077609 -0.002699971 -0.02316558 -0.02224218 -0.002985298 -0.02802699 -0.02353209 -0.002985298 -0.02305537 -0.02341318 -0.002999961 -0.02296066 -0.02311807 -0.002985298 -0.02296286 -0.02341938 -0.002985298 -0.02309185 -0.02370119 -0.002999961 -0.02326518 -0.0242542 -0.002999961 -0.02442336 -0.02555358 -0.002985298 -0.02501308 -0.02565109 -0.002999961 -0.02473247 -0.02557665 -0.002999961 -0.02694284 -0.02522999 -0.002999961 -0.02743828 -0.02489566 -0.002985298 -0.02780288 -0.02408605 -0.002999961 -0.02768784 -0.02435255 -0.002999961 -0.02787697 -0.02234709 -0.002985298 -0.02752184 -0.02186638 -0.002999961 -0.02714025 -0.02143019 -0.002999961 -0.02741378 -0.02157586 -0.002985298 -0.02497768 -0.02085626 -0.002999961 -0.02438956 -0.02096259 -0.002985298 -0.02643817 -0.02088665 -0.002985298 -0.02794986 -0.02323186 -0.002999961 -0.02804255 -0.02323114 -0.002985298 -0.02793055 -0.0229423 -0.002999961 -0.02618825 -0.02569776 -0.002985298 -0.02647298 -0.02559918 -0.002985298 -0.02349036 -0.02480775 -0.002985298 -0.02325069 -0.0222789 -0.002999961 -0.0267111 -0.02101427 -0.002985298 -0.02666699 -0.02109575 -0.002999961 -0.0262109 -0.02577829 -0.002942681 -0.02590686 -0.02584457 -0.002942681 -0.02589398 -0.02576196 -0.002985298 -0.02616316 -0.02560847 -0.002999961 -0.02587956 -0.02567034 -0.002999961 -0.02342426 -0.02485895 -0.002942681 -0.02332019 -0.02455919 -0.002985298 -0.02330106 -0.02197307 -0.002985298 -0.0273028 -0.02124989 -0.002876281 -0.02701526 -0.02110487 -0.002942681 -0.02696704 -0.02117317 -0.002985298 -0.02720236 -0.02136129 -0.002985298 -0.02803099 -0.02416896 -0.002876281 -0.02805727 -0.02384799 -0.002942681 -0.02797585 -0.02382898 -0.002985298 -0.02789008 -0.02411776 -0.002985298 -0.02559715 -0.02587449 -0.002942681 -0.02358186 -0.02513974 -0.002876281 -0.02381879 -0.02535337 -0.002876281 -0.02324849 -0.02460217 -0.002942681 -0.02340066 -0.02167177 -0.002942681 -0.0234676 -0.02172195 -0.002985298 -0.02372956 -0.02155649 -0.002999961 -0.02524107 -0.0205698 -0.002876281 -0.02625536 -0.02060848 -0.002699971 -0.0262053 -0.02059197 -0.002699971 -0.02620148 -0.02060616 -0.002792656 -0.0255599 -0.02055799 -0.002876281 -0.02526438 -0.02081125 -0.002999961 -0.02586859 -0.02064967 -0.002942681 -0.02585685 -0.02073246 -0.002985298 -0.02649354 -0.0207473 -0.002876281 -0.02680289 -0.02084487 -0.002792656 -0.02617359 -0.02071148 -0.002942681 -0.02707815 -0.02101588 -0.002792656 -0.02823519 -0.02322977 -0.002792656 -0.02819257 -0.02323007 -0.002876281 -0.02817606 -0.02354866 -0.002876281 -0.02812629 -0.02323055 -0.002942681 -0.02683818 -0.0256356 -0.002792656 -0.02681738 -0.0255984 -0.002876281 -0.02589976 -0.02596926 -0.002699971 -0.02592378 -0.02595227 -0.002792656 -0.02624034 -0.02588319 -0.002792656 -0.02650499 -0.02567636 -0.002942681 -0.02653038 -0.02573776 -0.002876281 -0.02678489 -0.02554059 -0.002942681 -0.02333807 -0.02492576 -0.002792656 -0.02315509 -0.02465826 -0.002792656 -0.02337175 -0.02489966 -0.002876281 -0.02362906 -0.02509319 -0.002942681 -0.02287805 -0.02247047 -0.002792656 -0.02291899 -0.02248257 -0.002876281 -0.02302777 -0.0221827 -0.002876281 -0.02298867 -0.02216577 -0.002792656 -0.02330189 -0.0215975 -0.002699971 -0.02313458 -0.02187639 -0.002792656 -0.02417689 -0.02118796 -0.002999961 -0.02435296 -0.02088725 -0.002942681 -0.02408164 -0.0210396 -0.002942681 -0.02432405 -0.02082759 -0.002876281 -0.02460485 -0.02066528 -0.002792656 -0.0243054 -0.02078926 -0.002792656 -0.02460008 -0.0206514 -0.002699971 -0.0244292 -0.02072215 -0.002699971 -0.02491366 -0.02056318 -0.002699971 -0.02494007 -0.020684 -0.002942681 -0.02466785 -0.02084726 -0.002985298 -0.0246405 -0.02076828 -0.002942681 -0.02492588 -0.02061915 -0.002876281 -0.0246188 -0.02070558 -0.002876281 -0.02491676 -0.02057754 -0.002792656 -0.02495789 -0.02076578 -0.002985298 -0.02524745 -0.02063578 -0.002942681 -0.02523696 -0.02052736 -0.002792656 -0.02523559 -0.0205127 -0.002699971 -0.02588587 -0.02052718 -0.002699971 -0.02588385 -0.02054178 -0.002792656 -0.0257982 -0.02051997 -0.002699971 -0.02556085 -0.02051538 -0.002792656 -0.02556115 -0.02050065 -0.002699971 -0.0252555 -0.02071905 -0.002985298 -0.02555656 -0.0207079 -0.002985298 -0.02555847 -0.02062427 -0.002942681 -0.02587789 -0.02058386 -0.002876281 -0.02619057 -0.0206474 -0.002876281 -0.02650928 -0.02070766 -0.002792656 -0.02651464 -0.02069395 -0.002699971 -0.02734118 -0.02120727 -0.002699971 -0.02709347 -0.02100938 -0.002699971 -0.02705359 -0.02105069 -0.002876281 -0.02678257 -0.02088236 -0.002876281 -0.02675098 -0.02094066 -0.002942681 -0.02646905 -0.02080899 -0.002942681 -0.02615207 -0.0207923 -0.002985298 -0.02747678 -0.02152079 -0.002942681 -0.02725839 -0.02129918 -0.002942681 -0.02752667 -0.0214771 -0.002876281 -0.0276674 -0.02176678 -0.002942681 -0.02772217 -0.02172929 -0.002876281 -0.0277574 -0.02170515 -0.002792656 -0.0275588 -0.02144908 -0.002792656 -0.02775347 -0.02207225 -0.002985298 -0.02759838 -0.02181398 -0.002985298 -0.02782756 -0.02203345 -0.002942681 -0.02792418 -0.02198308 -0.002792656 -0.02767127 -0.02211517 -0.002999961 -0.02795517 -0.02231734 -0.002942681 -0.02805697 -0.02227866 -0.002792656 -0.02788639 -0.02200275 -0.002876281 -0.02815395 -0.02258789 -0.002792656 -0.02814447 -0.0225088 -0.002699971 -0.02779024 -0.02237999 -0.002999961 -0.02796709 -0.0226345 -0.002985298 -0.02804815 -0.0226143 -0.002942681 -0.02801716 -0.0222938 -0.002876281 -0.02811259 -0.02259814 -0.002876281 -0.02807074 -0.02227336 -0.002699971 -0.02787709 -0.02265697 -0.002999961 -0.02810549 -0.02292007 -0.002942681 -0.02817136 -0.02291178 -0.002876281 -0.02821838 -0.02355349 -0.002792656 -0.02823299 -0.02355509 -0.002699971 -0.02823936 -0.02343195 -0.002699971 -0.02821367 -0.02290648 -0.002792656 -0.02812194 -0.02386307 -0.002876281 -0.02816349 -0.02387285 -0.002792656 -0.02811008 -0.02354139 -0.002942681 -0.02802258 -0.02293056 -0.002985298 -0.0279687 -0.02414625 -0.002942681 -0.02790457 -0.02446186 -0.002876281 -0.02777987 -0.02476125 -0.002792656 -0.02761936 -0.02465486 -0.002985298 -0.02777057 -0.02439427 -0.002985298 -0.02784526 -0.024432 -0.002942681 -0.02768909 -0.02470105 -0.002942681 -0.02794259 -0.02448099 -0.002792656 -0.02795577 -0.02448755 -0.002699971 -0.02754205 -0.02460366 -0.002999961 -0.02755266 -0.02499276 -0.002876281 -0.02774435 -0.02473765 -0.002876281 -0.02758514 -0.0250203 -0.002792656 -0.02750205 -0.02494978 -0.002942681 -0.02733206 -0.02522325 -0.002876281 -0.02723008 -0.0251134 -0.002985298 -0.027287 -0.02517467 -0.002942681 -0.02736109 -0.02525448 -0.002792656 -0.02717399 -0.02542769 -0.002699971 -0.0269975 -0.02530485 -0.002985298 -0.02704679 -0.0253725 -0.002942681 -0.0270859 -0.02542608 -0.002876281 -0.02711099 -0.0254606 -0.002792656 -0.02684539 -0.02564835 -0.002699971 -0.02635258 -0.02585989 -0.002699971 -0.02654665 -0.0257771 -0.002792656 -0.0256018 -0.02599805 -0.002699971 -0.02591717 -0.02591019 -0.002876281 -0.0262289 -0.02584218 -0.002876281 -0.02669858 -0.02538675 -0.002999961 -0.02674394 -0.02546757 -0.002985298 -0.025276 -0.0259909 -0.002699971 -0.02559405 -0.02579098 -0.002985298 -0.02528065 -0.0259338 -0.002876281 -0.02559965 -0.02594089 -0.002876281 -0.02560114 -0.02598339 -0.002792656 -0.02543449 -0.02599436 -0.002699971 -0.02497088 -0.02594757 -0.002699971 -0.0253005 -0.02569186 -0.002999961 -0.02529287 -0.02578425 -0.002985298 -0.02499455 -0.02574199 -0.002985298 -0.02528607 -0.02586758 -0.002942681 -0.02527719 -0.02597618 -0.002792656 -0.02467715 -0.02574408 -0.002942681 -0.02497798 -0.02582389 -0.002942681 -0.02465647 -0.0258072 -0.002876281 -0.02496474 -0.02588897 -0.002876281 -0.0249564 -0.0259307 -0.002792656 -0.02463847 -0.02586156 -0.002699971 -0.02470338 -0.02566468 -0.002985298 -0.02438795 -0.02562928 -0.002942681 -0.02435988 -0.02568936 -0.002876281 -0.02452385 -0.02581608 -0.002699971 -0.02415847 -0.02541005 -0.002985298 -0.02407938 -0.02553749 -0.002876281 -0.02434188 -0.0257281 -0.002792656 -0.0241034 -0.02561545 -0.002699971 -0.02391248 -0.02523618 -0.002985298 -0.02386027 -0.02530157 -0.002942681 -0.02411437 -0.0254811 -0.002942681 -0.02379214 -0.02538669 -0.002792656 -0.02405685 -0.02557367 -0.002792656 -0.02378308 -0.02539819 -0.002699971 -0.02314245 -0.02466589 -0.002699971 -0.02332645 -0.02493476 -0.002699971 -0.02355146 -0.02516967 -0.002792656 -0.02354097 -0.02517998 -0.002699971 -0.02372419 -0.02534508 -0.002699971 -0.02300494 -0.02437108 -0.002792656 -0.02319157 -0.02463638 -0.002876281 -0.02368867 -0.02503448 -0.002985298 -0.02397036 -0.02516376 -0.002999961 -0.02420747 -0.02533125 -0.002999961 -0.02307367 -0.02401047 -0.002985298 -0.02318066 -0.02429217 -0.002985298 -0.02310436 -0.02432638 -0.002942681 -0.02299386 -0.02403557 -0.002942681 -0.02293056 -0.02405536 -0.002876281 -0.02304387 -0.02435356 -0.002876281 -0.02288985 -0.02406817 -0.002792656 -0.02279698 -0.02375638 -0.002699971 -0.02300077 -0.02371817 -0.002985298 -0.02291858 -0.02373355 -0.002942681 -0.02285325 -0.02374589 -0.002876281 -0.02281147 -0.0237537 -0.002792656 -0.02279919 -0.02376484 -0.002699971 -0.02281326 -0.02342927 -0.002876281 -0.02277076 -0.02343219 -0.002792656 -0.02287948 -0.02342486 -0.002942681 -0.02281087 -0.02311027 -0.002876281 -0.02275365 -0.02310729 -0.002699971 -0.02287715 -0.02311378 -0.002942681 -0.02280426 -0.02278596 -0.002792656 -0.02276837 -0.02310806 -0.002792656 -0.02278399 -0.02283596 -0.002699971 -0.02308547 -0.02283436 -0.002999961 -0.0230627 -0.02252537 -0.002985298 -0.0229941 -0.02281868 -0.002985298 -0.02298259 -0.02250146 -0.002942681 -0.02291166 -0.02280449 -0.002942681 -0.02284628 -0.02279329 -0.002876281 -0.02333039 -0.02156388 -0.002699971 -0.02334767 -0.02163189 -0.002876281 -0.02331358 -0.02160626 -0.002792656 -0.02317136 -0.02189779 -0.002876281 -0.02322876 -0.02193117 -0.002942681 -0.02308875 -0.02220898 -0.002942681 -0.02315157 -0.02255177 -0.002999961 -0.02375149 -0.0211274 -0.002699971 -0.02366256 -0.02149236 -0.002985298 -0.02360206 -0.0214346 -0.002942681 -0.02383017 -0.02122288 -0.002942681 -0.02378797 -0.02117156 -0.002876281 -0.0235542 -0.02138864 -0.002876281 -0.02352339 -0.0213592 -0.002792656 -0.02351278 -0.02134907 -0.002699971 -0.02388328 -0.02128738 -0.002985298 -0.02412676 -0.02110999 -0.002985298 -0.02404576 -0.02098369 -0.002876281 -0.02402275 -0.02094787 -0.002792656 -0.02376085 -0.02113866 -0.002792656 -0.0265907 -0.02388077 -0.001699984 -0.02652585 -0.02398157 -0.001699984 -0.0267927 -0.02391755 -0.001699984 -0.02645164 -0.0240758 -0.001699984 -0.02675849 -0.02331078 -0.001699984 -0.02675855 -0.02319085 -0.001699984 -0.02674698 -0.02343016 -0.001699984 -0.02672427 -0.02354788 -0.001699984 -0.02669036 -0.02366286 -0.001699984 -0.02664577 -0.0237742 -0.001699984 -0.02636885 -0.02416247 -0.001699984 -0.02627819 -0.02424097 -0.001699984 -0.0261805 -0.02431046 -0.001699984 -0.02405905 0.02345126 -0.001699984 -0.02433216 0.02277696 -0.001699984 -0.02460515 0.02210265 -0.001699984 -0.02532565 0.0220021 -0.001699984 -0.02604615 0.02190148 -0.001699984 -0.02694088 0.02304869 -0.001699984 -0.02666777 0.023723 -0.001699984 -0.02639478 0.02439725 -0.001699984 -0.02567428 0.02449786 -0.001699984 -0.02495378 0.02459847 -0.001699984 -0.02559566 0.0208019 -0.002999961 -0.02734076 0.02486675 -0.002999961 -0.02713656 0.02507317 -0.002999961 -0.026703 0.02111566 -0.002999961 -0.02604615 0.02190148 -0.002999961 -0.02616798 0.02089279 -0.002999961 -0.02666258 0.02540659 -0.002999961 -0.02794986 0.02327305 -0.002999961 -0.02792996 0.02356266 -0.002999961 -0.02778846 0.02412468 -0.002999961 -0.02639478 0.02439725 -0.002999961 -0.02751904 0.02463775 -0.002999961 -0.02780455 0.02241855 -0.002999961 -0.02694088 0.02304869 -0.002999961 -0.02793538 0.02298307 -0.002999961 -0.02305579 0.02308177 -0.002999961 -0.02495378 0.02459847 -0.002999961 -0.02525949 0.02568817 -0.002999961 -0.02340227 0.02198427 -0.002999961 -0.02356666 0.02174508 -0.002999961 -0.02397429 0.02133309 -0.002999961 -0.02393835 0.0251379 -0.002999961 -0.0237261 0.02493989 -0.002999961 -0.02405905 0.02345126 -0.002999961 -0.02353864 0.02471828 -0.002999961 -0.02337878 0.02447599 -0.002999961 -0.02717065 0.02145797 -0.002999961 -0.02769005 0.02215176 -0.002999961 -0.02316367 0.02251237 -0.002999961 -0.02460515 0.02210265 -0.002999961 -0.02588039 0.02597355 0 -0.02633517 0.02587008 0 -0.02619987 0.02590948 -0.002699971 -0.02708208 0.02549928 -0.002699971 -0.026766 0.02569127 0 -0.0271604 0.02544218 0 -0.0271579 0.02543896 -0.002699971 -0.02750694 0.02513009 0 -0.02776628 0.02480769 -0.002699971 -0.02779579 0.02476376 0 -0.02801859 0.0243541 0 -0.02816849 0.02391237 -0.002699971 -0.02816897 0.02391248 0 -0.02823537 0.02298557 -0.002699971 -0.02823728 0.02298545 0 -0.02824985 0.02327585 -0.002699971 -0.02824258 0.02345186 0 -0.02823358 0.02295047 -0.002699971 -0.02799278 0.02208876 0 -0.02808678 0.02231675 -0.002699971 -0.02815318 0.02252668 0 -0.02776068 0.02168416 0 -0.02746349 0.02132457 0 -0.0277583 0.02168589 -0.002699971 -0.02710986 0.02102047 0 -0.02712416 0.0210309 -0.002699971 -0.02710938 0.0210213 -0.002699971 -0.02685028 0.02085429 -0.002699971 -0.02670997 0.0207805 0 -0.02627515 0.02061146 0 -0.02560734 0.02050209 -0.002699971 -0.02535188 0.02050399 0 -0.02581816 0.02051848 0 -0.02581769 0.02052277 -0.002699971 -0.02528154 0.0205087 -0.002699971 -0.02489 0.02056849 0 -0.02434068 0.0207563 -0.002699971 -0.02444559 0.02071017 0 -0.02403146 0.02092486 0 -0.0236597 0.02120649 0 -0.02378737 0.02109825 -0.002699971 -0.02332997 0.02156078 -0.002699971 -0.02334076 0.0215469 0 -0.02314537 0.02182924 -0.002699971 -0.02289676 0.02236348 0 -0.02299386 0.02211779 -0.002699971 -0.0230841 0.02193629 0 -0.02308809 0.02193838 -0.002699971 -0.02289956 0.02236455 -0.002699971 -0.02287757 0.02242207 -0.002699971 -0.02275437 0.02328139 -0.002699971 -0.02278798 0.02281665 -0.002699971 -0.02278435 0.02281618 0 -0.02275019 0.02328139 0 -0.02279496 0.02374565 0 -0.02291768 0.02419567 0 -0.02311468 0.0246185 0 -0.02311909 0.02462607 -0.002699971 -0.02338027 0.02500188 0 -0.02338379 0.0249989 -0.002699971 -0.0232985 0.02489799 -0.002699971 -0.0237472 0.02536898 -0.002699971 -0.02370679 0.02533489 0 -0.02401018 0.02556145 -0.002699971 -0.02429395 0.02572137 -0.002699971 -0.02408498 0.025608 0 -0.02459478 0.02584666 -0.002699971 -0.02450376 0.02581316 0 -0.02495169 0.0259425 -0.002699971 -0.02495127 0.02594465 0 -0.02541458 0.02599865 0 -0.02541476 0.02599388 -0.002699971 -0.02555555 0.02599936 -0.002699971 -0.02588039 0.02597355 -0.002699971 -0.0233103 0.02488917 -0.002792656 -0.02593159 0.02053409 -0.002699971 -0.02670776 0.02078479 -0.002699971 -0.02816468 0.02263259 -0.002792656 -0.02822744 0.02360087 -0.002699971 -0.02438485 0.02553516 -0.002985298 -0.02470839 0.02083367 -0.002985298 -0.02723389 0.02139008 -0.002985298 -0.02583885 0.02567636 -0.002999961 -0.02554947 0.02569949 -0.002999961 -0.02326726 0.02224129 -0.002999961 -0.02307528 0.02248448 -0.002985298 -0.02318274 0.02220308 -0.002985298 -0.02529805 0.02071529 -0.002985298 -0.02644205 0.0209884 -0.002999961 -0.02788674 0.02269697 -0.002999961 -0.02639937 0.02552896 -0.002999961 -0.02612346 0.02561926 -0.002999961 -0.02766895 0.02438914 -0.002999961 -0.02787506 0.02415776 -0.002985298 -0.02775108 0.0244323 -0.002985298 -0.02737087 0.02166807 -0.002999961 -0.02754479 0.02190047 -0.002999961 -0.02446717 0.02102828 -0.002999961 -0.02473717 0.02092176 -0.002999961 -0.02296328 0.02307546 -0.002985298 -0.02469348 0.02556347 -0.002999961 -0.02442556 0.02545177 -0.002999961 -0.02466297 0.02565097 -0.002985298 -0.02795326 0.02418756 -0.002942681 -0.0280469 0.02389085 -0.002942681 -0.02796578 0.02387046 -0.002985298 -0.0278759 0.02384787 -0.002999961 -0.02709025 0.02107709 -0.002876281 -0.02729088 0.02132898 -0.002942681 -0.02705109 0.02113056 -0.002942681 -0.02700167 0.02119809 -0.002985298 -0.02694696 0.02127289 -0.002999961 -0.02411895 0.02101606 -0.002942681 -0.02416288 0.02108716 -0.002985298 -0.02442806 0.02094429 -0.002985298 -0.02284538 0.02370125 -0.002876281 -0.02287685 0.02338087 -0.002942681 -0.02296048 0.0233767 -0.002985298 -0.02299326 0.02367615 -0.002985298 -0.02305299 0.02337205 -0.002999961 -0.02492058 0.02587956 -0.002876281 -0.02493488 0.02581477 -0.002942681 -0.02495288 0.02573305 -0.002985298 -0.02497279 0.02564257 -0.002999961 -0.02701085 0.02539819 -0.002942681 -0.02802187 0.02357447 -0.002985298 -0.02769196 0.02180337 -0.002942681 -0.02498328 0.020675 -0.002942681 -0.02408409 0.02095955 -0.002876281 -0.02382308 0.02114319 -0.002876281 -0.02386444 0.02119505 -0.002942681 -0.0242117 0.02116608 -0.002999961 -0.02285438 0.02274876 -0.002876281 -0.02291077 0.02369016 -0.002942681 -0.02306127 0.02396965 -0.002985298 -0.0230847 0.02366065 -0.002999961 -0.0231502 0.02394336 -0.002999961 -0.02523148 0.02597206 -0.002792656 -0.02523565 0.02592968 -0.002876281 -0.02525037 0.02578037 -0.002985298 -0.02779358 0.02476245 -0.002699971 -0.0275231 0.02502697 -0.002876281 -0.02729868 0.02525377 -0.002876281 -0.0272544 0.02520436 -0.002942681 -0.02741038 0.02492797 -0.002985298 -0.02766436 0.02473759 -0.002942681 -0.02788388 0.02450209 -0.002876281 -0.02805507 0.02422648 -0.002792656 -0.02815258 0.02391749 -0.002792656 -0.02816689 0.02392107 -0.002699971 -0.02758878 0.02148389 -0.002792656 -0.02755618 0.02151137 -0.002876281 -0.02736514 0.02124929 -0.002792656 -0.02750545 0.02155429 -0.002942681 -0.02496176 0.02056819 -0.002792656 -0.02403235 0.02092605 -0.002699971 -0.02406167 0.02092337 -0.002792656 -0.02434688 0.02076959 -0.002792656 -0.02466166 0.02069109 -0.002876281 -0.02468228 0.02075415 -0.002942681 -0.02281248 0.02274078 -0.002792656 -0.02277106 0.02306228 -0.002792656 -0.02278888 0.0237109 -0.002699971 -0.02280336 0.02370846 -0.002792656 -0.02276808 0.02338629 -0.002792656 -0.02281057 0.02338415 -0.002876281 -0.02281355 0.02306514 -0.002876281 -0.02291959 0.0227611 -0.002942681 -0.02430039 0.02570825 -0.002792656 -0.02490818 0.02593559 -0.002699971 -0.02431905 0.02566999 -0.002876281 -0.02618527 0.02585399 -0.002876281 -0.02587836 0.02595895 -0.002792656 -0.02614706 0.02570897 -0.002985298 -0.02643334 0.02561515 -0.002985298 -0.0261684 0.02578985 -0.002942681 -0.02619606 0.02589529 -0.002792656 -0.02633368 0.02586555 -0.002699971 -0.02670657 0.02548819 -0.002985298 -0.0264641 0.02569299 -0.002942681 -0.02674627 0.02556174 -0.002942681 -0.0267778 0.02562016 -0.002876281 -0.02648848 0.02575469 -0.002876281 -0.02676498 0.02568918 -0.002699971 -0.02650409 0.02579438 -0.002792656 -0.02650946 0.02580797 -0.002699971 -0.02696275 0.02532976 -0.002985298 -0.02704906 0.02545249 -0.002876281 -0.02679795 0.02565765 -0.002792656 -0.02680486 0.02567064 -0.002699971 -0.02756619 0.02506476 -0.002699971 -0.02755504 0.02505505 -0.002792656 -0.02732717 0.02528548 -0.002792656 -0.02750426 0.02512735 -0.002699971 -0.02733695 0.02529639 -0.002699971 -0.02707356 0.0254873 -0.002792656 -0.02690947 0.02525395 -0.002999961 -0.02719849 0.02514219 -0.002985298 -0.02747315 0.02498316 -0.002942681 -0.02771908 0.02477514 -0.002876281 -0.02775418 0.0247994 -0.002792656 -0.02792155 0.02452188 -0.002792656 -0.02806878 0.02423179 -0.002699971 -0.02801436 0.02435207 -0.002699971 -0.02793455 0.02452868 -0.002699971 -0.02821296 0.02359908 -0.002792656 -0.02811127 0.02390706 -0.002876281 -0.02801525 0.02421128 -0.002876281 -0.02782505 0.02447116 -0.002942681 -0.02759546 0.02469027 -0.002985298 -0.02812618 0.02327466 -0.002942681 -0.02819257 0.02327537 -0.002876281 -0.0281049 0.0235852 -0.002942681 -0.0281707 0.0235936 -0.002876281 -0.02823519 0.02327579 -0.002792656 -0.02823776 0.02345156 -0.002699971 -0.02802759 0.02297306 -0.002985298 -0.02804255 0.02327388 -0.002985298 -0.02811068 0.02296388 -0.002942681 -0.02817666 0.02295666 -0.002876281 -0.02821898 0.02295207 -0.002792656 -0.02805858 0.02265715 -0.002942681 -0.02817898 0.02262926 -0.002699971 -0.02797704 0.02267605 -0.002985298 -0.02789175 0.02238708 -0.002985298 -0.02812319 0.02264219 -0.002876281 -0.02807295 0.0223217 -0.002792656 -0.02814906 0.02252787 -0.002699971 -0.02795827 0.02201735 -0.002699971 -0.0279895 0.02209019 -0.002699971 -0.02797049 0.02235865 -0.002942681 -0.02784764 0.02207279 -0.002942681 -0.02803289 0.02233618 -0.002876281 -0.02790707 0.02204298 -0.002876281 -0.0279451 0.02202385 -0.002792656 -0.02777296 0.02211028 -0.002985298 -0.02774739 0.02176678 -0.002876281 -0.02778297 0.02174335 -0.002792656 -0.02737516 0.0212385 -0.002699971 -0.02746015 0.02132779 -0.002699971 -0.02759999 0.02147436 -0.002699971 -0.02779519 0.02173525 -0.002699971 -0.02684307 0.02086704 -0.002792656 -0.02711546 0.0210427 -0.002792656 -0.02733618 0.02128034 -0.002876281 -0.02744168 0.02160829 -0.002985298 -0.02762216 0.02184939 -0.002985298 -0.02674847 0.02103489 -0.002985298 -0.02650988 0.02082556 -0.002942681 -0.0267896 0.02096205 -0.002942681 -0.02682214 0.02090418 -0.002876281 -0.02624577 0.02061825 -0.002792656 -0.02647775 0.02090275 -0.002985298 -0.02653539 0.02076429 -0.002876281 -0.02655178 0.02072495 -0.002792656 -0.02627468 0.02061289 -0.002699971 -0.0265575 0.02071136 -0.002699971 -0.02619326 0.02080357 -0.002985298 -0.02621608 0.02072316 -0.002942681 -0.02623414 0.02065926 -0.002876281 -0.02592927 0.02054858 -0.002792656 -0.02624976 0.02060419 -0.002699971 -0.02588444 0.02083039 -0.002999961 -0.02589905 0.02073878 -0.002985298 -0.02560245 0.02062565 -0.002942681 -0.02560508 0.02055925 -0.002876281 -0.02591216 0.02065616 -0.002942681 -0.02592259 0.02059066 -0.002876281 -0.025352 0.02050727 -0.002699971 -0.0255993 0.02070915 -0.002985298 -0.02528619 0.02056574 -0.002876281 -0.0252828 0.02052325 -0.002792656 -0.02560675 0.02051675 -0.002792656 -0.02530539 0.02080768 -0.002999961 -0.02529138 0.02063196 -0.002942681 -0.02497017 0.02060985 -0.002876281 -0.02495884 0.02055376 -0.002699971 -0.02405387 0.02091085 -0.002699971 -0.0244472 0.02071428 -0.002699971 -0.02464836 0.02065056 -0.002792656 -0.02464377 0.02063667 -0.002699971 -0.02489078 0.02057164 -0.002699971 -0.02379655 0.02110975 -0.002792656 -0.02436488 0.02080816 -0.002876281 -0.0243929 0.02086836 -0.002942681 -0.02499967 0.02075695 -0.002985298 -0.02501785 0.02084785 -0.002999961 -0.02355539 0.0213263 -0.002792656 -0.02354496 0.02131599 -0.002699971 -0.02391648 0.02126049 -0.002985298 -0.02366286 0.02121007 -0.002699971 -0.02375829 0.02152699 -0.002999961 -0.02349346 0.0216881 -0.002985298 -0.02369225 0.02146178 -0.002985298 -0.02363288 0.02140295 -0.002942681 -0.02358567 0.02135628 -0.002876281 -0.02334159 0.02154755 -0.002699971 -0.02342748 0.02163678 -0.002942681 -0.02325129 0.0218932 -0.002942681 -0.02337515 0.02159595 -0.002876281 -0.02319449 0.02185887 -0.002876281 -0.02334147 0.02156978 -0.002792656 -0.02332288 0.02193635 -0.002985298 -0.02315795 0.02183687 -0.002792656 -0.02289158 0.02242648 -0.002792656 -0.02310657 0.02216869 -0.002942681 -0.02293217 0.02243936 -0.002876281 -0.02304607 0.02214139 -0.002876281 -0.02300727 0.02212375 -0.002792656 -0.02300167 0.02277666 -0.002985298 -0.02299547 0.02245926 -0.002942681 -0.02279806 0.02273809 -0.002699971 -0.02275335 0.02338707 -0.002699971 -0.02275645 0.02306115 -0.002699971 -0.02279686 0.02374517 -0.002699971 -0.02287989 0.02306967 -0.002942681 -0.0230928 0.02279388 -0.002999961 -0.022973 0.02433478 -0.002699971 -0.02292215 0.024194 -0.002699971 -0.02316349 0.02425307 -0.002985298 -0.02308666 0.02428609 -0.002942681 -0.02298104 0.02399337 -0.002942681 -0.02291738 0.02401208 -0.002876281 -0.0228765 0.02402418 -0.002792656 -0.02298647 0.02432906 -0.002792656 -0.02286249 0.02402836 -0.002699971 -0.02311509 0.02461814 -0.002699971 -0.02324867 0.02421647 -0.002999961 -0.0232985 0.02452236 -0.002985298 -0.02322608 0.0245642 -0.002942681 -0.02313178 0.0246188 -0.002792656 -0.02302569 0.02431219 -0.002876281 -0.0233975 0.0248239 -0.002942681 -0.02316868 0.0245974 -0.002876281 -0.0234645 0.02477377 -0.002985298 -0.02359837 0.02506154 -0.002942681 -0.02355039 0.02510726 -0.002876281 -0.02334439 0.02486366 -0.002876281 -0.0235089 0.0251469 -0.002699971 -0.02365899 0.02500385 -0.002985298 -0.023826 0.02527368 -0.002942681 -0.02378368 0.02532488 -0.002876281 -0.02375656 0.02535766 -0.002792656 -0.02351945 0.02513664 -0.002792656 -0.02370858 0.02533298 -0.002699971 -0.02387934 0.02520924 -0.002985298 -0.02407717 0.0254575 -0.002942681 -0.02404117 0.02551329 -0.002876281 -0.02459955 0.02583289 -0.002792656 -0.02450537 0.02580946 -0.002699971 -0.02401804 0.02554905 -0.002792656 -0.02408677 0.02560466 -0.002699971 -0.02522999 0.02598667 -0.002699971 -0.0249114 0.02592116 -0.002792656 -0.02461355 0.02579259 -0.002876281 -0.02434819 0.02561026 -0.002942681 -0.02463549 0.02572995 -0.002942681 -0.02412247 0.02538716 -0.002985298 -0.02417266 0.02530926 -0.002999961 -0.02555525 0.02598476 -0.002792656 -0.02524214 0.02586358 -0.002942681 -0.02555435 0.0259422 -0.002876281 -0.02585166 0.02576828 -0.002985298 -0.02586328 0.02585107 -0.002942681 -0.02555137 0.02579218 -0.002985298 -0.02555304 0.0258758 -0.002942681 -0.02587246 0.02591675 -0.002876281 0.02561324 0.0217995 -0.001699984 0.02495688 0.02211308 -0.001699984 0.02430045 0.0224266 -0.001699984 0.02424377 0.02315187 -0.001699984 0.02418714 0.02387708 -0.001699984 0.02478688 0.02428877 -0.001699984 0.02538669 0.02470046 -0.001699984 0.0267083 0.02360719 -0.001699984 0.02669948 0.02407336 -0.001699984 0.02660769 0.02385056 -0.001699984 0.02645856 0.02406769 -0.001699984 0.02626758 0.02424919 -0.001699984 0.02604305 0.02438688 -0.001699984 0.02675616 0.02334809 -0.001699984 0.02681279 0.02262288 -0.001699984 0.0248568 0.02561396 -0.002999961 0.02514088 0.02567344 -0.002999961 0.02542996 0.02569895 -0.002999961 0.02761089 0.02449357 -0.002999961 0.02774316 0.02423518 -0.002999961 0.02332144 0.02437108 -0.002999961 0.02320235 0.02239936 -0.002999961 0.02572017 0.02569007 -0.002999961 0.02538669 0.02470046 -0.002999961 0.02628719 0.02557009 -0.002999961 0.02384817 0.02505946 -0.002999961 0.02418714 0.02387708 -0.002999961 0.02431946 0.02539676 -0.002999961 0.02458167 0.02552139 -0.002999961 0.02430045 0.0224266 -0.002999961 0.02485167 0.02088725 -0.002999961 0.02457678 0.02098059 -0.002999961 0.02431488 0.0211057 -0.002999961 0.02331906 0.02213358 -0.002999961 0.02681279 0.02262288 -0.002999961 0.02774095 0.02225989 -0.002999961 0.02561324 0.0217995 -0.002999961 0.02669948 0.02407336 -0.002999961 0.02704578 0.02515077 -0.002999961 0.02725964 0.02495467 -0.002999961 0.02704167 0.02134585 -0.002999961 0.02638345 0.02585417 -0.002699971 0.02579098 0.02598458 0 0.02624887 0.02589607 0 0.02624768 0.02589148 -0.002699971 0.02532458 0.02599436 0 0.02509689 0.02597028 -0.002699971 0.025325 0.02599036 -0.002699971 0.02486336 0.02592527 0 0.02442038 0.02577918 0 0.02401095 0.02555638 -0.002699971 0.02417486 0.02565968 -0.002699971 0.02400845 0.02556037 0 0.02389919 0.02548605 -0.002699971 0.02364599 0.02528095 -0.002699971 0.0236395 0.02527505 0 0.02363979 0.02527469 -0.002699971 0.02341878 0.02504748 -0.002699971 0.02332395 0.02493149 0 0.02305477 0.02450835 -0.002699971 0.02307105 0.02453958 0 0.02278375 0.02365607 -0.002699971 0.02288806 0.02411055 0 0.02276968 0.02357816 -0.002699971 0.02278029 0.02365678 0 0.02274996 0.02325296 -0.002699971 0.02275055 0.02319127 0 0.02280008 0.02272748 0 0.02276897 0.0229277 -0.002699971 0.02275359 0.02319145 -0.002699971 0.02282619 0.02260684 -0.002699971 0.02292716 0.02227866 0 0.02292805 0.02227908 -0.002699971 0.02305209 0.02199685 -0.002699971 0.02312839 0.02185785 0 0.02339887 0.02147799 -0.002699971 0.0233978 0.0214771 0 0.02364158 0.02122294 -0.002699971 0.02389436 0.02101737 -0.002699971 0.02372759 0.02114725 0 0.02373039 0.02115064 -0.002699971 0.02410846 0.02087795 0 0.02477228 0.02059799 -0.002699971 0.02497816 0.02054995 0 0.02452939 0.02067697 0 0.02446365 0.02070266 -0.002699971 0.02541559 0.02050125 -0.002699971 0.025442 0.0205006 0 0.02590745 0.0205304 0 0.0260635 0.02055835 -0.002699971 0.02574115 0.02051055 -0.002699971 0.02636098 0.0206393 -0.002699971 0.02667999 0.02076596 -0.002699971 0.02636116 0.02063828 0 0.0267902 0.02082139 0 0.02696549 0.02092295 -0.002699971 0.02678799 0.02082538 -0.002699971 0.02747106 0.02133238 -0.002699971 0.0271821 0.02107435 0 0.0275256 0.02138996 0 0.02768409 0.02157896 -0.002699971 0.02786636 0.02184897 -0.002699971 0.02781075 0.02175909 0 0.0280295 0.02217096 0 0.02817547 0.022614 0 0.02817076 0.02261519 -0.002699971 0.02824437 0.02307528 0 0.02824389 0.0230754 -0.002699971 0.02823448 0.02354168 0 0.02814584 0.02399957 0 0.02820718 0.02373349 -0.002699971 0.02822989 0.02354109 -0.002699971 0.02774167 0.024836 -0.002699971 0.0279811 0.02443599 0 0.0279777 0.02443414 -0.002699971 0.02768754 0.02491629 -0.002699971 0.02774494 0.02483814 0 0.02744275 0.02519309 -0.002699971 0.0274443 0.02519476 0 0.02723497 0.02538359 -0.002699971 0.02708488 0.02549159 -0.002699971 0.02708768 0.02549535 0 0.0269705 0.02557379 -0.002699971 0.02668529 0.02573138 0 0.02313256 0.0218603 -0.002699971 0.02292305 0.02421027 -0.002699971 0.02637875 0.02584028 -0.002792656 0.02769076 0.02454066 -0.002985298 0.02427476 0.02547806 -0.002985298 0.02681005 0.02532029 -0.002999961 0.02655595 0.02546066 -0.002999961 0.02784395 0.02396297 -0.002999961 0.02791178 0.0236808 -0.002999961 0.02794587 0.02339249 -0.002999961 0.02803838 0.02339786 -0.002985298 0.02794545 0.02310216 -0.002999961 0.02791088 0.02281397 -0.002999961 0.02680557 0.02117687 -0.002999961 0.02685499 0.02109837 -0.002985298 0.02628219 0.0209282 -0.002999961 0.0265513 0.02103698 -0.002999961 0.02659106 0.02095329 -0.002985298 0.02600204 0.02085196 -0.002999961 0.02406954 0.02126085 -0.002999961 0.02401536 0.02118569 -0.002985298 0.02364236 0.02165257 -0.002999961 0.02357208 0.02159208 -0.002985298 0.02346646 0.02188348 -0.002999961 0.02311915 0.02382797 -0.002999961 0.02320414 0.02410554 -0.002999961 0.02339255 0.02467268 -0.002985298 0.02407377 0.02524209 -0.002999961 0.02302777 0.02265536 -0.002985298 0.02306687 0.02296274 -0.002999961 0.02304995 0.0232526 -0.002999961 0.02482706 0.02079784 -0.002985298 0.02768796 0.02195459 -0.002985298 0.02744579 0.02176117 -0.002999961 0.02725607 0.02154159 -0.002999961 0.02744895 0.02473455 -0.002999961 0.02752268 0.0247907 -0.002985298 0.02397119 0.02538549 -0.002942681 0.02401989 0.02531749 -0.002985298 0.02303695 0.02233815 -0.002942681 0.02294647 0.02263587 -0.002942681 0.02311789 0.02267706 -0.002999961 0.02512186 0.02073556 -0.002985298 0.02542185 0.0207085 -0.002985298 0.02513569 0.02082717 -0.002999961 0.02775996 0.02191197 -0.002942681 0.0279023 0.02218866 -0.002942681 0.02760815 0.0220018 -0.002999961 0.02758926 0.02484136 -0.002942681 0.02738636 0.0250774 -0.002942681 0.02372938 0.02518969 -0.002942681 0.02378565 0.02512788 -0.002985298 0.02357566 0.02491199 -0.002985298 0.02364575 0.02485138 -0.002999961 0.02306514 0.02200359 -0.002792656 0.02310305 0.02202296 -0.002876281 0.02311545 0.02236717 -0.002985298 0.02323657 0.02209138 -0.002985298 0.02448529 0.02075576 -0.002876281 0.02451026 0.02081727 -0.002942681 0.02573615 0.02056765 -0.002876281 0.02541726 0.02055859 -0.002876281 0.02541935 0.02062487 -0.002942681 0.02542477 0.02080118 -0.002999961 0.02571487 0.02080935 -0.002999961 0.02738237 0.02141857 -0.002942681 0.0280745 0.02246075 -0.002876281 0.02782577 0.02222245 -0.002985298 0.02793097 0.0225048 -0.002985298 0.0278424 0.02253186 -0.002999961 0.02719885 0.02533906 -0.002876281 0.02715694 0.02528756 -0.002942681 0.02732628 0.02501916 -0.002985298 0.02446919 0.02579945 -0.002699971 0.02447468 0.02578586 -0.002792656 0.02510529 0.02591359 -0.002876281 0.02511495 0.02584797 -0.002942681 0.02542495 0.02587527 -0.002942681 0.02451556 0.02568489 -0.002942681 0.02418196 0.0256468 -0.002792656 0.02420246 0.02560949 -0.002876281 0.02454686 0.02560728 -0.002985298 0.02483236 0.02570348 -0.002985298 0.02390778 0.02547407 -0.002792656 0.02276468 0.0232529 -0.002792656 0.0228073 0.0232529 -0.002876281 0.02282589 0.02293437 -0.002876281 0.02293479 0.0223003 -0.002792656 0.02288198 0.02262026 -0.002876281 0.02289175 0.02294218 -0.002942681 0.02287369 0.02325278 -0.002942681 0.02477616 0.02061218 -0.002792656 0.02478736 0.02065324 -0.002876281 0.02544188 0.02050209 -0.002699971 0.02509957 0.0205872 -0.002876281 0.02746057 0.02134257 -0.002792656 0.02767235 0.02158784 -0.002792656 0.02742999 0.02137225 -0.002876281 0.02763855 0.02161377 -0.002876281 0.02800196 0.02214455 -0.002792656 0.02781707 0.02187818 -0.002876281 0.0275858 0.02165406 -0.002942681 0.02796536 0.02433276 -0.002876281 0.02785664 0.02463847 -0.002792656 0.02747517 0.02516335 -0.002699971 0.02764207 0.0248816 -0.002876281 0.02781999 0.02461677 -0.002876281 0.02776277 0.0245831 -0.002942681 0.02790457 0.02430617 -0.002942681 0.02634376 0.0257371 -0.002942681 0.02659595 0.0255444 -0.002985298 0.02666068 0.02567964 -0.002876281 0.0263651 0.02579987 -0.002876281 0.02667897 0.02571815 -0.002792656 0.02602636 0.02573758 -0.002985298 0.02631688 0.02565789 -0.002985298 0.02604365 0.02581936 -0.002942681 0.02605748 0.02588438 -0.002876281 0.0260663 0.02592605 -0.002792656 0.02574706 0.02598887 -0.002699971 0.02600717 0.02564686 -0.002999961 0.02574199 0.02593177 -0.002876281 0.02574574 0.02597415 -0.002792656 0.02579057 0.02598226 -0.002699971 0.02606928 0.02594035 -0.002699971 0.02572846 0.0257824 -0.002985298 0.0254274 0.0257917 -0.002985298 0.02573597 0.02586567 -0.002942681 0.02542304 0.02594155 -0.002876281 0.02542185 0.02598416 -0.002792656 0.02477794 0.02590346 -0.002699971 0.02478176 0.02588939 -0.002792656 0.02486407 0.02592158 -0.002699971 0.02509897 0.02595579 -0.002792656 0.0254215 0.02599889 -0.002699971 0.02512729 0.02576518 -0.002985298 0.02481049 0.02578419 -0.002942681 0.02479296 0.02584815 -0.002876281 0.02449065 0.0257464 -0.002876281 0.02442145 0.02577686 -0.002699971 0.02365589 0.02527016 -0.002792656 0.02368456 0.02523869 -0.002876281 0.02393257 0.0254395 -0.002876281 0.02423447 0.02555125 -0.002942681 0.02332329 0.02471947 -0.002942681 0.02351236 0.02496665 -0.002942681 0.02346205 0.02500998 -0.002876281 0.02342987 0.02503788 -0.002792656 0.02322077 0.02478867 -0.002699971 0.02332776 0.02492856 -0.002699971 0.02346938 0.02462089 -0.002999961 0.02326828 0.02475666 -0.002876281 0.02323299 0.02478045 -0.002792656 0.02307265 0.02453857 -0.002699971 0.02311736 0.02413785 -0.002985298 0.02323907 0.02441346 -0.002985298 0.02303898 0.02416706 -0.002942681 0.02316474 0.02445179 -0.002942681 0.02310568 0.02448207 -0.002876281 0.02297675 0.0241903 -0.002876281 0.02306789 0.02450156 -0.002792656 0.02302908 0.0238499 -0.002985298 0.02294778 0.02386957 -0.002942681 0.02284187 0.02389526 -0.002792656 0.02282756 0.02389878 -0.002699971 0.02293688 0.02420514 -0.002792656 0.02289217 0.0241093 -0.002699971 0.0229755 0.02355337 -0.002985298 0.02288329 0.02388525 -0.002876281 0.02278417 0.02357637 -0.002792656 0.02306747 0.0235424 -0.002999961 0.02289235 0.02356338 -0.002942681 0.02282649 0.02357125 -0.002876281 0.02292108 0.02229517 -0.002699971 0.02280455 0.02272826 -0.002699971 0.02284049 0.02261036 -0.002792656 0.02278345 0.02292937 -0.002792656 0.02297478 0.02231508 -0.002876281 0.02297478 0.02295196 -0.002985298 0.02295726 0.02325266 -0.002985298 0.02316218 0.0220533 -0.002942681 0.02321749 0.02171617 -0.002699971 0.02341485 0.02145695 -0.002699971 0.02338945 0.02183175 -0.002985298 0.02332007 0.02178508 -0.002942681 0.023265 0.02174806 -0.002876281 0.02322965 0.0217244 -0.002792656 0.02378165 0.02137577 -0.002985298 0.02372515 0.02131408 -0.002942681 0.02350866 0.0215376 -0.002942681 0.02368026 0.02126514 -0.002876281 0.02345836 0.02149426 -0.002876281 0.02342599 0.02146655 -0.002792656 0.02384436 0.02144408 -0.002999961 0.02396655 0.0211178 -0.002942681 0.02390295 0.02102929 -0.002792656 0.02365148 0.02123379 -0.002792656 0.02392786 0.02106386 -0.002876281 0.02419739 0.02089327 -0.002876281 0.02417677 0.02085596 -0.002792656 0.02411019 0.02088075 -0.002699971 0.02426999 0.02102458 -0.002985298 0.02422958 0.02095139 -0.002942681 0.02416968 0.02084314 -0.002699971 0.02509319 0.02054506 -0.002792656 0.02509099 0.02053058 -0.002699971 0.02497905 0.0205543 -0.002699971 0.02446925 0.02071624 -0.002792656 0.02453035 0.02068006 -0.002699971 0.02573996 0.02052515 -0.002792656 0.02541595 0.02051597 -0.002792656 0.02510935 0.02065289 -0.002942681 0.02480494 0.02071726 -0.002942681 0.02454179 0.0208947 -0.002985298 0.02572309 0.02071708 -0.002985298 0.02573037 0.02063375 -0.002942681 0.02605175 0.02061438 -0.002876281 0.0259068 0.02053505 -0.002699971 0.02637326 0.02065777 -0.002792656 0.02602106 0.02076125 -0.002985298 0.02631175 0.0208404 -0.002985298 0.02603816 0.02067935 -0.002942681 0.02633845 0.02076107 -0.002942681 0.02635955 0.02069818 -0.002876281 0.02606046 0.02057266 -0.002792656 0.02665537 0.02081775 -0.002876281 0.02637785 0.02064388 -0.002699971 0.02693498 0.02097147 -0.002876281 0.02662688 0.02087765 -0.002942681 0.02667367 0.02077925 -0.002792656 0.02695769 0.02093547 -0.002792656 0.02689957 0.02102768 -0.002942681 0.02715259 0.02120876 -0.002942681 0.02719438 0.0211572 -0.002876281 0.02718037 0.02107679 -0.002699971 0.02709996 0.02127379 -0.002985298 0.0272212 0.02112406 -0.002792656 0.02723038 0.02111268 -0.002699971 0.02801549 0.02213865 -0.002699971 0.02785366 0.02185648 -0.002792656 0.02780729 0.02176135 -0.002699971 0.02752286 0.02139228 -0.002699971 0.02802765 0.02217167 -0.002699971 0.02811515 0.0224483 -0.002792656 0.02796298 0.0221619 -0.002876281 0.0275194 0.02170485 -0.002985298 0.02732247 0.02147686 -0.002985298 0.02800208 0.02279746 -0.002985298 0.02801096 0.02248024 -0.002942681 0.02808439 0.02278256 -0.002942681 0.02814966 0.02277076 -0.002876281 0.02812916 0.02244395 -0.002699971 0.02824497 0.0230841 -0.002699971 0.02812159 0.02309155 -0.002942681 0.02823024 0.02308499 -0.002792656 0.02819168 0.02276325 -0.002792656 0.02820605 0.02276057 -0.002699971 0.02803808 0.02309656 -0.002985298 0.02812188 0.02340275 -0.002942681 0.02818775 0.02308756 -0.002876281 0.02823066 0.02340906 -0.002792656 0.02824527 0.02340996 -0.002699971 0.02818804 0.02340656 -0.002876281 0.02811688 0.02404606 -0.002792656 0.02814328 0.02399897 -0.002699971 0.02800309 0.02369707 -0.002985298 0.02801269 0.02401429 -0.002942681 0.02808535 0.0237118 -0.002942681 0.02815079 0.02372348 -0.002876281 0.02819269 0.02373099 -0.002792656 0.02793258 0.02398997 -0.002985298 0.02782797 0.0242725 -0.002985298 0.02807605 0.02403366 -0.002876281 0.02800434 0.02434998 -0.002792656 0.02813094 0.02405029 -0.002699971 0.02767598 0.02490746 -0.002792656 0.0278694 0.02464586 -0.002699971 0.02801775 0.02435588 -0.002699971 0.02722579 0.02537214 -0.002792656 0.02746468 0.02515316 -0.002792656 0.02743405 0.02512347 -0.002876281 0.02710419 0.02522265 -0.002985298 0.0269044 0.0254693 -0.002942681 0.02696269 0.02556139 -0.002792656 0.0268597 0.02539855 -0.002985298 0.02663195 0.0256198 -0.002942681 0.02693986 0.02552539 -0.002876281 0.02668529 0.02573138 -0.002699971 0.02523934 -0.0220173 -0.001699984 0.02595108 -0.02186679 -0.002999961 0.02595108 -0.02186679 -0.001699984 0.02430206 -0.02285927 -0.001699984 0.02452754 -0.02216768 -0.001699984 0.02456265 -0.02409207 -0.001699984 0.02407646 -0.02355098 -0.001699984 0.02647238 -0.02433228 -0.002999961 0.02576059 -0.02448266 -0.001699984 0.02504885 -0.02463316 -0.001699984 0.02692347 -0.02294898 -0.001699984 0.02692347 -0.02294898 -0.002999961 0.02647238 -0.02433228 -0.001699984 0.02552199 -0.02080005 -0.002999961 0.02581155 -0.0208199 -0.002999961 0.02504885 -0.02463316 -0.002999961 0.02449226 -0.02548307 -0.002999961 0.02755987 -0.02457636 -0.002999961 0.02719068 -0.0250231 -0.002999961 0.02609676 -0.02087378 -0.002999961 0.02370715 -0.0215801 -0.002999961 0.02423518 -0.0253483 -0.002999961 0.02399587 -0.02518397 -0.002999961 0.02789276 -0.02377617 -0.002999961 0.02440088 -0.02106034 -0.002999961 0.02314245 -0.02258294 -0.002999961 0.023238 -0.02230888 -0.002999961 0.02452754 -0.02216768 -0.002999961 0.02336519 -0.02204787 -0.002999961 0.02352225 -0.02180385 -0.002999961 0.02341657 -0.02453917 -0.002999961 0.02327877 -0.02428376 -0.002999961 0.02407646 -0.02355098 -0.002999961 0.02750325 -0.02183955 -0.002999961 0.02466756 -0.02094578 -0.002999961 0.02494585 -0.02086347 -0.002999961 0.02523207 -0.02081465 -0.002999961 0.02681648 -0.02083557 0 0.02720558 -0.02109277 0 0.02720266 -0.02109658 -0.002699971 0.02677756 -0.02081477 -0.002699971 0.02638947 -0.02064776 0 0.02638828 -0.02065169 -0.002699971 0.02593696 -0.02053487 0 0.0254718 -0.02050006 0 0.02500826 -0.02054905 -0.002699971 0.02519929 -0.02051645 -0.002699971 0.02487808 -0.02057117 -0.002699971 0.02500748 -0.02054446 0 0.02455747 -0.02066707 -0.002699971 0.02455729 -0.02066659 0 0.0237506 -0.02112817 0 0.02413427 -0.02086305 0 0.02375167 -0.02112966 -0.002699971 0.02341705 -0.02145439 0 0.02314358 -0.02183216 0 0.02328008 -0.02162677 -0.002699971 0.02314656 -0.02183407 -0.002699971 0.02310365 -0.02190077 -0.002699971 0.02293789 -0.02225077 0 0.02278387 -0.02281957 -0.002699971 0.02280586 -0.02269816 0 0.0227521 -0.02314376 -0.002699971 0.0227524 -0.02316135 -0.002699971 0.02275139 -0.02316135 0 0.02277594 -0.02362716 0 0.02280396 -0.02379226 -0.002699971 0.02275878 -0.02346956 -0.002699971 0.02288699 -0.02410727 -0.002699971 0.02287888 -0.02408218 0 0.02330589 -0.02490776 0 0.02306109 -0.02451109 -0.002699971 0.02305728 -0.02451318 0 0.02300679 -0.02441024 -0.002699971 0.02361756 -0.02525478 0 0.02398347 -0.02554404 0 0.02381169 -0.02542078 -0.002699971 0.02361977 -0.02525228 -0.002699971 0.02408027 -0.0256052 -0.002699971 0.02439296 -0.02576738 0 0.02529495 -0.02599138 -0.002699971 0.02483546 -0.02591347 -0.002699971 0.02483439 -0.02591818 0 0.02467328 -0.02587276 -0.002699971 0.02531236 -0.02599358 -0.002699971 0.02529489 -0.02599227 0 0.02596205 -0.02596086 -0.002699971 0.0262202 -0.02590399 0 0.0257613 -0.02598756 0 0.02563828 -0.0259965 -0.002699971 0.02665829 -0.02574408 0 0.02706319 -0.02551245 0 0.02665668 -0.02574098 -0.002699971 0.02742165 -0.02521449 -0.002699971 0.02742308 -0.0252158 0 0.02761977 -0.02500176 -0.002699971 0.02781206 -0.02473878 -0.002699971 0.0277276 -0.02486246 0 0.02796804 -0.02446275 0 0.0282312 -0.02357125 0 0.02818578 -0.0238406 -0.002699971 0.02813309 -0.02402698 -0.002699971 0.02813756 -0.0240283 0 0.02824938 -0.02319318 -0.002699971 0.02822339 -0.02286839 -0.002699971 0.02824616 -0.02310508 0 0.02818214 -0.02264308 0 0.02815908 -0.02254897 -0.002699971 0.02804106 -0.02219855 0 0.02782279 -0.02178668 -0.002699971 0.02782678 -0.02178418 0 0.02754557 -0.02141207 0 0.02731388 -0.02118295 -0.002699971 0.02576076 -0.02598297 -0.002699971 0.02302008 -0.02440404 -0.002792656 0.02277338 -0.02346837 -0.002792656 0.02342039 -0.02145707 -0.002699971 0.02413666 -0.02086716 -0.002699971 0.0242663 -0.0207923 -0.002699971 0.02707487 -0.02535176 -0.002942681 0.02298855 -0.022852 -0.002985298 0.022906 -0.02283889 -0.002942681 0.02490609 -0.02069169 -0.002942681 0.02732247 -0.02161258 -0.002999961 0.02739137 -0.02155059 -0.002985298 0.02781379 -0.02405548 -0.002999961 0.02763777 -0.02462655 -0.002985298 0.02619445 -0.02559947 -0.002999961 0.02622067 -0.02568835 -0.002985298 0.02591168 -0.02566516 -0.002999961 0.0259273 -0.02575647 -0.002985298 0.02533286 -0.02569425 -0.002999961 0.02504497 -0.02565735 -0.002999961 0.02305775 -0.0234456 -0.002999961 0.02414959 -0.02120566 -0.002999961 0.02385735 -0.02130895 -0.002985298 0.02663826 -0.02108049 -0.002999961 0.0266813 -0.02099835 -0.002985298 0.027116 -0.02140849 -0.002999961 0.02717715 -0.02133888 -0.002985298 0.02308017 -0.02286648 -0.002999961 0.02305328 -0.02255779 -0.002985298 0.02377766 -0.02499246 -0.002999961 0.02702468 -0.02528488 -0.002985298 0.02677327 -0.02545088 -0.002985298 0.0267269 -0.02537065 -0.002999961 0.0264675 -0.02550089 -0.002999961 0.02795869 -0.02260178 -0.002985298 0.02792626 -0.02290999 -0.002999961 0.02458506 -0.0207175 -0.002876281 0.02492499 -0.02077317 -0.002985298 0.02463608 -0.02085858 -0.002985298 0.02295917 -0.02315175 -0.002985298 0.02418726 -0.02542769 -0.002985298 0.02731239 -0.02515077 -0.002942681 0.0272547 -0.02509015 -0.002985298 0.02696907 -0.02521067 -0.002999961 0.02794259 -0.0222848 -0.002942681 0.02786475 -0.02231556 -0.002985298 0.0278691 -0.0226255 -0.002999961 0.02777856 -0.02234959 -0.002999961 0.02429199 -0.0208435 -0.002876281 0.02460759 -0.02077984 -0.002942681 0.02432179 -0.02090275 -0.002942681 0.02290898 -0.0225169 -0.002876281 0.02281588 -0.02346497 -0.002876281 0.02287554 -0.02314859 -0.002942681 0.02305179 -0.02315539 -0.002999961 0.02296537 -0.02345299 -0.002985298 0.02360707 -0.02516508 -0.002876281 0.0236538 -0.02511787 -0.002942681 0.02439236 -0.02570438 -0.002876281 0.02469044 -0.02581804 -0.002876281 0.02441966 -0.02564388 -0.002942681 0.02471035 -0.02575474 -0.002942681 0.02445405 -0.02556759 -0.002985298 0.02760845 -0.02499246 -0.002792656 0.02745997 -0.02486979 -0.002985298 0.02738845 -0.02481067 -0.002999961 0.0278697 -0.02197116 -0.002876281 0.02615594 -0.0206384 -0.002876281 0.02584785 -0.02053689 -0.002792656 0.02584248 -0.02057915 -0.002876281 0.02613979 -0.02070277 -0.002942681 0.0264067 -0.0208745 -0.002985298 0.02637368 -0.0209611 -0.002999961 0.02582335 -0.02072787 -0.002985298 0.02583396 -0.02064496 -0.002942681 0.0255236 -0.0206238 -0.002942681 0.02552419 -0.0205574 -0.002876281 0.02552276 -0.02070736 -0.002985298 0.02520549 -0.02057337 -0.002876281 0.02488136 -0.02058547 -0.002792656 0.02456557 -0.02066355 -0.002699971 0.02284049 -0.02282845 -0.002876281 0.02297288 -0.02253496 -0.002942681 0.02439349 -0.02576595 -0.002699971 0.0243749 -0.02574318 -0.002792656 0.02436888 -0.02575659 -0.002699971 0.0240879 -0.02559256 -0.002792656 0.02384686 -0.0253756 -0.002876281 0.02388769 -0.02532315 -0.002942681 0.02711468 -0.02540487 -0.002876281 0.02684849 -0.0255807 -0.002876281 0.02653706 -0.02566289 -0.002942681 0.0281921 -0.02319437 -0.002876281 0.02816665 -0.02287638 -0.002876281 0.02805757 -0.02223938 -0.002699971 0.02810364 -0.02256357 -0.002876281 0.02812576 -0.02319568 -0.002942681 0.02723228 -0.02127599 -0.002942681 0.02754557 -0.02141207 -0.002699971 0.02693939 -0.02115386 -0.002985298 0.02702426 -0.02103024 -0.002876281 0.02727609 -0.02122604 -0.002876281 0.02730417 -0.0211941 -0.002792656 0.02705669 -0.02098298 -0.002699971 0.02677077 -0.02082777 -0.002792656 0.02681529 -0.02083748 -0.002699971 0.02688688 -0.02123028 -0.002999961 0.02698665 -0.02108496 -0.002942681 0.02704834 -0.02099508 -0.002792656 0.02643656 -0.02079629 -0.002942681 0.02672016 -0.02092427 -0.002942681 0.02646017 -0.02073425 -0.002876281 0.02675098 -0.02086555 -0.002876281 0.02648067 -0.02068078 -0.002699971 0.02552467 -0.02050006 -0.002699971 0.02584975 -0.02052229 -0.002699971 0.0259363 -0.02053868 -0.002699971 0.02616989 -0.02058279 -0.002699971 0.02616626 -0.0205971 -0.002792656 0.02647536 -0.02069449 -0.002792656 0.02611935 -0.0207839 -0.002985298 0.02552455 -0.02051478 -0.002792656 0.0252009 -0.02053105 -0.002792656 0.02547198 -0.0205028 -0.002699971 0.02457058 -0.02067738 -0.002792656 0.02427285 -0.02080535 -0.002792656 0.02489095 -0.02062708 -0.002876281 0.02521276 -0.02063935 -0.002942681 0.02522188 -0.02072244 -0.002985298 0.02409845 -0.02112835 -0.002985298 0.02435928 -0.02097749 -0.002985298 0.02401578 -0.02100318 -0.002876281 0.02380335 -0.02124518 -0.002942681 0.02405238 -0.02105855 -0.002942681 0.02376049 -0.02119445 -0.002876281 0.02399235 -0.02096766 -0.002792656 0.02398425 -0.02095538 -0.002699971 0.02391725 -0.02137976 -0.002999961 0.02363938 -0.02151685 -0.002985298 0.02373296 -0.02116197 -0.002792656 0.02348768 -0.02137565 -0.002699971 0.02372348 -0.02115076 -0.002699971 0.02344745 -0.02174919 -0.002985298 0.02357816 -0.02145987 -0.002942681 0.02332639 -0.02166056 -0.002876281 0.02352958 -0.02141469 -0.002876281 0.02349847 -0.02138566 -0.002792656 0.023292 -0.02163547 -0.002792656 0.02328437 -0.02200245 -0.002985298 0.02321147 -0.02196139 -0.002942681 0.02337998 -0.02169978 -0.002942681 0.02311646 -0.02190798 -0.002792656 0.02307516 -0.02224105 -0.002942681 0.02301388 -0.0222156 -0.002876281 0.02315366 -0.0219289 -0.002876281 0.02297449 -0.02219927 -0.002792656 0.02296096 -0.02219355 -0.002699971 0.02279835 -0.0228219 -0.002792656 0.02281039 -0.02269917 -0.002699971 0.02285385 -0.02250128 -0.002699971 0.02286797 -0.02250528 -0.002792656 0.02294069 -0.02225178 -0.002699971 0.02276664 -0.02314436 -0.002792656 0.02280926 -0.02314597 -0.002876281 0.02315235 -0.0222733 -0.002985298 0.02292519 -0.02376788 -0.002942681 0.02288198 -0.02345967 -0.002942681 0.02286016 -0.023781 -0.002876281 0.02278077 -0.02362656 -0.002699971 0.02290099 -0.02410268 -0.002792656 0.02309805 -0.02373307 -0.002999961 0.02300715 -0.02375137 -0.002985298 0.02294147 -0.02408945 -0.002876281 0.02281838 -0.0237894 -0.002792656 0.02288025 -0.02408176 -0.002699971 0.02317208 -0.02401375 -0.002999961 0.02319467 -0.02432286 -0.002985298 0.02308398 -0.02404266 -0.002985298 0.02311885 -0.02435815 -0.002942681 0.02300459 -0.02406877 -0.002942681 0.02305865 -0.02438616 -0.002876281 0.02333778 -0.02458798 -0.002985298 0.02326667 -0.02463197 -0.002942681 0.02316147 -0.02469706 -0.002699971 0.0233491 -0.02496349 -0.002699971 0.02330857 -0.02490586 -0.002699971 0.02351117 -0.02483427 -0.002985298 0.02344578 -0.02488636 -0.002942681 0.02339386 -0.02492779 -0.002876281 0.02321016 -0.0246669 -0.002876281 0.02317398 -0.02468925 -0.002792656 0.02358365 -0.02477657 -0.002999961 0.02356678 -0.02520585 -0.002699971 0.02336055 -0.02495425 -0.002792656 0.02398598 -0.02554035 -0.002699971 0.02382075 -0.02540916 -0.002792656 0.02357715 -0.02519536 -0.002792656 0.02467769 -0.02585875 -0.002792656 0.02410989 -0.02555608 -0.002876281 0.02414417 -0.02549928 -0.002942681 0.02393895 -0.02525705 -0.002985298 0.02371257 -0.02505838 -0.002985298 0.02499198 -0.02593767 -0.002792656 0.02476346 -0.02558666 -0.002999961 0.02502775 -0.02574849 -0.002985298 0.02473556 -0.02567505 -0.002985298 0.02501219 -0.02583056 -0.002942681 0.02531337 -0.02597886 -0.002792656 0.02499985 -0.02589589 -0.002876281 0.02498924 -0.02595216 -0.002699971 0.02532655 -0.02578675 -0.002985298 0.02563196 -0.025873 -0.002942681 0.02532088 -0.0258702 -0.002942681 0.02531635 -0.02593636 -0.002876281 0.02563744 -0.0259819 -0.002792656 0.0256232 -0.02569687 -0.002999961 0.02562779 -0.02578949 -0.002985298 0.02594125 -0.02583897 -0.002942681 0.02595967 -0.02594637 -0.002792656 0.02563536 -0.02593928 -0.002876281 0.02627944 -0.02588719 -0.002699971 0.02624446 -0.02576857 -0.002942681 0.02626329 -0.02583229 -0.002876281 0.02595245 -0.02590435 -0.002876281 0.02621948 -0.02590107 -0.002699971 0.02650409 -0.02558606 -0.002985298 0.02656328 -0.02572387 -0.002876281 0.02658009 -0.02576297 -0.002792656 0.02627527 -0.02587306 -0.002792656 0.02739769 -0.0252403 -0.002699971 0.02714896 -0.0254507 -0.002699971 0.0271402 -0.02543896 -0.002792656 0.02706086 -0.02550899 -0.002699971 0.02686977 -0.02561759 -0.002792656 0.0268771 -0.02563029 -0.002699971 0.02658587 -0.0257765 -0.002699971 0.02735817 -0.02519875 -0.002876281 0.02738755 -0.02522957 -0.002792656 0.02681517 -0.0255233 -0.002942681 0.02752447 -0.02492308 -0.002942681 0.02757555 -0.02496528 -0.002876281 0.02772378 -0.02485966 -0.002699971 0.02795875 -0.02444845 -0.002792656 0.02796769 -0.02446258 -0.002699971 0.02786076 -0.02440065 -0.002942681 0.02770805 -0.02467185 -0.002942681 0.0277639 -0.02470779 -0.002876281 0.02779978 -0.02473086 -0.002792656 0.02770227 -0.02432346 -0.002999961 0.02778559 -0.02436405 -0.002985298 0.02798026 -0.02411335 -0.002942681 0.02804297 -0.02413529 -0.002876281 0.02792048 -0.02442979 -0.002876281 0.02809709 -0.02415406 -0.002699971 0.02797198 -0.02445489 -0.002699971 0.02790135 -0.02408587 -0.002985298 0.02812987 -0.02382826 -0.002876281 0.02817147 -0.02383738 -0.002792656 0.02808326 -0.02414929 -0.002792656 0.0282222 -0.02351725 -0.002792656 0.02803045 -0.02349847 -0.002985298 0.02798336 -0.02379608 -0.002985298 0.02817976 -0.02351319 -0.002876281 0.02806508 -0.02381396 -0.002942681 0.02822858 -0.02357089 -0.002699971 0.02804219 -0.02319747 -0.002985298 0.02811378 -0.0235067 -0.002942681 0.02823466 -0.02319347 -0.002792656 0.0282368 -0.0235188 -0.002699971 0.02814495 -0.02255266 -0.002792656 0.02817815 -0.02264386 -0.002699971 0.02820885 -0.02287036 -0.002792656 0.02824234 -0.02310538 -0.002699971 0.02790719 -0.02195096 -0.002792656 0.02803897 -0.02219945 -0.002699971 0.02804386 -0.02224475 -0.002792656 0.02800428 -0.02226048 -0.002876281 0.02803957 -0.0225805 -0.002942681 0.02810084 -0.02288556 -0.002942681 0.02801805 -0.02289718 -0.002985298 0.02794945 -0.02319937 -0.002999961 0.0279383 -0.02348947 -0.002999961 0.02765607 -0.0220865 -0.002999961 0.02773767 -0.02204239 -0.002985298 0.02757906 -0.02178627 -0.002985298 0.02781128 -0.02200269 -0.002942681 0.02770179 -0.0216999 -0.002876281 0.02792006 -0.02194398 -0.002699971 0.0274536 -0.02149468 -0.002942681 0.02764749 -0.02173805 -0.002942681 0.02750295 -0.0214504 -0.002876281 0.02753466 -0.02142184 -0.002792656 0.0277366 -0.02167534 -0.002792656 0.02774858 -0.02166688 -0.002699971 0.0266599 -0.02275788 -0.001699984 0.02643728 -0.02240788 -0.001699984 0.02656304 -0.02257364 -0.001699984 0.0267176 -0.02357405 -0.001699984 0.02675688 -0.02316117 -0.001699984 0.02675426 -0.02336919 -0.001699984 0.02672505 -0.02295547 -0.001699984 0.02654635 -0.02395188 -0.001699984 0.02641659 -0.02411448 -0.001699984 0.02664768 -0.02377009 -0.001699984 0.02669787 -0.02364057 -0.001699984 0.02608615 -0.0243653 -0.001699984 0.0262618 -0.0242536 -0.001699984 0.02507644 -0.02443665 -0.001699984 0.0254848 -0.0245099 -0.001699984 0.02527755 -0.02449017 -0.001699984 0.02569228 -0.02449518 -0.001699984 0.02471405 -0.02423489 -0.001699984 0.0248869 -0.02435076 -0.001699984 0.02427488 -0.02354449 -0.001699984 0.02434009 -0.02374207 -0.001699984 0.02443689 -0.02392625 -0.001699984 0.02424305 -0.02333885 -0.001699984 0.02424567 -0.02313077 -0.001699984 0.02445358 -0.02254807 -0.001699984 0.02458339 -0.02238547 -0.001699984 0.02435225 -0.02272987 -0.001699984 0.02510529 -0.02205336 -0.001699984 0.02491378 -0.02213466 -0.001699984 0.02473819 -0.02224636 -0.001699984 0.02551519 -0.02199006 -0.001699984 0.02530765 -0.02200478 -0.001699984 0.02611309 -0.0221492 -0.001699984 0.02572238 -0.02200978 -0.001699984 0.02592349 -0.02206325 -0.001699984 0.02628588 -0.02226507 -0.001699984 0.02549999 -0.02324998 -9.72539e-4 0.02428239 -0.02292585 -0.001699984 0.0258947 -0.0244466 -0.001699984 -0.01973295 0.07706809 0.00149995 -0.01973295 0.07706809 5e-4 -0.01929557 0.07710278 0.00149995 -0.01885819 0.07713747 0.00149995 -0.01836067 0.07641458 0.00149995 -0.01854926 0.07601839 0.00149995 -0.01873797 0.07562226 0.00149995 -0.02011024 0.07627576 5e-4 -0.01961278 0.07555288 5e-4 -0.02067285 0.0754376 5e-4 -0.02077019 0.07561385 5e-4 -0.01791524 0.07527416 5e-4 -0.01805126 0.07512545 5e-4 -0.01820379 0.07499396 5e-4 -0.0209288 0.0761941 5e-4 -0.02093476 0.07639539 5e-4 -0.01973176 0.0747193 5e-4 -0.0199207 0.0747894 5e-4 -0.01873797 0.07562226 5e-4 -0.01779788 0.07543778 5e-4 -0.01845937 0.07785767 5e-4 -0.01893454 0.07467198 5e-4 -0.01913458 0.0746482 5e-4 -0.0193361 0.0746482 5e-4 -0.01885819 0.07713747 5e-4 -0.01836067 0.07641458 5e-4 -0.02091687 0.07659596 5e-4 -0.02034538 0.0776329 5e-4 -0.01963496 0.07799756 5e-4 -0.01943665 0.0780332 5e-4 -0.01923567 0.07804518 5e-4 -0.01903456 0.07803326 5e-4 -0.01740896 0.07582169 0.002499997 -0.01734775 0.07612949 0.002499997 -0.01734 0.07644295 7e-4 -0.01733797 0.07644307 0.002499997 -0.01737999 0.07675409 0.002499997 -0.01747256 0.0770539 0.002499997 -0.01747298 0.07705378 7e-4 -0.01761329 0.0773344 0.002499997 -0.01757168 0.07726269 7e-4 -0.01780015 0.07758635 7e-4 -0.01769185 0.07745295 7e-4 -0.0177983 0.0775879 0.002499997 -0.01783365 0.07762777 7e-4 -0.01802235 0.07780748 0.002499997 -0.01799529 0.07778459 7e-4 -0.01856297 0.07812219 0.002499997 -0.0182814 0.07798439 7e-4 -0.01827967 0.07798725 0.002499997 -0.01817417 0.07792121 7e-4 -0.01857405 0.07812637 7e-4 -0.01917636 0.07824426 0.002499997 -0.01901096 0.07823187 7e-4 -0.01886457 0.07820868 0.002499997 -0.01886516 0.0782057 7e-4 -0.01948946 0.07822656 7e-4 -0.01948976 0.07822805 0.002499997 -0.01979625 0.07816058 0.002499997 -0.020087 0.07804256 7e-4 -0.02008736 0.07804346 0.002499997 -0.02010327 0.07803547 7e-4 -0.02035528 0.07788008 0.002499997 -0.02063745 0.07762748 7e-4 -0.02059268 0.07767486 0.002499997 -0.02079296 0.0774334 0.002499997 -0.02095085 0.0771622 0.002499997 -0.02106195 0.07686865 0.002499997 -0.02106076 0.07686829 7e-4 -0.021133 0.07624727 0.002499997 -0.02112317 0.07656085 0.002499997 -0.02109098 0.07593625 0.002499997 -0.02099525 0.07563769 7e-4 -0.02099835 0.0756365 0.002499997 -0.02085626 0.07535666 7e-4 -0.02085769 0.075356 0.002499997 -0.02044856 0.07488286 0.002499997 -0.02067267 0.0751025 0.002499997 -0.02067077 0.07510417 7e-4 -0.02071076 0.07514786 7e-4 -0.0203883 0.07483488 7e-4 -0.02020156 0.07470905 7e-4 -0.02019125 0.07470309 0.002499997 -0.01960635 0.07448166 0.002499997 -0.01979017 0.07452797 7e-4 -0.01990687 0.07457131 7e-4 -0.01990795 0.07456821 0.002499997 -0.0193479 0.07444846 7e-4 -0.01929455 0.07444608 0.002499997 -0.01912277 0.07444846 7e-4 -0.01929455 0.07444846 7e-4 -0.01898115 0.07446229 0.002499997 -0.01868039 0.07452809 7e-4 -0.01867479 0.07452976 0.002499997 -0.01867485 0.07453006 7e-4 -0.01838356 0.07464689 0.002499997 -0.01811677 0.07481187 7e-4 -0.01838505 0.07464981 7e-4 -0.01846939 0.07460647 7e-4 -0.01811569 0.07481026 0.002499997 -0.01791185 0.0749821 7e-4 -0.01787829 0.07501548 0.002499997 -0.01787996 0.07501697 7e-4 -0.01767796 0.075257 0.002499997 -0.01752007 0.0755282 0.002499997 -0.01762878 0.07533109 7e-4 -0.01752007 0.0755282 7e-4 -0.02102607 0.07573968 6.38197e-4 -0.01733624 0.07640171 7e-4 -0.01734608 0.07640135 6.38197e-4 -0.02099645 0.07639718 5.09789e-4 -0.02104586 0.07618355 5.38197e-4 -0.02053546 0.07753425 5.09789e-4 -0.02057665 0.07757186 5.38197e-4 -0.01902729 0.07809466 5.09789e-4 -0.01923567 0.07810699 5.09789e-4 -0.01770067 0.07561415 5e-4 -0.01837086 0.07488149 5e-4 -0.01953607 0.07467198 5e-4 -0.0208109 0.07698398 5e-4 -0.02086818 0.07700717 5.09789e-4 -0.0198276 0.07793879 5e-4 -0.01984906 0.07799667 5.09789e-4 -0.01828587 0.07775527 5e-4 -0.01755416 0.07659637 5e-4 -0.01759564 0.07679349 5e-4 -0.01754218 0.0761944 5e-4 -0.01757186 0.0759952 5e-4 -0.01798129 0.07749277 5e-4 -0.01793569 0.07753449 5.09789e-4 -0.01785439 0.07733637 5e-4 -0.02048987 0.07749259 5e-4 -0.0203858 0.07767969 5.09789e-4 -0.02026689 0.07499378 5e-4 -0.02041947 0.07512527 5e-4 -0.02030438 0.07494467 5.09789e-4 -0.02046257 0.07508099 5.09789e-4 -0.019131 0.07458651 5.09789e-4 -0.01804906 0.07772207 5.38197e-4 -0.01789456 0.0775721 5.38197e-4 -0.01808547 0.07767987 5.09789e-4 -0.01945585 0.0781939 5.82443e-4 -0.0194506 0.07814997 5.38197e-4 -0.01923567 0.07816278 5.38197e-4 -0.02071225 0.07740467 5.38197e-4 -0.02066695 0.07737219 5.09789e-4 -0.02061676 0.07733607 5e-4 -0.02099025 0.07618856 5.09789e-4 -0.02018207 0.07474195 5.82443e-4 -0.02013128 0.07482808 5.09789e-4 -0.01892369 0.07461118 5.09789e-4 -0.01760506 0.07724416 5.82443e-4 -0.01764386 0.07722288 5.38197e-4 -0.01802015 0.07775568 5.82443e-4 -0.01825135 0.07780647 5.09789e-4 -0.01812577 0.07763308 5e-4 -0.01967298 0.07815486 5.82443e-4 -0.01944398 0.0780946 5.09789e-4 -0.01966255 0.07811188 5.38197e-4 -0.0196495 0.0780577 5.09789e-4 -0.02045106 0.07775539 5.82443e-4 -0.02086597 0.07724386 5.82443e-4 -0.02082729 0.07722246 5.38197e-4 -0.02077847 0.07719558 5.09789e-4 -0.02072429 0.07716578 5e-4 -0.02105736 0.07596147 5.82443e-4 -0.02101409 0.07597059 5.38197e-4 -0.02095729 0.07576286 5.38197e-4 -0.02095949 0.07598209 5.09789e-4 -0.02089899 0.0759949 5e-4 -0.02084589 0.07580059 5e-4 -0.02053219 0.07500916 5.82443e-4 -0.02068108 0.075172 5.82443e-4 -0.01999729 0.07461529 6.38197e-4 -0.0201596 0.0747801 5.38197e-4 -0.01994556 0.07473278 5.09789e-4 -0.02009987 0.07488125 5e-4 -0.01912498 0.07448667 5.82443e-4 -0.01934558 0.07448667 5.82443e-4 -0.01869159 0.07456457 5.82443e-4 -0.01870447 0.07460689 5.38197e-4 -0.01848477 0.07464146 5.82443e-4 -0.0187208 0.0746603 5.09789e-4 -0.01850265 0.07468187 5.38197e-4 -0.01852506 0.07473295 5.09789e-4 -0.01873886 0.07471936 5e-4 -0.01769977 0.07744729 6.38197e-4 -0.0177229 0.07743066 5.82443e-4 -0.01802349 0.07780605 7e-4 -0.01800167 0.0777772 6.38197e-4 -0.01784098 0.07762116 6.38197e-4 -0.0177589 0.07740485 5.38197e-4 -0.01879167 0.07818257 6.38197e-4 -0.01879835 0.07815498 5.82443e-4 -0.01901209 0.07822215 6.38197e-4 -0.01945918 0.07822209 6.38197e-4 -0.01923567 0.07823538 6.38197e-4 -0.01901549 0.07819396 5.82443e-4 -0.01902067 0.07814997 5.38197e-4 -0.02077925 0.07745265 7e-4 -0.0206303 0.07762086 6.38197e-4 -0.02042216 0.07772189 5.38197e-4 -0.02107685 0.07661986 5.82443e-4 -0.02109646 0.07640016 5.82443e-4 -0.02112489 0.07640099 6.38197e-4 -0.02109467 0.07595366 7e-4 -0.0210523 0.0763989 5.38197e-4 -0.02103316 0.07661336 5.38197e-4 -0.02019095 0.07470369 7e-4 -0.01934725 0.0744583 6.38197e-4 -0.01912337 0.0744583 6.38197e-4 -0.01890599 0.07451277 5.82443e-4 -0.01890099 0.07448476 6.38197e-4 -0.01912766 0.07453078 5.38197e-4 -0.01934295 0.07453078 5.38197e-4 -0.01756638 0.0757811 5.09789e-4 -0.01764488 0.07558768 5.09789e-4 -0.01751357 0.07576328 5.38197e-4 -0.01759445 0.07556366 5.38197e-4 -0.01747167 0.07574909 5.82443e-4 -0.01744478 0.07573997 6.38197e-4 -0.01752895 0.07553237 6.38197e-4 -0.01743549 0.07573688 7e-4 -0.01762497 0.07580089 5e-4 -0.01745688 0.075971 5.38197e-4 -0.01741355 0.07596188 5.82443e-4 -0.01738578 0.07595598 6.38197e-4 -0.01741206 0.07582259 7e-4 -0.01734995 0.07612979 7e-4 -0.01751136 0.07598251 5.09789e-4 -0.01737618 0.07595396 7e-4 -0.01748055 0.07618886 5.09789e-4 -0.01742506 0.07618397 5.38197e-4 -0.0174188 0.0763992 5.38197e-4 -0.01738095 0.0761801 5.82443e-4 -0.0173527 0.07617747 6.38197e-4 -0.01734298 0.0761767 7e-4 -0.01753628 0.07639569 5e-4 -0.01749294 0.07660549 5.09789e-4 -0.01747447 0.07639759 5.09789e-4 -0.01743787 0.07661366 5.38197e-4 -0.01737445 0.07640045 5.82443e-4 -0.01739406 0.07662028 5.82443e-4 -0.01736599 0.07662445 6.38197e-4 -0.01735639 0.07662588 7e-4 -0.01740264 0.07684618 7e-4 -0.01738315 0.07675337 7e-4 -0.0175361 0.0768097 5.09789e-4 -0.01748228 0.07682436 5.38197e-4 -0.0174396 0.0768361 5.82443e-4 -0.01748389 0.07705581 6.38197e-4 -0.01747488 0.07705938 7e-4 -0.01760286 0.07700747 5.09789e-4 -0.0175513 0.07702839 5.38197e-4 -0.01751029 0.07704508 5.82443e-4 -0.01741218 0.07684355 6.38197e-4 -0.0176602 0.07698428 5e-4 -0.01769268 0.07719588 5.09789e-4 -0.01758027 0.07725787 6.38197e-4 -0.01761597 0.07733279 7e-4 -0.01817965 0.0779131 6.38197e-4 -0.0178619 0.07760196 5.82443e-4 -0.0178042 0.07737237 5.09789e-4 -0.0177468 0.07716608 5e-4 -0.01843118 0.07791268 5.09789e-4 -0.01840567 0.07796227 5.38197e-4 -0.0182203 0.07785278 5.38197e-4 -0.01819556 0.0778895 5.82443e-4 -0.01838546 0.07800155 5.82443e-4 -0.01856327 0.0781216 7e-4 -0.01860278 0.07804906 5.38197e-4 -0.01858735 0.07809048 5.82443e-4 -0.01837247 0.07802689 6.38197e-4 -0.01836806 0.07803559 7e-4 -0.01882177 0.07805776 5.09789e-4 -0.01880878 0.07811188 5.38197e-4 -0.01862215 0.07799679 5.09789e-4 -0.01857745 0.07811719 6.38197e-4 -0.01946038 0.07823181 7e-4 -0.01923567 0.07824516 7e-4 -0.0191766 0.0782417 7e-4 -0.01878935 0.07819205 7e-4 -0.01923567 0.07820695 5.82443e-4 -0.01883637 0.07799768 5e-4 -0.01864367 0.07793885 5e-4 -0.01989728 0.07812619 7e-4 -0.01986849 0.078049 5.38197e-4 -0.01988399 0.07809036 5.82443e-4 -0.01989376 0.07811707 6.38197e-4 -0.01967966 0.07818245 6.38197e-4 -0.01979529 0.07815736 7e-4 -0.01968199 0.07819199 7e-4 -0.0200988 0.07802677 6.38197e-4 -0.02004009 0.0779125 5.09789e-4 -0.02025097 0.0778526 5.38197e-4 -0.0200656 0.0779621 5.38197e-4 -0.02027565 0.07788926 5.82443e-4 -0.02008575 0.07800149 5.82443e-4 -0.02029705 0.07792097 7e-4 -0.02059078 0.07767289 7e-4 -0.0204696 0.0777769 6.38197e-4 -0.02047598 0.07778435 7e-4 -0.02035355 0.07787775 7e-4 -0.02029156 0.07791286 6.38197e-4 -0.02089947 0.07726228 7e-4 -0.02079194 0.07743269 7e-4 -0.02077138 0.07744699 6.38197e-4 -0.02074825 0.07743036 5.82443e-4 -0.02060925 0.07760179 5.82443e-4 -0.02021986 0.07780635 5.09789e-4 -0.02018529 0.07775509 5e-4 -0.0200119 0.07785749 5e-4 -0.02094787 0.07716065 7e-4 -0.02091985 0.07702809 5.38197e-4 -0.02089089 0.07725757 6.38197e-4 -0.02093499 0.0768094 5.09789e-4 -0.02098876 0.07682406 5.38197e-4 -0.02103149 0.07683581 5.82443e-4 -0.02096086 0.07704478 5.82443e-4 -0.02098715 0.07705539 6.38197e-4 -0.02099627 0.07705909 7e-4 -0.02087539 0.07679307 5e-4 -0.02097797 0.0766052 5.09789e-4 -0.02111464 0.07662546 7e-4 -0.02105885 0.07684326 6.38197e-4 -0.02106839 0.07684576 7e-4 -0.02112799 0.07617628 7e-4 -0.02113008 0.07624727 7e-4 -0.02111816 0.07617717 6.38197e-4 -0.02113467 0.07640129 7e-4 -0.02110499 0.07662409 6.38197e-4 -0.02112048 0.07656067 7e-4 -0.02103537 0.07573646 7e-4 -0.02108997 0.07593649 7e-4 -0.02108508 0.07595568 6.38197e-4 -0.02108985 0.07617968 5.82443e-4 -0.02090448 0.0757808 5.09789e-4 -0.02087628 0.07556337 5.38197e-4 -0.02099919 0.0757488 5.82443e-4 -0.02095067 0.0755279 7e-4 -0.02084195 0.07533079 7e-4 -0.02082598 0.07558739 5.09789e-4 -0.02077227 0.07537478 5.38197e-4 -0.02091628 0.07554429 5.82443e-4 -0.02080965 0.07535117 5.82443e-4 -0.02094185 0.07553207 6.38197e-4 -0.02083379 0.07533597 6.38197e-4 -0.02060347 0.075235 5.09789e-4 -0.02072519 0.07540458 5.09789e-4 -0.02064675 0.07519978 5.38197e-4 -0.02070319 0.07515406 6.38197e-4 -0.02038228 0.07484257 6.38197e-4 -0.02055197 0.07498878 6.38197e-4 -0.02044659 0.07488507 7e-4 -0.02055877 0.0749818 7e-4 -0.02000129 0.07460635 7e-4 -0.02019655 0.07471758 6.38197e-4 -0.02036505 0.07486516 5.82443e-4 -0.02050137 0.07504099 5.38197e-4 -0.02033829 0.07490038 5.38197e-4 -0.02055549 0.07527387 5e-4 -0.01974987 0.07466018 5.09789e-4 -0.01976615 0.07460677 5.38197e-4 -0.01996797 0.07468175 5.38197e-4 -0.01977908 0.07456445 5.82443e-4 -0.01998585 0.07464128 5.82443e-4 -0.01978737 0.07453727 6.38197e-4 -0.01956468 0.07451266 5.82443e-4 -0.01960587 0.07448345 7e-4 -0.01954698 0.07461106 5.09789e-4 -0.01933968 0.07458651 5.09789e-4 -0.01955676 0.07455629 5.38197e-4 -0.01956969 0.07448476 6.38197e-4 -0.01957136 0.0744751 7e-4 -0.0188992 0.07447516 7e-4 -0.01898157 0.07446539 7e-4 -0.01847338 0.07461535 6.38197e-4 -0.01868325 0.07453739 6.38197e-4 -0.0189138 0.07455629 5.38197e-4 -0.01854997 0.07478946 5e-4 -0.01828855 0.07474219 5.82443e-4 -0.01826906 0.07470929 7e-4 -0.01808238 0.07483506 7e-4 -0.01833939 0.07482826 5.09789e-4 -0.01810556 0.0748654 5.82443e-4 -0.01831108 0.07478028 5.38197e-4 -0.01827406 0.0747177 6.38197e-4 -0.01800817 0.07508116 5.09789e-4 -0.0181663 0.07494485 5.09789e-4 -0.01813244 0.07490056 5.38197e-4 -0.0180884 0.07484287 6.38197e-4 -0.01782399 0.07520008 5.38197e-4 -0.01796936 0.07504117 5.38197e-4 -0.01793849 0.07500946 5.82443e-4 -0.01776754 0.0751543 6.38197e-4 -0.01791876 0.07498908 6.38197e-4 -0.01786726 0.07523518 5.09789e-4 -0.01766109 0.07535147 5.82443e-4 -0.01778966 0.07517218 5.82443e-4 -0.01768058 0.07525891 7e-4 -0.01775997 0.07514816 7e-4 -0.01774555 0.07540476 5.09789e-4 -0.01769846 0.07537508 5.38197e-4 -0.01755458 0.07554465 5.82443e-4 -0.01763707 0.07533627 6.38197e-4 -0.02019226 0.07663577 0.01227396 -0.02019226 0.07663577 0.002599954 -0.02023547 0.07634085 0.002599954 -0.02023547 0.07634085 0.01227396 -0.02018976 0.07604628 0.01227396 -0.02018976 0.07604628 0.002599954 -0.02005928 0.0757783 0.002599954 -0.02005928 0.0757783 0.01227396 -0.01985555 0.07556068 0.002599954 -0.01985555 0.07556068 0.01227396 -0.01959675 0.0754128 0.002599954 -0.01959675 0.0754128 0.01227396 -0.01930588 0.07534766 0.002599954 -0.01900875 0.0753712 0.002599954 -0.01930588 0.07534766 0.01227396 -0.01900875 0.0753712 0.01227396 -0.01873177 0.07548129 0.01227396 -0.01873177 0.07548129 0.002599954 -0.01849949 0.07566815 0.002599954 -0.01849949 0.07566815 0.01227396 -0.01833266 0.07591515 0.002599954 -0.01833266 0.07591515 0.01227396 -0.01824599 0.07620036 0.002599954 -0.0182473 0.0764985 0.002599954 -0.01824599 0.07620036 0.01227396 -0.0182473 0.0764985 0.01227396 -0.01833635 0.076783 0.002599954 -0.01850539 0.07702845 0.002599954 -0.01833635 0.076783 0.01227396 -0.01850539 0.07702845 0.01227396 -0.01873928 0.0772134 0.01227396 -0.01873928 0.0772134 0.002599954 -0.01901715 0.07732105 0.01227396 -0.01901715 0.07732105 0.002599954 -0.01931458 0.07734209 0.002599954 -0.01931458 0.07734209 0.01227396 -0.01960486 0.0772745 0.01227396 -0.01960486 0.0772745 0.002599954 -0.01986235 0.07712429 0.002599954 -0.01986235 0.07712429 0.01227396 -0.02006417 0.07690489 0.002599954 -0.02013826 0.07677519 0.002599954 -0.02006417 0.07690489 0.01227396 0.02026569 0.07769238 5e-4 0.01837009 0.07781225 5e-4 0.01854956 0.07790356 5e-4 0.0197317 0.07796907 5e-4 0.0188232 0.07469427 5e-4 0.01863068 0.07475388 5e-4 0.0209279 0.07628816 5e-4 0.02086699 0.07589066 5e-4 0.02066987 0.07724708 5e-4 0.01965558 0.07711207 5e-4 0.02010637 0.07635909 5e-4 0.0200991 0.07780557 5e-4 0.01753616 0.07650268 5e-4 0.01791298 0.07742148 5e-4 0.0207144 0.07551866 5e-4 0.02047866 0.07519286 5e-4 0.01762056 0.07689589 5e-4 0.01877808 0.07709807 5e-4 0.01827365 0.07493889 5e-4 0.01765096 0.07571238 5e-4 0.01913475 0.07804256 5e-4 0.01967966 0.07559227 5e-4 0.01981455 0.07474929 5e-4 0.01962178 0.07469117 5e-4 0.01922225 0.07464516 5e-4 0.01902127 0.07465785 5e-4 0.01797008 0.07520258 5e-4 0.01880216 0.07557827 5e-4 0.01784378 0.07535946 5e-4 0.01773697 0.07553029 5e-4 0.01835137 0.07633125 5e-4 0.02088916 0.07542139 0.002499997 0.021097 0.076011 7e-4 0.02109915 0.07601058 0.002499997 0.02101558 0.07570827 7e-4 0.02101856 0.07570725 0.002499997 0.02112877 0.07632297 0.002499997 0.0211268 0.07632285 7e-4 0.02110648 0.07663595 0.002499997 0.02103298 0.07694107 0.002499997 0.02108967 0.07672929 7e-4 0.02091038 0.07722985 0.002499997 0.0210312 0.07694667 7e-4 0.02074176 0.07749456 0.002499997 0.02083945 0.07735317 7e-4 0.02090758 0.07722836 7e-4 0.02073979 0.07749319 7e-4 0.02070885 0.07753658 7e-4 0.02055758 0.07770329 7e-4 0.02053195 0.07772785 0.002499997 0.02028656 0.07792359 0.002499997 0.02001208 0.07807546 7e-4 0.02000159 0.07808095 7e-4 0.02001237 0.07807606 0.002499997 0.01940786 0.07823669 0.002499997 0.01971608 0.07817858 7e-4 0.01971679 0.0781815 0.002499997 0.0193488 0.0782414 7e-4 0.01909404 0.07824039 0.002499997 0.01909428 0.0782389 7e-4 0.01890009 0.07821649 7e-4 0.01878476 0.07818907 7e-4 0.01878398 0.07819235 0.002499997 0.01848608 0.078094 0.002499997 0.01820838 0.07794785 0.002499997 0.01791077 0.0777136 7e-4 0.01795846 0.07775795 0.002499997 0.01775819 0.07754808 7e-4 0.0177443 0.07752889 7e-4 0.01774328 0.07752966 0.002499997 0.01743918 0.07698309 0.002499997 0.01756858 0.07726895 0.002499997 0.01757144 0.0772674 7e-4 0.01744025 0.07698255 7e-4 0.01743137 0.07696068 7e-4 0.0173586 0.07667976 0.002499997 0.01733189 0.07636725 7e-4 0.01732945 0.07629626 7e-4 0.01732897 0.07636737 0.002499997 0.01735126 0.07605439 0.002499997 0.01734858 0.07607197 7e-4 0.01754879 0.07546108 7e-4 0.01746535 0.07563799 7e-4 0.0174247 0.07574927 0.002499997 0.01742786 0.07575041 7e-4 0.01756137 0.07543438 7e-4 0.01754736 0.07546049 0.002499997 0.01792788 0.07496458 7e-4 0.01771795 0.07519739 7e-4 0.01771599 0.07519578 0.002499997 0.01768088 0.07524359 7e-4 0.01792579 0.07496249 0.002499997 0.01817119 0.07476675 0.002499997 0.01874148 0.07451057 7e-4 0.01844537 0.07461428 0.002499997 0.01874095 0.0745089 0.002499997 0.01899677 0.07445937 7e-4 0.01936346 0.07445305 7e-4 0.01904988 0.07445371 0.002499997 0.01936358 0.07444995 0.002499997 0.01966798 0.07449656 7e-4 0.0196737 0.07449799 0.002499997 0.02008986 0.07465147 7e-4 0.01997166 0.0745964 0.002499997 0.02024835 0.07474428 7e-4 0.02024936 0.07474249 0.002499997 0.02049779 0.074934 7e-4 0.02062577 0.07505726 7e-4 0.02049928 0.07493239 0.002499997 0.02071446 0.07516068 0.002499997 0.02076828 0.07523149 7e-4 0.02088916 0.07542139 7e-4 0.01739406 0.0758515 7e-4 0.01762616 0.07736569 7e-4 0.02112776 0.07628148 7e-4 0.01922196 0.07458341 5.09789e-4 0.01943045 0.07459497 5.09789e-4 0.01943677 0.0745396 5.38197e-4 0.01792436 0.07516109 5.09789e-4 0.01746767 0.07629978 5.09789e-4 0.01800656 0.07761406 5.09789e-4 0.01934355 0.07815909 5.38197e-4 0.02064466 0.0774849 5.38197e-4 0.02060627 0.07534879 5e-4 0.0205242 0.07515096 5.09789e-4 0.02017307 0.0749315 5e-4 0.01999926 0.07482975 5e-4 0.0175873 0.07590347 5e-4 0.01779484 0.07725828 5e-4 0.01769697 0.07708227 5e-4 0.01873868 0.077973 5e-4 0.01992028 0.07789826 5e-4 0.02089375 0.07668888 5e-4 0.02098965 0.07628607 5.09789e-4 0.02080178 0.07570016 5e-4 0.02092659 0.0758742 5.09789e-4 0.02055305 0.07741117 5e-4 0.01933616 0.07804179 5e-4 0.01953607 0.07801717 5e-4 0.0182026 0.07770049 5e-4 0.01752948 0.07630139 5e-4 0.01756668 0.07670176 5e-4 0.01807355 0.07501506 5.09789e-4 0.02053087 0.07767599 5.82443e-4 0.02060127 0.07744997 5.09789e-4 0.0205 0.0776444 5.38197e-4 0.01912575 0.07820409 5.82443e-4 0.01912826 0.07815998 5.38197e-4 0.01934009 0.07810348 5.09789e-4 0.01913136 0.07810425 5.09789e-4 0.01804947 0.0775696 5e-4 0.01743018 0.07608377 5.38197e-4 0.01748538 0.07609188 5.09789e-4 0.01803696 0.07497298 5.38197e-4 0.01820766 0.07484167 5.38197e-4 0.01811408 0.07506179 5e-4 0.01823896 0.07488775 5.09789e-4 0.01965916 0.07453376 5.82443e-4 0.01964884 0.07457679 5.38197e-4 0.01963597 0.07463109 5.09789e-4 0.01942336 0.07465636 5e-4 0.02087277 0.07712048 5.38197e-4 0.02046096 0.07760447 5.09789e-4 0.02041774 0.0775603 5e-4 0.0189144 0.07813531 5.38197e-4 0.01892399 0.07808035 5.09789e-4 0.01893466 0.07801955 5e-4 0.01831066 0.07791376 5.38197e-4 0.01782196 0.07749587 5.38197e-4 0.01765835 0.07734519 5.82443e-4 0.01769578 0.07732141 5.38197e-4 0.01786506 0.07746058 5.09789e-4 0.01754659 0.07610076 5e-4 0.01752758 0.07588738 5.09789e-4 0.01771199 0.0752657 5.82443e-4 0.01818275 0.07480508 5.82443e-4 0.01841825 0.07478088 5.09789e-4 0.01900148 0.07449728 5.82443e-4 0.0198704 0.07459735 5.82443e-4 0.01985508 0.0746389 5.38197e-4 0.01983588 0.07469129 5.09789e-4 0.02093845 0.07715147 6.38197e-4 0.02053076 0.0777266 7e-4 0.02070128 0.0775305 6.38197e-4 0.02080708 0.07733285 5.82443e-4 0.0208224 0.0770967 5.09789e-4 0.01978796 0.0781508 6.38197e-4 0.01977956 0.07812368 5.82443e-4 0.01912367 0.0782423 7e-4 0.0193482 0.07823157 6.38197e-4 0.0195654 0.07817625 5.82443e-4 0.01810485 0.07782948 5.82443e-4 0.0177657 0.07754188 6.38197e-4 0.0179373 0.07768607 5.82443e-4 0.01737505 0.0765177 5.82443e-4 0.01735216 0.07605457 7e-4 0.01733928 0.0762965 6.38197e-4 0.01736766 0.07629728 5.82443e-4 0.01782929 0.07507479 6.38197e-4 0.01785027 0.07509386 5.82443e-4 0.01817148 0.07476741 7e-4 0.01816129 0.07477349 7e-4 0.01816678 0.07478159 6.38197e-4 0.01788306 0.0751236 5.38197e-4 0.01774799 0.07529139 5.38197e-4 0.01966565 0.07450616 6.38197e-4 0.0194419 0.07449555 5.82443e-4 0.0192216 0.07448339 5.82443e-4 0.01922178 0.07452768 5.38197e-4 0.0190137 0.07459658 5.09789e-4 0.02085888 0.07567667 5.09789e-4 0.02095144 0.07563877 5.82443e-4 0.02088069 0.07542616 6.38197e-4 0.02098679 0.07562428 7e-4 0.02098029 0.0758593 5.38197e-4 0.0209105 0.07565557 5.38197e-4 0.02102285 0.0758475 5.82443e-4 0.02105027 0.07583987 6.38197e-4 0.02097779 0.07562798 6.38197e-4 0.02105969 0.07583719 7e-4 0.0209704 0.07607829 5.09789e-4 0.02106916 0.07606309 5.82443e-4 0.02090924 0.07608765 5e-4 0.02104538 0.07628428 5.38197e-4 0.02102547 0.07606977 5.38197e-4 0.02111798 0.07628178 6.38197e-4 0.0210973 0.0760588 6.38197e-4 0.02110695 0.07605737 7e-4 0.02108967 0.07628279 5.82443e-4 0.02112197 0.07650649 7e-4 0.02092278 0.07648956 5e-4 0.02098429 0.07649475 5.09789e-4 0.0210399 0.07649946 5.38197e-4 0.02108007 0.07672727 6.38197e-4 0.02108395 0.07650327 5.82443e-4 0.02111226 0.07650566 6.38197e-4 0.02110326 0.07663547 7e-4 0.02103269 0.07694095 7e-4 0.02095425 0.0767014 5.09789e-4 0.02100884 0.0767126 5.38197e-4 0.0210523 0.0767216 5.82443e-4 0.02090007 0.07690286 5.09789e-4 0.02095299 0.07692056 5.38197e-4 0.02091276 0.07713925 5.82443e-4 0.0209949 0.07693457 5.82443e-4 0.0210219 0.07694357 6.38197e-4 0.02083116 0.07734799 6.38197e-4 0.02094739 0.07715559 7e-4 0.02038764 0.07785087 7e-4 0.02055078 0.07769626 6.38197e-4 0.02067917 0.07751268 5.82443e-4 0.02076959 0.07730948 5.38197e-4 0.02072227 0.07727986 5.09789e-4 0.02076649 0.07707029 5e-4 0.02084147 0.07688337 5e-4 0.02013069 0.07785868 5.09789e-4 0.02030336 0.07774138 5.09789e-4 0.0203374 0.07778561 5.38197e-4 0.02019649 0.07796895 6.38197e-4 0.0203644 0.07782065 5.82443e-4 0.02038168 0.07784318 6.38197e-4 0.02028477 0.07792079 7e-4 0.0201593 0.0779066 5.38197e-4 0.01998609 0.07804608 5.82443e-4 0.02018189 0.07794457 5.82443e-4 0.01999759 0.07807195 6.38197e-4 0.0202015 0.07797735 7e-4 0.01994538 0.0779547 5.09789e-4 0.01996809 0.07800567 5.38197e-4 0.01976644 0.07808136 5.38197e-4 0.01979088 0.07816016 7e-4 0.01940757 0.07823419 7e-4 0.01957046 0.07820427 6.38197e-4 0.01957225 0.07821387 7e-4 0.01890176 0.07820689 6.38197e-4 0.01912426 0.07823246 6.38197e-4 0.01934635 0.07820326 5.82443e-4 0.01955735 0.0781328 5.38197e-4 0.01954728 0.07807797 5.09789e-4 0.01974999 0.0780282 5.09789e-4 0.01868104 0.07816445 7e-4 0.01872086 0.07803219 5.09789e-4 0.01870477 0.0780856 5.38197e-4 0.01890665 0.07817888 5.82443e-4 0.01850265 0.07801139 5.38197e-4 0.01869207 0.07812786 5.82443e-4 0.01868385 0.0781551 6.38197e-4 0.01847356 0.07807797 6.38197e-4 0.01848638 0.07809311 7e-4 0.018525 0.07796025 5.09789e-4 0.01828837 0.07795196 5.82443e-4 0.01848495 0.07805186 5.82443e-4 0.01827394 0.07797646 6.38197e-4 0.01846969 0.07808685 7e-4 0.01796025 0.07775586 7e-4 0.01791757 0.07770657 6.38197e-4 0.0180878 0.07785207 6.38197e-4 0.0180819 0.07785987 7e-4 0.01820999 0.07794547 7e-4 0.01826906 0.07798486 7e-4 0.01763445 0.07736051 6.38197e-4 0.01778769 0.07752388 5.82443e-4 0.01796799 0.07765418 5.38197e-4 0.01813155 0.07779419 5.38197e-4 0.01816529 0.07774966 5.09789e-4 0.01833885 0.07786566 5.09789e-4 0.0176413 0.07710909 5.09789e-4 0.01774275 0.07729148 5.09789e-4 0.01759105 0.07713329 5.38197e-4 0.01752555 0.07716476 6.38197e-4 0.01751679 0.077169 7e-4 0.01756209 0.07691586 5.09789e-4 0.01746749 0.07694828 5.82443e-4 0.01755118 0.07715237 5.82443e-4 0.01745176 0.07672649 5.38197e-4 0.0175094 0.07693397 5.38197e-4 0.01740849 0.07673579 5.82443e-4 0.01738065 0.07674169 6.38197e-4 0.01744055 0.07695746 6.38197e-4 0.01734679 0.07652038 6.38197e-4 0.01733708 0.07652127 7e-4 0.01736128 0.0766794 7e-4 0.01737117 0.07674378 7e-4 0.0174036 0.07585406 6.38197e-4 0.0173583 0.0760734 6.38197e-4 0.01738637 0.07607746 5.82443e-4 0.01741188 0.07629835 5.38197e-4 0.01741915 0.07651358 5.38197e-4 0.01747465 0.07650846 5.09789e-4 0.0175063 0.07671475 5.09789e-4 0.01759368 0.07568937 5.09789e-4 0.01747375 0.07587289 5.38197e-4 0.01743096 0.07586139 5.82443e-4 0.01747447 0.07564157 6.38197e-4 0.01759499 0.07545268 5.82443e-4 0.01754188 0.07566869 5.38197e-4 0.01750087 0.07565218 5.82443e-4 0.01779347 0.0753237 5.09789e-4 0.01768267 0.0755006 5.09789e-4 0.01763379 0.0754739 5.38197e-4 0.01768875 0.07524919 6.38197e-4 0.01756995 0.07543909 6.38197e-4 0.0179829 0.07491075 7e-4 0.01798939 0.07491821 6.38197e-4 0.01782196 0.07506817 7e-4 0.01835465 0.07465815 7e-4 0.01800799 0.0749396 5.82443e-4 0.01844668 0.07483577 5e-4 0.01860898 0.074696 5.09789e-4 0.01858937 0.0746439 5.38197e-4 0.01839268 0.0747314 5.38197e-4 0.01837229 0.07469218 5.82443e-4 0.01835918 0.07466685 6.38197e-4 0.01856034 0.07456666 7e-4 0.01844668 0.07461726 7e-4 0.0187754 0.07450008 7e-4 0.01880836 0.07463425 5.09789e-4 0.01879507 0.07458019 5.38197e-4 0.01857376 0.07460236 5.82443e-4 0.01856374 0.0745759 6.38197e-4 0.01900684 0.07454121 5.38197e-4 0.01878446 0.07453715 5.82443e-4 0.01877778 0.07450956 6.38197e-4 0.01944506 0.07446736 6.38197e-4 0.01944625 0.0744577 7e-4 0.01922148 0.07445496 6.38197e-4 0.01922148 0.07444518 7e-4 0.01905 0.07445609 7e-4 0.01899796 0.07446908 6.38197e-4 0.01988345 0.07456147 7e-4 0.01967358 0.07449829 7e-4 0.02005249 0.07472497 5.38197e-4 0.02007257 0.07468545 5.82443e-4 0.02008545 0.07466018 6.38197e-4 0.01988017 0.07457065 6.38197e-4 0.01997035 0.07459938 7e-4 0.02002727 0.07477468 5.09789e-4 0.0202074 0.07488006 5.09789e-4 0.02041006 0.0749638 5.38197e-4 0.02023839 0.07483381 5.38197e-4 0.02026295 0.07479697 5.82443e-4 0.02046358 0.0749011 7e-4 0.02027869 0.07477331 6.38197e-4 0.02028417 0.0747652 7e-4 0.02033364 0.07505309 5e-4 0.02037376 0.07500606 5.09789e-4 0.02059769 0.07508319 5.82443e-4 0.02043879 0.07493007 5.82443e-4 0.02045726 0.07490849 6.38197e-4 0.02061855 0.07506388 6.38197e-4 0.02071195 0.07516276 7e-4 0.02056515 0.07511317 5.38197e-4 0.02073729 0.0752539 5.82443e-4 0.0207684 0.07548856 5.09789e-4 0.02065628 0.07531249 5.09789e-4 0.02081716 0.0754615 5.38197e-4 0.02070146 0.07527989 5.38197e-4 0.02085578 0.07543998 5.82443e-4 0.02076035 0.07523727 6.38197e-4 0.01829224 0.07669568 0.002599954 0.01829224 0.07669568 0.01227396 0.01823055 0.07640409 0.002599954 0.01823055 0.07640409 0.01227396 0.01825755 0.0761072 0.002599954 0.01825755 0.0761072 0.01227396 0.01837086 0.07583147 0.002599954 0.01837086 0.07583147 0.01227396 0.01856034 0.07560145 0.002599954 0.01856034 0.07560145 0.01227396 0.01880937 0.07543748 0.002599954 0.01880937 0.07543748 0.01227396 0.01909559 0.07535409 0.002599954 0.01909559 0.07535409 0.01227396 0.01939356 0.07535886 0.002599954 0.01967698 0.07545119 0.002599954 0.01939356 0.07535886 0.01227396 0.01967698 0.07545119 0.01227396 0.01992058 0.07562297 0.002599954 0.01992058 0.07562297 0.01227396 0.02010267 0.07585901 0.01227396 0.02010267 0.07585901 0.002599954 0.02020716 0.07613819 0.002599954 0.02022475 0.07643568 0.002599954 0.02020716 0.07613819 0.01227396 0.02022475 0.07643568 0.01227396 0.02015388 0.0767253 0.002599954 0.02015388 0.0767253 0.01227396 0.02000069 0.076981 0.002599954 0.02000069 0.076981 0.01227396 0.01977896 0.07718026 0.002599954 0.01977896 0.07718026 0.01227396 0.01950848 0.07730525 0.002599954 0.01950848 0.07730525 0.01227396 0.01921296 0.07734507 0.002599954 0.01921296 0.07734507 0.01227396 0.01891899 0.07729595 0.002599954 0.01891899 0.07729595 0.01227396 0.01865249 0.07716238 0.01227396 0.01865249 0.07716238 0.002599954 0.01843726 0.07695615 0.002599954 0.01843726 0.07695615 0.01227396 0.01835495 0.0768314 0.002599954 -0.03037995 -0.06837749 0.01369994 -0.03048008 -0.06808018 0.01189994 -0.03036677 -0.06842297 0.01369994 -0.03037786 -0.06837689 0.01189994 -0.03032588 -0.06868636 0.01189994 -0.03032785 -0.06868648 0.01369994 -0.03032886 -0.069 0.01369994 -0.03032559 -0.06900018 0.01189994 -0.03033566 -0.06909447 0.01369994 -0.03037685 -0.06930977 0.01189994 -0.03037726 -0.06930971 0.01369994 -0.0303784 -0.06931549 0.01369994 -0.03044688 -0.06952989 0.01369994 -0.03062754 -0.06988281 0.01189994 -0.03047847 -0.06960666 0.01189994 -0.0305404 -0.06973469 0.01369994 -0.03048139 -0.06960541 0.01369994 -0.03065735 -0.06992709 0.01369994 -0.03082007 -0.07013058 0.01189994 -0.03095519 -0.07026368 0.01369994 -0.0311318 -0.07040315 0.01369994 -0.0310508 -0.07034337 0.01189994 -0.03152817 -0.07061505 0.01369994 -0.0313133 -0.07051527 0.01189994 -0.03160047 -0.07064157 0.01189994 -0.03196328 -0.07072788 0.01369994 -0.03190469 -0.070719 0.01189994 -0.0321877 -0.07074487 0.01369994 -0.03221738 -0.07074517 0.01189994 -0.03283405 -0.07064187 0.01369994 -0.03283435 -0.07064288 0.01189994 -0.03263479 -0.07069915 0.01369994 -0.03252959 -0.07071626 0.01369994 -0.03253006 -0.07071959 0.01189994 -0.03241258 -0.07073527 0.01369994 -0.03285115 -0.07063698 0.01369994 -0.0330587 -0.07054966 0.01369994 -0.03338479 -0.07034569 0.01189994 -0.03312188 -0.07051706 0.01189994 -0.03359967 -0.07015079 0.01369994 -0.03361576 -0.07013338 0.01189994 -0.03374439 -0.06997829 0.01369994 -0.03395849 -0.06961017 0.01189994 -0.03386765 -0.06979 0.01369994 -0.03380876 -0.06988596 0.01189994 -0.03396785 -0.06958836 0.01369994 -0.03406065 -0.06931346 0.01189994 -0.03411257 -0.06900399 0.01189994 -0.0341143 -0.06870788 0.01369994 -0.03411287 -0.06869018 0.01189994 -0.03406155 -0.06838059 0.01189994 -0.03402906 -0.06826668 0.01369994 -0.03405839 -0.06838148 0.01369994 -0.03408479 -0.06848478 0.01369994 -0.03395998 -0.0680837 0.01189994 -0.0338425 -0.0678578 0.01369994 -0.03381085 -0.06780755 0.01189994 -0.03361618 -0.0675618 0.01369994 -0.03361845 -0.06755977 0.01189994 -0.03356516 -0.0675041 0.01369994 -0.03338778 -0.06734699 0.01189994 -0.03312528 -0.06717509 0.01189994 -0.03283798 -0.06704878 0.01189994 -0.03321248 -0.06722545 0.01369994 -0.03280425 -0.06703746 0.01369994 -0.03253388 -0.06697136 0.01189994 -0.03253358 -0.0669738 0.01369994 -0.03222119 -0.06694519 0.01189994 -0.03190839 -0.06697076 0.01189994 -0.03169459 -0.0670191 0.01369994 -0.03160417 -0.06704747 0.01189994 -0.03131669 -0.0671733 0.01189994 -0.03148227 -0.0670939 0.01369994 -0.03109157 -0.06731599 0.01369994 -0.03105378 -0.06734466 0.01189994 -0.03082269 -0.06755697 0.01189994 -0.03062969 -0.06780439 0.01189994 -0.03062969 -0.06780439 0.01369994 -0.03051775 -0.06799966 0.01369994 -0.03105515 -0.06734639 0.01369994 -0.03160518 -0.06705057 0.01369994 -0.03312367 -0.06717801 0.01369994 -0.03214168 -0.06702929 0.01386177 -0.03360557 -0.06775796 0.01389014 -0.03346729 -0.06760156 0.01389014 -0.03338277 -0.07024151 0.01386177 -0.03091716 -0.0677523 0.01389998 -0.0312103 -0.06747698 0.01389998 -0.03105556 -0.06760585 0.01389998 -0.03137916 -0.06736725 0.01389998 -0.03174978 -0.06721127 0.01389998 -0.03293025 -0.06730097 0.01389998 -0.03376597 -0.06813967 0.01389998 -0.03388839 -0.06852269 0.01389998 -0.03369414 -0.06969058 0.01389998 -0.0327847 -0.07044839 0.01389998 -0.0328052 -0.07050669 0.01389014 -0.03260457 -0.07056427 0.01389014 -0.0312463 -0.07023918 0.01389998 -0.03053396 -0.06906819 0.01389998 -0.03051936 -0.06886726 0.01389998 -0.03052866 -0.0686661 0.01389998 -0.0305618 -0.06846749 0.01389998 -0.030797 -0.06791388 0.01389998 -0.0308218 -0.06981319 0.01389998 -0.03077095 -0.06984835 0.01389014 -0.03071707 -0.06964105 0.01389998 -0.03066247 -0.06966996 0.01389014 -0.03198188 -0.07059085 0.01389014 -0.03179258 -0.07049077 0.01389998 -0.03314536 -0.07027077 0.01389998 -0.03334707 -0.07019865 0.01389014 -0.03297024 -0.07037025 0.01389998 -0.03391748 -0.06892377 0.01389998 -0.03397917 -0.06892657 0.01389014 -0.03389614 -0.0691241 0.01389998 -0.03395718 -0.06913417 0.01389014 -0.03355699 -0.06779611 0.01389998 -0.03367167 -0.06796169 0.01389998 -0.03214406 -0.06708496 0.01389014 -0.03234815 -0.06715005 0.01389998 -0.0323528 -0.06708848 0.01389014 -0.03082489 -0.0700789 0.01381754 -0.03072506 -0.06988006 0.01386177 -0.03085798 -0.07004958 0.01386177 -0.03089976 -0.07001256 0.01389014 -0.03094607 -0.06997168 0.01389998 -0.03218996 -0.07060676 0.01389014 -0.03199017 -0.07052969 0.01389998 -0.03219097 -0.07054495 0.01389998 -0.03330749 -0.0701512 0.01389998 -0.03345435 -0.07001328 0.01389998 -0.03403484 -0.06892919 0.01386177 -0.03403204 -0.0687139 0.01386177 -0.03397649 -0.06871789 0.01389014 -0.0339148 -0.06872236 0.01389998 -0.03342348 -0.06764531 0.01389998 -0.03214675 -0.06714665 0.01389998 -0.03193646 -0.06710618 0.01389014 -0.03098058 -0.07023519 0.01381754 -0.03108817 -0.07011437 0.01389998 -0.03218835 -0.07070666 0.01381754 -0.03240865 -0.0706973 0.01381754 -0.03218907 -0.07066249 0.01386177 -0.03240418 -0.07065325 0.01386177 -0.03239858 -0.07059788 0.01389014 -0.03357189 -0.0701245 0.01381754 -0.03371369 -0.06995558 0.01381754 -0.03353977 -0.0700941 0.01386177 -0.0334993 -0.07005578 0.01389014 -0.03363347 -0.06989586 0.01389014 -0.0340473 -0.06849199 0.01381754 -0.03400379 -0.06850039 0.01386177 -0.03337335 -0.0673843 0.01381754 -0.03334599 -0.06741899 0.01386177 -0.0331403 -0.06734329 0.01389014 -0.03331136 -0.0674628 0.01389014 -0.0332731 -0.06751126 0.01389998 -0.03310799 -0.06739598 0.01389998 -0.03236037 -0.06698876 0.01381754 -0.03257036 -0.0670619 0.01386177 -0.03192746 -0.06705117 0.01386177 -0.03171736 -0.06709825 0.01386177 -0.03194636 -0.06716716 0.01389998 -0.03054898 -0.06973016 0.01376175 -0.03066539 -0.06992149 0.01376175 -0.03079628 -0.07010418 0.01369994 -0.03068876 -0.06990528 0.01381754 -0.03057408 -0.06971687 0.01381754 -0.03061318 -0.06969606 0.01386177 -0.03175199 -0.07064735 0.01381754 -0.03324908 -0.07043027 0.01376175 -0.03342926 -0.07029736 0.01376175 -0.03323358 -0.07040649 0.01381754 -0.0332095 -0.0703693 0.01386177 -0.0340839 -0.06915527 0.01376175 -0.03405588 -0.06915056 0.01381754 -0.03407907 -0.06893128 0.01381754 -0.03401219 -0.06914335 0.01386177 -0.03368425 -0.06769627 0.01381754 -0.03339099 -0.06736201 0.01376175 -0.0335381 -0.0675311 0.01381754 -0.03372448 -0.06792956 0.01389014 -0.032579 -0.0670185 0.01381754 -0.03236258 -0.06696039 0.01376175 -0.03190845 -0.06697106 0.01369994 -0.0319159 -0.06697946 0.01376175 -0.03191429 -0.06696981 0.01369994 -0.03235709 -0.06703287 0.01386177 -0.03255969 -0.06711655 0.01389014 -0.03064149 -0.06806117 0.01389014 -0.03074526 -0.06788009 0.01389014 -0.03059154 -0.06803637 0.01386177 -0.03055197 -0.0680167 0.01381754 -0.03063786 -0.06780976 0.01376175 -0.03052645 -0.06800407 0.01376175 -0.03069686 -0.06808871 0.01389998 -0.03050738 -0.06823456 0.01386177 -0.03042966 -0.0682069 0.01369994 -0.03048294 -0.06808149 0.01369994 -0.03061807 -0.06827408 0.01389998 -0.03055989 -0.06825327 0.01389014 -0.03040397 -0.06843149 0.01381754 -0.03046566 -0.06821966 0.01381754 -0.03037625 -0.06842517 0.01376175 -0.03043889 -0.06821018 0.01376175 -0.03050148 -0.06845366 0.01389014 -0.03044718 -0.06844127 0.01386177 -0.03033959 -0.06864607 0.01376175 -0.03032976 -0.06864506 0.01369994 -0.03046727 -0.0686596 0.01389014 -0.03041177 -0.06865376 0.01386177 -0.03036779 -0.06864905 0.01381754 -0.03045755 -0.06886816 0.01389014 -0.03047269 -0.06907635 0.01389014 -0.03040188 -0.06886887 0.01386177 -0.03035759 -0.06886947 0.01381754 -0.03032916 -0.06886976 0.01376175 -0.03031939 -0.06887 0.01369994 -0.03045827 -0.0692951 0.01386177 -0.03041738 -0.06908369 0.01386177 -0.03037357 -0.06908947 0.01381754 -0.03041535 -0.06930607 0.01381754 -0.03034538 -0.06909316 0.01376175 -0.03051227 -0.06928128 0.01389014 -0.03052389 -0.0695002 0.01386177 -0.03048259 -0.06951618 0.01381754 -0.03045606 -0.06952637 0.01376175 -0.03038787 -0.0693131 0.01376175 -0.03062969 -0.06988149 0.01369994 -0.03082138 -0.07012939 0.01369994 -0.03096169 -0.07025635 0.01376175 -0.03080356 -0.07009768 0.01376175 -0.03057587 -0.06948006 0.01389014 -0.03063344 -0.06945788 0.01389998 -0.03057217 -0.06926596 0.01389998 -0.0310471 -0.0701605 0.01389014 -0.03121089 -0.0702899 0.01389014 -0.03100997 -0.07020205 0.01386177 -0.03115367 -0.07037186 0.01381754 -0.0311374 -0.07039517 0.01376175 -0.03105276 -0.07034075 0.01369994 -0.03132367 -0.07052087 0.01369994 -0.03131359 -0.07051467 0.01369994 -0.03117895 -0.07033556 0.01386177 -0.03136259 -0.07044816 0.01386177 -0.03134167 -0.0704872 0.01381754 -0.03141796 -0.0703445 0.01389998 -0.03157848 -0.0704863 0.01389014 -0.03138887 -0.07039898 0.01389014 -0.03155815 -0.07053828 0.01386177 -0.03154206 -0.07057946 0.01381754 -0.03153175 -0.07060587 0.01376175 -0.03132826 -0.07051229 0.01376175 -0.0319646 -0.07071816 0.01376175 -0.03174477 -0.07067489 0.01376175 -0.03190517 -0.07071638 0.01369994 -0.03174239 -0.07068437 0.01369994 -0.03160148 -0.07063877 0.01369994 -0.03221726 -0.07074368 0.01369994 -0.03241157 -0.07072556 0.01376175 -0.03218787 -0.07073509 0.01376175 -0.03196835 -0.07068997 0.01381754 -0.03197437 -0.07064616 0.01386177 -0.03176307 -0.07060456 0.01386177 -0.03177708 -0.07055056 0.01389014 -0.03160089 -0.07042878 0.01389998 -0.03239226 -0.07053637 0.01389998 -0.03261679 -0.07061868 0.01386177 -0.03263264 -0.07068955 0.01376175 -0.0325911 -0.070504 0.01389998 -0.0328238 -0.07055926 0.01386177 -0.03262645 -0.0706619 0.01381754 -0.03299754 -0.07042568 0.01389014 -0.03302228 -0.07047575 0.01386177 -0.03304177 -0.07051545 0.01381754 -0.03283846 -0.07060098 0.01381754 -0.03284788 -0.0706278 0.01376175 -0.03343558 -0.07030487 0.01369994 -0.03338307 -0.07034349 0.01369994 -0.03325438 -0.0704385 0.01369994 -0.03312045 -0.07051455 0.01369994 -0.03305435 -0.0705409 0.01376175 -0.03361487 -0.07013255 0.01369994 -0.03359258 -0.07014399 0.01376175 -0.03341108 -0.07027548 0.01381754 -0.0331791 -0.07032257 0.01389014 -0.03358387 -0.06985908 0.01389998 -0.03367817 -0.06992918 0.01386177 -0.03383457 -0.06977099 0.01381754 -0.03373646 -0.06997245 0.01376175 -0.03380596 -0.06988418 0.01369994 -0.03374779 -0.06972128 0.01389014 -0.03379619 -0.06974899 0.01386177 -0.03385919 -0.06978505 0.01376175 -0.0339573 -0.06960958 0.01369994 -0.03378379 -0.06951016 0.01389998 -0.03391075 -0.06933766 0.01389014 -0.03384065 -0.06953436 0.01389014 -0.03396439 -0.06935328 0.01386177 -0.03389197 -0.06955617 0.01386177 -0.03400677 -0.06936568 0.01381754 -0.03393268 -0.06957346 0.01381754 -0.03395885 -0.0695846 0.01376175 -0.03404349 -0.0693764 0.01369994 -0.03411716 -0.06893301 0.01369994 -0.03410744 -0.06893259 0.01376175 -0.03410977 -0.0690037 0.01369994 -0.03403407 -0.0693736 0.01376175 -0.03409349 -0.06915688 0.01369994 -0.03405797 -0.06931287 0.01369994 -0.03411197 -0.06869029 0.01369994 -0.03410446 -0.06870859 0.01376175 -0.03407615 -0.06871068 0.01381754 -0.0338515 -0.06932049 0.01389998 -0.03394907 -0.068511 0.01389014 -0.03399264 -0.06827825 0.01381754 -0.0340752 -0.06848657 0.01376175 -0.03394788 -0.0680567 0.01369994 -0.03395855 -0.06808429 0.01369994 -0.03383845 -0.0683276 0.01389998 -0.03389739 -0.06830871 0.01389014 -0.0338729 -0.06809085 0.01386177 -0.03395044 -0.06829178 0.01386177 -0.03401964 -0.06826961 0.01376175 -0.033939 -0.06806069 0.01376175 -0.03382217 -0.06811398 0.01389014 -0.03377205 -0.06790059 0.01386177 -0.0338099 -0.06787759 0.01381754 -0.03391319 -0.06807249 0.01381754 -0.03383415 -0.0678628 0.01376175 -0.03339707 -0.06735426 0.01369994 -0.03355818 -0.06751096 0.01376175 -0.0337066 -0.06767868 0.01376175 -0.03371429 -0.06767266 0.01369994 -0.03380876 -0.0678091 0.01369994 -0.03320735 -0.0672338 0.01376175 -0.03338736 -0.06734758 0.01369994 -0.03350675 -0.06756228 0.01386177 -0.0336495 -0.06772357 0.01386177 -0.03316938 -0.06729578 0.01386177 -0.03319257 -0.06725805 0.01381754 -0.03300988 -0.0671283 0.01376175 -0.03301399 -0.06711935 0.01369994 -0.03276169 -0.06716901 0.01389014 -0.03277885 -0.0671159 0.01386177 -0.03295618 -0.06724488 0.01389014 -0.03279244 -0.06707376 0.01381754 -0.03297948 -0.06719428 0.01386177 -0.03299796 -0.0671541 0.01381754 -0.03280127 -0.06704676 0.01376175 -0.03283739 -0.06705039 0.01369994 -0.03258448 -0.06699055 0.01376175 -0.03258639 -0.06698095 0.01369994 -0.03213816 -0.06694686 0.01369994 -0.03213858 -0.06695669 0.01376175 -0.03222107 -0.06694829 0.01369994 -0.03236329 -0.06695067 0.01369994 -0.03192037 -0.06700748 0.01381754 -0.03213989 -0.06698507 0.01381754 -0.03254765 -0.06717717 0.01389998 -0.03274267 -0.06722778 0.01389998 -0.03151428 -0.0671699 0.01386177 -0.03173279 -0.0671519 0.01389014 -0.0317052 -0.06705576 0.01381754 -0.03148609 -0.06710296 0.01376175 -0.03169727 -0.06702846 0.01376175 -0.03131747 -0.06717509 0.01369994 -0.03155988 -0.06727826 0.01389998 -0.03153586 -0.06722128 0.01389014 -0.03132104 -0.06726509 0.01386177 -0.03129917 -0.06722658 0.01381754 -0.03149706 -0.06712919 0.01381754 -0.0313487 -0.06731349 0.01389014 -0.03117358 -0.06742727 0.01389014 -0.03128516 -0.06720185 0.01376175 -0.03128039 -0.06719338 0.01369994 -0.0309751 -0.0675202 0.01386177 -0.0311405 -0.06738239 0.01386177 -0.03111428 -0.06734681 0.01381754 -0.03092539 -0.06746727 0.01376175 -0.03109735 -0.06732386 0.01376175 -0.03091865 -0.06746006 0.01369994 -0.03077149 -0.06762999 0.01376175 -0.03076398 -0.06762367 0.01369994 -0.03101325 -0.06756091 0.01389014 -0.0308271 -0.06767666 0.01386177 -0.03094476 -0.06748795 0.01381754 -0.03082495 -0.06755906 0.01369994 -0.03086978 -0.06771248 0.01389014 -0.03069865 -0.06784957 0.01386177 -0.0306617 -0.06782525 0.01381754 -0.03079319 -0.06764817 0.01381754 -0.03312265 -0.069274 0.01179999 -0.03312265 -0.069274 0.004125952 -0.03320485 -0.06901431 0.004125952 -0.03320485 -0.06901431 0.01179999 -0.03321397 -0.06874209 0.004125952 -0.03321397 -0.06874209 0.01179999 -0.0331493 -0.06847757 0.004125952 -0.0331493 -0.06847757 0.01179999 -0.03301554 -0.06824028 0.01179999 -0.03301554 -0.06824028 0.004125952 -0.03282284 -0.06804788 0.004125952 -0.03282284 -0.06804788 0.01179999 -0.03258538 -0.0679146 0.004125952 -0.03258538 -0.0679146 0.01179999 -0.03232079 -0.06785041 0.004125952 -0.03232079 -0.06785041 0.01179999 -0.03204858 -0.06785988 0.01179999 -0.03178906 -0.0679425 0.01179999 -0.03204858 -0.06785988 0.004125952 -0.03156149 -0.06809198 0.01179999 -0.03178906 -0.0679425 0.004125952 -0.03156149 -0.06809198 0.004125952 -0.03138267 -0.06829738 0.004125952 -0.03138267 -0.06829738 0.01179999 -0.03126585 -0.06854337 0.01179999 -0.03126585 -0.06854337 0.004125952 -0.03121978 -0.06881177 0.01179999 -0.03121978 -0.06881177 0.004125952 -0.03124785 -0.06908267 0.01179999 -0.03124785 -0.06908267 0.004125952 -0.03134799 -0.06933599 0.004125952 -0.03134799 -0.06933599 0.01179999 -0.03151267 -0.06955289 0.01179999 -0.03151267 -0.06955289 0.004125952 -0.03172987 -0.06971716 0.004125952 -0.03172987 -0.06971716 0.01179999 -0.03198325 -0.069817 0.004125952 -0.03198325 -0.069817 0.01179999 -0.03225415 -0.0698446 0.01179999 -0.03225415 -0.0698446 0.004125952 -0.03252249 -0.06979811 0.01179999 -0.03252249 -0.06979811 0.004125952 -0.03276836 -0.06968098 0.01179999 -0.03276836 -0.06968098 0.004125952 -0.03297346 -0.06950175 0.004125952 -0.03297346 -0.06950175 0.01179999 -0.0330559 -0.06939297 0.01179999 -0.01848769 -0.07459568 0.01189994 -0.01820987 -0.0747416 0.01189994 -0.01820987 -0.0747416 0.01369994 -0.01795977 -0.0749312 0.01369994 -0.01795977 -0.0749312 0.01189994 -0.01774436 -0.07515931 0.01189994 -0.01774436 -0.07515931 0.01369994 -0.01756948 -0.07541978 0.01369994 -0.01756948 -0.07541978 0.01189994 -0.01743978 -0.07570558 0.01369994 -0.01735889 -0.07600879 0.01369994 -0.01743978 -0.07570558 0.01189994 -0.01735889 -0.07600879 0.01189994 -0.01732897 -0.07632118 0.01369994 -0.01732897 -0.07632118 0.01189994 -0.01735097 -0.07663416 0.01369994 -0.01735097 -0.07663416 0.01189994 -0.01742416 -0.07693928 0.01369994 -0.01742416 -0.07693928 0.01189994 -0.01754659 -0.0772283 0.01189994 -0.01754659 -0.0772283 0.01369994 -0.01771485 -0.07749307 0.01369994 -0.01771485 -0.07749307 0.01189994 -0.01792448 -0.07772666 0.01369994 -0.01792448 -0.07772666 0.01189994 -0.0181697 -0.07792246 0.01189994 -0.0181697 -0.07792246 0.01369994 -0.0184437 -0.0780754 0.01369994 -0.0184437 -0.0780754 0.01189994 -0.01873916 -0.07818096 0.01369994 -0.01873916 -0.07818096 0.01189994 -0.01904809 -0.07823657 0.01189994 -0.01904809 -0.07823657 0.01369994 -0.01936179 -0.07824045 0.01189994 -0.01936179 -0.07824045 0.01369994 -0.01967197 -0.07819277 0.01189994 -0.01967197 -0.07819277 0.01369994 -0.01996999 -0.07809466 0.01369994 -0.01996999 -0.07809466 0.01189994 -0.02024787 -0.0779488 0.01369994 -0.02049785 -0.0777592 0.01369994 -0.02024787 -0.0779488 0.01189994 -0.02049785 -0.0777592 0.01189994 -0.02071338 -0.07753109 0.01369994 -0.02088826 -0.07727056 0.01369994 -0.02071338 -0.07753109 0.01189994 -0.02101796 -0.07698476 0.01369994 -0.02088826 -0.07727056 0.01189994 -0.02109885 -0.07668155 0.01369994 -0.02101796 -0.07698476 0.01189994 -0.02109885 -0.07668155 0.01189994 -0.02112865 -0.07636916 0.01369994 -0.02112865 -0.07636916 0.01189994 -0.02110677 -0.07605618 0.01369994 -0.02110677 -0.07605618 0.01189994 -0.02103358 -0.07575106 0.01189994 -0.02103358 -0.07575106 0.01369994 -0.02091115 -0.0754621 0.01189994 -0.02091115 -0.0754621 0.01369994 -0.02074289 -0.07519716 0.01369994 -0.02074289 -0.07519716 0.01189994 -0.02053326 -0.07496368 0.01369994 -0.02053326 -0.07496368 0.01189994 -0.02028805 -0.07476788 0.01369994 -0.02028805 -0.07476788 0.01189994 -0.02001404 -0.074615 0.01369994 -0.01971858 -0.07450938 0.01369994 -0.02001404 -0.074615 0.01189994 -0.01971858 -0.07450938 0.01189994 -0.01940965 -0.07445377 0.01369994 -0.01940965 -0.07445377 0.01189994 -0.01909595 -0.07444989 0.01189994 -0.01909595 -0.07444989 0.01369994 -0.01878577 -0.07449758 0.01369994 -0.01878577 -0.07449758 0.01189994 -0.01848769 -0.07459568 0.01369994 -0.01976519 -0.0771892 0.01179999 -0.01987504 -0.07710826 0.004125952 -0.01987504 -0.07710826 0.01179999 -0.02005708 -0.07690566 0.004125952 -0.02005708 -0.07690566 0.01179999 -0.0201776 -0.07666146 0.004125952 -0.0201776 -0.07666146 0.01179999 -0.02022767 -0.07639378 0.01179999 -0.02020376 -0.07612246 0.01179999 -0.02022767 -0.07639378 0.004125952 -0.02010744 -0.07586765 0.01179999 -0.02020376 -0.07612246 0.004125952 -0.01994609 -0.07564836 0.01179999 -0.02010744 -0.07586765 0.004125952 -0.01994609 -0.07564836 0.004125952 -0.01973146 -0.07548069 0.01179999 -0.01947969 -0.07537716 0.01179999 -0.01973146 -0.07548069 0.004125952 -0.01947969 -0.07537716 0.004125952 -0.0192092 -0.07534539 0.004125952 -0.0192092 -0.07534539 0.01179999 -0.01894015 -0.07538777 0.01179999 -0.01894015 -0.07538777 0.004125952 -0.01869255 -0.0755012 0.01179999 -0.01869255 -0.0755012 0.004125952 -0.01848477 -0.07567715 0.01179999 -0.01848477 -0.07567715 0.004125952 -0.01833206 -0.0759027 0.01179999 -0.01833206 -0.0759027 0.004125952 -0.01824599 -0.07616108 0.004125952 -0.01824599 -0.07616108 0.01179999 -0.01823276 -0.07643306 0.01179999 -0.01823276 -0.07643306 0.004125952 -0.01829338 -0.0766986 0.01179999 -0.01829338 -0.0766986 0.004125952 -0.01842337 -0.07693785 0.004125952 -0.01842337 -0.07693785 0.01179999 -0.01861315 -0.07713317 0.01179999 -0.01861315 -0.07713317 0.004125952 -0.01884859 -0.07727009 0.01179999 -0.01911228 -0.07733839 0.01179999 -0.01884859 -0.07727009 0.004125952 -0.0193845 -0.07733297 0.01179999 -0.01911228 -0.07733839 0.004125952 -0.0193845 -0.07733297 0.004125952 -0.01964527 -0.07725435 0.01179999 -0.01964527 -0.07725435 0.004125952 -0.01916486 -0.0755738 0.003899991 -0.0193547 -0.07710886 0.003899991 -0.01978826 -0.07688009 0.003899991 -0.01969516 -0.07696288 0.003899991 -0.01959007 -0.0770297 0.003899991 -0.01904195 -0.07559406 0.003899991 -0.01892399 -0.07563376 0.003899991 -0.01855766 -0.07595968 0.003899991 -0.01986676 -0.07678347 0.003899991 -0.01947557 -0.07707875 0.003899991 -0.01881378 -0.07569187 0.003899991 -0.01871436 -0.07576698 0.003899991 -0.01862829 -0.07585698 0.003899991 -0.01953065 -0.07563245 0.003899991 -0.01941245 -0.07559329 0.003899991 -0.01928949 -0.07557356 0.003899991 -0.01898539 -0.07707989 0.003899991 -0.01910638 -0.07710939 0.003899991 -0.01850455 -0.07607227 0.003899991 -0.0192306 -0.07711917 0.003899991 -0.01847016 -0.07619196 0.003899991 -0.0184555 -0.0763157 0.003899991 -0.01887065 -0.07703125 0.003899991 -0.01846069 -0.07644015 0.003899991 -0.0184859 -0.07656216 0.003899991 -0.01853036 -0.07667845 0.003899991 -0.01999747 -0.07643675 0.003899991 -0.01992887 -0.07667547 0.003899991 -0.0199728 -0.07655888 0.003899991 -0.02000218 -0.0763123 0.003899991 -0.01998686 -0.07618868 0.003899991 -0.01995199 -0.07606917 0.003899991 -0.01859289 -0.07678627 0.003899991 -0.01867187 -0.0768826 0.003899991 -0.01876527 -0.07696497 0.003899991 -0.01989829 -0.0759567 0.003899991 -0.01982736 -0.07585436 0.003899991 -0.01974087 -0.07576465 0.003899991 -0.0196411 -0.07569009 0.003899991 0.05762428 -0.05319219 0.01849997 0.05746549 -0.05312985 0.01849997 0.0571804 -0.05294376 0.01849997 0.05695617 -0.0526877 0.01849997 0.05680936 -0.05238056 0.01849997 0.05695617 -0.0526877 0.008853495 0.05680936 -0.05238056 0.008853495 0.05675077 -0.05204516 0.01849997 0.05678486 -0.05170649 0.008853495 0.05678486 -0.05170649 0.01849997 0.0569092 -0.05138957 0.01849997 0.0571143 -0.05111789 0.01849997 0.05738508 -0.05091166 0.01849997 0.05738508 -0.05091166 0.008853495 0.05770146 -0.05078619 0.01849997 0.05804008 -0.05075055 0.01849997 0.05837565 -0.05080777 0.01849997 0.05837565 -0.05080777 0.008853495 0.05868339 -0.05095338 0.008853495 0.05868339 -0.05095338 0.01849997 0.05894047 -0.05117654 0.01849997 0.05912768 -0.0514608 0.01849997 0.05894047 -0.05117654 0.008853495 0.0592314 -0.05178505 0.01849997 0.05924367 -0.05212527 0.01849997 0.05924367 -0.05212527 0.008853495 0.05916374 -0.0524562 0.01849997 0.05899757 -0.05275315 0.01849997 0.0587573 -0.05299448 0.01849997 0.05846095 -0.05316185 0.01849997 0.0587573 -0.05299448 0.008853495 0.05813038 -0.05324316 0.01849997 0.05813038 -0.05324316 0.008853495 0.0577901 -0.05323225 0.01849997 0.0577901 -0.05323225 0.008853495 0.05746549 -0.05312985 0.008853495 0.05770146 -0.05078619 0.008853495 0.05776208 -0.0510323 0.008599996 0.05750977 -0.05113238 0.008599996 0.0571143 -0.05111789 0.008853495 0.05729389 -0.05129677 0.008599996 0.0569092 -0.05138957 0.008853495 0.05713039 -0.05151337 0.008599996 0.05703139 -0.05176609 0.008599996 0.05675077 -0.05204516 0.008853495 0.05700415 -0.05203604 0.008599996 0.05705076 -0.05230337 0.008599996 0.05716788 -0.05254817 0.008599996 0.0571804 -0.05294376 0.008853495 0.05734658 -0.05275237 0.008599996 0.05757385 -0.05290079 0.008599996 0.05783265 -0.05298238 0.008599996 0.05810385 -0.05299109 0.008599996 0.05846095 -0.05316185 0.008853495 0.05836749 -0.0529263 0.008599996 0.05899757 -0.05275315 0.008853495 0.05860376 -0.05279278 0.008599996 0.05916374 -0.0524562 0.008853495 0.05879527 -0.0526005 0.008599996 0.05892777 -0.05236369 0.008599996 0.05899149 -0.05209988 0.008599996 0.0592314 -0.05178505 0.008853495 0.05912768 -0.0514608 0.008853495 0.05898165 -0.05182868 0.008599996 0.05889898 -0.05157017 0.008599996 0.05874967 -0.05134356 0.008599996 0.05854475 -0.05116558 0.008599996 0.05829948 -0.05104959 0.008599996 0.05804008 -0.05075055 0.008853495 0.05803197 -0.05100399 0.008599996 -0.0586366 0.0509243 0.01849997 -0.05890315 0.05113589 0.01849997 -0.05910289 0.05141156 0.01849997 -0.05922067 0.05173099 0.008853495 -0.05922067 0.05173099 0.01849997 -0.05924797 0.05207026 0.01849997 -0.05924797 0.05207026 0.008853495 -0.05918276 0.0524044 0.01849997 -0.05902975 0.05270844 0.01849997 -0.05880039 0.05296009 0.01849997 -0.05851167 0.05314046 0.01849997 -0.0581851 0.05323618 0.008853495 -0.0581851 0.05323618 0.01849997 -0.05784469 0.05324029 0.01849997 -0.05751579 0.05315238 0.01849997 -0.05751579 0.05315238 0.008853495 -0.05722278 0.05297899 0.01849997 -0.05698746 0.05273306 0.01849997 -0.05722278 0.05297899 0.008853495 -0.05682724 0.05243265 0.01849997 -0.05675399 0.0521003 0.01849997 -0.05675399 0.0521003 0.008853495 -0.05677318 0.05176037 0.01849997 -0.05688327 0.05143827 0.01849997 -0.05688327 0.05143827 0.008853495 -0.05707627 0.05115777 0.01849997 -0.05707627 0.05115777 0.008853495 -0.0573377 0.05093979 0.008853495 -0.0573377 0.05093979 0.01849997 -0.0576483 0.0508005 0.01849997 -0.05798494 0.05075007 0.01849997 -0.05798494 0.05075007 0.008853495 -0.05832278 0.05079239 0.01849997 -0.05848419 0.05084758 0.01849997 -0.0584079 0.05290919 0.008599996 -0.05851167 0.05314046 0.008853495 -0.05880039 0.05296009 0.008853495 -0.05863809 0.05276536 0.008599996 -0.05902975 0.05270844 0.008853495 -0.05918276 0.0524044 0.008853495 -0.05894285 0.05232238 0.008599996 -0.05899488 0.05205607 0.008599996 -0.05910289 0.05141156 0.008853495 -0.05887919 0.05153095 0.008599996 -0.05890315 0.05113589 0.008853495 -0.0586366 0.0509243 0.008853495 -0.0585075 0.05114239 0.008599996 -0.05832278 0.05079239 0.008853495 -0.05825728 0.05103725 0.008599996 -0.0576483 0.0508005 0.008853495 -0.05771964 0.05104368 0.008599996 -0.05726355 0.05132859 0.008599996 -0.05677318 0.05176037 0.008853495 -0.05702197 0.05180895 0.008599996 -0.05682724 0.05243265 0.008853495 -0.05706506 0.05234497 0.008599996 -0.05698746 0.05273306 0.008853495 -0.0571928 0.05258435 0.008599996 -0.05738037 0.05278044 0.008599996 -0.05784469 0.05324029 0.008853495 -0.05761396 0.05291867 0.008599996 -0.05872005 0.05131107 0.008599996 -0.05798798 0.05100357 0.008599996 -0.05710977 0.05155217 0.008599996 -0.05700665 0.05207985 0.008599996 -0.05747205 0.05115479 0.008599996 -0.0588209 0.05256485 0.008599996 -0.05787616 0.05298876 0.008599996 -0.05897319 0.05178558 0.008599996 -0.05814749 0.05298548 0.008599996 0.05733186 0.05094349 0.01849997 0.05707156 0.05116295 0.01849997 0.05688017 0.05144447 0.01849997 0.05677187 0.05176717 0.01849997 0.05677187 0.05176717 0.008853495 0.05675458 0.05210715 0.01849997 0.05682969 0.05243915 0.01849997 0.05699157 0.05273866 0.01849997 0.05722826 0.05298328 0.01849997 0.05699157 0.05273866 0.008853495 0.05752217 0.05315506 0.01849997 0.05722826 0.05298328 0.008853495 0.05785155 0.05324119 0.01849997 0.05819189 0.05323517 0.01849997 0.05851805 0.0531376 0.01849997 0.05851805 0.0531376 0.008853495 0.05880576 0.05295556 0.01849997 0.05880576 0.05295556 0.008853495 0.05903369 0.05270278 0.01849997 0.05918496 0.05239778 0.01849997 0.05903369 0.05270278 0.008853495 0.05924838 0.0520634 0.01849997 0.05921918 0.05172419 0.01849997 0.05921918 0.05172419 0.008853495 0.05909955 0.05140548 0.01849997 0.05909955 0.05140548 0.008853495 0.05889838 0.05113089 0.008853495 0.05889838 0.05113089 0.01849997 0.05863058 0.05092066 0.01849997 0.05831599 0.05079054 0.01849997 0.05797797 0.05075019 0.01849997 0.05831599 0.05079054 0.008853495 0.05797797 0.05075019 0.008853495 0.05764168 0.05080246 0.01849997 0.05748188 0.05086237 0.01849997 0.05819189 0.05323517 0.008853495 0.05785155 0.05324119 0.008853495 0.05815297 0.05298465 0.008599996 0.05788165 0.05298936 0.008599996 0.05752217 0.05315506 0.008853495 0.05761909 0.05292075 0.008599996 0.05738478 0.05278384 0.008599996 0.05682969 0.05243915 0.008853495 0.05706697 0.0523501 0.008599996 0.05675458 0.05210715 0.008853495 0.05700719 0.05208545 0.008599996 0.0570209 0.05181437 0.008599996 0.05688017 0.05144447 0.008853495 0.05707156 0.05116295 0.008853495 0.05733186 0.05094349 0.008853495 0.0574674 0.05115777 0.008599996 0.05771428 0.05104529 0.008599996 0.05764168 0.05080246 0.008853495 0.05863058 0.05092066 0.008853495 0.05850267 0.05113959 0.008599996 0.05871617 0.05130708 0.008599996 0.05887657 0.05152606 0.008599996 0.05897188 0.0517801 0.008599996 0.05924838 0.0520634 0.008853495 0.05918496 0.05239778 0.008853495 0.0589447 0.0523172 0.008599996 0.05882406 0.05256026 0.008599996 0.05864238 0.05276179 0.008599996 0.05841296 0.05290687 0.008599996 0.0579825 0.05100369 0.008599996 0.05725985 0.05133265 0.008599996 0.05710726 0.05155718 0.008599996 0.05899518 0.05205047 0.008599996 0.05825197 0.05103588 0.008599996 0.05719608 0.05258888 0.008599996 -0.05865395 -0.05306529 0.01849997 -0.05879294 -0.05296629 0.01849997 -0.05902427 -0.05271649 0.01849997 -0.05902427 -0.05271649 0.008853495 -0.0591796 -0.05241358 0.01849997 -0.05924737 -0.05207997 0.01849997 -0.05922275 -0.05174046 0.01849997 -0.05924737 -0.05207997 0.008853495 -0.05922275 -0.05174046 0.008853495 -0.05910736 -0.05142015 0.01849997 -0.05890989 -0.05114287 0.008853495 -0.05890989 -0.05114287 0.01849997 -0.05864489 -0.05092918 0.008853495 -0.05864489 -0.05092918 0.01849997 -0.05833208 -0.05079489 0.01849997 -0.05833208 -0.05079489 0.008853495 -0.05799466 -0.05074995 0.008853495 -0.05799466 -0.05074995 0.01849997 -0.05765759 -0.05079776 0.008853495 -0.05765759 -0.05079776 0.01849997 -0.05734598 -0.05093467 0.01849997 -0.05708277 -0.05115067 0.008853495 -0.05708277 -0.05115067 0.01849997 -0.05688768 -0.05142956 0.01849997 -0.05677509 -0.05175089 0.01849997 -0.05688768 -0.05142956 0.008853495 -0.05675327 -0.05209058 0.01849997 -0.05682396 -0.05242359 0.01849997 -0.05698186 -0.05272519 0.01849997 -0.05721527 -0.05297297 0.01849997 -0.05750685 -0.05314856 0.01849997 -0.05783498 -0.05323904 0.01849997 -0.0581755 -0.05323755 0.01849997 -0.05850285 -0.05314439 0.01849997 -0.05879294 -0.05296629 0.008853495 -0.05772709 -0.0510416 0.008599996 -0.05799579 -0.05100345 0.008599996 -0.05826479 -0.05103927 0.008599996 -0.05851405 -0.05114638 0.008599996 -0.05872535 -0.05131667 0.008599996 -0.05910736 -0.05142015 0.008853495 -0.05888277 -0.05153775 0.008599996 -0.0589748 -0.05179309 0.008599996 -0.0591796 -0.05241358 0.008853495 -0.05899447 -0.05206376 0.008599996 -0.05894035 -0.05232965 0.008599996 -0.05881649 -0.05257117 0.008599996 -0.05863219 -0.05277025 0.008599996 -0.05850285 -0.05314439 0.008853495 -0.05840086 -0.05291229 0.008599996 -0.0581755 -0.05323755 0.008853495 -0.05813986 -0.05298656 0.008599996 -0.05783498 -0.05323904 0.008853495 -0.05750685 -0.05314856 0.008853495 -0.05786848 -0.05298775 0.008599996 -0.05760687 -0.05291569 0.008599996 -0.05721527 -0.05297297 0.008853495 -0.05737435 -0.05277568 0.008599996 -0.05698186 -0.05272519 0.008853495 -0.05718827 -0.05257809 0.008599996 -0.05706244 -0.0523377 0.008599996 -0.05682396 -0.05242359 0.008853495 -0.05675327 -0.05209058 0.008853495 -0.05700606 -0.05207216 0.008599996 -0.05677509 -0.05175089 0.008853495 -0.05702346 -0.05180138 0.008599996 -0.05711328 -0.05154526 0.008599996 -0.05734598 -0.05093467 0.008853495 -0.05726879 -0.05132287 0.008599996 -0.05747854 -0.05115079 0.008599996 0.04820036 -0.05143916 0 0.04777777 -0.05149996 -0.00999999 0.04777777 -0.05149996 0 0.04696679 -0.0512619 -0.00999999 0.04735517 -0.05143916 0 0.04696679 -0.0512619 0 0.04664415 -0.05098229 -0.00999999 0.04664415 -0.05098229 0 0.0464133 -0.05062305 0 0.04629296 -0.05021345 0 0.04629296 -0.04978644 0 0.0464133 -0.0493769 0 0.0464133 -0.0493769 -0.00999999 0.04664415 -0.04901766 -0.00999999 0.04664415 -0.04901766 0 0.04696679 -0.04873806 -0.00999999 0.04735517 -0.04856079 -0.00999999 0.04696679 -0.04873806 0 0.04735517 -0.04856079 0 0.04777777 -0.0485 0 0.04820036 -0.04856079 0 0.04858869 -0.04873806 0 0.04891139 -0.04901766 0 0.04914218 -0.0493769 -0.00999999 0.04914218 -0.0493769 0 0.04926246 -0.04978644 0 0.04926246 -0.05021345 0 0.04914218 -0.05062305 0 0.04891139 -0.05098229 -0.00999999 0.04891139 -0.05098229 0 0.04858869 -0.0512619 -0.00999999 0.04858869 -0.0512619 0 0.05077779 -0.0482679 0 0.04477775 -0.0482679 0 0.04477775 -0.0482679 -0.00999999 0.04777777 -0.04653584 0 0.04777777 -0.05346405 -0.00999999 0.04777777 -0.05346405 0 0.04477775 -0.05173206 0 0.04735517 -0.05143916 -0.00999999 0.04820036 -0.05143916 -0.00999999 0.04891139 -0.04901766 -0.00999999 0.04858869 -0.04873806 -0.00999999 0.04820036 -0.04856079 -0.00999999 0.04777777 -0.04653584 -0.00999999 0.04777777 -0.0485 -0.00999999 0.04914218 -0.05062305 -0.00999999 0.04926246 -0.05021345 -0.00999999 0.05077779 -0.0482679 -0.00999999 0.04926246 -0.04978644 -0.00999999 0.04477775 -0.05173206 -0.00999999 0.04629296 -0.04978644 -0.00999999 0.04629296 -0.05021345 -0.00999999 0.0464133 -0.05062305 -0.00999999 0.05077779 -0.05173206 0 0.05077779 -0.05173206 -0.00999999 0.04752999 0.05147939 0 0.04795676 0.05148929 -0.00999999 0.04795676 0.05148929 0 0.04836905 0.05137848 0 0.04873359 0.0511561 0 0.04873359 0.0511561 -0.00999999 0.04902046 0.05083996 0 0.04920679 0.05045574 0 0.04927736 0.0500347 0 0.0492264 0.04961079 0 0.04905807 0.04921847 0 0.04905807 0.04921847 -0.00999999 0.0487861 0.04888939 -0.00999999 0.0487861 0.04888939 0 0.04843229 0.04865026 0 0.04802554 0.04852056 0 0.04759865 0.04851067 -0.00999999 0.04759865 0.04851067 0 0.04718637 0.04862147 -0.00999999 0.04682195 0.04884386 -0.00999999 0.04718637 0.04862147 0 0.04682195 0.04884386 0 0.04653495 0.04916 0 0.04653495 0.04916 -0.00999999 0.04634869 0.04954415 0 0.04627817 0.04996526 -0.00999999 0.04627817 0.04996526 0 0.04632908 0.05038917 0 0.04676949 0.05111056 -0.00999999 0.04649746 0.05078148 0 0.04676949 0.05111056 0 0.04712319 0.05134969 0 0.04510509 0.04779618 -0.00999999 0.04834997 0.04658347 0 0.04834997 0.04658347 -0.00999999 0.04720544 0.05341649 0 0.05045038 0.05220377 0 0.05102264 0.04878729 0 0.05102264 0.04878729 -0.00999999 0.04843229 0.04865026 -0.00999999 0.0492264 0.04961079 -0.00999999 0.04927736 0.0500347 -0.00999999 0.05045038 0.05220377 -0.00999999 0.04920679 0.05045574 -0.00999999 0.04902046 0.05083996 -0.00999999 0.04632908 0.05038917 -0.00999999 0.04453289 0.05121266 -0.00999999 0.04634869 0.04954415 -0.00999999 0.04802554 0.04852056 -0.00999999 0.04720544 0.05341649 -0.00999999 0.04712319 0.05134969 -0.00999999 0.04649746 0.05078148 -0.00999999 0.04836905 0.05137848 -0.00999999 0.04752999 0.05147939 -0.00999999 0.04510509 0.04779618 0 0.04453289 0.05121266 0 0.04972225 -0.04805546 0.003899991 0.04972225 -0.04805546 0.00119996 0.05001586 -0.04840195 0.003899991 0.05001586 -0.04840195 0.00119996 0.05024838 -0.04879218 0.00119996 0.05024838 -0.04879218 0.003899991 0.05041348 -0.04921525 0.003899991 0.05041348 -0.04921525 0.00119996 0.05050665 -0.04965978 0.00119996 0.05050665 -0.04965978 0.003899991 0.05052536 -0.05011355 0.003899991 0.05046916 -0.05056428 0.003899991 0.05052536 -0.05011355 0.00119996 0.05046916 -0.05056428 0.00119996 0.05033969 -0.05099958 0.003899991 0.05033969 -0.05099958 0.00119996 0.0501402 -0.05140769 0.00119996 0.0501402 -0.05140769 0.003899991 0.04987627 -0.0517773 0.00119996 0.04987627 -0.0517773 0.003899991 0.04955506 -0.05209845 0.003899991 0.04955506 -0.05209845 0.00119996 0.04918545 -0.05236238 0.003899991 0.04918545 -0.05236238 0.00119996 0.0487774 -0.05256187 0.003899991 0.0487774 -0.05256187 0.00119996 0.04834204 -0.05269145 0.00119996 0.04834204 -0.05269145 0.003899991 0.04789137 -0.05274766 0.003899991 0.04789137 -0.05274766 0.00119996 0.04743754 -0.05272889 0.003899991 0.04743754 -0.05272889 0.00119996 0.04699307 -0.05263566 0.003899991 0.04699307 -0.05263566 0.00119996 0.04657 -0.05247056 0.003899991 0.04657 -0.05247056 0.00119996 0.04617977 -0.05223804 0.003899991 0.04583317 -0.05194449 0.003899991 0.04617977 -0.05223804 0.00119996 0.04583317 -0.05194449 0.00119996 0.04553967 -0.05159795 0.003899991 0.04553967 -0.05159795 0.00119996 0.04530715 -0.05120778 0.003899991 0.04514205 -0.05078464 0.003899991 0.04530715 -0.05120778 0.00119996 0.04514205 -0.05078464 0.00119996 0.04504889 -0.05034017 0.003899991 0.04503005 -0.0498864 0.003899991 0.04504889 -0.05034017 0.00119996 0.04503005 -0.0498864 0.00119996 0.04508626 -0.04943567 0.003899991 0.0452159 -0.04900038 0.003899991 0.04508626 -0.04943567 0.00119996 0.0452159 -0.04900038 0.00119996 0.0454154 -0.04859226 0.003899991 0.0454154 -0.04859226 0.00119996 0.04567927 -0.04822266 0.003899991 0.04567927 -0.04822266 0.00119996 0.04600048 -0.04790145 0.00119996 0.04600048 -0.04790145 0.003899991 0.04637008 -0.04763758 0.003899991 0.04637008 -0.04763758 0.00119996 0.04677808 -0.04743808 0.003899991 0.04677808 -0.04743808 0.00119996 0.04721337 -0.0473085 0.003899991 0.0476641 -0.04725229 0.003899991 0.04721337 -0.0473085 0.00119996 0.04811787 -0.04727107 0.003899991 0.0476641 -0.04725229 0.00119996 0.04811787 -0.04727107 0.00119996 0.04856246 -0.04736429 0.00119996 0.04856246 -0.04736429 0.003899991 0.0489856 -0.04752939 0.003899991 0.04937565 -0.04776185 0.003899991 0.0489856 -0.04752939 0.00119996 0.04937565 -0.04776185 0.00119996 -0.04633837 -0.04959315 0 -0.04634767 -0.0504384 -0.00999999 -0.04628229 -0.05001646 0 -0.04634767 -0.0504384 0 -0.04652929 -0.05082476 0 -0.04681235 -0.0511443 0 -0.04717409 -0.05137115 0 -0.04758507 -0.05148696 -0.00999999 -0.04758507 -0.05148696 0 -0.04801195 -0.05148226 0 -0.04842025 -0.05135744 -0.00999999 -0.04842025 -0.05135744 0 -0.04877686 -0.05112278 0 -0.04905289 -0.0507971 -0.00999999 -0.04922598 -0.05040675 -0.00999999 -0.04905289 -0.0507971 0 -0.04922598 -0.05040675 0 -0.04928207 -0.0499835 0 -0.04928207 -0.0499835 -0.00999999 -0.04921668 -0.04956156 0 -0.04903507 -0.0491752 0 -0.04875195 -0.04885566 -0.00999999 -0.04875195 -0.04885566 0 -0.04839026 -0.04862874 0 -0.04797935 -0.04851299 0 -0.04755246 -0.0485177 -0.00999999 -0.04755246 -0.0485177 0 -0.04714417 -0.04864245 0 -0.0467875 -0.04887717 0 -0.04651147 -0.04920285 -0.00999999 -0.04651147 -0.04920285 0 -0.04633837 -0.04959315 -0.00999999 -0.05124604 -0.04996198 0 -0.05124604 -0.04996198 -0.00999999 -0.04954707 -0.05298078 0 -0.04954707 -0.05298078 -0.00999999 -0.04431825 -0.05003798 0 -0.04608315 -0.05301874 0 -0.04608315 -0.05301874 -0.00999999 -0.04801195 -0.05148226 -0.00999999 -0.04717409 -0.05137115 -0.00999999 -0.0467875 -0.04887717 -0.00999999 -0.04877686 -0.05112278 -0.00999999 -0.04628229 -0.05001646 -0.00999999 -0.04714417 -0.04864245 -0.00999999 -0.04797935 -0.04851299 -0.00999999 -0.04839026 -0.04862874 -0.00999999 -0.04681235 -0.0511443 -0.00999999 -0.04652929 -0.05082476 -0.00999999 -0.04431825 -0.05003798 -0.00999999 -0.04903507 -0.0491752 -0.00999999 -0.04921668 -0.04956156 -0.00999999 -0.04948115 -0.04698115 0 -0.04948115 -0.04698115 -0.00999999 -0.04601728 -0.04701918 0 -0.04601728 -0.04701918 -0.00999999 -0.04629236 0.04982548 0 -0.04640185 0.04941278 0 -0.04662328 0.04904764 -0.00999999 -0.04662328 0.04904764 0 -0.04693847 0.04875975 0 -0.04732209 0.0485723 0 -0.0477429 0.04850047 0 -0.0477429 0.04850047 -0.00999999 -0.04816699 0.04855018 0 -0.0485599 0.04871726 0 -0.04888969 0.0489884 0 -0.0491299 0.04934138 0 -0.04926085 0.0497477 0 -0.049272 0.05017447 0 -0.04916244 0.05058717 -0.00999999 -0.04916244 0.05058717 0 -0.04894119 0.05095225 -0.00999999 -0.04862588 0.0512402 -0.00999999 -0.04894119 0.05095225 0 -0.04824239 0.05142766 -0.00999999 -0.04862588 0.0512402 0 -0.04824239 0.05142766 0 -0.04782146 0.05149948 -0.00999999 -0.04782146 0.05149948 0 -0.04739749 0.05144977 0 -0.04700458 0.0512827 0 -0.04700458 0.0512827 -0.00999999 -0.04667466 0.05101156 -0.00999999 -0.04667466 0.05101156 0 -0.04643458 0.05065858 0 -0.04643458 0.05065858 -0.00999999 -0.04630357 0.05025225 -0.00999999 -0.04630357 0.05025225 0 -0.04915344 0.05318105 0 -0.0512228 0.05040299 -0.00999999 -0.04915344 0.05318105 -0.00999999 -0.0512228 0.05040299 0 -0.04434156 0.04959696 0 -0.04434156 0.04959696 -0.00999999 -0.04641097 0.04681885 0 -0.04641097 0.04681885 -0.00999999 -0.04985159 0.04722189 0 -0.04926085 0.0497477 -0.00999999 -0.0491299 0.04934138 -0.00999999 -0.04985159 0.04722189 -0.00999999 -0.04888969 0.0489884 -0.00999999 -0.0485599 0.04871726 -0.00999999 -0.04816699 0.04855018 -0.00999999 -0.04732209 0.0485723 -0.00999999 -0.04693847 0.04875975 -0.00999999 -0.04640185 0.04941278 -0.00999999 -0.04629236 0.04982548 -0.00999999 -0.04571288 0.05277806 -0.00999999 -0.04739749 0.05144977 -0.00999999 -0.049272 0.05017447 -0.00999999 -0.04571288 0.05277806 0 0.0119397 0.09071135 0.02029997 0.01251184 0.09135967 0.02029997 0.01220685 0.09256178 0.02029997 0.01210469 0.09220451 0.02029997 0.01210469 0.09220451 0.02254998 0.01194506 0.09186899 0.02254998 0.01194506 0.09186899 0.02029997 0.01173239 0.09156417 0.02029997 0.01173239 0.09156417 0.02254998 0.0114724 0.09129869 0.02254998 0.0114724 0.09129869 0.02029997 0.01117229 0.09107947 0.02254998 0.01117229 0.09107947 0.02029997 0.01084017 0.09091275 0.02254998 0.01084017 0.09091275 0.02029997 0.01048517 0.0908029 0.02029997 0.01048517 0.0908029 0.02254998 0.01011699 0.09075295 0.02254998 0.009745538 0.0907644 0.02254998 0.01011699 0.09075295 0.02029997 0.009745538 0.0907644 0.02029997 0.009381055 0.09083676 0.02254998 0.009033441 0.09096819 0.02254998 0.09328675 0.05385917 0.03037327 0.074 0.06454819 0.01069998 0.07697325 0.04444044 0.04143339 -0.002471327 0.08846175 0.03107959 -0.004266262 0.08903729 0.02961158 -0.006164789 0.0895037 0.02808618 -0.007805943 0.08978098 0.02679157 0.00171113 0.0866506 0.03458988 -4.04894e-4 0.0876469 0.03279858 -0.02886909 0.09060448 0.01069998 -0.02796018 0.09420019 0.01069998 -0.009515225 0.08993339 0.02546936 0.01422655 0.09319865 0.02049195 0.02264118 0.09420019 0.01069998 0.01322537 0.09301328 0.02169585 0.01219975 0.09269046 0.02300667 -3.51883e-4 0.10506 0.02950894 0.011123 0.09221357 0.02446365 0.009964585 0.0915504 0.02611875 0.008819639 0.09074598 0.02784168 0.007658362 0.08978217 0.02967566 0.006495058 0.0886684 0.0315997 0.005245625 0.08730477 0.03376376 0.003989875 0.08575487 0.03604376 0.00380367 0.08550918 0.03639119 0.01205974 -0.09263628 0.02319157 0.01316165 -0.09299707 0.02177506 0.01411956 -0.09318518 0.02061694 0.01422655 -0.09319865 0.02049195 0.007592141 -0.08972281 0.02978289 0.008771955 -0.09070926 0.02791535 0.009919822 -0.09152168 0.02618455 0.01100367 -0.09215235 0.02462989 0.005134582 -0.08717495 0.03396117 -3.51883e-4 -0.10506 0.02950894 0.00637269 -0.08854246 0.03180706 -0.02796018 -0.09420019 0.01069998 -0.02886909 -0.09060448 0.01069998 -0.00834459 -0.0898447 0.02637195 -0.006687581 -0.08960521 0.02767127 -0.005044698 -0.0892468 0.02898269 -0.003259301 -0.08872997 0.0304321 -0.001440703 -0.08807528 0.03193306 4.85965e-4 -0.08724695 0.03354895 0.002413809 -0.08628445 0.03519147 -0.09793245 0.006394267 0.04745298 -0.0984857 0.006905496 0.04460686 -0.09314197 0.002083003 0.07144886 -0.08699536 0.003527164 0.0630725 -0.05776917 0.002401769 0.06811457 -0.05892598 0.002038955 0.07020217 -0.0781781 0.004659235 0.05633157 -0.08328258 0.003047943 0.06560075 -0.0794655 0.00480163 0.0555883 -0.08011031 0.004872977 0.05521595 -0.0864216 0.00340265 0.06374627 -0.0788235 0.004730641 0.05595886 -0.0841484 0.003108441 0.06529879 -0.08904099 0.001510262 0.0744853 -0.0923599 0.001841366 0.07277119 -0.09306329 0.002039253 0.07169079 -0.08746498 0.003656804 0.06236499 -0.08076435 0.004945337 0.05483835 -0.082111 0.005094289 0.05406087 -0.08754527 0.005695343 0.05092334 -0.09142267 0.004828512 0.0559594 -0.0849784 0.003189265 0.0648815 -0.09197866 0.001777589 0.0731126 -0.08574396 0.003288447 0.06435799 -0.091995 0.001780331 0.073098 -0.09369689 0.002480149 0.06924331 -0.09346038 0.002261579 0.07045996 -0.05975788 0.002043902 0.07021069 -0.05944615 0.001604378 0.07266479 -0.05813705 0.002048313 0.07011508 -0.05853438 0.00169295 0.07212769 -0.0602926 0.001541137 0.07305675 -0.06039434 0.001538217 0.07307749 -0.06041789 0.001537561 0.07308226 -0.06144136 0.001508414 0.07329058 -0.06061828 0.002065122 0.07012915 -0.0594182 0.001606464 0.07265186 -0.05912369 0.002551615 0.06733256 -0.06148946 0.002100884 0.06996637 -0.06048136 0.002701759 0.0665487 -0.06594729 0.003306388 0.06339299 -0.0824083 0.003006219 0.06579679 -0.07676315 0.004502713 0.05714839 -0.07685148 0.004512488 0.05709749 -0.07752287 0.004586756 0.05670976 -0.08790385 0.003787219 0.06165206 -0.0952652 0.003929436 0.06117475 -0.07108056 0.00149995 0.0737589 -0.06845998 0.002403199 0.06857359 -0.0879653 0.001502156 0.07448387 -0.06174856 0 0.07334899 -0.06141918 0 0.07328456 -0.06032669 0 0.073071 -0.06171059 0.001500785 0.0733453 -0.06146049 0.001507878 0.0732944 -0.06037956 0 0.07308125 -0.05904549 0.001634299 0.07247936 -0.0709728 0.00149995 0.07375419 -0.06526219 0.00149995 0.0735048 -0.06252205 0.001500606 0.07338178 -0.06249767 0.001500606 0.0733807 -0.08457458 0.00149995 0.07434797 -0.08604657 0.00149995 0.07441228 -0.0875715 0.00149995 0.07447886 -0.08309066 0.00149995 0.07428318 -0.08154785 0.00149995 0.07421588 -0.09308511 0 0.07155799 -0.09269666 0.001936137 0.07225388 -0.09349566 0.002294182 0.07027846 -0.0934416 0 0.07055145 -0.09345579 0.002257347 0.07048368 -0.0931918 0.00211066 0.07129567 -0.08887308 0 0.07449859 -0.08992958 0 0.07430976 -0.09025168 0.001568257 0.07421249 -0.09019976 0.001563191 0.07423859 -0.09011656 0.001559376 0.0742563 -0.09253096 0 0.07247436 -0.09264045 0.001920342 0.07234019 -0.0913884 0.001678824 0.07364135 -0.0909186 0 0.07388025 -0.09117788 0.00165832 0.07374715 -0.09111911 0.001652657 0.07377666 -0.09441846 0.003147006 0.06553065 -0.09364438 0 0.06950926 -0.09366047 0.002446532 0.06943029 -0.09530007 0.003961682 0.06099528 -0.05504065 0.00209999 0.06968986 -0.05504065 0 0.06968986 -0.05784314 0.001772284 0.07165217 -0.05850827 0 0.07210928 -0.05850887 0.001695871 0.07211017 -0.08923208 0.001518964 0.07444471 -0.08898669 0.001507759 0.07449686 -0.08817696 0.001503288 0.07448655 -0.05912369 -0.002551615 0.06733256 -0.05776917 -0.002401769 0.06811457 -0.05813705 -0.002048313 0.07011508 -0.0881769 -0.001500248 0.07450389 -0.0841484 -0.003108441 0.06529879 -0.08328258 -0.003047943 0.06560075 -0.08903777 -0.001516282 0.0744512 -0.08844977 -0.001500248 0.07451558 -0.08699536 -0.003527164 0.0630725 -0.09274208 -0.001934945 0.07226246 -0.09273129 -0.001932561 0.07227545 -0.09266567 -0.001917958 0.07235437 -0.08574396 -0.003288447 0.06435799 -0.09366047 -0.002446532 0.06943029 -0.09355598 -0.002350032 0.0699678 -0.0934844 -0.0022946 0.0702759 -0.08746498 -0.003656804 0.06236499 -0.06040179 -0.001535713 0.0730918 -0.06061828 -0.002065122 0.07012915 -0.05975788 -0.002043902 0.07021069 -0.05892598 -0.002038955 0.07020217 -0.05853605 -0.001693367 0.07212519 -0.05739915 -0.0018242 0.07134127 -0.06175005 -0.001500487 0.0733484 -0.06041526 -0.001535356 0.07309436 -0.06845998 -0.002403199 0.06857359 -0.06148946 -0.002100884 0.06996637 -0.06383436 -0.00149995 0.07344245 -0.08790385 -0.003787219 0.06165206 -0.082111 -0.005094289 0.05406087 -0.08076435 -0.004945337 0.05483835 -0.08011031 -0.004872977 0.05521595 -0.0864216 -0.00340265 0.06374627 -0.0794655 -0.00480163 0.0555883 -0.0788235 -0.004730641 0.05595886 -0.0849784 -0.003189265 0.0648815 -0.0781781 -0.004659235 0.05633157 -0.07752287 -0.004586756 0.05670976 -0.07685148 -0.004512488 0.05709749 -0.07676315 -0.004502713 0.05714839 -0.0824083 -0.003006219 0.06579679 -0.06594729 -0.003306388 0.06339299 -0.06048136 -0.002701759 0.0665487 -0.08754527 -0.005695343 0.05092334 -0.09142267 -0.004828512 0.0559594 -0.09618759 -0.004781842 0.05642956 -0.09581691 -0.004439294 0.05833649 -0.07190668 -0.00149995 0.0737949 -0.09117227 -0.00165838 0.0737468 -0.09010529 -0.001563608 0.07423239 -0.09023988 -0.00157386 0.07418066 -0.06249755 -0.001500308 0.07338219 -0.06144118 -0.001508593 0.07328969 -0.06146037 -0.001508057 0.07329326 -0.05944597 -0.001604497 0.07266396 -0.05941206 0 0.07265245 -0.06252205 -0.001500308 0.07338327 -0.06246864 0 0.07338076 -0.06603658 0 0.0735386 -0.06646555 -0.00149995 0.07355737 -0.06914019 -0.00149995 0.07367408 -0.0709728 -0.00149995 0.07375419 -0.07108056 -0.00149995 0.0737589 -0.07090938 0 0.07375138 -0.09299975 0 0.07179731 -0.0931406 -0.002083778 0.07144427 -0.09343898 0 0.07056498 -0.09321105 -0.002110123 0.07129937 -0.09327858 -0.002135336 0.07116079 -0.09344249 -0.002262175 0.07045596 -0.09003835 0 0.07429039 -0.09095257 -0.00162816 0.07390677 -0.09111928 -0.001651108 0.07378536 -0.09202247 -0.001775264 0.07312768 -0.09200489 -0.00177282 0.0731405 -0.09225106 0 0.07287847 -0.09179878 0 0.07326066 -0.09124559 0 0.07372796 -0.09369689 -0.002480149 0.06924331 -0.09426009 0 0.06634569 -0.0937438 -0.002523481 0.06900185 -0.0952652 -0.003929436 0.06117475 -0.09530007 -0.003961682 0.06099528 -0.0952624 0 0.06118959 -0.09660756 -0.005169928 0.05426919 -0.09708327 -0.005609512 0.05182164 -0.0984857 0 0.04460686 -0.09804487 -0.006498098 0.04687488 -0.09760659 -0.006093144 0.04912936 -0.09826099 0 0.04576295 -0.05786567 0 0.07166796 -0.05851066 -0.001696348 0.07210767 -0.05907458 0 0.07249808 -0.05907988 -0.001630842 0.07250016 -0.05941796 -0.001606523 0.0726515 -0.08681565 0 0.0744459 -0.08651417 -0.00149995 0.07443267 -0.0879653 -0.001500189 0.07449477 -0.08781188 0 0.07447791 -0.08880966 0 0.07450985 -0.08923298 -0.001521646 0.07442981 -0.08973437 -0.001535296 0.07437485 0.03863304 0 0.07723146 0.03498506 0 0.07883137 0.03219145 -0.04290586 0.07975167 0.03286707 0 0.07944697 0.02719789 -0.04247128 0.08104455 0.02693879 0 0.08117008 0.02503466 0 0.08172351 0.02087289 0 0.08211719 0.02453225 -0.04223924 0.08173477 0.0209279 -0.04116386 0.08216416 0.01293146 -0.03393679 0.08269995 0.01355397 -0.03356724 0.08269995 0.01392948 -0.03295487 0.08269995 0.01397645 -0.03223407 0.08269995 0.01373165 -0.03164345 0.08269995 0.01319664 -0.03117138 0.08269995 0.01249998 -0.03099995 0.08269995 0.0123468 -0.03100764 0.08269995 0.01166576 -0.03125298 0.08269995 0.01118475 -0.03177827 0.08269995 0.01100015 -0.03247648 0.08269995 0.01112455 -0.03309857 0.08269995 0.01156115 -0.03367006 0.08269995 0.01221889 -0.03397369 0.08269995 -0.02499997 -0.01999998 0.08269995 -0.02499997 0 0.08269995 -0.09210425 0.05317646 0.0280205 -0.04984456 0.02877777 0.07268989 -0.09290039 0.03179764 0.01069998 -0.101517 0.02399998 0.04285687 -0.04984456 0 0.07268989 -0.05504065 -0.00209999 0.06968986 -0.0984857 -0.006905496 0.04460686 -0.101517 -0.02399998 0.04285687 -0.101517 0 0.04285687 -0.09290039 -0.03179764 0.01069998 -0.09210425 -0.05317646 0.0280205 0.09328675 -0.05385917 0.03037327 0.09314805 -0.04594588 0.02331209 0.074 -0.06454819 0.01069998 0.07697325 -0.04444044 0.04143339 0.02264118 -0.09420019 0.01069998 -0.002970933 -0.08856099 0.0306825 0.003935277 -0.06250679 0.06835067 -0.008327007 -0.08984255 0.0263856 -0.00468111 -0.08915197 0.02927565 -0.002227306 -0.05926167 0.06895905 -7.40853e-4 -0.08779019 0.03251695 0.00380367 -0.08550918 0.03639119 0.004236161 -0.08606237 0.03559458 0.004659473 -0.08660399 0.03481489 0.01195359 -0.09259325 0.02333295 0.009799897 -0.09144347 0.02636146 0.01590365 -0.06364709 0.06624341 0.009271681 -0.09101867 0.02718776 0.007140398 -0.0893045 0.03052175 -0.009954869 -0.08994835 0.02513396 -0.04984456 -0.02877777 0.07268989 -0.07398778 -0.06455516 0.01069998 0.01471197 -0.03899997 0.08269995 0.0220384 -0.06217759 0.06479477 0.003507614 -0.06228154 0.06839287 0.01683515 -0.03994286 0.08265167 0.009656012 -0.06374466 0.06746768 0.01074308 -0.06397986 0.0672999 0.03345787 -0.042741 0.07924175 0.01765495 -0.0635342 0.06588476 0.03955477 -0.04194664 0.07678687 0.117354 -0.02243036 0.0392552 0.117354 0 0.0392552 0.117354 0.02243036 0.0392552 0.02453225 0.04223924 0.08173477 0.02503466 0 0.08172351 0.0209279 0.04116386 0.08216416 0.02087289 0 0.08211719 0.02693879 0 0.08117008 0.02719789 0.04247128 0.08104455 0.03286707 0 0.07944697 0.03498506 0 0.07883137 0.03955477 0.04194664 0.07678687 -0.02499997 0.01999998 0.08269995 0.01112467 0.03190129 0.08269995 0.01471197 0 0.08269995 0.01156145 0.03132969 0.08269995 0.01221936 0.03102618 0.08269995 0.01293188 0.03106337 0.08269995 0.01355439 0.0314331 0.08269995 0.01392954 0.03204536 0.08269995 0.01397645 0.03276616 0.08269995 0.01373207 0.03335607 0.08269995 0.01319676 0.03382849 0.08269995 0.01249998 0.03399997 0.08269995 0.01234626 0.03399229 0.08269995 0.01166546 0.03374665 0.08269995 0.01118475 0.0332216 0.08269995 0.01100015 0.03252357 0.08269995 0.01471197 0.03899997 0.08269995 -0.002227306 0.05926167 0.06895905 0.01590424 0.06377118 0.06626546 0.03345787 0.042741 0.07924175 0.01544678 0.06388998 0.06637519 0.03219145 0.04290586 0.07975167 0.008526742 0.06371361 0.06768018 0.003529429 0.06216019 0.06836688 0.01683515 0.03994286 0.08265167 0.0220384 0.06217759 0.06479477 0.09314805 0.04594588 0.02331209 0.01154488 0.0924167 0.0238834 0.01375418 0.09312748 0.02105057 0.004248201 0.08602607 0.03560268 0.006686031 0.08886116 0.03127807 0.009259939 0.09107106 0.02716988 0.009249925 0.09106528 0.02718424 0.001333653 0.08684009 0.03426796 0.009631752 0.0637418 0.0674718 0.00380367 0.08550918 0.03639119 -0.009954869 0.08994835 0.02513396 0.001833498 0.06163299 0.06859999 -0.006290376 0.08952939 0.02798604 -0.002971708 0.0885955 0.03067535 -0.002377986 0.08842837 0.03115648 -0.07398778 0.06455516 0.01069998 + + + + + + + + + + 0.4999697 0.8660429 0 0.4999675 0.8660443 0 0.500001 0.8660249 0 0.4999947 0.8660284 0 0.4999949 0.8660285 0 0.5000231 0.866012 0 1 0 0 -0.4999892 -0.8660317 0 -0.4999882 -0.8660323 0 -0.5000424 -0.8660009 0 -0.500041 -0.8660018 0 -0.9468721 0.3216105 0 -0.9468768 0.3215966 0 -0.9978451 -0.06561535 0 -0.997844 -0.06563085 0 -0.8969796 -0.4420721 0 -0.8969737 -0.4420838 0 -0.6591997 -0.751968 0 -0.659192 -0.7519748 0 -0.4999611 -0.8660478 0 -0.4999586 -0.8660494 0 -1 0 0 -0.9659133 0.2588658 0 -0.9659132 0.2588664 0 -0.7071078 0.7071058 0 -0.7071083 0.7071053 0 -0.258867 0.9659131 0 0.258869 0.9659125 0 0.258867 0.9659131 0 0.5000057 0.8660221 0 0.5000051 0.8660225 0 0.4999797 0.8660372 0 0.4999811 0.8660364 0 0.5000017 0.8660244 0 0.5000025 0.866024 0 0.500009 0.8660202 0 0.5000079 0.8660209 0 0.8660287 -0.4999942 0 0.8660303 -0.4999915 0 0.8660231 -0.5000041 0 -0.5000048 -0.8660227 0 -0.5000046 -0.8660229 0 -0.4998655 -0.8661031 0 -0.5000583 -0.8659918 0 -0.5000579 -0.8659921 0 0.8660086 -0.5000293 0 0.8660089 -0.5000288 0 0.8660171 -0.5000144 0 0.8660174 -0.5000139 0 0 -1 0 0 1 0 0.4999913 0.8660305 0 0.4999909 0.8660307 0 0.5000082 0.8660207 0 0.5000085 0.8660206 0 0.4999999 0.8660256 0 0.4999973 0.866027 0 0.4999967 0.8660272 0 0.4999855 0.8660337 0 0.4999877 0.8660325 0 -0.2587464 -0.9659454 0 -0.2587459 -0.9659455 0 0.2587464 -0.9659454 0 0.2587479 -0.965945 0 0.7071058 -0.7071078 0 0.7071019 -0.7071117 0 0.9659245 -0.2588239 0 0.9659226 -0.2588312 0 -0.5000085 -0.8660206 0 -0.5000086 -0.8660206 0 -0.5000008 -0.866025 0 -0.5000004 -0.8660253 0 -0.2493234 -0.9684203 0 -0.2493239 -0.9684202 0 -0.2492852 -0.9684302 0 -0.2492852 -0.9684302 0 -0.2493157 -0.9684223 0 -0.2493163 -0.9684222 0 -0.6859604 -0.727639 0 -0.6859613 -0.727638 0 -0.6859064 -0.7276899 0 -0.6859049 -0.7276912 0 -0.9520411 -0.3059703 0 -0.9520408 -0.3059711 0 -0.9520369 -0.3059836 0 -0.8660257 0.4999995 0 -0.8660254 0.5 0 -0.8660348 0.4999837 0 -0.8660326 0.4999877 0 -0.5000011 0.8660249 0 -0.5000005 0.8660252 0 0.2588625 -0.9659142 0 0.2588605 -0.9659148 0 0.7071097 -0.7071039 0 0.9659121 -0.2588707 0 -0.9659291 -0.2588069 0 -0.9659288 -0.2588083 0 -0.7070732 -0.7071405 0 -0.7070724 -0.7071412 0 -0.2588629 -0.9659141 0 -0.258862 -0.9659144 0 0.2588625 -0.9659143 0 0.2588621 -0.9659144 0 0.7070732 -0.7071405 0 0.7070724 -0.7071412 0 0.9659293 -0.2588062 0 0.9659273 0.2588135 0 0.9659275 0.2588132 0 0.7070797 0.7071339 0 0.7070804 0.7071332 0 0.2588758 0.9659106 0 -0.2588756 0.9659107 0 -0.2588762 0.9659105 0 -0.7070797 0.7071339 0 -0.7070804 0.7071332 0 -0.9659268 0.2588156 0 -0.9659273 0.2588139 0 0.9659291 -0.2588069 0 -0.9659293 -0.2588062 0 -0.2588625 -0.9659143 0 -0.2588621 -0.9659144 0 0.2588623 -0.9659143 0 0.707103 -0.7071105 0 0.7071014 -0.7071121 0 0.7070086 -0.7072049 0 0.7070109 -0.7072026 0 0.9659288 -0.2588083 0 0.965927 0.2588152 0 0.9659272 0.2588142 0 0.7070335 0.7071802 0 0.7070312 0.7071825 0 0.707102 0.7071117 0 0.7071025 0.7071111 0 0.2588762 0.9659105 0 0.2588756 0.9659107 0 -0.2588758 0.9659106 0 -0.9659273 0.2588135 0 -0.9659275 0.2588132 0 -0.2588739 0.9659112 0 -0.2588798 0.9659096 0 -0.707101 0.7071127 0 -0.7071068 0.7071068 0 -0.9659142 0.2588624 0 -0.9659142 -0.2588624 0 -0.7071068 -0.7071068 0 -0.707101 -0.7071127 0 -0.2588597 -0.965915 0 -0.2588538 -0.9659165 0 0.2588538 -0.9659165 0 0.7071127 -0.7071009 0 0.707101 -0.7071127 0 0.9659171 -0.2588515 0 0.9659171 0.2588515 0 0.707101 0.7071127 0 0.7071127 0.7071009 0 0.2588739 0.9659112 0 -0.2588672 0.9659129 0 -0.2588733 0.9659113 0 -0.7071039 0.7071097 0 -0.7071105 0.7071031 0 -0.9659138 0.2588639 0 -0.9659137 0.2588643 0 -0.7071098 -0.7071039 0 -0.7071046 -0.707109 0 0.7071156 -0.707098 0 0.7071046 -0.707109 0 0.9659168 0.258853 0 0.9659166 0.2588533 0 0.7071039 0.7071097 0 0.7071163 0.7070972 0 0.2588672 0.9659129 0 0.2588675 0.9659129 0 0.2588597 -0.965915 0 0.7071068 -0.7071068 0 0.9659142 -0.2588624 0 0.9659142 0.2588624 0 0.7071068 0.7071068 0 0.2588798 0.9659096 0 0.7071039 -0.7071097 0 0.7071105 -0.7071031 0 0.9659138 0.2588639 0 0.9659137 0.2588643 0 0.7071098 0.7071039 0 0.7071046 0.707109 0 0.258873 0.9659114 0 -0.2588635 0.965914 0 0.2588635 0.965914 0 0.707115 0.7070986 0 0.7071062 0.7071074 0 0.9659118 0.2588718 0 0.9659118 -0.2588718 0 0.7071092 -0.7071045 0 0.7071185 -0.7070951 0 0.2588635 -0.965914 0 -0.2588635 -0.965914 0 -0.2588681 -0.9659127 0 -0.7071092 -0.7071045 0 -0.9659164 -0.2588543 0 -0.9659118 -0.2588718 0 -0.9659118 0.2588718 0 -0.9659164 0.2588543 0 -0.7071056 0.707108 0 -0.7071062 0.7071074 0 -0.2588681 0.9659127 0 0.2588681 0.9659127 0 0.7071056 0.707108 0 0.9659164 0.2588543 0 0.9659164 -0.2588543 0 0.2588681 -0.9659127 0 -0.7071185 -0.7070951 0 -0.7071156 0.707098 0 0.8660145 -0.5000188 0 0.866028 -0.4999957 0 -0.5000093 -0.86602 0 -0.500011 -0.8660191 0 -0.4999887 -0.8660319 0 -0.4999901 -0.8660311 0 -0.5000038 -0.8660233 0 -0.5000046 -0.8660228 0 0.5000038 0.8660233 0 0.5000031 0.8660237 0 0.4999935 0.8660293 0 0.4999923 0.8660299 0 0.5000101 0.8660196 0 0.5000128 0.866018 0 -0.5000128 0.866018 0 -0.5000101 0.8660196 0 -0.4999988 0.8660262 0 0.499999 -0.8660261 0 0.4999994 -0.8660258 0 0.5000115 -0.8660189 0 0.5000089 -0.8660204 0 -0.9659026 -0.2589062 0 -0.7071207 -0.7070929 0 -0.7070965 -0.707117 0 -0.2588739 -0.9659112 0 -0.2588857 -0.9659081 0 0.2588739 -0.9659112 0 0.7070972 -0.7071163 0 0.70712 -0.7070937 0 0.9659026 -0.2589062 0 0.2588724 0.9659116 0 0.2588486 0.965918 0 -0.2588724 0.9659116 0 -0.2588603 0.9659148 0 -0.7071281 0.7070856 0 -0.7071273 -0.7070863 0 0.4999829 0.8660354 0 0.4999834 0.8660351 0 0.5000055 0.8660223 0 0.5000096 0.86602 0 0.5000202 0.8660138 0 0.5000187 0.8660147 0 -0.5000017 0.8660245 0 -0.5000015 0.8660246 0 -0.8808579 0.4733809 0 -0.8808582 0.4733804 0 -0.8808624 0.4733726 0 -0.88086 0.4733769 0 -0.866036 -0.4999817 0 -0.8660357 -0.4999822 0 -0.8660269 -0.4999973 0 -0.8660274 -0.4999967 0 -0.8660237 -0.5000031 0 -0.8660268 -0.4999975 0 -0.5000175 -0.8660153 0 -0.5000133 -0.8660178 0 -0.4999459 -0.8660567 0 -0.4999418 -0.8660591 0 -0.5000085 -0.8660205 0 -0.500009 -0.8660202 0 -0.4999983 -0.8660264 0 -0.5 -0.8660255 0 -0.3091167 -0.9510242 0 -0.3090938 -0.9510316 0 0.1045304 -0.9945217 0 0.1045302 -0.9945217 0 0.5002967 -0.8658541 0 0.5002634 -0.8658733 0 0.8088697 -0.5879879 0 0.8088878 -0.5879631 0 0.9781637 -0.2078361 0 0.9781637 -0.2078364 0 -0.2588623 -0.9659143 0 0.2588857 -0.9659081 0 0.7070965 -0.707117 0 0.9659026 0.2589062 0 -0.5000095 -0.86602 0 -0.50001 -0.8660197 0 -0.500002 -0.8660243 0 -0.5000022 -0.8660241 0 -0.4999991 -0.8660259 0 -0.5000019 -0.8660244 0 -0.5000014 -0.8660246 0 -0.4999574 -0.86605 0 -0.500025 -0.866011 0 -0.5000255 -0.8660108 0 -0.499996 -0.8660278 0 -0.500008 -0.8660209 0 -0.5000081 -0.8660207 0 -0.4999895 -0.8660315 0 -0.4999884 -0.8660321 0 -0.5000117 -0.8660187 0 -0.5000124 -0.8660182 0 -0.4999939 -0.866029 0 -0.8660174 -0.5000141 0 -0.8660186 -0.5000117 0 -0.8660237 -0.5000032 0 -0.8660239 -0.5000026 0 -0.8660298 -0.4999924 0 -0.8660295 -0.499993 0 -0.8659967 -0.5000498 0 -0.8659969 -0.5000494 0 0.8503269 -0.526255 0 0.850326 -0.5262564 0 0.8504059 -0.5261273 0 0.8503937 -0.526147 0 0.8503932 -0.5261477 0 0.8503779 -0.5261724 0 0.8503772 -0.5261737 0 0.5000054 -0.8660224 0 0.4999991 -0.8660259 0 0.4999975 -0.8660269 0 0.4999977 -0.8660268 0 0.5000107 -0.8660193 0 0.4999574 -0.86605 0 0.5000255 -0.8660108 0 0.500025 -0.866011 0 0.499996 -0.8660278 0 0.5000071 -0.8660213 0 0.500009 -0.8660203 0 0.4999975 -0.8660269 0 0.4999981 -0.8660265 0 0.4999939 -0.866029 0 -0.9781637 -0.2078361 0 -0.9781637 -0.2078364 0 -0.8088883 -0.5879625 0 -0.8088693 -0.5879885 0 -0.500263 -0.8658736 0 -0.5002971 -0.8658539 0 -0.1045304 -0.9945217 0 -0.1045302 -0.9945217 0 0.3090938 -0.9510316 0 0.3091167 -0.9510242 0 0.4999814 -0.8660362 0 0.500009 -0.8660202 0 0.5000085 -0.8660205 0 0.4999988 -0.8660261 0 0.4999995 -0.8660258 0 0.03046911 -0.9995357 0 0.03046905 -0.9995358 0 0.03046447 -0.9995359 0 0.03046435 -0.9995359 0 0.03052002 -0.9995342 0 0.8660181 -0.5000126 0 0.8660168 -0.5000151 0 0.8660269 -0.4999973 0 0.8660274 -0.4999967 0 0.8660199 -0.5000097 0 0.8660179 -0.5000129 0 0.8660173 0.5000141 0 0.8660168 0.5000148 0 0.866029 0.4999938 0 0.8660287 0.4999942 0 0.5000026 0.8660239 0 0.5000059 0.8660221 0 0.5000004 0.8660252 0 0.5000011 0.8660249 0 0.500003 0.8660237 0 0.5000018 0.8660244 0 -0.5000165 0.866016 0 -0.4999829 0.8660354 0 -0.4999834 0.8660351 0 -0.2588651 0.9659136 0 -0.2588729 0.9659115 0 -0.7070961 0.7071176 0 -0.7071278 0.7070858 0 -0.9659101 0.258878 0 -0.2588607 0.9659147 0 -0.258872 0.9659117 0 -0.7071046 0.707109 0 -0.9659026 0.2589062 0 -0.7071039 -0.7071097 0 0.7071281 -0.7070856 0 0.7071273 0.7070863 0 0.2588607 0.9659147 0 0.258872 0.9659117 0 -0.2588489 0.9659179 0 0.6556447 0.7550696 0 0.8395084 -0.543347 0 0.8395071 -0.5433488 0 0.9952335 -0.09752041 0 0.9952334 -0.09752213 0 0.9290079 0.3700602 0 0.9290097 0.3700556 0 0.9290349 0.3699922 0 0.9290348 0.3699926 0 0.655645 0.7550693 0 0.2361736 0.9717109 0 0.2361751 0.9717105 0 0.2361134 0.9717255 0 0.2361134 0.9717256 0 -0.2361286 0.9717218 0 -0.236129 0.9717217 0 -0.6556442 0.7550701 0 -0.6556451 0.7550693 0 -0.929027 0.3700121 0 -0.9290277 0.3700105 0 -0.9290307 0.3700028 0 -0.9290325 0.3699982 0 -0.9952319 -0.09753787 0 -0.9952319 -0.09753799 0 -0.8395175 -0.5433328 0 -0.8395174 -0.5433329 0 0.2361241 0.9717229 0 0.9952319 -0.09753763 0 0.839513 -0.5433398 0 0.8395132 -0.5433393 0 0.8396804 -0.5430809 0 0.9952319 -0.09753745 0 0.9290273 0.3700113 0 0.9290275 0.3700109 0 0.9311061 0.3647485 0 0.931106 0.3647489 0 0.9290274 0.3700111 0 0.9290274 0.370011 0 0.6556712 0.7550467 0 0.6556718 0.7550461 0 0.655077 0.7555622 0 0.2361238 0.9717231 0 -0.2360972 0.9717295 0 -0.2360974 0.9717294 0 -0.2361978 0.9717051 0 -0.2361973 0.9717051 0 -0.655077 0.7555622 0 -0.6556713 0.7550466 0 -0.6556717 0.7550462 0 -0.9290276 0.3700106 0 -0.9290272 0.3700115 0 -0.9290316 0.3700005 0 -0.9952319 -0.09753745 0 -0.9952319 -0.09753763 0 -0.8395171 -0.5433334 0 -0.6556455 0.7550689 0 0.8395179 -0.5433322 0 0.8395171 -0.5433335 0 0.9952319 -0.09753787 0 0.9952319 -0.09753799 0 0.9290325 0.3699982 0 0.9290307 0.3700028 0 0.9290278 0.3700101 0 0.9290269 0.3700125 0 0.6556447 0.7550697 0 0.2361286 0.9717218 0 0.236129 0.9717217 0 -0.2361131 0.9717256 0 -0.2361137 0.9717255 0 -0.2361751 0.9717105 0 -0.2361736 0.9717109 0 -0.9290349 0.3699922 0 -0.9290348 0.3699926 0 -0.9290097 0.3700556 0 -0.9290079 0.3700602 0 -0.9952335 -0.09752196 0 -0.9952336 -0.09752053 0 -0.8395076 -0.5433481 0 -0.8395078 -0.5433477 0 -0.4999871 0.866033 0 -0.4999862 0.8660334 0 -0.4999974 0.8660268 0 -0.4999966 0.8660274 0 -0.5000013 0.8660247 0 -0.5000011 0.8660248 0 -0.5000079 0.8660209 0 -0.5000087 0.8660203 0 -0.5000028 0.8660238 0 -0.5000034 0.8660236 0 -0.4999681 0.8660439 0 -0.4999676 0.8660441 0 0.5000076 -0.866021 0 0.5000094 -0.86602 0 0.5000008 -0.866025 0 0.5000004 -0.8660253 0 0.9520369 -0.3059836 0 0.9520408 -0.3059711 0 0.9520411 -0.3059703 0 0.685928 -0.7276694 0 0.2493236 -0.9684202 0 0.2493237 -0.9684203 0 0.2492847 -0.9684303 0 0.2492856 -0.9684301 0 0.2493163 -0.9684222 0 0.2493157 -0.9684223 0 0.6859276 -0.7276698 0 0.5000016 0.8660245 0 0.5 0.8660254 0 -0.9659121 -0.2588707 0 -0.7071097 -0.7071039 0 -0.7071058 -0.7071078 0 -0.2588605 -0.9659148 0 -0.2588625 -0.9659142 0 -0.258869 0.9659125 0 0.7071078 0.7071058 0 0.7071083 0.7071053 0 0.9659133 0.2588658 0 0.9659132 0.2588664 0 -0.5000051 0.8660225 0 -0.5000057 0.8660221 0 -0.4999801 0.8660369 0 -0.4999806 0.8660366 0 -0.5000028 0.8660238 0 -0.5000032 0.8660236 0 -0.8660291 -0.4999936 0 -0.86603 -0.4999921 0 -0.8660231 -0.5000041 0 0.2588618 -0.9659144 0 -0.2588632 -0.965914 0 -0.7071075 -0.7071061 0 -0.8660089 -0.5000288 0 -0.8660086 -0.5000293 0 -0.8660174 -0.5000139 0 -0.8660171 -0.5000144 0 -0.2586876 -0.9659611 0 0.2586905 -0.9659603 0 0.2586861 -0.9659615 0 0.5000048 -0.8660227 0 0.5000046 -0.8660229 0 0.4998655 -0.8661031 0 0.5000579 -0.8659921 0 0.5000583 -0.8659918 0 0.9468721 0.3216105 0 0.9468768 0.3215966 0 0.9978451 -0.06561535 0 0.997844 -0.06563085 0 0.8969799 -0.4420713 0 0.8969734 -0.4420846 0 0.6591997 -0.751968 0 0.659192 -0.7519748 0 0.4999892 -0.8660317 0 0.4999882 -0.8660323 0 0.5000424 -0.8660009 0 0.500041 -0.8660018 0 -0.4999876 -0.8660326 0 -0.4999871 -0.866033 0 -0.5000349 -0.8660054 0 -0.5000372 -0.8660041 0 -0.5000231 0.866012 0 -0.4999954 0.8660281 0 -0.4999941 0.8660288 0 -0.500001 0.8660249 0 -0.4999675 0.8660443 0 -0.4999697 0.8660429 0 0.7071031 -0.7071105 0 -0.2588784 0.96591 0 0.2588779 0.9659101 0 0.2588802 0.9659095 0 0.7071077 0.7071059 0 0.9659123 0.25887 0 0.9659139 0.2588635 0 0.9659141 -0.2588631 0 0.9659122 -0.2588704 0 0.7071077 -0.7071059 0 0.2588631 -0.965914 0 0.2588613 -0.9659146 0 -0.2588613 -0.9659146 0 -0.2588631 -0.965914 0 -0.7071077 -0.7071059 0 -0.7071114 -0.7071022 0 -0.9659123 -0.25887 0 -0.9659139 -0.2588635 0 -0.9659141 0.2588631 0 -0.9659122 0.2588704 0 -0.7071114 0.7071022 0 -0.7071077 0.7071059 0 -0.2588798 0.9659096 0 -0.5000019 0.8660244 0 -0.5000032 0.8660236 0 -0.4999992 0.8660259 0 -0.4999995 0.8660257 0 -0.4999958 0.8660278 0 -0.4999973 0.8660271 0 -0.8660924 -0.499884 0 -0.8660928 -0.4998835 0 -0.8660141 -0.5000199 0 -0.8660133 -0.5000212 0 0.5000002 -0.8660253 0 0.8660245 0.5000016 0 0.8660231 0.5000042 0 0.8660246 0.5000016 0 0.8660262 0.4999987 0 0 0 -1 -1.36044e-6 0 -1 5.35683e-5 0 -1 1.1895e-6 0 -1 -4.87702e-7 0 -1 3.41988e-6 0 -1 -3.16456e-7 0 -1 2.2833e-6 0 -1 -7.61162e-7 0 -1 2.13814e-6 0 -1 -2.87263e-6 0 -1 3.39524e-6 0 -1 -6.30684e-6 0 -1 4.06918e-6 0 -1 -1.61987e-6 0 -1 3.17925e-6 0 -1 1.02777e-6 0 -1 -4.02162e-7 0 -1 1.32666e-6 0 -1 -1.56139e-6 0 -1 -2.55363e-6 0 -1 -1.81466e-6 0 -1 2.37366e-7 0 -1 2.23086e-5 0 -1 2.37808e-6 0 -1 -2.56585e-6 0 -1 4.1132e-6 0 -1 1.06025e-6 0 -1 -4.36379e-7 0 -1 2.08876e-7 0 -1 1.42693e-6 0 -1 -4.5923e-6 0 -1 2.00535e-6 0 -1 1.24257e-6 0 -1 -1.02824e-6 0 -1 2.7923e-6 0 -1 3.40496e-6 0 -1 -1.80492e-6 0 -1 5.10698e-7 0 -1 1.51247e-6 0 -1 4.39431e-6 0 -1 0 0 -1 -4.13774e-7 0 -1 9.96087e-7 0 -1 2.39831e-6 0 -1 -8.35159e-7 0 -1 1.43886e-6 0 -1 -1.99626e-7 0 -1 4.82539e-6 0 -1 -2.59856e-7 0 -1 -4.7955e-7 0 -1 1.11421e-5 0 -1 2.19991e-6 0 -1 -9.987e-7 0 -1 8.34907e-7 0 -1 7.60213e-6 0 -1 -1.45519e-5 0 -1 -5.74169e-7 0 -1 6.39787e-7 0 -1 -2.63794e-6 0 -1 -7.05164e-6 0 -1 1.84367e-6 0 -1 -2.63607e-6 0 -1 1.16727e-6 0 -1 6.12486e-7 0 -1 -1.03055e-6 0 -1 3.02139e-7 0 -1 6.01928e-7 0 -1 3.71944e-6 0 -1 3.43131e-6 0 -1 -2.20451e-6 0 -1 2.12903e-6 0 -1 -2.67523e-6 0 -1 -8.41111e-7 0 -1 1.30867e-7 0 -1 1.72685e-6 0 -1 -4.4472e-6 0 -1 -2.05745e-6 0 -1 4.47246e-7 0 -1 -1.7225e-6 0 -1 1.38909e-7 0 -1 -2.01259e-6 0 -1 -1.15364e-6 0 -1 -1.96707e-7 0 -1 5.10119e-7 0 -1 2.05612e-6 0 -1 -3.00822e-7 0 -1 2.5572e-6 0 -1 6.03232e-6 0 -1 -7.23657e-6 0 -1 8.63638e-6 0 -1 -7.73406e-6 0 -1 5.31244e-6 0 -1 -2.45009e-7 0 -1 2.55061e-7 0 -1 4.36799e-6 0 -1 -1.44809e-7 0 -1 2.67462e-7 0 -1 -2.52584e-6 0 -1 3.64419e-7 0 -1 4.66821e-7 0 -1 -6.8276e-7 0 -1 2.79157e-7 0 -1 -2.55113e-7 0 -1 1.44023e-5 0 -1 -1.0773e-5 0 -1 4.54159e-7 0 -1 -2.43205e-6 0 -1 1.36485e-6 0 -1 -1.69768e-5 0 -1 3.87633e-6 0 -1 1.0529e-5 0 -1 -4.06002e-6 0 -1 4.7325e-6 0 -1 -4.6563e-6 0 -1 -2.75226e-6 0 -1 1.19277e-6 0 -1 4.05328e-6 0 -1 -4.76897e-7 0 -1 0 0 -1 0 0 -1 -5.86703e-7 0 -1 3.69955e-7 0 -1 -2.35251e-6 0 -1 -3.48868e-7 0 -1 -1.79455e-6 0 -1 8.37785e-7 0 -1 -2.23552e-6 0 -1 2.71348e-5 0 -1 3.47857e-6 0 -1 -7.64441e-7 0 -1 -8.05226e-7 0 -1 -7.27611e-7 0 -1 -8.34916e-7 0 -1 -1.21265e-5 0 -1 2.20553e-7 0 -1 -1.19224e-7 0 -1 4.89891e-7 0 -1 -2.14694e-7 0 -1 -4.02484e-6 0 -1 -3.65895e-7 0 -1 2.11322e-7 0 -1 8.7528e-7 0 -1 -6.03008e-7 0 -1 2.70016e-7 0 -1 -2.25814e-6 0 -1 -2.72087e-6 0 -1 1.71664e-6 0 -1 -5.6317e-7 0 -1 -2.9223e-6 0 -1 -4.27023e-5 0 -1 6.13784e-7 0 -1 3.28314e-7 0 -1 2.91567e-5 0 -1 2.87752e-5 0 -1 2.87755e-5 0 -1 -1.2891e-5 0 -1 2.06765e-6 0 -1 -2.79412e-7 0 -1 1.57099e-6 0 -1 0 0 -1 -3.96173e-7 0 -1 2.46022e-7 0 -1 1.25682e-6 0 -1 -1.10063e-6 0 -1 -4.79184e-6 0 -1 -5.30046e-7 0 -1 -1.60028e-7 0 -1 8.21551e-7 0 -1 3.31891e-6 0 -1 3.78605e-7 0 -1 -1.10443e-6 0 -1 -7.82197e-6 0 -1 -1.05568e-6 0 -1 -3.85501e-7 0 -1 -1.00306e-6 0 -1 -6.7649e-7 0 -1 5.92091e-6 0 -1 -2.95542e-6 0 -1 1.07435e-6 0 -1 -1.03066e-6 0 -1 1.25936e-6 0 -1 -4.00726e-6 0 -1 1.41906e-7 0 -1 2.18994e-7 0 -1 7.42604e-7 0 -1 1.75597e-7 0 -1 -5.74343e-6 0 -1 -6.67681e-6 0 -1 4.06755e-6 0 -1 -3.97047e-7 0 -1 8.92042e-7 0 -1 1.70047e-6 0 -1 1.38271e-6 0 -1 -1.05031e-5 0 -1 1.39559e-6 0 -1 -1.33237e-6 0 -1 1.3324e-6 0 -1 6.0589e-7 0 -1 7.63308e-7 0 -1 -3.87979e-7 0 -1 6.03486e-6 0 -1 -6.61049e-7 0 -1 -1.08627e-6 0 -1 -4.57771e-7 0 -1 3.7191e-6 0 -1 5.13296e-7 0 -1 -1.0404e-6 0 -1 6.26745e-7 0 -1 -1.43042e-6 0 -1 -1.20056e-6 0 -1 2.08467e-7 0 -1 2.82305e-7 0 -1 7.71382e-6 0 -1 -1.3324e-6 0 -1 1.33237e-6 0 -1 9.91338e-6 0 -1 0 0 -1 1.94927e-7 0 -1 -1.75632e-7 0 -1 0 0 -1 -1.35916e-7 0 -1 8.89166e-7 0 -1 0 0 -1 -3.14802e-7 0 -1 2.87303e-6 0 -1 -2.03186e-6 0 -1 1.95274e-6 0 -1 -6.31511e-7 0 -1 4.00072e-7 0 -1 -1.2416e-7 0 -1 -1.10792e-6 0 -1 4.61162e-7 0 -1 -1.41188e-7 0 -1 3.72058e-7 0 -1 2.00363e-6 0 -1 1.60026e-7 0 -1 -1.68937e-7 0 -1 -3.43048e-6 0 -1 4.27638e-7 0 -1 0 0 -1 0 0 -1 -2.03411e-6 0 -1 2.18825e-7 0 -1 -4.44067e-6 0 -1 3.85501e-7 0 -1 -3.85504e-7 0 -1 4.44073e-6 0 -1 1.47771e-6 0 -1 -1.47771e-6 0 -1 1.29377e-6 0 -1 -1.07435e-6 0 -1 1.60028e-7 0 -1 -1.70763e-7 0 -1 1.89302e-7 0 -1 0 0 -1 -3.01719e-7 0 -1 4.53725e-7 0 -1 -8.92506e-7 0 -1 0 0 -1 6.89578e-7 0 -1 -1.57099e-6 0 -1 1.42304e-7 0 -1 -2.46022e-7 0 -1 6.15341e-7 0 -1 0 0 -1 7.49408e-7 0 -1 1.7188e-5 0 -1 4.04609e-6 0 -1 -1.81031e-7 0 -1 -1.1895e-6 0 -1 -4.39431e-6 0 -1 4.75197e-7 0 -1 2.76676e-7 0 -1 -7.60213e-6 0 -1 2.30398e-6 0 -1 -1.46456e-6 0 -1 -8.34907e-7 0 -1 -2.19991e-6 0 -1 2.28848e-6 0 -1 -5.87782e-7 0 -1 4.7955e-7 0 -1 -5.44805e-6 0 -1 5.69365e-5 0 -1 8.35159e-7 0 -1 -6.50209e-7 0 -1 7.20726e-7 0 -1 -1.73639e-6 0 -1 -5.00108e-6 0 -1 1.45519e-5 0 -1 -7.6137e-6 0 -1 2.87066e-6 0 -1 3.46712e-6 0 -1 -4.1132e-6 0 -1 8.42171e-7 0 -1 -1.06025e-6 0 -1 -1.81635e-7 0 -1 3.19775e-6 0 -1 2.03226e-6 0 -1 -9.43371e-7 0 -1 3.12281e-6 0 -1 1.81466e-6 0 -1 2.55363e-6 0 -1 -1.06176e-6 0 -1 3.02253e-6 0 -1 -7.56233e-7 0 -1 2.56585e-6 0 -1 -6.24097e-7 0 -1 5.2794e-7 0 -1 7.87885e-7 0 -1 4.66731e-6 0 -1 3.24204e-7 0 -1 -2.15623e-7 0 -1 -3.41988e-6 0 -1 -2.2833e-6 0 -1 7.61162e-7 0 -1 3.16456e-7 0 -1 0 0 -1 -4.46335e-7 0 -1 2.08934e-7 0 -1 -2.75482e-7 0 -1 6.11025e-7 0 -1 -4.6297e-7 0 -1 -1.92906e-6 0 -1 4.87702e-7 0 -1 -7.50354e-7 0 -1 -6.79048e-6 0 -1 4.88718e-6 0 -1 2.87263e-6 0 -1 -2.13814e-6 0 -1 -1.74896e-5 0 -1 1.2394e-6 0 -1 4.28036e-6 0 -1 -2.12903e-6 0 -1 1.10226e-6 0 -1 -3.43131e-6 0 -1 1.11708e-6 0 -1 -2.27945e-7 0 -1 -6.06159e-7 0 -1 -2.32056e-7 0 -1 1.01512e-6 0 -1 -3.0493e-6 0 -1 2.88412e-6 0 -1 -3.25451e-6 0 -1 7.05164e-6 0 -1 1.31898e-6 0 -1 -1.32214e-6 0 -1 -3.18866e-6 0 -1 -4.76934e-7 0 -1 5.49294e-7 0 -1 3.15342e-6 0 -1 2.84855e-6 0 -1 1.0773e-5 0 -1 -1.44023e-5 0 -1 -2.98047e-6 0 -1 -4.17629e-6 0 -1 -3.40085e-7 0 -1 5.0104e-7 0 -1 -4.10626e-7 0 -1 -3.79338e-7 0 -1 1.02872e-6 0 -1 -4.47246e-7 0 -1 -3.72058e-7 0 -1 -1.29343e-7 0 -1 -8.8285e-7 0 -1 0.4999977 0.8660267 0 0.4999952 0.8660282 0 0.5000001 0.8660255 0 0.5000004 0.8660253 0 -4.39433e-6 0 1 0 0 1 2.57043e-5 0 1 -9.94674e-5 0 1 -7.83053e-7 0 1 1.70996e-6 0 1 -7.96978e-6 0 1 2.2833e-6 0 1 -7.61162e-7 0 1 -4.20274e-6 0 1 -1.88123e-7 0 1 4.75242e-7 0 1 2.25625e-7 0 1 -7.18796e-7 0 1 -4.37747e-7 0 1 -1.69762e-6 0 1 -3.96328e-6 0 1 4.87702e-7 0 1 -1.55902e-6 0 1 -4.76887e-6 0 1 -5.42558e-6 0 1 1.57671e-6 0 1 1.55956e-6 0 1 2.77564e-7 0 1 1.44824e-6 0 1 9.20629e-7 0 1 6.07864e-7 0 1 -3.36037e-7 0 1 1.55627e-7 0 1 2.85386e-6 0 1 1.24291e-6 0 1 -9.1846e-7 0 1 -2.1205e-6 0 1 5.94519e-7 0 1 -1.28293e-6 0 1 1.26375e-6 0 1 -2.57043e-5 0 1 3.12278e-6 0 1 2.21923e-6 0 1 -4.7398e-6 0 1 2.90322e-6 0 1 -8.68113e-7 0 1 -6.48408e-7 0 1 4.31246e-7 0 1 -2.12019e-6 0 1 1.51442e-6 0 1 -1.99216e-6 0 1 -1.19915e-6 0 1 2.96037e-6 0 1 -3.33848e-7 0 1 6.89495e-7 0 1 -9.27283e-7 0 1 -1.67032e-6 0 1 -2.81557e-7 0 1 -1.42818e-7 0 1 8.27551e-7 0 1 -1.81031e-7 0 1 -4.16092e-7 0 1 4.96965e-7 0 1 -3.27455e-6 0 1 1.30042e-6 0 1 2.40242e-7 0 1 3.95627e-7 0 1 1.42818e-7 0 1 8.57883e-7 0 1 -5.28231e-7 0 1 -1.03352e-6 0 1 8.92503e-7 0 1 -1.31252e-6 0 1 5.92527e-7 0 1 6.3897e-6 0 1 3.31891e-6 0 1 5.52213e-6 0 1 2.95542e-6 0 1 -3.06956e-7 0 1 3.06958e-7 0 1 -1.47771e-6 0 1 -1.1842e-5 0 1 -1.57282e-6 0 1 7.40111e-6 0 1 -6.99266e-6 0 1 4.163e-6 0 1 6.99266e-6 0 1 4.77188e-6 0 1 -4.41782e-6 0 1 -4.36873e-7 0 1 1.28291e-6 0 1 -1.82575e-6 0 1 -4.03013e-6 0 1 4.73514e-6 0 1 -3.5672e-6 0 1 -4.78346e-6 0 1 4.7884e-6 0 1 2.69927e-6 0 1 -4.09384e-7 0 1 1.98049e-5 0 1 0 0 1 1.22309e-5 0 1 1.35917e-7 0 1 -2.66479e-6 0 1 -5.20638e-6 0 1 1.44927e-7 0 1 0 0 1 -2.03226e-6 0 1 6.04244e-6 0 1 -3.40094e-6 0 1 1.39559e-6 0 1 -1.33237e-6 0 1 1.3324e-6 0 1 -1.45964e-5 0 1 6.03588e-7 0 1 1.44716e-6 0 1 0 0 1 -4.27064e-7 0 1 6.89944e-7 0 1 3.22551e-7 0 1 1.57702e-7 0 1 -1.04161e-6 0 1 -9.29774e-7 0 1 1.20697e-5 0 1 2.15525e-6 0 1 -6.39787e-7 0 1 1.69393e-7 0 1 -1.3324e-6 0 1 1.33237e-6 0 1 -2.79114e-6 0 1 -8.92042e-7 0 1 7.94115e-7 0 1 -2.15622e-6 0 1 3.89854e-7 0 1 -1.69785e-7 0 1 2.13786e-7 0 1 -1.60028e-6 0 1 4.48258e-7 0 1 1.60714e-6 0 1 -4.41107e-7 0 1 6.06327e-6 0 1 -8.90583e-6 0 1 -3.30993e-7 0 1 5.61205e-6 0 1 -3.89669e-7 0 1 2.68409e-6 0 1 -7.19199e-6 0 1 4.70334e-6 0 1 2.00349e-7 0 1 -2.3104e-6 0 1 4.34324e-6 0 1 -4.66035e-6 0 1 0 0 1 1.23318e-7 0 1 -2.39738e-7 0 1 5.42398e-7 0 1 -1.19224e-7 0 1 -4.85438e-6 0 1 -5.67382e-6 0 1 2.26764e-6 0 1 4.42877e-6 0 1 -4.26393e-6 0 1 1.09718e-5 0 1 -5.00045e-6 0 1 -2.68242e-5 0 1 -4.64289e-6 0 1 -5.92091e-6 0 1 7.71003e-7 0 1 3.06956e-7 0 1 -1.47771e-6 0 1 -5.63273e-7 0 1 1.3196e-6 0 1 1.21832e-6 0 1 1.05496e-5 0 1 -5.97714e-6 0 1 -4.72143e-7 0 1 2.66539e-6 0 1 1.25936e-6 0 1 -4.41774e-6 0 1 0 0 1 8.20455e-7 0 1 -8.57883e-7 0 1 1.58036e-6 0 1 1.7188e-5 0 1 0 0 1 -1.23663e-6 0 1 -7.60861e-7 0 1 1.09438e-6 0 1 1.34464e-7 0 1 3.7578e-7 0 1 2.3274e-7 0 1 4.06104e-7 0 1 -1.06756e-5 0 1 -1.7188e-5 0 1 -2.30398e-6 0 1 -2.58564e-6 0 1 3.29987e-6 0 1 -6.86543e-6 0 1 -5.65234e-6 0 1 3.57041e-6 0 1 -2.35055e-6 0 1 1.28561e-6 0 1 1.31898e-6 0 1 -3.31332e-6 0 1 -2.12903e-6 0 1 1.10226e-6 0 1 -1.02244e-6 0 1 1.95998e-6 0 1 -1.14409e-5 0 1 -2.57637e-7 0 1 -1.6958e-7 0 1 4.66906e-7 0 1 8.5926e-7 0 1 7.28838e-7 0 1 -1.26831e-5 0 1 1.37256e-5 0 1 -5.44241e-6 0 1 4.33081e-6 0 1 -5.00691e-6 0 1 6.03377e-6 0 1 1.5563e-5 0 1 0 0 1 -3.96071e-7 0 1 -2.43155e-7 0 1 5.67154e-6 0 1 1.01312e-6 0 1 -8.87343e-7 0 1 5.11715e-6 0 1 9.30347e-6 0 1 -4.77108e-6 0 1 7.09119e-6 0 1 1.14546e-6 0 1 -1.07727e-6 0 1 -4.20554e-7 0 1 2.61734e-7 0 1 -8.94493e-7 0 1 -1.44935e-6 0 1 1.85876e-6 0 1 -4.13058e-7 0 1 -4.05082e-7 0 1 -4.13059e-7 0 1 4.13058e-7 0 1 -1.33416e-6 0 1 -1.02872e-6 0 1 2.68345e-6 0 1 8.94493e-7 0 1 -1.02024e-6 0 1 3.93415e-7 0 1 -3.18023e-7 0 1 1.69579e-7 0 1 -6.98792e-6 0 1 -1.20602e-6 0 1 2.03598e-6 0 1 -4.16436e-7 0 1 3.78487e-7 0 1 4.54159e-7 0 1 3.49858e-7 0 1 9.1539e-6 0 1 -3.29987e-6 0 1 7.62105e-7 0 1 6.80993e-7 0 1 3.80107e-6 0 1 1.52144e-6 0 1 -4.39431e-6 0 1 1.99217e-6 0 1 2.39831e-6 0 1 1.26447e-6 0 1 -8.09219e-6 0 1 1.67032e-6 0 1 -1.30042e-6 0 1 3.27455e-6 0 1 0 0 1 -4.82539e-6 0 1 -3.93943e-7 0 1 -6.33505e-7 0 1 1.87899e-6 0 1 -3.34594e-6 0 1 1.28293e-6 0 1 2.29975e-6 0 1 -2.90322e-6 0 1 -1.20649e-6 0 1 1.32666e-6 0 1 -1.06137e-6 0 1 1.16352e-6 0 1 -3.12278e-6 0 1 1.35694e-6 0 1 -3.6327e-7 0 1 1.67584e-6 0 1 -7.71224e-7 0 1 2.1205e-6 0 1 2.86479e-6 0 1 -1.24257e-6 0 1 1.02824e-6 0 1 1.70803e-7 0 1 -3.02493e-6 0 1 1.28081e-7 0 1 -1.92906e-6 0 1 1.85192e-6 0 1 7.38614e-7 0 1 -4.32191e-7 0 1 1.78404e-7 0 1 1.80492e-6 0 1 -1.0214e-6 0 1 3.98489e-6 0 1 1.11584e-6 0 1 3.43768e-7 0 1 -5.77239e-7 0 1 -3.05252e-7 0 1 -3.41993e-6 0 1 1.35796e-5 0 1 7.61162e-7 0 1 -1.57671e-6 0 1 -1.14165e-6 0 1 6.35849e-6 0 1 -1.02777e-6 0 1 -4.83965e-6 0 1 3.96328e-6 0 1 1.43631e-6 0 1 -6.51624e-6 0 1 1.69762e-6 0 1 -6.54752e-5 0 1 -6.55153e-5 0 1 -6.54249e-5 0 1 1.51247e-6 0 1 -5.38649e-6 0 1 -1.53323e-6 0 1 1.83117e-6 0 1 -2.23484e-5 0 1 -7.20113e-6 0 1 1.43533e-6 0 1 -1.51442e-6 0 1 1.66922e-6 0 1 -4.5589e-7 0 1 -7.62326e-7 0 1 2.00467e-6 0 1 6.197e-7 0 1 6.09376e-7 0 1 -2.63794e-6 0 1 -2.57121e-6 0 1 2.35055e-6 0 1 1.84367e-6 0 1 3.81545e-6 0 1 -1.25957e-6 0 1 2.56202e-7 0 1 -1.90868e-6 0 1 1.32214e-6 0 1 -1.09941e-6 0 1 1.57899e-6 0 1 -2.20173e-6 0 1 -0.6701796 -0.742199 0 -0.6701797 -0.7421988 0 -0.670624 -0.7417976 0 -0.6706242 -0.7417973 0 -0.8613501 -0.5080119 0 -0.8613327 -0.5080416 0 -0.8613331 -0.5080408 0 -0.8613688 -0.50798 0 -0.8613826 -0.5079569 0 0.7421805 -0.6702001 0 0.7421823 -0.6701981 0 0.419853 -0.9075921 0 0.4198529 -0.9075923 0 0.02646881 -0.9996497 0 0.02646869 -0.9996497 0 -0.3704937 -0.928835 0 -0.3704918 -0.9288358 0 0.8628522 -0.5054565 0 0.8627761 -0.5055863 0 0.8627765 -0.5055857 0 0.7185696 0.6954551 0 0.7185691 0.6954557 0 0.7185857 0.6954385 0 0.7185862 0.6954379 0 0.718105 0.6959348 0 0.7181062 0.6959336 0 -0.2592201 -0.9658183 0 -0.2592195 -0.9658185 0 -0.7069132 -0.7073004 0 -0.7069123 -0.7073012 0 -0.9659134 -0.2588658 0 -0.9659133 -0.258866 0 -0.9659146 0.2588612 0 -0.9659145 0.2588614 0 -0.7069216 0.7072919 0 -0.7069225 0.7072911 0 -0.2592024 0.9658231 0 -0.2592027 0.9658231 0 0.2592028 0.9658229 0 0.2592018 0.9658232 0 0.7068977 0.7073158 0 0.9659265 0.2588165 0 0.9659269 0.2588152 0 0.9659257 -0.2588196 0 0.9659252 -0.2588214 0 0.7068884 -0.7073251 0 0.2592193 -0.9658186 0 0.25922 -0.9658184 0 -0.7073631 0.7068505 0 -0.7073632 0.7068503 0 -0.7068586 0.7073549 0 -0.7071556 0.707058 0 -0.7070215 0.707192 0 -0.707022 0.7071916 0 0.6285851 -0.7777408 0 0.6285849 -0.7777411 0 0.6290088 -0.7773983 0 0.6290091 -0.7773981 0 0.7775608 -0.6288077 0 0.777561 -0.6288075 0 0.7776544 -0.6286922 0 0.2592023 0.9658231 0 0.7069225 0.7072911 0 0.7069216 0.7072919 0 0.9659146 0.2588612 0 0.9659145 0.2588614 0 0.9659134 -0.2588658 0 0.9659133 -0.258866 0 0.7069123 -0.7073012 0 0.7069132 -0.7073004 0 0.2592197 -0.9658184 0 -0.2592191 -0.9658186 0 -0.7068884 -0.7073251 0 -0.9659253 -0.2588212 0 -0.9659256 -0.2588199 0 -0.965927 0.2588151 0 -0.9659265 0.2588168 0 -0.7068977 0.7073158 0 -0.259202 0.9658232 0 -0.7181062 0.6959336 0 -0.718105 0.6959348 0 -0.7185862 0.695438 0 -0.7185858 0.6954384 0 -0.7185691 0.6954557 0 -0.7185696 0.6954551 0 0.6702416 -0.742143 0 0.8613826 -0.5079569 0 0.8613688 -0.50798 0 0.8613392 -0.5080305 0 0.8613394 -0.5080301 0 0.6702419 -0.7421427 0 0.3704922 -0.9288356 0 0.3704934 -0.9288352 0 -0.02646869 -0.9996497 0 -0.02646881 -0.9996497 0 -0.419853 -0.9075921 0 -0.4198529 -0.9075923 0 -0.7421827 -0.6701977 0 -0.7421801 -0.6702005 0 -0.8627765 -0.5055857 0 -0.8627761 -0.5055863 0 -0.8628522 -0.5054565 0 0.7071278 0.7070859 0 0.7071275 0.7070861 0 0.7070215 0.707192 0 0.707022 0.7071916 0 -0.7776544 -0.6286922 0 -0.7775608 -0.6288077 0 -0.777561 -0.6288075 0 -0.6290088 -0.7773983 0 -0.6290091 -0.7773981 0 -0.6285851 -0.7777408 0 -0.6285849 -0.7777411 0 -0.2587089 0.9659554 0 0.2587089 0.9659554 0 0.2586198 0.9659793 0 0.2586199 0.9659793 0 0.2624969 0.9649329 0 0.2624957 0.9649332 0 0.7070735 0.7071402 0 0.7070735 0.70714 0 0.7075747 0.7066386 0 0.7075699 0.7066434 0 0.7069999 0.7072136 0 0.7070001 0.7072136 0 0.9659135 0.2588653 0 0.9659581 0.258699 0 0.9659584 0.258698 0 0.9659556 -0.2587081 0 0.9659554 -0.2587087 0 0.965914 -0.2588633 0 0.965914 -0.2588632 0 0.7069999 -0.7072136 0 0.7070001 -0.7072136 0 0.7076251 -0.7065881 0 0.7076302 -0.706583 0 0.7070692 -0.7071444 0 0.7070695 -0.7071441 0 0.2623885 -0.9649624 0 0.2623898 -0.964962 0 0.2586341 -0.9659754 0 0.2586342 -0.9659754 0 0.2587089 -0.9659554 0 -0.2587089 -0.9659554 0 -0.2590766 -0.9658568 0 -0.2590765 -0.9658568 0 -0.7070692 -0.7071443 0 -0.7070695 -0.7071442 0 -0.7071083 -0.7071053 0 -0.7071084 -0.7071052 0 -0.965914 -0.2588633 0 -0.965914 -0.2588632 0 -0.9659554 -0.258709 0 -0.9659557 -0.2587079 0 -0.9659582 0.2586982 0 -0.9659581 0.2586988 0 -0.9659135 0.2588653 0 -0.7070987 0.7071149 0 -0.7070989 0.7071148 0 -0.7070733 0.7071402 0 -0.7070736 0.70714 0 -0.2590766 0.9658568 0 -0.2590765 0.9658568 0 0.8314065 -0.5556646 0 0.9805756 -0.1961422 0 0.9805881 -0.1960791 0 0.9808087 -0.1949726 0 0.9808097 -0.1949679 0 0.8314054 -0.5556663 0 0.7071042 -0.7071095 0 0.7071043 -0.7071093 0 0.7045564 -0.709648 0 0.7045901 -0.7096146 0 0.7071889 -0.7070247 0 0.7071897 -0.7070239 0 0.7071194 -0.7070942 0 0.7071197 -0.7070939 0 0.7067946 -0.7074189 0 0.7067947 -0.7074188 0 0.5553848 -0.8315936 0 0.1977305 -0.9802565 0 0.1977273 -0.980257 0 0.1954591 -0.9807119 0 0.1954588 -0.980712 0 0.5553844 -0.8315937 0 -0.5553849 -0.8315934 0 -0.1977305 -0.9802565 0 -0.1977273 -0.980257 0 -0.1954592 -0.9807119 0 -0.1954587 -0.980712 0 -0.5553842 -0.8315939 0 -0.7070834 -0.7071302 0 -0.7070835 -0.7071301 0 -0.7071072 -0.7071064 0 -0.8314064 -0.5556647 0 -0.9805755 -0.1961423 0 -0.9805882 -0.196079 0 -0.9808088 -0.1949726 0 -0.9808097 -0.194968 0 -0.8314056 -0.5556662 0 -0.9769152 0.2136272 0 -0.9769158 0.2136251 0 -0.5698024 0.8217818 0 -0.5698021 0.8217821 0 -0.7309467 0.6824347 0 -0.7309464 0.682435 0 -0.858961 0.5120411 0 -0.8589607 0.5120416 0 -0.9882984 0.1525334 0 -0.9882984 0.1525334 0 -0.8674688 0.4974917 0 -0.8674682 0.4974926 0 -0.6314434 0.775422 0 -0.6314428 0.7754225 0 -0.9995357 -0.03046798 0 -0.9995358 -0.03046798 0 -0.9995357 -0.03046822 0 -0.9995358 -0.03046828 0 -0.9995357 -0.03046882 0 -0.9995357 -0.03046882 0 -0.9995358 -0.03046488 0 -0.9995359 -0.03046476 0 -0.9575974 -0.2881099 0 -0.9575974 -0.2881101 0 -0.850393 -0.526148 0 -0.8503397 -0.5262343 0 -0.8503393 -0.5262349 0 -0.5000005 0.8660251 0 0.4999908 0.8660307 0 0.4999897 0.8660314 0 0.4999879 0.8660324 0 0.4999882 0.8660323 0 0.5000067 0.8660216 0 0.5000069 0.8660215 0 0.850381 -0.5261676 0 0.85038 -0.526169 0 0.8504589 -0.5260416 0 0.8504588 -0.5260418 0 0.8503708 -0.526184 0 0.8503707 -0.5261842 0 0.8502964 -0.5263043 0 0.8502972 -0.5263028 0 0.9575974 -0.2881099 0 0.9575974 -0.2881101 0 0.9995358 -0.03046798 0 0.9995357 -0.03046798 0 0.9995358 -0.03046822 0 0.9995357 -0.03046828 0 0.9995357 -0.03046882 0 0.9995357 -0.03046882 0 0.9995359 -0.03046494 0 0.9995359 -0.03046476 0 0.6314428 0.7754225 0 0.6314434 0.775422 0 0.8674682 0.4974926 0 0.8674688 0.4974917 0 0.9882984 0.1525334 0 0.9882984 0.1525334 0 0.858992 0.5119892 0 0.858992 0.511989 0 0.8589246 0.5121023 0 0.8589252 0.5121011 0 0.7310388 0.682336 0 0.730676 0.6827244 0 0.570296 0.8214393 0 0.5696801 0.8218666 0 0.5696805 0.8218664 0 0.9769158 0.2136253 0 0.9769154 0.213627 0 -0.2584257 0.9660311 0 0.2584262 0.966031 0 0.2584257 0.9660311 0 0.7073257 0.7068878 0 0.7073263 0.7068872 0 0.9659264 0.2588174 0 0.965927 0.2588146 0 0.9659223 -0.2588323 0 0.9659214 -0.2588355 0 0.7073445 -0.7068691 0 0.7073435 -0.70687 0 0.2584258 -0.9660311 0 0.2584261 -0.9660311 0 -0.2584258 -0.9660311 0 -0.2584261 -0.9660311 0 -0.7073445 -0.7068691 0 -0.7073435 -0.70687 0 -0.9659219 -0.2588338 0 -0.9659222 -0.2588326 0 -0.9659271 0.2588144 0 -0.9659267 0.2588161 0 -0.7073257 0.7068878 0 -0.7073263 0.7068872 0 -0.2584262 0.966031 0 3.7794e-6 0 1 7.55344e-6 0 1 -1.80944e-6 0 1 7.7554e-7 0 1 -1.84633e-6 0 1 -3.93479e-6 0 1 -1.76199e-6 0 1 6.07156e-7 0 1 5.93725e-6 0 1 -2.16999e-6 0 1 -3.47869e-7 0 1 7.67573e-7 0 1 -4.77902e-6 0 1 7.11764e-6 0 1 -1.89611e-5 0 1 8.01282e-7 0 1 -4.48466e-7 0 1 -7.0988e-7 0 1 2.32877e-6 0 1 3.09644e-6 0 1 -1.76772e-6 0 1 6.64865e-7 0 1 -4.52014e-6 0 1 -1.81372e-6 0 1 5.81864e-6 0 1 2.84589e-6 0 1 -1.53042e-7 0 1 1.1517e-6 0 1 4.09774e-6 0 1 -2.08075e-7 0 1 -1.13496e-6 0 1 -5.13471e-7 0 1 9.51321e-6 0 1 -1.38115e-6 0 1 -6.49854e-6 0 1 -1.9886e-5 0 1 4.30424e-6 0 1 1.86994e-6 0 1 -5.41379e-7 0 1 -2.96861e-6 0 1 1.15968e-6 0 1 -6.47179e-7 0 1 2.33919e-6 0 1 -7.33568e-7 0 1 9.29327e-7 0 1 1.46878e-5 0 1 2.66025e-6 0 1 -5.38654e-6 0 1 8.66131e-6 0 1 -1.4937e-6 0 1 -2.84589e-6 0 1 2.73638e-7 0 1 -7.76179e-7 0 1 1.03509e-6 0 1 -5.29679e-7 0 1 -5.02755e-7 0 1 5.17573e-7 0 1 1.23986e-5 0 1 -8.1817e-6 0 1 1.30358e-5 0 1 -7.80049e-6 0 1 -2.3008e-6 0 1 3.0079e-5 0 1 4.10583e-6 0 1 6.03865e-6 0 1 -2.93979e-6 0 1 1.98951e-6 0 1 -2.24099e-6 0 1 2.06092e-5 0 1 -2.11291e-6 0 1 2.11291e-6 0 1 -6.5786e-6 0 1 1.64467e-6 0 1 -7.67955e-7 0 1 1.54233e-6 0 1 -5.70006e-7 0 1 -2.1384e-5 0 1 7.12803e-7 0 1 5.69985e-7 0 1 -5.69985e-7 0 1 8.50201e-7 0 1 -2.06092e-5 0 1 4.01994e-6 0 1 -2.00997e-6 0 1 -2.73121e-6 0 1 9.05835e-6 0 1 2.59616e-6 0 1 -1.4005e-6 0 1 6.56153e-6 0 1 -4.83994e-6 0 1 4.42127e-7 0 1 1.93378e-7 0 1 0 0 1 1.38115e-6 0 1 1.38114e-6 0 1 1.13496e-6 0 1 -1.06663e-6 0 1 9.2846e-7 0 1 -1.4775e-6 0 1 -1.18137e-6 0 1 -2.26992e-6 0 1 2.52288e-6 0 1 1.63883e-5 0 1 -1.45675e-6 0 1 1.58802e-6 0 1 -4.42127e-7 0 1 3.12188e-6 0 1 7.71538e-7 0 1 4.3592e-6 0 1 -1.03267e-5 0 1 1.90776e-6 0 1 1.26733e-5 0 1 -1.58642e-4 0 1 -2.05062e-6 0 1 1.58535e-4 0 1 1.52449e-5 0 1 8.40531e-7 0 1 -1.94614e-6 0 1 1.58355e-6 0 1 -5.48744e-6 0 1 3.25741e-6 0 1 -3.23558e-5 0 1 1.65218e-5 0 1 1.77673e-4 0 1 1.77672e-4 0 1 1.7767e-4 0 1 1.22594e-5 0 1 -1.52449e-5 0 1 2.14491e-5 0 1 -5.27961e-6 0 1 -1.25233e-6 0 1 1.94775e-6 0 1 7.10434e-6 0 1 8.60477e-6 0 1 -7.61513e-6 0 1 -7.61522e-6 0 1 -7.6151e-6 0 1 -2.69201e-7 0 1 -4.07987e-6 0 1 -1.52702e-5 0 1 7.48834e-6 0 1 3.97547e-6 0 1 4.10164e-6 0 1 -8.38403e-6 0 1 -3.61664e-7 0 1 -2.50041e-6 0 1 7.49374e-6 0 1 -2.36897e-5 0 1 1.20913e-4 0 1 -4.90467e-6 0 1 -1.52386e-6 0 1 -4.03367e-7 0 1 3.14112e-5 0 1 1.16355e-6 0 1 -6.18772e-6 0 1 1.28277e-6 0 1 3.84282e-6 0 1 -1.37508e-6 0 1 4.77938e-6 0 1 -9.99696e-7 0 1 6.08747e-6 0 1 -1.99942e-6 0 1 1.11204e-6 0 1 3.88054e-6 0 1 1.59138e-6 0 1 -7.33794e-7 0 1 -3.66907e-7 0 1 3.97823e-7 0 1 -1.53515e-6 0 1 2.28144e-6 0 1 1.97813e-6 0 1 -7.3635e-5 0 1 -7.36348e-5 0 1 -7.36346e-5 0 1 -3.97446e-6 0 1 -1.22594e-5 0 1 -4.27893e-6 0 1 -3.90863e-7 0 1 -1.05574e-6 0 1 1.01065e-5 0 1 -4.13873e-6 0 1 -1.4106e-6 0 1 1.58642e-4 0 1 1.48262e-6 0 1 3.44577e-5 0 1 -3.84282e-6 0 1 3.78528e-6 0 1 -1.13046e-6 0 1 -2.85248e-5 0 1 3.99962e-7 0 1 2.05062e-6 0 1 7.61519e-6 0 1 7.6151e-6 0 1 7.61513e-6 0 1 -5.7723e-6 0 1 5.51903e-6 0 1 -3.78881e-6 0 1 -3.86234e-6 0 1 -4.4752e-7 0 1 4.4128e-7 0 1 1.56054e-6 0 1 -1.46878e-5 0 1 7.3635e-5 0 1 7.36345e-5 0 1 7.36348e-5 0 1 6.5786e-6 0 1 -4.37512e-5 0 1 -2.48316e-6 0 1 1.20808e-6 0 1 -1.11204e-6 0 1 3.99885e-6 0 1 -3.04375e-6 0 1 -1.52188e-6 0 1 9.99696e-7 0 1 0.2583925 0.96604 0 0.7073355 0.706878 0 0.7073345 0.706879 0 0.9659255 0.2588204 0 0.9659258 0.2588191 0 0.9659247 -0.2588233 0 0.9659243 -0.2588251 0 0.7073257 -0.7068878 0 0.7073263 -0.7068872 0 0.2584262 -0.966031 0 0.2584257 -0.9660311 0 -0.2552981 -0.9668624 0 -0.2552993 -0.9668621 0 -0.2598447 -0.9656504 0 -0.7073257 -0.7068878 0 -0.7073263 -0.7068872 0 -0.9659239 -0.2588264 0 -0.9659246 -0.2588236 0 -0.9659259 0.2588189 0 -0.965925 0.258822 0 -0.7073355 0.706878 0 -0.7073345 0.706879 0 -0.2598447 0.9656504 0 -0.2551916 0.9668905 0 -0.2551904 0.9668908 0 0.2583923 0.9660401 0 3.70829e-6 0 -1 1.18308e-6 0 -1 4.16486e-6 0 -1 9.68017e-6 0 -1 -1.76199e-6 0 -1 6.35809e-7 0 -1 -1.84633e-6 0 -1 7.7554e-7 0 -1 -6.65846e-7 0 -1 -2.15131e-6 0 -1 -2.33538e-6 0 -1 3.79455e-6 0 -1 -1.7922e-6 0 -1 1.93599e-5 0 -1 7.01617e-6 0 -1 -1.93955e-6 0 -1 3.13926e-6 0 -1 2.53467e-7 0 -1 6.64865e-7 0 -1 -1.98845e-5 0 -1 -4.54539e-6 0 -1 1.00731e-5 0 -1 3.80124e-6 0 -1 -4.74315e-7 0 -1 2.28881e-6 0 -1 -2.68592e-6 0 -1 1.13496e-6 0 -1 -2.76231e-6 0 -1 1.13496e-6 0 -1 -2.52602e-7 0 -1 2.08075e-7 0 -1 -4.09774e-6 0 -1 -3.24927e-6 0 -1 5.1214e-6 0 -1 -2.04888e-6 0 -1 1.7922e-6 0 -1 -3.32031e-6 0 -1 5.11968e-7 0 -1 -1.55029e-6 0 -1 1.55946e-6 0 -1 1.36204e-6 0 -1 3.26845e-7 0 -1 -7.65111e-6 0 -1 -4.98934e-7 0 -1 -2.47268e-5 0 -1 3.47869e-7 0 -1 -1.89611e-5 0 -1 8.99067e-7 0 -1 8.28001e-6 0 -1 -1.00619e-5 0 -1 4.10457e-7 0 -1 -1.60255e-6 0 -1 5.17543e-7 0 -1 -3.32521e-7 0 -1 1.79244e-6 0 -1 -2.18287e-6 0 -1 -8.34223e-7 0 -1 -3.24799e-6 0 -1 -7.80031e-6 0 -1 4.57272e-6 0 -1 3.01932e-6 0 -1 1.12406e-5 0 -1 -6.84011e-7 0 -1 1.02646e-6 0 -1 -1.05646e-6 0 -1 1.05646e-6 0 -1 8.22325e-7 0 -1 -3.83977e-7 0 -1 -5.70006e-7 0 -1 5.70006e-7 0 -1 -2.12571e-7 0 -1 6.34837e-6 0 -1 -3.56402e-7 0 -1 1.62729e-6 0 -1 1.6272e-6 0 -1 -5.1523e-6 0 -1 5.69985e-7 0 -1 -5.69985e-7 0 -1 1.31101e-6 0 -1 5.1523e-6 0 -1 -1.29808e-6 0 -1 7.00249e-7 0 -1 1.45831e-7 0 -1 -1.41885e-7 0 -1 3.78132e-6 0 -1 -1.13496e-6 0 -1 2.56736e-7 0 -1 -2.3783e-6 0 -1 1.72644e-6 0 -1 -2.73236e-6 0 -1 1.18137e-6 0 -1 2.46082e-6 0 -1 -4.6423e-7 0 -1 -7.08598e-7 0 -1 1.63189e-6 0 -1 -1.93378e-7 0 -1 -2.0996e-7 0 -1 4.42127e-7 0 -1 -4.82432e-7 0 -1 -1.94498e-6 0 -1 4.16223e-6 0 -1 -3.96598e-5 0 -1 -8.55786e-6 0 -1 7.56315e-6 0 -1 1.43338e-7 0 -1 -3.31474e-6 0 -1 -4.14772e-6 0 -1 -7.79107e-6 0 -1 4.82991e-6 0 -1 -1.53989e-6 0 -1 2.70625e-6 0 -1 -1.90774e-6 0 -1 3.96346e-5 0 -1 2.85842e-6 0 -1 6.12968e-6 0 -1 3.44729e-6 0 -1 -1.65218e-6 0 -1 1.61424e-6 0 -1 2.98084e-6 0 -1 1.65467e-6 0 -1 -1.52741e-5 0 -1 -1.34601e-6 0 -1 2.35884e-4 0 -1 5.47577e-6 0 -1 -5.3048e-6 0 -1 3.64069e-6 0 -1 -2.35081e-6 0 -1 -1.89659e-6 0 -1 8.75013e-6 0 -1 -4.27185e-6 0 -1 -1.66694e-6 0 -1 1.22699e-6 0 -1 1.16355e-6 0 -1 3.95366e-6 0 -1 -1.53855e-6 0 -1 -6.93965e-6 0 -1 1.06217e-6 0 -1 -9.81601e-7 0 -1 -6.59604e-7 0 -1 1.0056e-6 0 -1 6.0404e-7 0 -1 -2.55843e-6 0 -1 1.52188e-6 0 -1 3.04375e-6 0 -1 -1.02336e-5 0 -1 1.81212e-6 0 -1 -1.66809e-6 0 -1 -3.25453e-6 0 -1 -8.22336e-7 0 -1 -6.12968e-6 0 -1 -2.85842e-6 0 -1 -7.56317e-6 0 -1 4.27893e-6 0 -1 6.53955e-7 0 -1 -2.28571e-6 0 -1 2.17467e-6 0 -1 -8.84255e-7 0 -1 2.81187e-7 0 -1 5.1857e-7 0 -1 -1.41307e-6 0 -1 1.43579e-6 0 -1 -1.41578e-6 0 -1 -1.92939e-6 0 -1 -3.55218e-6 0 -1 5.3048e-6 0 -1 -5.47577e-6 0 -1 -2.35884e-4 0 -1 1.34601e-6 0 -1 -1.11425e-6 0 -1 7.80269e-7 0 -1 3.41299e-6 0 -1 -4.54658e-6 0 -1 1.33323e-6 0 -1 -1.36226e-7 0 -1 5.89084e-7 0 -1 2.76509e-4 0 -1 1.66809e-6 0 -1 -3.43762e-7 0 -1 5.5602e-7 0 -1 -3.04375e-6 0 -1 -1.52188e-6 0 -1 -9.99696e-7 0 -1 -1.3752e-6 0 -1 3.97823e-7 0 -1 2.06097e-7 0 -1 -1.47853e-6 0 -1 7.33794e-7 0 -1 0.2964594 0.9550455 0 0.296458 0.9550459 0 -0.1527279 0.9882684 0 -0.1527268 0.9882686 0 -0.5622403 0.8269739 0 -0.5622389 0.8269748 0 -0.8663531 0.4994322 0 -0.8663522 0.4994336 0 -0.9972064 0.07469671 0 -0.9306104 -0.3660115 0 -0.9306107 -0.3660107 0 -0.6800453 -0.7331702 0 -0.680043 -0.7331722 0 0.707085 -0.7071286 0 0.7070829 -0.7071308 0 0.9659255 -0.2588203 0 0.9659253 -0.258821 0 0.9659273 0.2588137 0 0.7070696 0.707144 0 0.7070689 0.7071447 0 0.2588765 0.9659105 0 0.2588759 0.9659106 0 -0.2588765 0.9659105 0 -0.2588759 0.9659106 0 0.8660302 -0.4999917 0 0.8660278 -0.4999958 0 0.8660081 -0.5000301 0 0.8660073 -0.5000313 0 0.8660315 -0.4999895 0 0.8660293 -0.4999932 0 0.8808748 0.4733495 0 0.8808673 0.4733634 0 0.8808597 0.4733775 0 0.880858 0.4733809 0 0.880858 0.4733806 0 0.880858 0.4733808 0 0.5000244 0.8660113 0 0.5000287 0.8660089 0 0.499996 0.8660277 0 0.4999935 0.8660292 0 -0.5000316 0.8660072 0 -0.5000278 0.8660094 0 -0.4999095 0.8660776 0 -0.4999125 0.8660759 0 -0.4999984 0.8660263 0 -0.4999976 0.8660269 0 -0.8660269 0.4999974 0 -0.8660324 0.4999879 0 -0.8660315 0.4999895 0 -0.8660276 0.4999963 0 -0.8660265 0.4999982 0 -0.4999997 0.8660257 0 -0.499999 0.866026 0 -0.499997 0.8660271 0 -0.5000003 0.8660253 0 -0.500001 0.8660249 0 -0.5000036 0.8660234 0 -0.5000041 0.8660231 0 -0.4999994 0.8660258 0 -0.5000018 0.8660244 0 -0.4999923 0.8660299 0 -0.4999921 0.86603 0 -0.500002 0.8660243 0 0.499999 0.8660261 0 0.4999997 0.8660256 0 0.499997 0.8660271 0 0.4999958 0.8660278 0 0.5000011 0.8660248 0 0.5000002 0.8660253 0 0.5000032 0.8660236 0 0.5000017 0.8660245 0 0.4999936 0.8660291 0 0.4999908 0.8660308 0 0.5000031 0.8660236 0 0.8660276 0.4999963 0 0.8660265 0.4999982 0 0.8660324 0.4999879 0 0.8660315 0.4999895 0 0.8660269 0.4999974 0 0.4999984 0.8660263 0 0.4999976 0.8660269 0 0.4999148 0.8660746 0 0.4999073 0.866079 0 0.50003 0.8660081 0 0.5000295 0.8660084 0 -0.500003 0.8660237 0 -0.5000022 0.8660241 0 -0.8808588 0.4733791 0 -0.8808572 0.4733823 0 -0.8808583 0.4733802 0 -0.8808594 0.4733783 0 -0.8808681 0.4733617 0 -0.8808739 0.4733511 0 -0.8660305 -0.4999912 0 -0.8660303 -0.4999915 0 -0.8660081 -0.5000301 0 -0.8660073 -0.5000313 0 -0.8660284 -0.4999949 0 -0.8660296 -0.4999927 0 -0.03047442 -0.9995356 0 -0.03047442 -0.9995356 0 -0.03046685 -0.9995359 0 -0.03046679 -0.9995359 0 -0.03040856 -0.9995375 0 -0.03040891 -0.9995375 0 -0.03048449 -0.9995353 0 -0.03048437 -0.9995353 0 -0.4999849 -0.8660342 0 -0.4999823 -0.8660357 0 -0.4999974 -0.8660269 0 -0.4999942 -0.8660288 0 -0.5000058 -0.8660221 0 -0.4999987 -0.8660262 0 -0.4999977 -0.8660267 0 -0.5000118 -0.8660187 0 -0.4999986 -0.8660263 0 -0.4999994 -0.8660258 0 -0.4999979 -0.8660266 0 -0.4999999 -0.8660256 0 -0.8503925 -0.526149 0 -0.8503918 -0.5261501 0 -0.8503469 -0.5262225 0 -0.8503491 -0.5262192 0 -0.8503895 -0.5261538 0 -0.8503882 -0.5261558 0 0.8503895 -0.5261538 0 0.8503882 -0.5261558 0 0.85035 -0.5262177 0 0.850346 -0.5262241 0 0.8503925 -0.526149 0 0.8503918 -0.5261501 0 0.4999997 0.8660256 0 0.4999988 0.8660262 0 0.4999928 0.8660296 0 0.4999887 0.8660319 0 -0.5000013 -0.8660247 0 -0.4999996 -0.8660257 0 -0.5000001 -0.8660253 0 -0.8660262 -0.4999988 0 -0.8660262 -0.4999986 0 0.5000013 -0.8660247 0 0.5000014 -0.8660246 0 0.5000002 -0.8660253 0 0.4999995 -0.8660258 0 8.24484e-6 0 -1 7.11327e-7 0 -1 -2.22568e-6 0 -1 7.0541e-7 0 -1 8.23205e-7 0 -1 3.20408e-6 0 -1 -4.00982e-6 0 -1 8.95342e-7 0 -1 -8.60073e-7 0 -1 -7.11331e-7 0 -1 2.22568e-6 0 -1 1.30952e-5 0 -1 -8.95342e-7 0 -1 8.98704e-7 0 -1 -1.57653e-6 0 -1 9.01908e-6 0 -1 -1.4953e-6 0 -1 -1.16892e-6 0 -1 1.62738e-6 0 -1 -6.21115e-7 0 -1 2.3269e-6 0 -1 1.96504e-6 0 -1 -1.96505e-6 0 -1 1.71985e-6 0 -1 -4.96761e-7 0 -1 1.20269e-6 0 -1 -3.7465e-6 0 -1 6.17906e-7 0 -1 -5.12101e-7 0 -1 3.31079e-6 0 -1 -8.80043e-7 0 -1 -6.45891e-7 0 -1 1.83452e-6 0 -1 -1.12083e-6 0 -1 1.53719e-6 0 -1 4.04948e-7 0 -1 6.73521e-7 0 -1 8.5437e-7 0 -1 -1.71899e-6 0 -1 4.95026e-7 0 -1 -6.97991e-7 0 -1 -6.65131e-7 0 -1 9.41895e-7 0 -1 -6.17906e-7 0 -1 7.14264e-6 0 -1 -4.04948e-7 0 -1 -4.76076e-7 0 -1 2.10469e-6 0 -1 -1.83452e-6 0 -1 2.58561e-7 0 -1 -2.4215e-6 0 -1 3.48413e-6 0 -1 -2.78687e-6 0 -1 2.95106e-7 0 -1 2.28095e-6 0 -1 -1.0745e-6 0 -1 9.32683e-7 0 -1 -6.98722e-7 0 -1 -6.38961e-6 0 -1 7.29425e-6 0 -1 3.93585e-6 0 -1 3.86394e-6 0 -1 -1.64278e-5 0 -1 1.28732e-5 0 -1 -1.44356e-5 0 -1 7.40737e-6 0 -1 -2.32948e-5 0 -1 7.64688e-6 0 -1 -3.62147e-6 0 -1 -2.33799e-5 0 -1 -3.58552e-7 0 -1 -7.64688e-6 0 -1 6.45698e-6 0 -1 1.93934e-5 0 -1 -2.2586e-6 0 -1 -3.12612e-6 0 -1 3.51977e-6 0 -1 5.61861e-5 0 -1 1.3299e-6 0 -1 -5.88315e-6 0 -1 1.5115e-6 0 -1 -4.38012e-6 0 -1 1.55872e-6 0 -1 -1.02865e-6 0 -1 6.43534e-6 0 -1 -7.24468e-7 0 -1 1.2731e-6 0 -1 -2.35347e-7 0 -1 1.8221e-6 0 -1 -9.83973e-7 0 -1 -3.92573e-6 0 -1 2.30968e-5 0 -1 -1.04595e-5 0 -1 2.7826e-5 0 -1 -3.86394e-6 0 -1 9.69764e-6 0 -1 -3.93585e-6 0 -1 -6.78397e-6 0 -1 -9.54135e-7 0 -1 7.1054e-7 0 -1 5.44748e-7 0 -1 1.707e-6 0 -1 -7.11569e-7 0 -1 2.17867e-7 0 -1 4.27504e-6 0 -1 -7.7952e-6 0 -1 1.98295e-6 0 -1 2.91557e-6 0 -1 -3.00129e-6 0 -1 -5.8427e-7 0 -1 6.55391e-7 0 -1 -3.06538e-6 0 -1 -3.68163e-7 0 -1 1.81663e-7 0 -1 -1.92623e-6 0 -1 1.29981e-6 0 -1 -5.44264e-6 0 -1 -4.36811e-6 0 -1 1.10944e-6 0 -1 1.01962e-6 0 -1 -6.04496e-7 0 -1 -4.17018e-7 0 -1 -1.779e-5 0 -1 8.36157e-7 0 -1 2.5552e-7 0 -1 -9.8459e-7 0 -1 2.59488e-7 0 -1 1.56121e-5 0 -1 -3.41054e-7 0 -1 1.57529e-7 0 -1 -4.54747e-7 0 -1 3.19073e-6 0 -1 -4.39139e-7 0 -1 3.04098e-7 0 -1 -1.06269e-5 0 -1 1.54328e-6 0 -1 -1.52813e-6 0 -1 -2.40682e-5 0 -1 1.779e-5 0 -1 6.65131e-7 0 -1 5.91741e-7 0 -1 5.94639e-7 0 -1 -1.01051e-6 0 -1 1.91586e-6 0 -1 -3.93042e-7 0 -1 4.03388e-7 0 -1 -1.3855e-6 0 -1 1.0287e-6 0 -1 6.61301e-7 0 -1 -4.27504e-6 0 -1 -1.98295e-6 0 -1 8.62426e-7 0 -1 1.42314e-6 0 -1 -7.35627e-7 0 -1 1.76724e-7 0 -1 2.41343e-6 0 -1 -5.44748e-7 0 -1 -1.15007e-6 0 -1 8.60209e-7 0 -1 7.7952e-6 0 -1 -6.43903e-7 0 -1 1.09808e-6 0 -1 -2.20317e-6 0 -1 -1.51627e-7 0 -1 2.57771e-6 0 -1 -2.17898e-6 0 -1 1.41532e-6 0 -1 -2.04198e-6 0 -1 -1.81914e-6 0 -1 -2.30487e-7 0 -1 0 0 -1 1.11585e-6 0 -1 -1.34749e-6 0 -1 -8.56267e-6 0 -1 7.03607e-7 0 -1 2.4795e-6 0 -1 -2.08721e-6 0 -1 8.48446e-6 0 -1 -2.63545e-6 0 -1 1.67968e-6 0 -1 2.30655e-6 0 -1 -3.35936e-6 0 -1 2.63545e-6 0 -1 -8.48446e-6 0 -1 8.55729e-7 0 -1 -5.23091e-7 0 -1 1.54538e-7 0 -1 9.98352e-7 0 -1 7.08164e-7 0 -1 1.65523e-7 0 -1 -9.48097e-7 0 -1 2.20317e-6 0 -1 -1.09808e-6 0 -1 6.43903e-7 0 -1 -5.52652e-7 0 -1 1.76324e-6 0 -1 -2.15961e-6 0 -1 5.71237e-6 0 -1 -7.88569e-7 0 -1 -5.32671e-6 0 -1 6.06377e-7 0 -1 -3.98511e-7 0 -1 -1.36606e-5 0 -1 1.52813e-6 0 -1 -1.3561e-6 0 -1 3.24585e-7 0 -1 4.74289e-7 0 -1 -2.92391e-6 0 -1 -2.72236e-6 0 -1 2.72236e-6 0 -1 9.54135e-7 0 -1 3.58552e-7 0 -1 2.33799e-5 0 -1 -1.04588e-6 0 -1 1.33394e-5 0 -1 5.4108e-7 0 -1 -4.79592e-6 0 -1 0.03048449 -0.9995353 0 0.03048437 -0.9995353 0 0.03040897 -0.9995375 0 0.0304085 -0.9995375 0 0.03046685 -0.9995359 0 0.03046679 -0.9995359 0 0.03046745 -0.9995357 0 0.03046751 -0.9995357 0 0.03050053 -0.9995348 0 0.03050065 -0.9995348 0 9.30761e-6 0 1 7.11331e-7 0 1 -2.36416e-7 0 1 -2.22568e-6 0 1 5.27258e-7 0 1 1.52683e-6 0 1 5.4439e-6 0 1 2.00491e-6 0 1 -8.36157e-7 0 1 4.30024e-6 0 1 -1.43631e-5 0 1 -6.44244e-6 0 1 -7.11327e-7 0 1 2.22568e-6 0 1 1.61279e-5 0 1 -1.4953e-6 0 1 -1.11918e-6 0 1 1.07509e-6 0 1 -2.03715e-6 0 1 5.39197e-7 0 1 -1.07112e-6 0 1 7.36892e-7 0 1 -2.91253e-6 0 1 2.49766e-6 0 1 -1.15697e-6 0 1 -4.63429e-7 0 1 6.97991e-7 0 1 2.42969e-6 0 1 -6.55186e-7 0 1 -2.8479e-7 0 1 8.80043e-7 0 1 4.63429e-7 0 1 -3.84076e-7 0 1 -8.80046e-7 0 1 5.15012e-6 0 1 6.55186e-7 0 1 -4.26997e-7 0 1 -2.42969e-6 0 1 -4.77067e-7 0 1 4.5619e-6 0 1 -6.63671e-6 0 1 1.27066e-5 0 1 -2.86526e-6 0 1 -4.19249e-6 0 1 -4.24365e-7 0 1 -6.07368e-7 0 1 -4.57117e-5 0 1 3.93482e-6 0 1 -1.11475e-6 0 1 5.10877e-7 0 1 6.32385e-6 0 1 -8.56626e-6 0 1 1.88444e-6 0 1 7.03701e-6 0 1 -4.82745e-6 0 1 -1.85506e-5 0 1 2.89796e-5 0 1 1.30164e-5 0 1 9.35195e-7 0 1 -1.43421e-6 0 1 2.41432e-6 0 1 -1.39034e-6 0 1 -1.42083e-5 0 1 2.86842e-6 0 1 -2.91172e-6 0 1 1.39034e-6 0 1 -1.15908e-5 0 1 1.48216e-6 0 1 1.04588e-6 0 1 -1.69692e-5 0 1 1.09197e-5 0 1 -7.70997e-6 0 1 6.84768e-6 0 1 -6.91295e-6 0 1 9.68983e-6 0 1 -6.42388e-6 0 1 9.40495e-6 0 1 -6.64948e-7 0 1 -7.03701e-6 0 1 -3.93482e-6 0 1 4.57117e-5 0 1 -2.89796e-5 0 1 1.09519e-5 0 1 4.82745e-6 0 1 -4.23766e-6 0 1 1.02583e-6 0 1 -2.7633e-7 0 1 2.14899e-6 0 1 -2.74303e-6 0 1 5.83864e-7 0 1 -3.11744e-6 0 1 3.27991e-6 0 1 4.91016e-7 0 1 4.33538e-7 0 1 -1.44894e-6 0 1 1.48173e-5 0 1 -6.38808e-7 0 1 -2.14801e-7 0 1 4.87877e-6 0 1 -2.54688e-6 0 1 -7.38324e-6 0 1 0 0 1 -5.70588e-7 0 1 4.39139e-7 0 1 2.2358e-7 0 1 -5.51546e-7 0 1 4.12226e-6 0 1 -3.68435e-7 0 1 -6.83995e-6 0 1 4.35798e-6 0 1 4.7019e-6 0 1 -8.16791e-7 0 1 5.66128e-7 0 1 -3.143e-6 0 1 5.18977e-7 0 1 -1.07886e-6 0 1 1.09808e-6 0 1 6.64384e-7 0 1 -8.06181e-6 0 1 1.94027e-6 0 1 -2.57214e-6 0 1 2.54688e-6 0 1 3.46964e-6 0 1 -2.10597e-5 0 1 1.55662e-5 0 1 -1.14249e-5 0 1 -1.21276e-6 0 1 4.85098e-6 0 1 -4.9104e-6 0 1 1.05316e-5 0 1 -2.52713e-7 0 1 4.60973e-7 0 1 -2.4502e-6 0 1 2.14555e-6 0 1 3.96176e-6 0 1 2.91071e-6 0 1 2.54534e-6 0 1 -1.02556e-6 0 1 3.95317e-6 0 1 -1.67968e-6 0 1 -1.06225e-6 0 1 -9.34983e-7 0 1 -5.23091e-7 0 1 -3.95317e-6 0 1 2.05112e-6 0 1 -2.54534e-6 0 1 -8.55729e-7 0 1 1.15327e-6 0 1 7.03607e-7 0 1 3.37592e-7 0 1 -7.53841e-6 0 1 2.02124e-6 0 1 -4.60973e-7 0 1 1.07526e-6 0 1 -3.79555e-7 0 1 2.84214e-6 0 1 -5.44748e-7 0 1 8.53499e-7 0 1 2.17867e-7 0 1 3.85244e-6 0 1 1.94972e-6 0 1 -1.3226e-6 0 1 -7.26654e-7 0 1 -1.39365e-6 0 1 -1.54305e-6 0 1 3.83806e-7 0 1 -9.28567e-7 0 1 1.62823e-6 0 1 -1.05372e-6 0 1 2.03923e-7 0 1 -2.41798e-7 0 1 2.72307e-7 0 1 4.17018e-7 0 1 3.60068e-7 0 1 1.13685e-6 0 1 6.51859e-7 0 1 -5.91741e-7 0 1 5.92143e-7 0 1 3.28556e-6 0 1 1.08853e-5 0 1 1.26466e-6 0 1 1.10944e-6 0 1 -3.0559e-6 0 1 3.84015e-7 0 1 -2.59132e-7 0 1 -1.94972e-6 0 1 6.56828e-6 0 1 -1.84082e-6 0 1 -1.16854e-6 0 1 1.44894e-6 0 1 1.43876e-7 0 1 8.62426e-7 0 1 0 0 1 -9.71857e-7 0 1 1.98295e-6 0 1 -3.53448e-7 0 1 -1.98295e-6 0 1 4.3115e-6 0 1 -1.87261e-7 0 1 -5.24791e-6 0 1 7.59869e-7 0 1 -0.2587903 -0.9659336 0 -0.2587907 -0.9659335 0 0.8691963 0.4944674 0 0.8691038 0.4946299 0 0.8691036 0.49463 0 -0.2431837 0.9699803 0 -0.2431836 0.9699803 0 -0.2430785 0.9700067 0 -0.2430786 0.9700067 0 -0.2433102 0.9699486 0 -0.243322 0.9699456 0 0.3076429 -0.951502 0 0.3076462 -0.9515009 0 0.3080062 -0.9513844 0 0.3080065 -0.9513843 0 0.009232103 -0.9999574 0 0.009231865 -0.9999574 0 0.009264171 -0.9999571 0 0.009263992 -0.9999571 0 0.00890541 -0.9999604 0 0.00890541 -0.9999604 0 -0.376633 -0.9263626 0 -0.3766328 -0.9263626 0 -0.7677282 -0.6407757 0 -0.7677857 -0.6407067 0 -0.9783365 -0.2070211 0 -0.9611763 0.2759351 0 -0.9611454 0.2760432 0 -0.8660476 0.4999614 0 -0.8660475 0.4999619 0 -0.8660162 0.500016 0 -0.8660018 0.500041 0 -0.8659592 0.5001148 0 0.8660496 -0.4999581 0 0.8660497 -0.4999579 0 -0.7327381 0.6805108 0 -0.7327382 0.6805107 0 -0.3653747 0.9308605 0 -0.3653955 0.9308524 0 0.07392466 0.9972639 0 0.5003633 0.8658156 0 0.5003365 0.8658311 0 0.8259841 0.5636935 0 0.8259556 0.5637353 0 0.9887881 0.1493262 0 0.9887881 0.1493262 0 0.9552749 -0.2957193 0 -0.9657977 -0.2592973 0 -0.96579 -0.2593259 0 -0.9659417 -0.2587597 0 -0.9659419 -0.2587596 0 -0.9659514 -0.2587239 0 -0.9659497 -0.2587302 0 -0.9658831 -0.2589787 0 -0.9658901 -0.2589525 0 0.8660556 -0.4999478 0 0.8660621 -0.4999367 0 0.8660423 -0.4999708 0 0.8660423 -0.4999707 0 0.8659929 -0.5000565 0 0.9658513 0.2590972 0 0.9658513 0.2590971 0 0.9660501 0.2583552 0 0.9660425 0.2583832 0 0.9659086 0.2588837 0 0.9659086 0.2588835 0 0.6975839 0.7165032 0 0.9548214 0.2971806 0 0.954827 0.2971621 0 0.954827 0.2971621 0 0.954827 0.2971621 0 0.9558768 0.2937679 0 0.9558768 0.2937681 0 0.5000936 0.8659714 0 0.5000979 0.865969 0 0.5005142 0.8657283 0 0.500514 0.8657285 0 0.9778638 0.2092424 0 0.8722184 0.4891169 0 0.870545 0.4920889 0 0.8705471 0.4920852 0 0.9778639 0.2092424 0 -0.8660656 0.4999305 0 -0.8660619 0.4999368 0 -0.9750267 -0.2220877 0 -0.9627452 0.2704103 0 -0.9616572 -0.2742545 0 -0.9616441 -0.2743004 0 -0.9615272 -0.2747098 0 -0.9615196 -0.2747363 0 -0.9616628 -0.2742348 0 -0.9616532 -0.2742684 0 -0.2406362 -0.9706155 0 -0.6753469 -0.7375003 0 -0.6754037 -0.7374482 0 -0.9456494 -0.3251883 0 -0.9456845 -0.3250858 0 0.006864786 -0.9999765 0 0.006864666 -0.9999765 0 0.006194174 -0.9999809 0 0.006194114 -0.9999809 0 -0.2588173 0.9659264 0 -0.2588185 0.965926 0 -0.2583601 0.9660487 0 -0.2583599 0.9660488 0 -0.7517384 0.6594615 0 -0.4449605 0.8955503 0 -0.4447603 0.8956497 0 -0.4439936 0.89603 0 -0.9469373 0.3214185 0 -0.9469373 0.3214187 0 -0.9976728 -0.06818389 0 -0.9976614 -0.06834989 0 -0.9976614 -0.06834983 0 -0.9976614 -0.06834989 0 -0.9989212 -0.04643911 0 -0.9989211 -0.04643934 0 -0.9989211 -0.04643952 0 -0.9989156 -0.04655939 -2.17874e-7 -0.9989156 -0.04655945 0 -0.9989156 -0.04655939 0 -0.8964562 -0.4431326 0 -0.8964562 -0.4431325 0 -0.6594793 -0.7517228 0 -0.6594796 -0.7517225 0 -0.5005379 -0.8657147 0 -0.5005037 -0.8657345 0 -0.4999193 -0.8660721 0 0.2590897 -0.9658533 0 0.2590987 -0.965851 0 0.258368 -0.9660466 0 0.2583681 -0.9660466 0 0.258877 -0.9659103 0 0.9469373 -0.3214187 0 0.9469373 -0.3214185 0 0.997888 0.06495743 0 0.8964611 0.4431225 0 0.8965184 0.4430064 0 0.659465 0.7517354 0 0.6594653 0.751735 0 0.8660343 -0.4999848 0 -0.9659823 0.2586085 0 -0.9659752 0.258635 0 -0.7071164 0.7070972 0 -0.7071022 0.7071114 0 -0.7071201 0.7070935 0 -0.7070983 0.7071153 0 -0.7071871 0.7070264 0 -0.7070229 0.7071908 0 -0.2590088 0.965875 0 -0.2590031 0.9658766 0 -0.2547848 0.9669978 0 -0.2549414 0.9669565 0 -0.2592862 0.9658005 0 -0.2593028 0.9657962 0 0.2590125 0.965874 0 0.2590126 0.965874 0 0.2585015 0.9660109 0 0.2585157 0.9660072 0 0.7064225 0.7077904 0 0.7064509 0.707762 0 0.7073717 0.7068418 0 0.7073718 0.7068417 0 0.9657939 0.2593109 0 0.9658105 0.2592495 0 0.9650105 0.2622117 0 0.9651706 0.2616218 0 0.9660105 0.2585029 0 0.9660164 0.2584809 0 0.9669213 -0.2550752 0 0.9669212 -0.2550752 0 0.9669212 -0.2550752 0 0.9668356 -0.2553995 0 0.9657528 -0.2594642 0 0.9657637 -0.2594233 0 0.9659302 -0.2588027 0 0.9659374 -0.2587761 0 0.7070879 -0.7071257 0 0.7071165 -0.7070971 0 0.7071086 -0.7071051 0 0.7070896 -0.7071241 0 0.259005 -0.9658761 0 0.2590051 -0.9658761 0 0.2585502 -0.9659979 0 0.2585368 -0.9660015 0 -0.2590163 -0.965873 0 -0.2590222 -0.9658715 0 -0.2584923 -0.9660134 0 -0.2584782 -0.9660172 0 -0.7071 -0.7071136 0 -0.7071002 -0.7071135 0 -0.7071183 -0.7070953 0 -0.707107 -0.7071066 0 -0.9659876 -0.2585884 0 -0.9660149 -0.2584868 0 -0.9658756 -0.2590066 0 -0.9658756 -0.2590065 0 -0.96583 0.2591763 0 -0.9658204 0.2592123 0 -0.8660681 0.4999262 0 -0.8660513 0.4999552 0 -0.8660135 0.5000207 0 -0.8660135 0.5000209 0 -0.8660553 0.4999485 0 -0.8660502 0.4999572 0 -0.8660218 0.5000066 0 -0.8660185 0.5000118 0 -0.8660009 0.5000424 0 -0.8660008 0.5000426 0 -0.8660227 0.5000049 0 -0.8660241 0.5000024 0 -0.8660374 0.4999793 0 -0.866036 0.4999818 0 -0.8660126 0.5000224 0 -0.8660124 0.5000225 0 -0.8660548 0.499949 0 -0.8660881 0.4998915 0 -0.5000314 0.8660073 0 -0.5000341 0.8660058 0 -0.4999863 0.8660333 0 -0.4999864 0.8660333 0 -0.4999939 0.866029 0 -0.4999923 0.8660299 0 0.5000089 0.8660203 0 0.5000092 0.8660202 0 0.4999918 0.8660303 0 0.4999915 0.8660303 0 0.8808574 0.4733818 0 0.8808905 0.4733202 0 0.8808749 0.4733493 0 0.8808622 0.4733728 0 0.8808575 0.4733816 0 0.8808667 0.4733645 0 0.8808666 0.4733648 0 0.8115125 0.5843352 0 0.8115125 0.584335 0 0.6326936 0.7744023 0 0.6326673 0.7744238 0 0.5261589 0.8503863 0 0.5261636 0.8503835 0 0.5261547 0.850389 0 0.5261549 0.8503889 0 0.5261554 0.8503884 0 0.5261564 0.8503879 0 0.5261567 0.8503876 0 -0.3560901 0.9344516 0 -0.3560836 0.9344542 0 0.003197908 0.9999949 0 0.3618555 0.9322343 0 0.361849 0.9322368 0 -0.01391333 0.9999032 0 -0.01391386 0.9999032 0 -0.01392519 0.9999031 0 -0.01392483 0.9999031 0 -0.2255151 0.9742397 0 -0.2255184 0.974239 0 -0.2253422 0.9742797 0 -0.4269852 0.9042587 0 -0.4269421 0.9042791 0 -0.4268214 0.904336 0 -0.4999918 -0.8660303 0 -0.4999915 -0.8660303 0 -0.5000002 -0.8660254 0 -0.4999995 -0.8660257 0 0.03046411 -0.9995359 0 0.03046417 -0.9995359 0 0.03049212 -0.9995351 0 0.03049206 -0.999535 0 -0.2293154 -0.9733522 0 -0.2293168 -0.9733519 0 -0.4733783 -0.8808593 0 -0.4733779 -0.8808595 0 -0.473384 -0.8808562 0 -0.4733841 -0.8808562 0 -0.4733775 -0.8808596 0 -0.4733773 -0.8808599 0 -0.4733366 -0.8808817 0 -0.4733389 -0.8808805 0 -0.6268133 -0.7791696 0 -0.6267944 -0.7791847 0 -0.8643493 -0.502892 0 -0.8643409 -0.5029066 0 -0.9872877 -0.1589438 0 -0.9872968 -0.1588875 0 -0.9965819 -0.08261096 0 -0.9965815 -0.08261644 0 -0.9565043 -0.2917184 0 -0.9565012 -0.2917286 0 -0.8728885 -0.4879199 0 -0.8728883 -0.4879202 0 -0.6731821 -0.7394767 0 -0.6731741 -0.7394841 0 -0.4999245 -0.866069 0 -0.4999415 -0.8660593 0 -0.500077 -0.8659811 0 -0.5000808 -0.8659788 0 -0.5000523 -0.8659952 0 -0.500054 -0.8659943 0 -0.5000344 -0.8660056 0 0.0657767 -0.9978344 0 -0.3197718 -0.9474947 0 -0.3197718 -0.9474946 0 -0.3197718 -0.9474946 0 -0.320092 -0.9473866 0 -0.320092 -0.9473866 0 -0.320092 -0.9473866 0 -0.3211802 -0.9470182 0 -0.3211805 -0.947018 0 0.2588883 -0.9659074 0 0.2588881 -0.9659074 0 0.2587319 -0.9659493 0 0.4424317 -0.8968023 0 0.7548565 -0.6558901 0 0.7548562 -0.6558904 0 0.7514842 -0.6597512 0 0.7515035 -0.6597293 0 0.4424172 -0.8968094 0 0.8658978 -0.500221 0 0.865876 -0.5002588 0 0.8661921 -0.4997113 0 0.8661724 -0.4997453 0 0.8660283 -0.499995 0 0.8660162 -0.500016 0 0.8659543 -0.5001232 0 0.8659349 -0.5001569 0 0.8661113 -0.4998512 0 0.8661178 -0.4998399 0 0.8659114 -0.5001974 0 0.865917 -0.5001878 0 0.8658737 -0.5002627 0 0.8658956 -0.5002247 0 0.9978339 0.06578487 0 0.9474765 -0.3198257 0 0.9473185 -0.3202934 0 0.9470285 -0.3211498 0 0.9470166 -0.3211846 0 0.9978362 0.06574887 0 0.9659346 0.2587862 0 0.9659369 0.2587777 0 0.9687262 0.2481324 0 0.96864 0.2484687 0 0.9686399 0.2484689 2.10258e-7 0.96864 0.2484685 0 0.9658836 0.2589771 0 0.9658776 0.2589992 0 0.9659421 0.2587584 0 0.9659448 0.2587485 0 0.9658253 0.2591944 0 0.896778 0.4424809 0 0.6579803 0.7530352 0 0.6594712 0.75173 0 0.6594709 0.7517302 0 0.8967779 0.4424809 0 0.5001108 0.8659616 0 0.5000764 0.8659814 0 0.5001038 0.8659656 0 0.500097 0.8659695 0 0.4999849 0.8660342 0 0.4999787 0.8660377 0 0.5000115 0.8660188 0 0.5000042 0.8660231 0 -0.5000072 -0.8660213 0 -0.5000045 -0.866023 0 -0.4999988 -0.8660262 0 -0.4999992 -0.8660259 0 -0.499989 -0.8660319 0 -0.4999862 -0.8660335 0 0.4999604 0.8660483 0 0.4999606 0.8660483 0 0.4999998 0.8660256 0 0.4999983 0.8660265 0 0.5000355 0.8660051 0 0.500033 0.8660065 0 -0.8660485 0.4999603 0 -0.7068832 0.7073304 0 -0.2588863 0.9659078 0 -0.2588478 0.9659181 0 0.2588607 0.9659147 0 0.2588606 0.9659148 0 0.7068576 0.7073559 0 0.7068832 0.7073304 0 0.9660365 0.258406 0 0.9660364 0.2584062 0 0.9660377 -0.2584015 0 0.9660376 -0.2584017 0 0.7051921 -0.7090164 0 0.7051109 -0.7090972 0 0.7076027 -0.7066105 0 0.7076773 -0.7065358 0 0.2588775 -0.9659103 0 0.2588774 -0.9659103 0 -0.2588647 -0.9659136 0 -0.258903 -0.9659034 0 -0.7068742 -0.7073393 0 -0.7068231 -0.7073904 0 -0.9660377 -0.2584015 0 -0.9660248 -0.2584494 0 -0.9656501 0.2598461 0 -0.9656501 0.259846 0 -0.9668798 0.2552324 0 -0.9668394 0.2553853 0 -0.7068321 0.7073814 0 -0.9660364 0.2584062 0 -0.7068576 0.7073559 0 -0.2588607 0.9659147 0 -0.2588606 0.9659148 0 0.2588735 0.9659112 0 0.2588478 0.9659181 0 0.7080851 0.7061272 0 0.7080595 0.7061529 0 0.9654344 0.2606461 0 0.9654344 0.2606463 0 0.965435 -0.2606438 0 0.965435 -0.260644 0 0.708055 -0.7061573 0 0.7080805 -0.7061318 0 0.2588564 -0.9659159 0 0.2588818 -0.965909 0 -0.2588691 -0.9659125 0 -0.2588691 -0.9659125 0 -0.7068532 -0.7073603 0 -0.7068786 -0.7073349 0 -0.9660371 -0.2584038 0 -0.966037 -0.2584039 0 -0.9660365 0.258406 0 -1.60496e-7 0 1 -7.13878e-5 0 1 7.46068e-6 0 1 1.68348e-6 0 1 1.5393e-6 0 1 -1.05846e-5 0 1 5.42315e-6 0 1 1.84623e-6 0 1 -3.3322e-6 0 1 2.11494e-6 0 1 -4.07405e-7 0 1 -3.30907e-6 0 1 2.16991e-6 0 1 1.73986e-6 0 1 -3.83824e-7 0 1 3.06764e-6 0 1 -8.96144e-6 0 1 4.76785e-6 0 1 4.00584e-7 0 1 -5.17487e-7 0 1 2.8274e-6 0 1 -1.49058e-5 0 1 1.03522e-6 0 1 2.20144e-5 0 1 2.04523e-6 0 1 -3.34742e-5 0 1 1.59983e-5 0 1 6.79955e-7 0 1 -1.76758e-6 0 1 -7.23526e-6 0 1 -6.44963e-6 0 1 7.85571e-7 0 1 4.9866e-6 0 1 -5.86134e-6 0 1 -2.19329e-6 0 1 6.82195e-7 0 1 1.63518e-6 0 1 0 0 1 4.04197e-6 0 1 -2.49686e-6 0 1 -2.04881e-6 0 1 8.32309e-7 0 1 2.0146e-6 0 1 -1.13495e-6 0 1 -2.16625e-6 0 1 2.48799e-6 0 1 9.02414e-7 0 1 -1.07604e-6 0 1 1.12006e-6 0 1 -2.96648e-6 0 1 6.231e-6 0 1 -1.16069e-6 0 1 3.78926e-6 0 1 8.65831e-6 0 1 -9.78152e-7 0 1 -6.05386e-7 0 1 8.79906e-6 0 1 1.93829e-5 0 1 -5.82533e-6 0 1 -9.65958e-7 0 1 -1.03345e-6 0 1 -9.48176e-7 0 1 -3.67582e-6 0 1 -6.28348e-6 0 1 2.53874e-5 0 1 -2.26224e-5 0 1 2.73573e-7 0 1 1.43901e-5 0 1 -3.23429e-7 0 1 1.87487e-7 0 1 -2.51396e-7 0 1 1.5524e-6 0 1 2.16277e-5 0 1 2.0694e-6 0 1 1.4176e-6 0 1 -8.14874e-7 0 1 2.50065e-6 0 1 1.23362e-5 0 1 -4.0663e-6 0 1 1.06128e-5 0 1 4.87307e-7 0 1 2.54892e-7 0 1 -3.38781e-7 0 1 6.49454e-6 0 1 7.4497e-7 0 1 1.12219e-6 0 1 -5.15251e-6 0 1 -1.00497e-6 0 1 2.00997e-6 0 1 -2.57604e-6 0 1 2.09221e-6 0 1 -6.79964e-6 0 1 4.40793e-6 0 1 5.12854e-7 0 1 7.49384e-6 0 1 1.26595e-5 0 1 3.40604e-6 0 1 -8.22466e-7 0 1 -1.63015e-6 0 1 1.70214e-6 0 1 -2.87738e-6 0 1 6.62933e-7 0 1 7.74106e-7 0 1 -3.08273e-6 0 1 -6.5033e-6 0 1 -1.74662e-6 0 1 -2.28111e-6 0 1 -8.50491e-7 0 1 5.90026e-7 0 1 8.06306e-7 0 1 -2.09062e-6 0 1 5.15113e-6 0 1 5.92136e-6 0 1 -6.83419e-7 0 1 -1.46955e-6 0 1 1.51151e-6 0 1 1.05096e-6 0 1 -2.0099e-6 0 1 7.72941e-6 0 1 -3.10345e-6 0 1 6.66063e-6 0 1 -4.04138e-7 0 1 -5.76584e-7 0 1 -2.94253e-7 0 1 -1.2012e-6 0 1 9.72592e-6 0 1 0 0 1 -6.7575e-7 0 1 3.31671e-7 0 1 3.31583e-7 0 1 -7.73587e-7 0 1 9.28495e-7 0 1 1.68918e-7 0 1 5.90635e-7 0 1 -8.63198e-7 0 1 1.35477e-7 0 1 5.67454e-7 0 1 2.35051e-6 0 1 1.10301e-6 0 1 -1.3889e-7 0 1 -4.52338e-7 0 1 2.60757e-7 0 1 8.1943e-6 0 1 3.64184e-7 0 1 -7.94006e-7 0 1 0 0 1 -4.28225e-7 0 1 1.75818e-7 0 1 7.14384e-7 0 1 -7.71389e-7 0 1 -1.09008e-6 0 1 2.971e-5 0 1 4.16327e-6 0 1 6.33617e-6 0 1 -1.43561e-6 0 1 -7.93903e-5 0 1 2.00668e-6 0 1 -2.08154e-6 0 1 1.90696e-6 0 1 1.60039e-6 0 1 3.09294e-7 0 1 1.43563e-6 0 1 -1.58439e-6 0 1 -3.81241e-6 0 1 -1.60047e-6 0 1 6.46362e-6 0 1 -3.4748e-6 0 1 7.46175e-7 0 1 3.47454e-6 0 1 -2.74454e-6 0 1 1.61385e-6 0 1 1.68099e-6 0 1 -7.03826e-7 0 1 7.03786e-7 0 1 8.40475e-7 0 1 -1.0728e-5 0 1 1.75961e-6 0 1 2.40277e-6 0 1 5.97229e-6 0 1 1.94759e-6 0 1 -4.9433e-6 0 1 4.69363e-6 0 1 9.16322e-6 0 1 -2.38743e-6 0 1 1.36703e-6 0 1 -9.85717e-7 0 1 -3.71695e-6 0 1 -4.43928e-7 0 1 -4.72622e-7 0 1 0 0 1 -2.25415e-6 0 1 4.16685e-7 0 1 -6.41697e-7 0 1 2.24853e-6 0 1 2.02948e-6 0 1 6.06257e-7 0 1 1.61554e-6 0 1 1.7243e-6 0 1 -2.61904e-6 0 1 -3.01002e-6 0 1 2.3265e-6 0 1 -6.46474e-7 0 1 -8.09758e-6 0 1 2.20599e-6 0 1 5.51353e-6 0 1 -8.89819e-7 0 1 4.44688e-7 0 1 -1.46696e-6 0 1 -2.13797e-7 0 1 2.93528e-6 0 1 -3.1807e-6 0 1 -2.65286e-7 0 1 -8.8956e-7 0 1 1.61661e-6 0 1 -1.0941e-6 0 1 -2.20115e-7 0 1 3.51282e-7 0 1 -1.43877e-5 0 1 7.30618e-7 0 1 7.39472e-7 0 1 7.30593e-7 0 1 7.40019e-7 0 1 1.48759e-6 0 1 4.29304e-7 0 1 6.91452e-7 0 1 1.42524e-6 0 1 -1.74652e-6 0 1 4.96878e-7 0 1 -3.06436e-6 0 1 7.6619e-7 0 1 3.09325e-7 0 1 1.0928e-6 0 1 -1.22589e-6 0 1 7.66227e-7 0 1 7.96838e-7 0 1 -1.74858e-6 0 1 2.73196e-7 0 1 1.54328e-7 0 1 1.05539e-5 0 1 -1.70836e-6 0 1 1.88053e-7 0 1 2.39181e-7 0 1 -4.3547e-7 0 1 1.56326e-6 0 1 -5.35181e-7 0 1 4.52194e-7 0 1 5.65387e-7 0 1 6.28585e-7 0 1 -2.22965e-6 0 1 -1.21665e-7 0 1 1.76542e-6 0 1 -2.46252e-6 0 1 5.46373e-6 0 1 -1.42645e-5 0 1 4.99999e-7 0 1 -3.06492e-7 0 1 -2.15241e-6 0 1 -4.75097e-7 0 1 2.33033e-6 0 1 2.47367e-7 0 1 -5.23111e-6 0 1 7.57125e-6 0 1 -2.31911e-4 0 1 4.04209e-6 0 1 -2.48693e-6 0 1 -1.77654e-6 0 1 8.61891e-7 0 1 -3.81968e-6 0 1 2.52603e-6 0 1 -1.61541e-6 0 1 -1.56622e-6 0 1 2.35707e-6 0 1 -7.80226e-6 0 1 -7.80265e-7 0 1 0 0 1 4.90346e-7 0 1 -5.16942e-7 0 1 -1.27489e-6 0 1 -4.40283e-7 0 1 -1.23476e-6 0 1 1.0941e-6 0 1 7.13633e-6 0 1 7.53459e-7 0 1 -5.60943e-7 0 1 2.98432e-6 0 1 -2.20587e-6 0 1 -7.35352e-6 0 1 -2.16196e-6 0 1 -3.29034e-6 0 1 -7.39873e-7 0 1 -1.87316e-6 0 1 -1.0917e-5 0 1 2.16521e-6 0 1 8.50734e-7 0 1 3.25775e-6 0 1 2.65295e-7 0 1 -7.80869e-7 0 1 -3.44732e-6 0 1 1.3404e-6 0 1 -1.61681e-6 0 1 1.2091e-6 0 1 3.10426e-7 0 1 -1.61655e-6 0 1 -4.6996e-7 0 1 9.40104e-7 0 1 -9.39949e-7 0 1 -9.40118e-7 0 1 0 0 1 -1.35985e-6 0 1 -1.52828e-5 0 1 1.28204e-7 0 1 -8.99488e-7 0 1 -1.2746e-6 0 1 0.9654216 0.2606937 0 0.9654344 -0.2606461 0 0.9654216 -0.2606939 0 0.7091472 -0.7050605 0 0.7089833 -0.7052253 0 0.7076399 -0.7065732 0 0.7076401 -0.7065731 0 0.2588607 -0.9659147 0 0.2588606 -0.9659148 0 -0.2588607 -0.9659147 0 -0.2588606 -0.9659148 0 -0.7068832 -0.7073304 0 -0.7068576 -0.7073559 0 -0.9660365 -0.258406 0 -0.9660364 -0.2584062 0 -0.9665236 0.2565777 0 -0.9665237 0.2565777 0 -0.9649541 0.2624189 0 -0.9649541 0.2624189 0 3.35457e-7 0 -1 -2.31163e-7 0 -1 7.13878e-5 0 -1 -4.17865e-6 0 -1 -8.01508e-7 0 -1 2.54557e-5 0 -1 -9.1567e-7 0 -1 -1.44634e-5 0 -1 8.52079e-6 0 -1 3.00258e-7 0 -1 1.21131e-6 0 -1 -7.41875e-7 0 -1 -1.22798e-7 0 -1 3.11379e-6 0 -1 2.89863e-7 0 -1 -1.74085e-7 0 -1 -1.81412e-6 0 -1 3.17654e-7 0 -1 5.81785e-7 0 -1 -9.57282e-7 0 -1 -3.50441e-6 0 -1 9.03858e-7 0 -1 3.02382e-7 0 -1 2.38904e-6 0 -1 3.83824e-7 0 -1 -1.22664e-6 0 -1 1.24089e-6 0 -1 -5.977e-6 0 -1 -2.41861e-6 0 -1 -9.28046e-6 0 -1 -2.99397e-7 0 -1 1.66195e-7 0 -1 -2.7358e-7 0 -1 8.99453e-7 0 -1 6.7985e-7 0 -1 -1.55277e-5 0 -1 2.98357e-5 0 -1 -5.17485e-7 0 -1 2.04523e-6 0 -1 -7.22126e-7 0 -1 3.84385e-6 0 -1 -7.4529e-6 0 -1 -5.17608e-7 0 -1 3.53425e-6 0 -1 -5.41702e-7 0 -1 6.55261e-6 0 -1 -7.61086e-6 0 -1 -3.98699e-6 0 -1 -2.85284e-7 0 -1 -8.17635e-7 0 -1 5.6747e-7 0 -1 3.4524e-7 0 -1 -2.70949e-7 0 -1 -4.20623e-7 0 -1 -5.67476e-7 0 -1 0 0 -1 5.05131e-7 0 -1 -4.16154e-7 0 -1 -3.31606e-6 0 -1 3.46879e-7 0 -1 -1.08313e-6 0 -1 -1.79251e-6 0 -1 3.31732e-6 0 -1 5.12156e-7 0 -1 9.49339e-7 0 -1 -5.11804e-7 0 -1 3.71306e-6 0 -1 5.49941e-6 0 -1 -2.38699e-6 0 -1 -5.97372e-6 0 -1 9.72611e-6 0 -1 -1.65401e-6 0 -1 5.42978e-7 0 -1 -1.42097e-6 0 -1 3.26758e-7 0 -1 2.1362e-6 0 -1 -1.53398e-6 0 -1 1.81949e-7 0 -1 3.13456e-7 0 -1 -3.43446e-6 0 -1 6.11606e-7 0 -1 3.31018e-6 0 -1 6.12679e-7 0 -1 2.18859e-6 0 -1 -1.28161e-5 0 -1 4.13935e-6 0 -1 5.47154e-7 0 -1 -7.18143e-6 0 -1 2.58733e-7 0 -1 8.01477e-7 0 -1 -2.51327e-7 0 -1 1.87538e-7 0 -1 0 0 -1 -2.9766e-6 0 -1 -7.05812e-7 0 -1 2.98116e-5 0 -1 -4.91727e-6 0 -1 7.51164e-6 0 -1 -1.27997e-6 0 -1 9.16787e-7 0 -1 -4.32367e-6 0 -1 -2.0858e-5 0 -1 1.08142e-6 0 -1 -1.09649e-5 0 -1 -7.79691e-6 0 -1 -1.11739e-5 0 -1 2.50065e-6 0 -1 7.99335e-6 0 -1 5.66636e-6 0 -1 -6.92639e-6 0 -1 -5.86543e-7 0 -1 -2.56474e-7 0 -1 -3.1742e-6 0 -1 8.7271e-7 0 -1 -8.06306e-7 0 -1 3.83949e-7 0 -1 -8.22444e-7 0 -1 -5.89745e-7 0 -1 1.70221e-6 0 -1 1.1387e-6 0 -1 4.34861e-7 0 -1 -2.688e-6 0 -1 2.06834e-5 0 -1 -2.43448e-6 0 -1 8.22466e-7 0 -1 8.12934e-7 0 -1 -4.44107e-7 0 -1 -1.26595e-5 0 -1 1.4247e-6 0 -1 -2.09221e-6 0 -1 1.28802e-6 0 -1 1.14055e-6 0 -1 1.56901e-6 0 -1 -3.27586e-6 0 -1 6.12382e-7 0 -1 -6.44117e-6 0 -1 2.11617e-6 0 -1 2.61327e-7 0 -1 7.55753e-7 0 -1 -1.48336e-6 0 -1 8.44766e-7 0 -1 -1.29781e-6 0 -1 -2.81129e-7 0 -1 3.71123e-7 0 -1 -2.2942e-7 0 -1 0 0 -1 2.28899e-6 0 -1 7.23734e-7 0 -1 -6.42338e-7 0 -1 5.55568e-7 0 -1 5.21513e-7 0 -1 -7.88373e-7 0 -1 5.82243e-7 0 -1 0 0 -1 -1.37468e-6 0 -1 6.83105e-7 0 -1 -2.83727e-7 0 -1 -1.58593e-6 0 -1 -1.7264e-7 0 -1 -3.24973e-6 0 -1 7.08609e-7 0 -1 -4.07941e-7 0 -1 -7.73587e-7 0 -1 -1.32633e-6 0 -1 1.53079e-7 0 -1 -6.00598e-7 0 -1 0 0 -1 0 0 -1 2.20776e-7 0 -1 8.16865e-7 0 -1 5.15881e-7 0 -1 8.12353e-7 0 -1 4.48714e-7 0 -1 -1.30995e-5 0 -1 9.72294e-7 0 -1 -3.48893e-7 0 -1 2.08623e-7 0 -1 2.08153e-6 0 -1 -2.29333e-6 0 -1 9.45453e-7 0 -1 2.971e-5 0 -1 1.07295e-6 0 -1 5.20404e-7 0 -1 -1.9846e-5 0 -1 -1.58446e-6 0 -1 2.86643e-7 0 -1 3.81179e-6 0 -1 -1.26071e-6 0 -1 2.01882e-7 0 -1 3.51913e-7 0 -1 -3.89517e-6 0 -1 1.97738e-5 0 -1 6.18637e-7 0 -1 -3.81388e-6 0 -1 9.94906e-6 0 -1 1.5097e-6 0 -1 -2.71091e-5 0 -1 1.69208e-6 0 -1 -1.60185e-6 0 -1 2.63942e-6 0 -1 -1.44079e-6 0 -1 -4.21627e-7 0 -1 5.59594e-7 0 -1 3.47814e-6 0 -1 -1.44771e-6 0 -1 -7.17863e-7 0 -1 -6.18607e-7 0 -1 1.60041e-6 0 -1 7.62474e-6 0 -1 5.14926e-7 0 -1 -1.54209e-6 0 -1 -5.39013e-7 0 -1 5.56793e-5 0 -1 -7.43158e-6 0 -1 2.79972e-6 0 -1 1.81159e-7 0 -1 1.10604e-6 0 -1 -2.18723e-6 0 -1 3.05345e-6 0 -1 8.33367e-7 0 -1 9.21052e-7 0 -1 -6.66638e-7 0 -1 9.92197e-7 0 -1 7.679e-7 0 -1 2.60521e-6 0 -1 4.91221e-7 0 -1 6.26639e-6 0 -1 -6.373e-7 0 -1 1.02581e-6 0 -1 6.62819e-7 0 -1 -8.46935e-7 0 -1 2.31285e-7 0 -1 1.88097e-6 0 -1 -1.81365e-6 0 -1 1.20842e-6 0 -1 -1.2417e-6 0 -1 -1.72366e-6 0 -1 2.03393e-6 0 -1 -2.87623e-7 0 -1 4.47048e-7 0 -1 -9.40048e-7 0 -1 9.39991e-7 0 -1 -3.25165e-6 0 -1 9.15657e-7 0 -1 -4.96694e-7 0 -1 -8.50734e-7 0 -1 -2.05527e-7 0 -1 -2.4333e-7 0 -1 -8.65785e-7 0 -1 2.20911e-6 0 -1 -1.03564e-6 0 -1 -6.12314e-7 0 -1 1.49154e-7 0 -1 -2.94237e-7 0 -1 -1.62556e-7 0 -1 -7.80226e-6 0 -1 4.04165e-6 0 -1 -2.1319e-7 0 -1 3.38729e-7 0 -1 1.17853e-6 0 -1 -4.69867e-6 0 -1 2.8983e-7 0 -1 3.76729e-7 0 -1 3.27219e-7 0 -1 1.20135e-4 0 -1 -2.91153e-6 0 -1 7.25e-7 0 -1 2.13899e-7 0 -1 -4.78293e-7 0 -1 4.90342e-7 0 -1 -1.50445e-6 0 -1 -4.81603e-6 0 -1 5.464e-7 0 -1 6.66297e-7 0 -1 -3.41709e-7 0 -1 -2.94988e-7 0 -1 2.94984e-7 0 -1 2.05406e-7 0 -1 6.46663e-6 0 -1 -8.80548e-7 0 -1 1.23474e-6 0 -1 -1.04019e-6 0 -1 0 0 -1 9.2191e-7 0 -1 2.43375e-6 0 -1 -1.49668e-6 0 -1 1.49668e-6 0 -1 -7.39472e-7 0 -1 -7.3061e-7 0 -1 -4.94411e-7 0 -1 7.40265e-7 0 -1 7.30354e-7 0 -1 -8.9953e-7 0 -1 -2.56484e-7 0 -1 4.12201e-7 0 -1 -3.20508e-6 0 -1 1.46764e-6 0 -1 -3.1807e-6 0 -1 4.47974e-6 0 -1 -2.22344e-7 0 -1 -1.72371e-6 0 -1 -7.8086e-7 0 -1 7.95858e-7 0 -1 -1.43812e-6 0 -1 -6.88713e-7 0 -1 -3.97539e-7 0 -1 -0.9616532 0.2742686 0 -0.9616628 0.2742347 0 -0.9615197 0.2747365 0 -0.9615272 0.2747097 0 -0.9616441 0.2743005 0 -0.9616572 0.2742543 0 -0.9627452 -0.2704103 0 -0.9750267 0.2220877 0 -0.8659081 -0.5002033 0 -0.8659141 -0.5001928 0 -0.8663314 -0.4994698 0 -0.8663241 -0.4994824 0 -0.866212 -0.4996767 0 -0.8662003 -0.499697 0 0.6118132 -0.7910023 0 0.6118412 -0.7909808 0 0.1742553 -0.9847006 0 0.1742753 -0.984697 0 -0.3112795 -0.9503184 0 -0.3112794 -0.9503184 0 -0.7180514 -0.69599 0 0.9778286 -0.2094075 0 0.9778286 -0.2094074 0 0.9780806 -0.2082266 0 0.870599 -0.4919934 0 0.870599 -0.4919932 0 0.8705165 -0.4921392 0 0.8705134 -0.4921447 0 0.8722184 -0.4891169 0 0.2081355 0.9781 0 0.2081639 0.9780941 0 0.5780887 0.815974 0 0.5781543 0.8159275 0 0.852786 0.5222605 0 0.989812 0.1423814 0 0.9898316 0.1422442 0 0.006194114 0.9999809 0 0.006194174 0.9999809 0 0.006864666 0.9999765 0 0.006864786 0.9999765 0 -0.9658129 -0.2592403 0 -0.9658128 -0.2592405 0 -0.9658129 0.2592403 0 -0.9658128 0.2592405 0 -0.7071009 0.7071127 0 -0.7071274 0.7070862 0 -0.259202 0.9658232 0 -0.259215 0.9658197 0 0.2592152 0.9658196 0 0.259215 0.9658197 0 0.7071009 0.7071127 0 0.707101 0.7071126 0 -0.2586198 -0.9659793 0 -0.2586122 -0.9659813 0 -0.2587546 -0.9659432 0 -0.2587488 -0.9659447 0 -0.2588838 -0.9659085 0 -0.2588857 -0.9659081 0 -0.2583599 -0.9660488 0 -0.2583601 -0.9660487 0 -0.9662146 -0.257739 0 -0.7071252 0.7070884 0 -0.7071251 0.7070885 0 -0.9656779 0.2597429 0 -0.9656778 0.259743 0 -0.9669664 0.2549041 0 -0.9669045 0.2551389 0 -0.9662417 -0.2576374 0 -0.4999193 0.8660721 0 -0.5005038 0.8657343 0 -0.5005377 0.8657149 0 0.258877 0.9659103 0 0.258368 0.9660466 0 0.2583681 0.9660466 0 0.2590987 0.965851 0 0.2590897 0.9658533 0 0.8660556 0.4999478 0 0.8660559 0.4999474 0 0.8659845 0.500071 0 0.8660131 0.5000214 0 0.8659929 0.5000565 0 -0.243322 -0.9699457 0 -0.2433103 -0.9699486 0 -0.2430785 -0.9700067 0 -0.2430786 -0.9700067 0 -0.2431837 -0.9699803 0 -0.2431836 -0.9699803 0 0.7209847 -0.692951 0 0.7208702 -0.6930702 0 0.3022273 -0.9532359 0 -0.1898669 -0.9818099 0 -0.1898667 -0.9818099 0 0.8691038 -0.4946299 0 0.8691036 -0.49463 0 0.8691963 -0.4944674 0 0.619665 0.7848665 0 0.6195966 0.7849205 0 0.8778049 0.4790185 0 0.8778048 0.4790186 0 0.9960013 0.08934009 0 0.9960012 0.08934015 0 0.9514547 -0.307789 0 0.9514546 -0.307789 0 0.3076936 0.9514855 0 0.00890541 0.9999604 0 0.00890541 0.9999604 0 0.00925225 0.9999572 0 0.00925225 0.9999572 0 0.3076965 0.9514846 0 -0.9611453 -0.2760431 0 -0.9611762 -0.2759352 0 -0.9783365 0.2070211 0 -0.7677857 0.6407068 0 -0.7677282 0.6407756 0 -0.376633 0.9263626 0 -0.3766328 0.9263626 0 -0.8660258 -0.4999995 0 -0.8660221 -0.5000059 0 -0.9659253 0.2588211 0 -0.9659253 0.2588212 0 -0.9658831 0.2589786 0 -0.9658901 0.2589526 0 0.8660461 0.4999641 0 0.86605 0.4999575 0 0.9627169 0.2705112 0 0.9627466 0.2704051 0 0.9750267 -0.2220877 0 0.9659086 -0.2588837 0 0.9659086 -0.2588835 0 0.9660425 -0.2583832 0 0.9660501 -0.2583552 0 0.9658513 -0.2590972 0 0.9658513 -0.2590971 0 0.6975839 -0.7165032 0 0.9548214 -0.2971806 0 0.954827 -0.2971621 0 0.954827 -0.2971621 0 0.954827 -0.2971621 0 0.9558768 -0.2937681 0 0.9558768 -0.2937679 0 -0.7517384 -0.6594615 0 -0.4407517 -0.8976292 0 -0.4408188 -0.8975962 0 -0.4380546 -0.8989484 0 -0.4380543 -0.8989486 0 -0.06832122 -0.9976634 0 -0.06832128 -0.9976634 0 0.3213573 -0.946958 0 0.3213574 -0.9469581 0 0.5005142 -0.8657283 0 0.500514 -0.8657285 0 0.5000981 -0.8659688 0 0.5000935 -0.8659715 0 -0.7071021 -0.7071114 0 -0.7071165 -0.7070971 0 -0.9659752 -0.258635 0 -0.9659823 -0.2586085 0 -0.9659348 -0.2587858 0 -0.9659457 -0.258745 0 -0.9649581 -0.2624044 0 -0.964958 -0.2624043 0 -0.9658756 0.2590066 0 -0.9658756 0.2590065 0 -0.9669896 0.2548163 0 -0.9657948 0.259308 0 -0.9657948 0.2593079 0 -0.7071185 0.7070951 0 -0.7071 0.7071136 0 -0.7071002 0.7071135 0 -0.2584782 0.9660172 0 -0.2584923 0.9660134 0 -0.2590221 0.9658715 0 -0.2590164 0.965873 0 0.2593026 0.9657962 0 0.2593028 0.9657962 0 0.2549154 0.9669635 0 0.2548372 0.966984 0 0.259005 0.9658761 0 0.2590051 0.9658761 0 0.7031157 0.7110755 0 0.7032794 0.7109136 0 0.7076176 0.7065956 0 0.7071164 0.7070972 0 0.7070881 0.7071256 0 0.9659374 0.2587762 0 0.9659302 0.2588026 0 0.9658905 0.2589509 0 0.9658809 0.2589868 0 0.9660164 -0.258481 0 0.9660106 -0.2585027 0 0.9656735 -0.2597589 0 0.9656872 -0.2597082 0 0.7073717 -0.7068418 0 0.7073718 -0.7068417 0 0.7064508 -0.7077623 0 0.7064228 -0.7077902 0 0.2585157 -0.9660072 0 0.2585015 -0.9660109 0 0.2590125 -0.965874 0 0.2590126 -0.965874 0 -0.2585278 -0.9660038 0 -0.2585414 -0.9660003 0 -0.259003 -0.9658765 0 -0.259009 -0.965875 0 -0.7071086 -0.7071051 0 -0.7071088 -0.7071049 0 -0.8660882 -0.4998913 0 -0.8660548 -0.4999492 0 -0.8660126 -0.5000224 0 -0.8660124 -0.5000225 0 -0.8660553 -0.4999485 0 -0.8660502 -0.4999572 0 -0.8660192 -0.5000107 0 -0.8660162 -0.5000162 0 -0.8660536 -0.4999511 0 -0.8660487 -0.4999596 0 -0.8660242 -0.5000021 0 -0.8660225 -0.5000052 0 -0.8660237 -0.5000028 0 -0.8660238 -0.500003 0 -0.8660135 -0.5000207 0 -0.8660135 -0.5000209 0 -0.8660514 -0.4999551 0 -0.866068 -0.4999263 0 -0.4999999 -0.8660255 0 -0.4999995 -0.8660257 0 0.4999918 -0.8660303 0 0.4999915 -0.8660303 0 0.5000095 -0.86602 0 0.5000087 -0.8660205 0 0.8808615 -0.4733743 0 0.880864 -0.4733694 0 0.8808627 -0.473372 0 0.8808602 -0.4733766 0 0.6326671 -0.7744239 0 0.6326937 -0.7744022 0 0.8115125 -0.5843352 0 0.8115125 -0.584335 0 0.526159 -0.8503862 0 0.5261635 -0.8503835 0 0.5261549 -0.8503889 0 0.5261547 -0.850389 0 0.5261554 -0.8503884 0 0.5261567 -0.8503876 0 0.5261564 -0.8503879 0 0.361849 -0.9322368 0 0.3618555 -0.9322343 0 0.003197908 -0.9999949 0 -0.3560837 -0.9344541 0 -0.35609 -0.9344517 0 -0.4268454 -0.9043247 0 -0.4268537 -0.9043207 0 -0.2254735 -0.9742493 0 -0.2254711 -0.97425 0 -0.01391899 -0.9999032 0 -0.01391881 -0.9999032 0 0.3033238 -0.9528876 0 0.3033334 -0.9528846 0 0.5001104 -0.8659617 0 0.5000767 -0.8659812 0 0.5001038 -0.8659656 0 0.500097 -0.8659695 0 0.4999847 -0.8660343 0 0.4999788 -0.8660377 0 0.5000113 -0.866019 0 0.5000044 -0.8660229 0 0.8967779 -0.4424809 0 0.6579803 -0.7530352 0 0.6594709 -0.7517302 0 0.6594712 -0.75173 0 0.896778 -0.4424809 0 0.9659585 -0.2586972 0 0.9659585 -0.2586973 0 0.9659146 -0.2588613 0 0.9659145 -0.2588614 0 0.9978339 -0.06578487 0 0.9474763 0.3198259 0 0.9473185 0.3202932 0 0.9470285 0.3211498 0 0.9470167 0.3211847 0 0.9978362 -0.06574887 0 0.8658955 0.5002249 0 0.8658738 0.5002626 0 0.8657194 0.5005299 0 0.8657392 0.5004957 0 0.8660162 0.5000162 0 0.8660162 0.500016 0 0.8659347 0.500157 0 0.8659349 0.5001569 0 0.8661177 0.4998401 0 0.8661115 0.4998509 0 0.8660421 0.4999712 0 0.8660476 0.4999616 0 0.865876 0.5002588 0 0.8658978 0.500221 0 0.4424316 0.8968023 0 0.7548562 0.6558904 0 0.7548565 0.6558901 0 0.7514842 0.6597512 0 0.7515035 0.6597293 0 0.4424174 0.8968094 0 0.257754 0.9662106 0 0.2577874 0.9662017 0 0.2589992 0.9658777 0 0.2590018 0.9658769 0 0.2584594 0.9660222 0 0.2584653 0.9660205 0 0.2716371 0.9623998 0 0.2713642 0.9624768 0 0.2587823 0.9659357 0 0.25878 0.9659364 0 0.0657767 0.9978344 0 -0.3200898 0.9473872 0 -0.3202282 0.9473405 0 -0.3202281 0.9473405 -3.13415e-7 -0.3202282 0.9473405 0 -0.3211805 0.947018 0 -0.3211802 0.9470182 0 -0.4999245 0.866069 0 -0.4999415 0.8660593 0 -0.5000773 0.8659808 0 -0.5000804 0.8659791 0 -0.5000525 0.8659951 0 -0.5000538 0.8659944 0 -0.5000344 0.8660056 0 -0.4999997 0.8660256 0 -0.5000001 0.8660254 0 -0.4999918 0.8660303 0 -0.4999915 0.8660303 0 0.03046613 0.9995359 0 0.03046661 0.9995359 0 0.0305109 0.9995345 0 0.03051108 0.9995344 0 0.03034168 0.9995397 0 0.03034174 0.9995397 0 0.03048759 0.9995352 0 0.03048747 0.9995352 0 -0.2293169 0.9733519 0 -0.2293152 0.9733522 0 -0.4733387 0.8808805 0 -0.4733368 0.8808817 0 -0.4733773 0.8808599 0 -0.4733775 0.8808596 0 -0.473384 0.8808562 0 -0.4733841 0.8808562 0 -0.4733778 0.8808596 0 -0.4733785 0.8808592 0 -0.9872968 0.1588873 0 -0.9872877 0.158944 0 -0.8643409 0.5029065 0 -0.8643492 0.5028921 0 -0.6267944 0.7791847 0 -0.6268133 0.7791696 0 -0.8730498 0.4876313 0 -0.8730585 0.4876155 0 -0.8726919 0.4882714 0 -0.8727021 0.4882531 0 -0.9565468 0.2915792 0 -0.9565446 0.2915859 0 -0.9563798 0.2921264 0 -0.9563738 0.2921461 0 -0.9965535 0.08295261 0 -0.9965558 0.08292496 0 -0.9965878 0.08254033 0 -0.996589 0.08252668 0 -0.5000072 0.8660213 0 -0.5000045 0.866023 0 -0.4999988 0.8660262 0 -0.4999992 0.8660259 0 -0.4999888 0.866032 0 -0.4999862 0.8660333 0 0.8879227 0.4599927 0 0.8879098 0.4600178 0 0.6002859 0.7997855 0 0.1938647 0.9810283 0 0.1938648 0.9810283 0 -0.2507705 0.9680466 0 -0.2507784 0.9680446 0 -0.6460956 0.7632566 0 -0.6461272 0.7632299 0 -0.91333 0.4072204 0 -0.91333 0.4072206 0 -0.9995783 -0.02903842 0 -0.9995774 -0.02907007 0 0.4999606 -0.8660483 0 0.4999604 -0.8660483 0 0.4999998 -0.8660256 0 0.4999983 -0.8660265 0 0.5000356 -0.8660049 0 0.5000328 -0.8660065 0 -0.8660485 -0.4999603 0 -0.9660491 -0.2583585 0 -0.9660492 0.2583583 0 0.7068321 0.7073814 0 0.966876 0.2552466 0 0.9669164 0.2550934 0 0.9656518 0.2598395 0 0.9656518 0.2598395 0 0.9660492 -0.2583583 0 0.9660364 -0.2584062 0 0.7068321 -0.7073814 0 0.7068576 -0.7073559 0 0.2588734 -0.9659113 0 -0.7076027 -0.7066105 0 -0.7076401 -0.7065731 0 -0.7052211 -0.7089875 0 -0.7051396 -0.7090685 0 -0.7068321 -0.7073814 0 -0.9660236 -0.2584539 0 -0.9660249 0.2584492 0 -0.9660376 0.2584017 0 -0.7068231 0.7073904 0 -0.7068742 0.7073393 0 -0.2589031 0.9659034 0 -0.2588647 0.9659137 0 0.2588775 0.9659103 0 0.2588774 0.9659103 0 0.7068487 0.7073649 0 0.7068742 0.7073393 0 0.9660377 0.2584015 0 0.9660376 0.2584017 0 0.9660365 -0.258406 0 0.7068832 -0.7073304 0 -0.258848 -0.9659182 0 -0.2588861 -0.9659079 0 0.7080851 -0.7061272 0 3.35638e-7 0 -1 -1.44367e-5 0 -1 1.04481e-6 0 -1 1.55775e-6 0 -1 -3.30802e-6 0 -1 -3.47578e-7 0 -1 6.36552e-7 0 -1 2.68457e-7 0 -1 2.04107e-6 0 -1 3.32348e-7 0 -1 8.94217e-7 0 -1 -1.63406e-6 0 -1 -1.38581e-4 0 -1 1.06343e-6 0 -1 1.9545e-5 0 -1 -1.35728e-6 0 -1 -3.73375e-5 0 -1 2.99388e-7 0 -1 -3.34627e-7 0 -1 -1.57133e-6 0 -1 1.26737e-7 0 -1 -7.18102e-6 0 -1 4.1388e-6 0 -1 -3.20045e-7 0 -1 -9.10823e-7 0 -1 5.90216e-6 0 -1 -4.33433e-6 0 -1 -2.41518e-7 0 -1 2.81231e-7 0 -1 -2.0427e-7 0 -1 -4.16167e-7 0 -1 6.90501e-7 0 -1 2.02069e-6 0 -1 -8.32379e-7 0 -1 1.65845e-6 0 -1 2.70776e-7 0 -1 -1.82095e-7 0 -1 5.12157e-7 0 -1 2.37154e-7 0 -1 -1.54995e-6 0 -1 2.20409e-6 0 -1 -9.61487e-7 0 -1 3.81773e-6 0 -1 4.73637e-7 0 -1 -2.53194e-7 0 -1 -1.48375e-6 0 -1 -1.49693e-6 0 -1 5.41285e-7 0 -1 -2.32461e-7 0 -1 1.61775e-7 0 -1 -6.95945e-7 0 -1 -1.15036e-6 0 -1 1.37298e-6 0 -1 -2.89513e-6 0 -1 1.98852e-6 0 -1 8.99852e-7 0 -1 -7.22065e-7 0 -1 -4.65764e-6 0 -1 -5.47157e-7 0 -1 4.0059e-7 0 -1 4.99366e-7 0 -1 1.19347e-6 0 -1 1.03299e-6 0 -1 -2.41586e-6 0 -1 -5.18167e-6 0 -1 4.1394e-6 0 -1 -7.08454e-6 0 -1 -1.08261e-6 0 -1 1.0917e-5 0 -1 -2.79592e-6 0 -1 1.24933e-6 0 -1 7.3519e-7 0 -1 -7.56155e-7 0 -1 1.56328e-6 0 -1 7.69431e-7 0 -1 -1.16494e-6 0 -1 2.51242e-7 0 -1 1.74541e-6 0 -1 1.02777e-6 0 -1 -3.31621e-7 0 -1 7.74118e-7 0 -1 4.11233e-7 0 -1 -8.73369e-7 0 -1 -1.14055e-6 0 -1 6.92951e-7 0 -1 -8.06597e-7 0 -1 -8.69553e-7 0 -1 1.33345e-6 0 -1 -1.42594e-6 0 -1 8.22607e-7 0 -1 -1.62585e-6 0 -1 -4.11222e-7 0 -1 2.10739e-5 0 -1 1.64544e-5 0 -1 2.61471e-7 0 -1 -1.74747e-6 0 -1 1.38205e-6 0 -1 3.0595e-7 0 -1 -7.92745e-7 0 -1 -1.13348e-6 0 -1 4.41052e-6 0 -1 -3.9482e-6 0 -1 2.1023e-6 0 -1 -1.75821e-7 0 -1 0 0 -1 -4.29191e-7 0 -1 1.40222e-6 0 -1 5.21466e-7 0 -1 -3.15361e-7 0 -1 2.11855e-7 0 -1 -2.91661e-7 0 -1 2.18653e-7 0 -1 -2.61994e-7 0 -1 2.06292e-6 0 -1 7.08616e-7 0 -1 0 0 -1 -3.96498e-7 0 -1 -4.07963e-7 0 -1 -6.71534e-7 0 -1 -2.06726e-6 0 -1 4.24603e-7 0 -1 -6.1515e-7 0 -1 -9.28567e-7 0 -1 0 0 -1 2.37938e-7 0 -1 3.0026e-7 0 -1 0 0 -1 0 0 -1 -6.49364e-7 0 -1 -7.71643e-7 0 -1 2.06291e-6 0 -1 1.08864e-6 0 -1 -2.58211e-6 0 -1 -1.43334e-6 0 -1 1.30096e-6 0 -1 -1.60047e-6 0 -1 7.03829e-7 0 -1 2.74278e-6 0 -1 9.86972e-6 0 -1 -1.12845e-6 0 -1 9.88142e-6 0 -1 -9.73892e-7 0 -1 3.51924e-6 0 -1 -2.17886e-6 0 -1 -1.61501e-6 0 -1 -1.30295e-6 0 -1 2.79757e-7 0 -1 -1.01334e-6 0 -1 -1.68094e-6 0 -1 2.85885e-6 0 -1 -3.06463e-6 0 -1 8.00195e-7 0 -1 -6.18589e-7 0 -1 1.80413e-6 0 -1 -9.00512e-6 0 -1 1.98738e-6 0 -1 4.13682e-7 0 -1 -7.71605e-7 0 -1 -1.47058e-7 0 -1 -1.75003e-6 0 -1 0 0 -1 1.82083e-6 0 -1 1.80477e-6 0 -1 2.3727e-6 0 -1 3.9674e-6 0 -1 8.33589e-7 0 -1 -4.91224e-7 0 -1 -2.71433e-6 0 -1 -7.61364e-7 0 -1 -7.77422e-7 0 -1 9.43155e-7 0 -1 -5.96863e-7 0 -1 2.37304e-6 0 -1 -5.10104e-6 0 -1 2.493e-6 0 -1 1.59533e-6 0 -1 2.13664e-7 0 -1 -1.3162e-6 0 -1 1.00633e-6 0 -1 -1.27496e-6 0 -1 -3.84688e-7 0 -1 -4.49627e-7 0 -1 -1.05647e-6 0 -1 0 0 -1 4.62425e-7 0 -1 -1.63623e-6 0 -1 1.99867e-6 0 -1 -2.59678e-7 0 -1 5.5657e-7 0 -1 7.61935e-7 0 -1 4.28405e-6 0 -1 -4.62419e-7 0 -1 -1.11259e-6 0 -1 2.16239e-6 0 -1 -5.93475e-7 0 -1 7.39873e-7 0 -1 2.05822e-6 0 -1 -9.00437e-7 0 -1 -6.1865e-7 0 -1 -1.21665e-7 0 -1 -3.00344e-6 0 -1 -4.41485e-6 0 -1 4.92643e-6 0 -1 1.30952e-6 0 -1 -9.87483e-7 0 -1 -1.76844e-6 0 -1 0 0 -1 -1.23518e-4 0 -1 0 0 -1 2.40361e-7 0 -1 -4.70796e-7 0 -1 -3.76737e-7 0 -1 -2.80471e-7 0 -1 2.08891e-6 0 -1 1.47066e-7 0 -1 1.69342e-7 0 -1 2.54918e-7 0 -1 2.8145e-7 0 -1 -3.62136e-7 0 -1 8.94887e-7 0 -1 3.27401e-7 0 -1 -7.82052e-7 0 -1 2.80776e-7 0 -1 -1.07619e-6 0 -1 -1.19801e-5 0 -1 7.33361e-7 0 -1 -7.51825e-7 0 -1 8.74285e-7 0 -1 2.41048e-6 0 -1 -5.46393e-7 0 -1 5.46431e-7 0 -1 -3.66647e-7 0 -1 7.33301e-7 0 -1 -1.33291e-6 0 -1 -2.94006e-7 0 -1 -1.28401e-6 0 -1 0 0 -1 9.22564e-7 0 -1 -2.45117e-6 0 -1 -7.4793e-7 0 -1 8.91723e-7 0 -1 -7.40017e-7 0 -1 -7.3059e-7 0 -1 -9.89135e-7 0 -1 7.39719e-7 0 -1 2.68407e-6 0 -1 7.61406e-7 0 -1 4.11222e-7 0 -1 1.47941e-6 0 -1 -8.65931e-7 0 -1 -5.56572e-7 0 -1 2.5957e-6 0 -1 -1.85946e-6 0 -1 -0.9660371 0.2584038 0 -0.966037 0.2584039 0 -0.7068787 0.7073348 0 -0.706853 0.7073605 0 -0.2588691 0.9659125 0 -0.2588691 0.9659125 0 0.2588819 0.965909 0 0.2588562 0.9659159 0 0.7080806 0.7061317 0 0.7080549 0.7061574 0 0.9649561 0.2624117 0 0.9649561 0.2624116 0 0.9654344 -0.2606463 0 0.7080595 -0.7061529 0 0.258848 -0.9659182 0 -0.7058935 -0.708318 0 -0.7058566 -0.7083548 0 -0.7090652 -0.705143 0 -0.7090653 -0.7051429 0 4.81507e-7 0 1 4.17865e-6 0 1 -1.68146e-6 0 1 4.09637e-7 0 1 -1.02189e-6 0 1 1.04687e-6 0 1 -4.25206e-6 0 1 1.80761e-6 0 1 -6.65821e-7 0 1 7.755e-7 0 1 -4.64919e-7 0 1 1.05794e-6 0 1 -7.04286e-7 0 1 3.03606e-7 0 1 -1.91073e-6 0 1 1.94522e-5 0 1 -2.96651e-6 0 1 5.42978e-7 0 1 5.6214e-7 0 1 -2.45965e-7 0 1 -1.63577e-6 0 1 7.43278e-7 0 1 7.01459e-5 0 1 2.11309e-4 0 1 2.11332e-4 0 1 2.11301e-4 0 1 5.06945e-7 0 1 -6.01104e-7 0 1 2.06984e-6 0 1 -2.06967e-6 0 1 -1.30416e-5 0 1 2.32392e-6 0 1 4.5097e-6 0 1 9.08108e-7 0 1 1.53255e-6 0 1 -3.10409e-6 0 1 -4.91283e-5 0 1 1.78571e-6 0 1 -1.14774e-5 0 1 -2.07307e-6 0 1 -4.04217e-7 0 1 -4.89564e-6 0 1 4.83036e-7 0 1 4.75778e-6 0 1 2.49714e-6 0 1 -6.7153e-7 0 1 1.35388e-6 0 1 -8.2971e-6 0 1 4.51208e-7 0 1 -3.69912e-6 0 1 -4.84684e-6 0 1 2.61492e-6 0 1 0 0 1 1.48375e-6 0 1 -1.80319e-6 0 1 3.11379e-6 0 1 5.79726e-7 0 1 -3.26832e-7 0 1 -1.61775e-7 0 1 3.00262e-7 0 1 -6.23659e-6 0 1 -1.99591e-6 0 1 4.23749e-6 0 1 -3.58356e-6 0 1 -8.89528e-7 0 1 1.92355e-6 0 1 3.30613e-6 0 1 4.67199e-7 0 1 1.54934e-6 0 1 -1.19347e-6 0 1 -9.49399e-7 0 1 -8.27897e-6 0 1 2.33617e-5 0 1 -2.26696e-5 0 1 1.09471e-6 0 1 7.49834e-7 0 1 -3.2032e-6 0 1 1.00546e-6 0 1 2.19648e-5 0 1 -6.06687e-7 0 1 9.78933e-6 0 1 2.49865e-6 0 1 9.93388e-7 0 1 -1.14114e-6 0 1 -8.188e-6 0 1 -2.54073e-7 0 1 -1.95241e-6 0 1 7.84414e-7 0 1 1.47042e-6 0 1 -2.24347e-6 0 1 2.97975e-6 0 1 -4.76229e-6 0 1 -2.00995e-6 0 1 2.05164e-6 0 1 -8.69166e-7 0 1 1.85755e-6 0 1 -9.73763e-7 0 1 -3.28844e-6 0 1 1.62892e-6 0 1 -4.06462e-6 0 1 1.70147e-6 0 1 -1.64521e-6 0 1 8.88036e-7 0 1 -2.41979e-6 0 1 -1.15185e-6 0 1 7.74512e-7 0 1 2.28111e-6 0 1 -2.77483e-6 0 1 3.22587e-6 0 1 -2.09331e-6 0 1 4.00764e-7 0 1 -1.33291e-6 0 1 -1.47017e-6 0 1 5.28957e-6 0 1 -7.41681e-7 0 1 2.59562e-6 0 1 1.40127e-6 0 1 -8.11733e-7 0 1 8.32408e-6 0 1 5.12549e-7 0 1 2.35405e-7 0 1 -1.21131e-6 0 1 4.08203e-7 0 1 9.51753e-7 0 1 -5.46445e-6 0 1 0 0 1 9.00911e-7 0 1 -3.69422e-6 0 1 2.95322e-6 0 1 -3.37878e-7 0 1 -2.08934e-6 0 1 1.38891e-7 0 1 0 0 1 0 0 1 -2.60733e-7 0 1 -5.55523e-7 0 1 0 0 1 -4.19961e-7 0 1 -1.20706e-7 0 1 -1.26844e-6 0 1 1.43064e-7 0 1 -6.00598e-7 0 1 5.12465e-7 0 1 -3.51639e-7 0 1 7.14706e-7 0 1 -2.17592e-6 0 1 9.19653e-7 0 1 -1.71986e-6 0 1 3.81441e-6 0 1 -6.9461e-5 0 1 1.6003e-6 0 1 3.09319e-7 0 1 0 0 1 1.43574e-6 0 1 -7.63219e-6 0 1 7.8964e-5 0 1 -6.12865e-6 0 1 5.52196e-6 0 1 -1.59337e-4 0 1 3.23155e-6 0 1 2.68167e-6 0 1 1.31973e-6 0 1 -4.94071e-6 0 1 -1.73739e-6 0 1 -1.37184e-6 0 1 2.4217e-6 0 1 -3.55305e-6 0 1 5.84887e-7 0 1 6.15358e-7 0 1 4.71413e-6 0 1 8.06586e-6 0 1 6.36997e-7 0 1 -2.32657e-6 0 1 1.57193e-5 0 1 1.8334e-7 0 1 2.6208e-6 0 1 -1.64071e-6 0 1 -3.28975e-7 0 1 -5.4143e-7 0 1 1.71917e-6 0 1 2.54225e-7 0 1 -1.00627e-5 0 1 -1.73933e-4 0 1 -2.86079e-6 0 1 -5.81754e-7 0 1 0 0 1 -7.83298e-6 0 1 2.22629e-6 0 1 -9.99424e-7 0 1 -1.52258e-6 0 1 3.04562e-6 0 1 -1.99864e-6 0 1 -3.96574e-6 0 1 2.53612e-6 0 1 -1.64374e-6 0 1 2.37819e-7 0 1 1.73047e-6 0 1 1.61605e-6 0 1 1.11263e-6 0 1 -7.67644e-7 0 1 -1.49586e-6 0 1 1.49586e-6 0 1 -1.53352e-6 0 1 1.53395e-6 0 1 1.56309e-7 0 1 6.60417e-7 0 1 3.98398e-7 0 1 1.0755e-6 0 1 -7.01769e-7 0 1 6.04765e-7 0 1 9.89315e-7 0 1 -2.19255e-6 0 1 2.9209e-6 0 1 -1.47895e-6 0 1 4.37744e-6 0 1 5.72393e-7 0 1 1.49921e-6 0 1 7.33293e-7 0 1 1.42549e-6 0 1 -1.7474e-6 0 1 -1.98738e-6 0 1 3.60231e-5 0 1 -1.53247e-6 0 1 3.09304e-7 0 1 -6.55715e-7 0 1 2.45192e-6 0 1 -9.5778e-7 0 1 -3.18722e-7 0 1 -2.73212e-7 0 1 1.53244e-6 0 1 1.5433e-7 0 1 -6.57845e-7 0 1 -1.46671e-6 0 1 2.39188e-7 0 1 -2.80776e-7 0 1 -1.35659e-6 0 1 1.80879e-6 0 1 -5.65375e-7 0 1 1.13076e-6 0 1 -3.14347e-7 0 1 -1.22728e-5 0 1 -2.98416e-6 0 1 2.80472e-7 0 1 -7.58311e-6 0 1 -3.11143e-6 0 1 1.97497e-6 0 1 -5.97019e-7 0 1 -3.54844e-7 0 1 -4.86656e-7 0 1 6.82412e-7 0 1 -6.82413e-7 0 1 1.26282e-6 0 1 2.15428e-7 0 1 5.09696e-7 0 1 -3.38807e-7 0 1 -2.88422e-6 0 1 -7.80567e-6 0 1 0 0 1 9.86912e-7 0 1 -5.97597e-7 0 1 4.40217e-7 0 1 -1.76825e-6 0 1 -2.19012e-6 0 1 0 0 1 8.09169e-7 0 1 -1.49668e-6 0 1 1.49668e-6 0 1 -1.53434e-6 0 1 1.53384e-6 0 1 8.51058e-7 0 1 -1.87294e-6 0 1 2.19298e-5 0 1 9.99392e-7 0 1 1.52259e-6 0 1 -7.61341e-7 0 1 -2.03653e-6 0 1 -5.07957e-7 0 1 -2.22628e-6 0 1 1.61698e-6 0 1 2.77346e-6 0 1 -2.88319e-6 0 1 -9.40175e-7 0 1 1.84971e-6 0 1 -9.24843e-7 0 1 9.40543e-7 0 1 8.33108e-7 0 1 -4.16556e-7 0 1 -1.03421e-5 0 1 2.05015e-6 0 1 -1.05647e-6 0 1 -1.27496e-6 0 1 0.7071155 -0.7070981 0 0.7071701 -0.7070435 0 0.9662145 -0.2577393 0 0.9662418 -0.2576372 0 0.9662405 0.2576422 0 0.9662134 0.2577438 0 -0.8627765 0.5055857 0 -0.8627761 0.5055863 0 -0.8628522 0.5054565 0 -0.7421805 0.6702001 0 -0.7421823 0.6701981 0 -0.419853 0.9075921 0 -0.4198529 0.9075923 0 -0.02646881 0.9996497 0 -0.02646869 0.9996497 0 0.3704937 0.928835 0 0.3704918 0.9288358 0 0.8613826 0.5079569 0 0.8613688 0.50798 0 0.8613331 0.5080408 0 0.8613327 0.5080416 0 0.8613501 0.5080119 0 0.6706242 0.7417973 0 0.670624 0.7417976 0 0.6701797 0.7421988 0 0.6701796 0.742199 0 0.9906274 0.136592 0 0.9906274 0.136592 0 0.9390242 -0.3438512 0 0.6680041 -0.7441577 0 0.2427743 -0.9700829 0 0.2427723 -0.9700833 0 -0.7185696 -0.6954551 0 -0.7185691 -0.6954557 0 -0.7185857 -0.6954385 0 -0.7185862 -0.6954379 0 -0.718105 -0.6959348 0 -0.7181062 -0.6959336 0 -0.2461776 -0.9692248 0 -0.2461783 -0.9692246 0 -0.6791999 -0.7339534 0 -0.679198 -0.7339552 0 0.7073631 -0.7068505 0 0.7073632 -0.7068503 0 0.7068586 -0.7073549 0 0.7071556 -0.707058 0 0.7070215 -0.707192 0 0.707022 -0.7071916 0 -0.2600306 -0.9656004 0 -0.9659268 -0.2588157 0 -0.9659267 -0.2588159 0 -0.7062785 -0.7079341 0 -0.7062816 -0.7079311 0 -0.7066475 -0.7075658 0 -0.7066474 -0.7075659 0 -0.2600301 -0.9656006 0 -0.7776544 0.6286922 0 -0.777561 0.6288075 0 -0.7775608 0.6288077 0 -0.6290091 0.7773981 0 -0.6290088 0.7773983 0 -0.6285849 0.7777411 0 -0.6285851 0.7777408 0 -0.9692721 0.2459912 0 -0.735916 0.677073 0 -0.7359184 0.6770703 0 -0.7320664 0.6812334 0 -0.732066 0.6812337 0 -0.9692721 0.2459913 0 0.7181062 -0.6959336 0 0.718105 -0.6959348 0 0.7185862 -0.695438 0 0.7185858 -0.6954384 0 0.7185691 -0.6954557 0 0.7185696 -0.6954551 0 0.6791981 -0.7339551 0 0.6791997 -0.7339535 0 0.2461784 -0.9692245 0 0.2461774 -0.9692248 0 -0.2427725 -0.9700833 0 -0.242774 -0.9700829 0 -0.6680041 -0.7441577 0 -0.9390242 -0.3438512 0 -0.9906274 0.136592 0 -0.9906274 0.136592 0 -0.6702416 0.742143 0 -0.8613826 0.5079569 0 -0.8613688 0.50798 0 -0.8613392 0.5080305 0 -0.8613394 0.5080301 0 -0.6702419 0.7421427 0 -0.3704922 0.9288356 0 -0.3704934 0.9288352 0 0.02646869 0.9996497 0 0.02646881 0.9996497 0 0.419853 0.9075921 0 0.4198529 0.9075923 0 0.7421827 0.6701977 0 0.7421801 0.6702005 0 0.8627765 0.5055857 0 0.8627761 0.5055863 0 0.8628522 0.5054565 0 -0.9807795 -0.1951197 0 -0.8310348 -0.5562204 0 -0.8310422 -0.5562096 0 -0.8315398 -0.5554652 0 -0.8315498 -0.5554502 0 -0.9807795 -0.1951198 0 -0.7071278 -0.7070859 0 -0.7071275 -0.7070861 0 -0.7070215 -0.707192 0 -0.707022 -0.7071916 0 -0.1947845 -0.9808462 0 -0.5565781 -0.8307954 0 -0.5565532 -0.830812 0 -0.5565533 -0.8308119 0 -0.1947853 -0.980846 0 0.9692721 0.2459913 0 0.7359158 0.6770731 0 0.7359185 0.6770702 0 0.732066 0.6812337 0 0.7320664 0.6812334 0 0.9692721 0.2459912 0 0.6285849 0.7777411 0 0.6285851 0.7777408 0 0.6290091 0.7773981 0 0.6290088 0.7773983 0 0.777561 0.6288075 0 0.7775608 0.6288077 0 0.7776544 0.6286922 0 -0.2586198 -0.9659793 0 -0.2586199 -0.9659793 0 -0.2624969 -0.9649329 0 -0.2624957 -0.9649332 0 -0.7070735 -0.7071402 0 -0.7070735 -0.70714 0 -0.7075747 -0.7066386 0 -0.7075699 -0.7066434 0 -0.7069999 -0.7072136 0 -0.7070001 -0.7072136 0 -0.9659135 -0.2588653 0 -0.9659581 -0.258699 0 -0.9659584 -0.258698 0 -0.9659556 0.2587081 0 -0.9659554 0.2587087 0 -0.965914 0.2588633 0 -0.965914 0.2588632 0 -0.7069999 0.7072136 0 -0.7070001 0.7072136 0 -0.7076251 0.7065881 0 -0.7076302 0.706583 0 -0.7070692 0.7071444 0 -0.7070695 0.7071441 0 -0.2623885 0.9649624 0 -0.2623898 0.964962 0 -0.2586341 0.9659754 0 -0.2586342 0.9659754 0 0.2590766 0.9658568 0 0.2590765 0.9658568 0 0.7070692 0.7071443 0 0.7070695 0.7071442 0 0.7071083 0.7071053 0 0.7071084 0.7071052 0 0.965914 0.2588633 0 0.965914 0.2588632 0 0.9659554 0.258709 0 0.9659557 0.2587079 0 0.9659582 -0.2586982 0 0.9659581 -0.2586988 0 0.9659135 -0.2588653 0 0.7070987 -0.7071149 0 0.7070989 -0.7071148 0 0.7070733 -0.7071402 0 0.7070736 -0.70714 0 0.2590766 -0.9658568 0 0.2590765 -0.9658568 0 -0.8314065 0.5556646 0 -0.9805756 0.1961422 0 -0.9805881 0.1960791 0 -0.9808087 0.1949726 0 -0.9808097 0.1949679 0 -0.8314054 0.5556663 0 -0.7071042 0.7071095 0 -0.7071043 0.7071093 0 -0.7045564 0.709648 0 -0.7045901 0.7096146 0 -0.7071889 0.7070247 0 -0.7071897 0.7070239 0 -0.7071194 0.7070942 0 -0.7071197 0.7070939 0 -0.7067946 0.7074189 0 -0.7067947 0.7074188 0 -0.5553848 0.8315936 0 -0.1977305 0.9802565 0 -0.1977273 0.980257 0 -0.1954591 0.9807119 0 -0.1954588 0.980712 0 -0.5553844 0.8315937 0 0.5553849 0.8315934 0 0.1977305 0.9802565 0 0.1977273 0.980257 0 0.1954592 0.9807119 0 0.1954587 0.980712 0 0.5553842 0.8315939 0 0.7070834 0.7071302 0 0.7070835 0.7071301 0 0.7071072 0.7071064 0 0.8314064 0.5556647 0 0.9805755 0.1961423 0 0.9805882 0.196079 0 0.9808088 0.1949726 0 0.9808097 0.194968 0 0.8314056 0.5556662 0 0.9769152 -0.2136272 0 0.9769158 -0.2136251 0 0.5698024 -0.8217818 0 0.5698021 -0.8217821 0 0.7309467 -0.6824347 0 0.7309464 -0.682435 0 0.858961 -0.5120411 0 0.8589607 -0.5120416 0 0.9882984 -0.1525334 0 0.9882984 -0.1525334 0 0.8674688 -0.4974917 0 0.8674682 -0.4974926 0 0.6314434 -0.775422 0 0.6314428 -0.7754225 0 0.9995359 0.03046476 0 0.9995358 0.03046488 0 0.9995357 0.03046882 0 0.9995357 0.03046882 0 0.9995358 0.03046828 0 0.9995357 0.03046822 0 0.9995358 0.03046798 0 0.9995357 0.03046798 0 0.9575974 0.2881099 0 0.9575974 0.2881101 0 0.850393 0.526148 0 0.8503397 0.5262343 0 0.8503393 0.5262349 0 0.5000005 -0.8660251 0 -0.4999908 -0.8660307 0 -0.4999897 -0.8660314 0 -0.4999879 -0.8660324 0 -0.4999882 -0.8660323 0 -0.5000067 -0.8660216 0 -0.5000069 -0.8660215 0 -0.850381 0.5261676 0 -0.85038 0.526169 0 -0.8504589 0.5260416 0 -0.8504588 0.5260418 0 -0.8503708 0.526184 0 -0.8503707 0.5261842 0 -0.8502964 0.5263043 0 -0.8502972 0.5263028 0 -0.9575974 0.2881099 0 -0.9575974 0.2881101 0 -0.9995358 0.03046798 0 -0.9995357 0.03046798 0 -0.9995358 0.03046822 0 -0.9995357 0.03046828 0 -0.9995357 0.03046882 0 -0.9995357 0.03046882 0 -0.9995359 0.03046494 0 -0.9995359 0.03046476 0 -0.6314428 -0.7754225 0 -0.6314434 -0.775422 0 -0.8674682 -0.4974926 0 -0.8674688 -0.4974917 0 -0.9882984 -0.1525334 0 -0.9882984 -0.1525334 0 -0.5696805 -0.8218664 0 -0.5696801 -0.8218666 0 -0.570296 -0.8214393 0 -0.730676 -0.6827244 0 -0.7310388 -0.682336 0 -0.8589252 -0.5121011 0 -0.8589246 -0.5121023 0 -0.858992 -0.511989 0 -0.858992 -0.5119892 0 -0.9769158 -0.2136253 0 -0.9769154 -0.213627 0 -0.2584262 -0.966031 0 -0.2584257 -0.9660311 0 -0.9659264 -0.2588174 0 -0.965927 -0.2588146 0 -0.9659223 0.2588323 0 -0.9659214 0.2588355 0 -0.7073445 0.7068691 0 -0.7073435 0.70687 0 -0.2584258 0.9660311 0 -0.2584261 0.9660311 0 0.2584258 0.9660311 0 0.2584261 0.9660311 0 0.7073445 0.7068691 0 0.7073435 0.70687 0 0.9659219 0.2588338 0 0.9659222 0.2588326 0 0.9659271 -0.2588144 0 0.9659267 -0.2588161 0 0.2583921 -0.9660401 0 -0.2583926 -0.96604 0 -0.2583921 -0.9660401 0 -0.7073347 -0.7068789 0 -0.7073353 -0.7068783 0 -0.9659251 -0.2588219 0 -0.9659258 -0.2588191 0 -0.9659247 0.2588233 0 -0.9659239 0.2588266 0 -0.7073265 0.706887 0 -0.7073255 0.706888 0 0.7073265 0.706887 0 0.7073255 0.706888 0 0.9659243 0.2588248 0 0.9659246 0.2588236 0 0.9659259 -0.2588189 0 0.9659255 -0.2588205 0 0.7073347 -0.7068789 0 0.7073353 -0.7068783 0 0.2583926 -0.96604 0 -3.7794e-6 0 1 -7.55344e-6 0 1 1.80944e-6 0 1 -7.7554e-7 0 1 1.84633e-6 0 1 1.76199e-6 0 1 -6.07156e-7 0 1 -5.93725e-6 0 1 2.16999e-6 0 1 3.47869e-7 0 1 -7.67573e-7 0 1 4.77902e-6 0 1 -7.11764e-6 0 1 1.89611e-5 0 1 1.24019e-5 0 1 -1.60255e-6 0 1 6.79532e-7 0 1 1.76772e-6 0 1 -6.64865e-7 0 1 4.52014e-6 0 1 1.81372e-6 0 1 -5.81864e-6 0 1 1.45652e-6 0 1 -4.09774e-6 0 1 2.08075e-7 0 1 5.13471e-7 0 1 -9.51321e-6 0 1 6.49854e-6 0 1 1.9886e-5 0 1 -4.30424e-6 0 1 -1.86994e-6 0 1 1.08276e-6 0 1 2.96861e-6 0 1 -1.15968e-6 0 1 6.47179e-7 0 1 9.78091e-7 0 1 -3.11876e-6 0 1 -3.2857e-6 0 1 1.92507e-6 0 1 3.42616e-6 0 1 -8.66131e-6 0 1 -2.47024e-6 0 1 1.4937e-6 0 1 7.76179e-7 0 1 -1.03509e-6 0 1 5.29679e-7 0 1 5.02755e-7 0 1 -5.17573e-7 0 1 1.09895e-5 0 1 -2.30137e-6 0 1 2.32892e-6 0 1 -6.29594e-5 0 1 9.82048e-6 0 1 7.80049e-6 0 1 2.3008e-6 0 1 -3.0079e-5 0 1 6.81368e-7 0 1 -5.39092e-6 0 1 -1.2006e-7 0 1 3.0324e-6 0 1 -3.41113e-5 0 1 -6.03865e-6 0 1 2.93979e-6 0 1 -7.70434e-6 0 1 2.24099e-6 0 1 1.6272e-6 0 1 -1.62729e-6 0 1 -1.64467e-6 0 1 7.67955e-7 0 1 -1.54233e-6 0 1 5.70006e-7 0 1 2.1384e-5 0 1 -7.12803e-7 0 1 -8.50201e-7 0 1 -4.01994e-6 0 1 1.41774e-5 0 1 2.50467e-6 0 1 -9.05835e-6 0 1 4.01999e-6 0 1 1.53042e-7 0 1 -1.01144e-6 0 1 -1.41774e-5 0 1 -7.89062e-7 0 1 7.89062e-7 0 1 -6.56153e-6 0 1 4.83994e-6 0 1 1.4775e-6 0 1 1.18137e-6 0 1 -1.93378e-7 0 1 0 0 1 -9.2846e-7 0 1 -1.38114e-6 0 1 2.26992e-6 0 1 -2.52288e-6 0 1 -1.63883e-5 0 1 1.45675e-6 0 1 -1.58802e-6 0 1 -3.12188e-6 0 1 -7.71538e-7 0 1 -4.3592e-6 0 1 -1.26733e-5 0 1 1.03267e-5 0 1 -9.91494e-5 0 1 -7.09047e-6 0 1 3.23558e-5 0 1 -2.14491e-5 0 1 5.27961e-6 0 1 -3.47457e-6 0 1 2.74907e-6 0 1 6.97589e-6 0 1 -1.58535e-4 0 1 -8.40531e-7 0 1 1.94614e-6 0 1 -1.58355e-6 0 1 -1.83363e-5 0 1 -1.77673e-4 0 1 -1.77672e-4 0 1 -1.7767e-4 0 1 -1.94775e-6 0 1 -7.10434e-6 0 1 4.20536e-6 0 1 7.61522e-6 0 1 7.61513e-6 0 1 -4.10164e-6 0 1 8.38403e-6 0 1 3.61664e-7 0 1 1.52702e-5 0 1 -7.48834e-6 0 1 -3.97547e-6 0 1 2.50041e-6 0 1 3.41113e-5 0 1 1.52386e-6 0 1 4.03367e-7 0 1 2.36897e-5 0 1 -1.20913e-4 0 1 -4.32601e-6 0 1 4.90467e-6 0 1 -4.51505e-6 0 1 -3.14112e-5 0 1 -1.16355e-6 0 1 6.18772e-6 0 1 -1.28277e-6 0 1 1.46762e-6 0 1 -2.22404e-6 0 1 6.87523e-7 0 1 -7.95707e-7 0 1 1.99942e-6 0 1 1.53515e-6 0 1 -2.28144e-6 0 1 -1.97813e-6 0 1 7.3635e-5 0 1 7.36348e-5 0 1 7.36346e-5 0 1 3.97446e-6 0 1 4.27893e-6 0 1 1.05574e-6 0 1 -1.56113e-5 0 1 -1.48262e-6 0 1 5.90756e-6 0 1 1.55551e-6 0 1 1.96108e-5 0 1 -3.99962e-7 0 1 4.32601e-6 0 1 -1.19411e-6 0 1 -7.61519e-6 0 1 -7.61513e-6 0 1 5.7723e-6 0 1 -5.51903e-6 0 1 3.78881e-6 0 1 -1.56054e-6 0 1 3.86234e-6 0 1 4.4752e-7 0 1 -4.4128e-7 0 1 -7.3635e-5 0 1 -7.36345e-5 0 1 -7.36348e-5 0 1 4.37512e-5 0 1 -2.41616e-6 0 1 -2.55843e-6 0 1 -5.11676e-6 0 1 2.48316e-6 0 1 -0.2583923 -0.9660401 0 -0.2583925 -0.96604 0 -0.7073355 -0.706878 0 -0.7073345 -0.706879 0 -0.9659255 -0.2588204 0 -0.9659243 0.2588251 0 0.2552981 0.9668624 0 0.2552993 0.9668621 0 0.2598447 0.9656504 0 0.9659239 0.2588264 0 0.965925 -0.258822 0 0.7073355 -0.706878 0 0.2551904 -0.9668908 0 0.2551916 -0.9668905 0 0.2598447 -0.9656504 0 0.7073345 -0.706879 0 -2.22412e-6 0 -1 -7.25991e-6 0 -1 -6.23511e-6 0 -1 1.76199e-6 0 -1 -6.35809e-7 0 -1 1.84633e-6 0 -1 -7.7554e-7 0 -1 6.65846e-7 0 -1 2.15131e-6 0 -1 2.33538e-6 0 -1 -3.79455e-6 0 -1 3.10166e-7 0 -1 -1.0285e-5 0 -1 1.93955e-6 0 -1 -4.53431e-7 0 -1 -3.94659e-6 0 -1 -1.32973e-6 0 -1 -3.34561e-7 0 -1 -8.01282e-7 0 -1 1.98845e-5 0 -1 4.54539e-6 0 -1 -1.00731e-5 0 -1 4.74315e-7 0 -1 -2.26992e-6 0 -1 -3.32918e-6 0 -1 2.68592e-6 0 -1 2.76231e-6 0 -1 2.52602e-7 0 -1 -2.08075e-7 0 -1 4.09774e-6 0 -1 3.24927e-6 0 -1 -5.1214e-6 0 -1 2.04888e-6 0 -1 -5.11968e-7 0 -1 1.55029e-6 0 -1 -1.55946e-6 0 -1 3.32031e-6 0 -1 7.65088e-6 0 -1 -3.26845e-7 0 -1 4.98934e-7 0 -1 2.47268e-5 0 -1 -3.47869e-7 0 -1 8.18264e-6 0 -1 1.03027e-6 0 -1 -7.36543e-6 0 -1 -8.99067e-7 0 -1 -8.28001e-6 0 -1 1.00619e-5 0 -1 -4.10457e-7 0 -1 1.60255e-6 0 -1 -5.17543e-7 0 -1 -1.71311e-6 0 -1 4.58399e-7 0 -1 -1.79244e-6 0 -1 3.70537e-6 0 -1 3.24799e-6 0 -1 7.80031e-6 0 -1 -3.01932e-6 0 -1 -5.59775e-5 0 -1 -9.00452e-7 0 -1 -1.68467e-6 0 -1 -8.22325e-7 0 -1 3.83977e-7 0 -1 2.12571e-7 0 -1 -6.34837e-6 0 -1 3.56402e-7 0 -1 -1.62729e-6 0 -1 -1.6272e-6 0 -1 -1.31101e-6 0 -1 -8.08434e-7 0 -1 4.72581e-6 0 -1 -2.8124e-7 0 -1 -1.18359e-6 0 -1 1.18359e-6 0 -1 -1.45831e-7 0 -1 1.41885e-7 0 -1 -3.78132e-6 0 -1 2.73236e-6 0 -1 -1.18137e-6 0 -1 -2.56736e-7 0 -1 2.3783e-6 0 -1 -1.72644e-6 0 -1 -3.26377e-6 0 -1 7.08597e-7 0 -1 -2.46082e-6 0 -1 2.0996e-7 0 -1 4.82432e-7 0 -1 -3.84612e-7 0 -1 1.94498e-6 0 -1 -4.16223e-6 0 -1 3.96598e-5 0 -1 8.55786e-6 0 -1 -7.56315e-6 0 -1 -1.43338e-7 0 -1 3.31474e-6 0 -1 6.45421e-7 0 -1 1.94858e-6 0 -1 -3.96346e-5 0 -1 7.79107e-6 0 -1 -2.70625e-6 0 -1 -1.32874e-6 0 -1 -4.47646e-6 0 -1 4.14772e-6 0 -1 -4.82991e-6 0 -1 1.53989e-6 0 -1 -2.98084e-6 0 -1 -1.65467e-6 0 -1 -1.85705e-6 0 -1 -3.64069e-6 0 -1 2.35081e-6 0 -1 1.89659e-6 0 -1 -8.75013e-6 0 -1 4.27185e-6 0 -1 1.66694e-6 0 -1 -3.95366e-6 0 -1 8.41267e-6 0 -1 -8.65202e-7 0 -1 -1.0768e-6 0 -1 1.49264e-6 0 -1 6.93965e-6 0 -1 -1.06217e-6 0 -1 9.81601e-7 0 -1 6.59604e-7 0 -1 -1.81212e-6 0 -1 5.11676e-6 0 -1 2.55843e-6 0 -1 -6.0404e-7 0 -1 3.25453e-6 0 -1 8.22336e-7 0 -1 7.56317e-6 0 -1 -4.27893e-6 0 -1 1.41578e-6 0 -1 -1.49264e-6 0 -1 -6.53955e-7 0 -1 2.28571e-6 0 -1 -2.17467e-6 0 -1 8.84255e-7 0 -1 -2.81187e-7 0 -1 -5.1857e-7 0 -1 -8.91399e-7 0 -1 1.41307e-6 0 -1 1.85705e-6 0 -1 -1.82925e-6 0 -1 -3.70829e-6 0 -1 1.11425e-6 0 -1 -7.80269e-7 0 -1 -3.41299e-6 0 -1 3.55218e-6 0 -1 4.04138e-6 0 -1 5.59775e-5 0 -1 -1.33323e-6 0 -1 2.50467e-6 0 -1 1.36226e-7 0 -1 -5.89084e-7 0 -1 -2.76509e-4 0 -1 9.99696e-7 0 -1 1.3752e-6 0 -1 -3.97823e-7 0 -1 -2.06097e-7 0 -1 1.47853e-6 0 -1 -7.33794e-7 0 -1 3.43762e-7 0 -1 -5.5602e-7 0 -1 0.376633 0.9263626 0 0.3766328 0.9263626 0 0.7677282 0.6407757 0 0.7677857 0.6407067 0 0.9783365 0.2070211 0 0.9611763 -0.2759351 0 0.9611454 -0.2760432 0 -0.00890541 0.9999604 0 -0.00890541 0.9999604 0 -0.009263992 0.9999571 0 -0.009264171 0.9999571 0 -0.009231865 0.9999574 0 -0.009232103 0.9999574 0 -0.3080065 0.9513843 0 -0.3080062 0.9513844 0 -0.3076462 0.9515009 0 -0.3076429 0.951502 0 -0.9514547 -0.307789 0 -0.9514546 -0.307789 0 -0.9960013 0.08934009 0 -0.9960012 0.08934015 0 -0.8778049 0.4790185 0 -0.8778048 0.4790186 0 -0.6195968 0.7849203 0 -0.6196648 0.7848666 0 -0.8691963 -0.4944674 0 -0.8691038 -0.4946299 0 -0.8691036 -0.49463 0 0.1898669 -0.9818099 0 0.1898667 -0.9818099 0 -0.3022273 -0.9532359 0 -0.7208702 -0.6930702 0 -0.7209847 -0.692951 0 0.243322 -0.9699456 0 0.2433102 -0.9699486 0 0.2430786 -0.9700067 0 0.2430785 -0.9700067 0 0.2431836 -0.9699803 0 0.2431837 -0.9699803 0 0.7162198 -0.6978748 0 0.7162768 -0.6978163 0 0.2957676 -0.95526 0 0.2957999 -0.95525 0 0.8660476 -0.4999614 0 0.8660475 -0.4999619 0 0.8660162 -0.500016 0 0.8660018 -0.500041 0 0.8659592 -0.5001148 0 0.9657977 0.2592973 0 0.96579 0.2593259 0 0.9659417 0.2587597 0 0.9659419 0.2587596 0 0.9659514 0.2587239 0 0.9659497 0.2587302 0 0.9658831 0.2589787 0 0.9658901 0.2589525 0 0.7517384 -0.6594615 0 -0.3213573 -0.946958 0 -0.3213574 -0.9469581 0 0.06832122 -0.9976634 0 0.06832128 -0.9976634 0 0.4380546 -0.8989484 0 0.4380543 -0.8989486 0 0.4408188 -0.8975962 0 0.4407517 -0.8976292 0 -0.8660556 0.4999478 0 -0.8660621 0.4999367 0 -0.8660423 0.4999708 0 -0.8660423 0.4999707 0 -0.8659929 0.5000565 0 -0.9627466 0.2704051 0 -0.9627169 0.2705112 0 -0.9659086 -0.2588835 0 -0.9659086 -0.2588837 0 -0.9660425 -0.2583832 0 -0.9660501 -0.2583552 0 -0.9658513 -0.2590971 0 -0.9658513 -0.2590972 0 -0.6975839 -0.7165032 0 -0.9548214 -0.2971806 0 -0.954827 -0.2971621 0 -0.954827 -0.2971621 0 -0.954827 -0.2971621 0 -0.9558768 -0.2937679 0 -0.9558768 -0.2937681 0 -0.5000936 -0.8659714 0 -0.5000979 -0.865969 0 -0.5005142 -0.8657283 0 -0.500514 -0.8657285 0 0.7334385 -0.6797559 0 0.7334078 -0.679789 0 0.3653654 -0.9308643 0 0.3653861 -0.9308561 0 -0.07536369 -0.9971562 0 -0.07535904 -0.9971565 0 -0.5003633 -0.8658156 0 -0.5003365 -0.8658311 0 -0.8255522 -0.5643258 0 -0.8254949 -0.5644098 0 -0.988811 -0.1491742 0 -0.98882 -0.1491144 0 -0.9552585 0.2957722 0 -0.9552758 0.2957162 0 -0.707101 0.7071126 0 -0.2592152 0.9658196 0 0.2592018 0.9658232 0 0.9658129 0.2592403 0 0.9658128 0.2592405 0 0.9658129 -0.2592403 0 0.9658128 -0.2592405 0 -0.8660162 0.5000162 0 -0.8660284 0.4999948 0 0.2406362 0.9706155 0 0.6753469 0.7375003 0 0.6754037 0.7374482 0 0.9456494 0.3251883 0 0.9456845 0.3250858 0 0.9616532 0.2742684 0 0.9616628 0.2742348 0 0.9615196 0.2747363 0 0.9615272 0.2747098 0 0.9616441 0.2743004 0 0.9616572 0.2742545 0 0.9750267 0.2220877 0 0.9627452 -0.2704103 0 0.8660656 -0.4999305 0 0.8660619 -0.4999368 0 0.7180514 -0.69599 0 0.3112795 -0.9503184 0 0.3112794 -0.9503184 0 -0.1742753 -0.984697 0 -0.1742552 -0.9847006 0 -0.6118414 -0.7909805 0 -0.6118129 -0.7910025 0 -0.9778638 -0.2092424 0 -0.8722184 -0.4891169 0 -0.870545 -0.4920889 0 -0.8705471 -0.4920852 0 -0.9778639 -0.2092424 0 -0.9898316 0.1422441 0 -0.989812 0.1423816 0 -0.852786 0.5222605 0 -0.5781546 0.8159273 0 -0.5780883 0.8159742 0 -0.208164 0.9780941 0 -0.2081354 0.9781 0 -0.006864786 0.9999765 0 -0.006864666 0.9999765 0 -0.006194174 0.9999809 0 -0.006194114 0.9999809 0 0.2588173 -0.9659264 0 0.2588185 -0.965926 0 0.2583601 -0.9660487 0 0.2583599 -0.9660488 0 0.9976728 0.06818389 0 0.9976614 0.06834989 0 0.9976614 0.06834983 0 0.9976614 0.06834989 0 0.9989212 0.04643911 0 0.9989211 0.04643934 0 0.9989211 0.04643952 0 0.9989156 0.04655939 -2.17874e-7 0.9989156 0.04655945 0 0.9989156 0.04655939 0 0.8964562 0.4431326 0 0.8964562 0.4431325 0 0.6594793 0.7517228 0 0.6594796 0.7517225 0 0.5005379 0.8657147 0 0.5005037 0.8657345 0 0.4999193 0.8660721 0 -0.258877 0.9659103 0 -0.2583681 0.9660466 0 -0.258368 0.9660466 0 -0.2590987 0.965851 0 -0.2590897 0.9658533 0 -0.9662132 0.257744 0 -0.9662405 0.257642 0 -0.70717 -0.7070437 0 -0.7071156 -0.707098 0 -0.8660343 0.4999848 0 -0.5000147 -0.8660169 0 -0.5000149 -0.8660169 0 0.707102 0.7071115 0 0.7071022 0.7071114 0 0.7070994 0.7071141 0 0.9658254 0.2591934 0 0.9658254 0.2591936 0 0.9658267 -0.2591888 0 0.9658266 -0.259189 0 0.7070745 -0.7071391 0 0.7071274 -0.7070862 0 0.259202 -0.9658232 0 -0.2597997 -0.9656626 0 -0.259824 -0.9656561 0 -0.2584943 -0.9660128 0 -0.2584942 -0.9660128 0 0.259215 -0.9658197 0 0.5000061 0.8660219 0 0.5000187 0.8660147 0 0.9658204 -0.2592123 0 0.96583 -0.2591763 0 0.9658756 0.2590065 0 0.9658756 0.2590066 0 0.9660149 0.2584868 0 0.9659876 0.2585884 0 0.707107 0.7071066 0 0.7071183 0.7070953 0 0.7071002 0.7071135 0 0.7071 0.7071136 0 0.2584782 0.9660172 0 0.2584923 0.9660134 0 0.2590222 0.9658715 0 0.2590163 0.965873 0 -0.2585368 0.9660015 0 -0.2585502 0.9659979 0 -0.2590051 0.9658761 0 -0.259005 0.9658761 0 -0.7070896 0.7071241 0 -0.7071086 0.7071051 0 -0.7071165 0.7070971 0 -0.7070879 0.7071257 0 -0.9659374 0.2587761 0 -0.9659302 0.2588027 0 -0.9657637 0.2594233 0 -0.9657528 0.2594642 0 -0.9668356 0.2553995 0 -0.9669212 0.2550752 0 -0.9669212 0.2550752 0 -0.9669213 0.2550752 0 -0.9660164 -0.2584809 0 -0.9660105 -0.2585029 0 -0.9651706 -0.2616218 0 -0.9650105 -0.2622117 0 -0.9658105 -0.2592495 0 -0.9657939 -0.2593109 0 -0.7073718 -0.7068417 0 -0.7073717 -0.7068418 0 -0.7064509 -0.707762 0 -0.7064225 -0.7077904 0 -0.2585157 -0.9660072 0 -0.2585015 -0.9660109 0 -0.2590126 -0.965874 0 -0.2590125 -0.965874 0 0.2593028 -0.9657962 0 0.2592862 -0.9658005 0 0.2549414 -0.9669565 0 0.2547848 -0.9669978 0 0.2590031 -0.9658766 0 0.2590088 -0.965875 0 0.7070229 -0.7071908 0 0.7071871 -0.7070264 0 0.7070983 -0.7071153 0 0.7071201 -0.7070935 0 0.7071022 -0.7071114 0 0.7071164 -0.7070972 0 0.9659752 -0.258635 0 0.9659823 -0.2586085 0 -0.7071106 -0.707103 0 -0.7070621 -0.7071516 0 -0.7070994 -0.7071141 0 -0.7071571 -0.7070565 0 -0.965826 -0.2591912 0 -0.9658254 0.2591934 0 -0.9658123 0.2592428 0 -0.7071056 0.7071081 0 0.2598081 0.9656603 0 0.2598081 0.9656603 0 0.2585132 0.9660078 0 0.2585132 0.9660078 0 0.6799162 0.7332898 0 0.6794049 0.7337637 0 0.679405 0.7337635 0 0.9308539 0.3653917 0 0.9971576 -0.07534503 0 0.9971529 -0.07540607 0 0.8658155 -0.5003637 0 0.8658418 -0.5003179 0 0.563691 -0.8259858 0 0.5636909 -0.8259859 0 0.1493428 -0.9887855 0 -0.2947786 -0.9555657 0 -0.2948021 -0.9555584 0 -0.2982452 -0.9544894 0 0.1493428 -0.9887855 0 0.5000184 0.8660148 0 0.5000065 0.8660218 0 -0.03046411 0.9995359 0 -0.03046417 0.9995359 0 -0.03049212 0.9995351 0 -0.03049206 0.999535 0 0.5000002 0.8660254 0 0.4999995 0.8660257 0 0.4733783 0.8808593 0 0.4733779 0.8808595 0 0.473384 0.8808562 0 0.4733841 0.8808562 0 0.4733775 0.8808596 0 0.4733773 0.8808599 0 0.4733366 0.8808817 0 0.4733389 0.8808805 0 0.6268133 0.7791696 0 0.6267944 0.7791847 0 0.8643493 0.502892 0 0.8643409 0.5029066 0 0.9872877 0.1589438 0 0.9872968 0.1588875 0 0.9965819 0.08261096 0 0.9965815 0.08261644 0 0.9565043 0.2917184 0 0.9565012 0.2917286 0 0.8728885 0.4879199 0 0.8728883 0.4879202 0 0.6731821 0.7394767 0 0.6731741 0.7394841 0 0.4999245 0.866069 0 0.4999415 0.8660593 0 0.500077 0.8659811 0 0.5000808 0.8659788 0 0.5000523 0.8659952 0 0.500054 0.8659943 0 0.5000344 0.8660056 0 -0.0657767 0.9978344 0 0.3197718 0.9474947 0 0.3197718 0.9474946 0 0.3197718 0.9474946 0 0.320092 0.9473866 0 0.320092 0.9473866 0 0.320092 0.9473866 0 0.3211802 0.9470182 0 0.3211805 0.947018 0 -0.2588883 0.9659074 0 -0.2588881 0.9659074 0 -0.2587319 0.9659493 0 -0.4424317 0.8968023 0 -0.7548565 0.6558901 0 -0.7548562 0.6558904 0 -0.7514842 0.6597512 0 -0.7515035 0.6597293 0 -0.4424172 0.8968094 0 -0.8658978 0.500221 0 -0.865876 0.5002588 0 -0.8661921 0.4997113 0 -0.8661724 0.4997453 0 -0.8660283 0.499995 0 -0.8660162 0.500016 0 -0.8659543 0.5001232 0 -0.8659349 0.5001569 0 -0.8661113 0.4998512 0 -0.8661178 0.4998399 0 -0.8659114 0.5001974 0 -0.865917 0.5001878 0 -0.8658737 0.5002627 0 -0.8658956 0.5002247 0 -0.9978339 -0.06578487 0 -0.9474765 0.3198257 0 -0.9473185 0.3202934 0 -0.9470285 0.3211498 0 -0.9470166 0.3211846 0 -0.9978362 -0.06574887 0 -0.9659346 -0.2587862 0 -0.9659369 -0.2587777 0 -0.9687262 -0.2481324 0 -0.96864 -0.2484687 0 -0.9686399 -0.2484689 2.10258e-7 -0.96864 -0.2484685 0 -0.9658836 -0.2589771 0 -0.9658776 -0.2589992 0 -0.9659421 -0.2587584 0 -0.9659448 -0.2587485 0 -0.9658253 -0.2591944 0 -0.896778 -0.4424809 0 -0.6579803 -0.7530352 0 -0.6594712 -0.75173 0 -0.6594709 -0.7517302 0 -0.8967779 -0.4424809 0 0.8660681 -0.4999262 0 0.8660513 -0.4999552 0 0.8660135 -0.5000207 0 0.8660135 -0.5000209 0 0.8660553 -0.4999485 0 0.8660502 -0.4999572 0 0.8660218 -0.5000066 0 0.8660185 -0.5000118 0 0.8660009 -0.5000424 0 0.8660008 -0.5000426 0 0.8660227 -0.5000049 0 0.8660241 -0.5000024 0 0.8660374 -0.4999793 0 0.866036 -0.4999818 0 0.8660126 -0.5000224 0 0.8660124 -0.5000225 0 0.8660548 -0.499949 0 0.8660881 -0.4998915 0 0.5000314 -0.8660073 0 0.5000341 -0.8660058 0 0.4999863 -0.8660333 0 0.4999864 -0.8660333 0 0.4999939 -0.866029 0 0.4999923 -0.8660299 0 -0.5000089 -0.8660203 0 -0.5000092 -0.8660202 0 -0.8808666 -0.4733648 0 -0.8808667 -0.4733645 0 -0.8808575 -0.4733816 0 -0.8808622 -0.4733728 0 -0.8808749 -0.4733493 0 -0.8808905 -0.4733202 0 -0.8808574 -0.4733818 0 -0.72832 -0.6852373 0 -0.7283198 -0.6852374 0 -0.5261567 -0.8503876 0 -0.5261564 -0.8503879 0 -0.5261554 -0.8503884 0 -0.5261549 -0.8503889 0 -0.5261547 -0.850389 0 -0.5261636 -0.8503835 0 -0.5261589 -0.8503863 0 0.3560901 -0.9344516 0 0.3560836 -0.9344542 0 -0.003197908 -0.9999949 0 -0.3618555 -0.9322343 0 -0.361849 -0.9322368 0 0.4268214 -0.904336 0 0.4269421 -0.9042791 0 0.4269852 -0.9042587 0 0.2253422 -0.9742797 0 0.2255184 -0.974239 0 0.2255151 -0.9742397 0 0.01392483 -0.9999031 0 0.01392519 -0.9999031 0 0.01391386 -0.9999032 0 0.01391333 -0.9999032 0 -0.3033333 -0.9528846 0 -0.3033239 -0.9528875 0 -0.5001108 -0.8659616 0 -0.5000764 -0.8659814 0 -0.5001038 -0.8659656 0 -0.500097 -0.8659695 0 -0.4999849 -0.8660342 0 -0.4999787 -0.8660377 0 -0.5000115 -0.8660188 0 -0.5000042 -0.8660231 0 0.5000072 0.8660213 0 0.5000045 0.866023 0 0.4999988 0.8660262 0 0.4999992 0.8660259 0 0.499989 0.8660319 0 0.4999862 0.8660335 0 0.9999659 0.00826019 0 0.9999663 0.008205711 0 0.8620344 0.5068498 0 0.8620225 0.5068701 0 0.4927673 0.8701612 0 0.4927793 0.8701544 0 -0.007984042 0.9999682 0 -0.007983803 0.9999682 0 -0.5070372 0.8619242 0 -0.507061 0.8619102 0 -0.8700883 0.492896 0 -0.8700885 0.4928958 0 -0.4999604 -0.8660483 0 -0.4999606 -0.8660483 0 -0.4999998 -0.8660256 0 -0.4999983 -0.8660265 0 -0.5000355 -0.8660051 0 -0.500033 -0.8660065 0 0.2588863 -0.9659078 0 0.2588478 -0.9659181 0 -0.9660377 0.2584015 0 -0.7051921 0.7090164 0 -0.7051109 0.7090972 0 -0.7076027 0.7066105 0 -0.7076773 0.7065358 0 -0.2588775 0.9659103 0 -0.2588774 0.9659103 0 0.2588647 0.9659136 0 0.258903 0.9659034 0 0.7068231 0.7073904 0 0.9668394 -0.2553853 0 0.9668798 -0.2552324 0 0.9656501 -0.259846 0 0.9656501 -0.2598461 0 0.9660248 0.2584494 0 -0.2588735 -0.9659112 0 -0.2588734 0.9659113 0 0.9660491 0.2583585 0 -0.2588478 -0.9659181 0 -0.7080851 -0.7061272 0 -0.7080595 -0.7061529 0 -0.9654344 -0.2606461 0 -0.9654344 -0.2606463 0 -0.965435 0.2606438 0 -0.965435 0.260644 0 -0.708055 0.7061573 0 -0.7080805 0.7061318 0 -0.2588564 0.9659159 0 -0.2588818 0.965909 0 0.2588691 0.9659125 0 0.2588691 0.9659125 0 0.7068532 0.7073603 0 0.7068786 0.7073349 0 0.9660371 0.2584038 0 0.966037 0.2584039 0 1.60496e-7 0 1 7.13878e-5 0 1 -7.46068e-6 0 1 -1.68348e-6 0 1 -1.5393e-6 0 1 1.05846e-5 0 1 -5.42315e-6 0 1 -1.84623e-6 0 1 3.3322e-6 0 1 -2.11494e-6 0 1 4.07405e-7 0 1 3.30907e-6 0 1 -2.16991e-6 0 1 -3.06764e-6 0 1 -1.73986e-6 0 1 3.83824e-7 0 1 -1.37298e-6 0 1 8.96144e-6 0 1 -4.76785e-6 0 1 7.22065e-7 0 1 9.31529e-6 0 1 -8.01179e-7 0 1 -1.59983e-5 0 1 8.83795e-7 0 1 7.23526e-6 0 1 6.44963e-6 0 1 -7.85571e-7 0 1 -4.9866e-6 0 1 5.86134e-6 0 1 2.19329e-6 0 1 -6.82195e-7 0 1 -1.63518e-6 0 1 3.32916e-6 0 1 2.04881e-6 0 1 -8.32309e-7 0 1 1.13495e-6 0 1 0 0 1 2.16625e-6 0 1 -2.48799e-6 0 1 -9.02414e-7 0 1 1.07604e-6 0 1 -1.12006e-6 0 1 2.96648e-6 0 1 -6.231e-6 0 1 1.16069e-6 0 1 -3.78926e-6 0 1 -8.65831e-6 0 1 9.78152e-7 0 1 6.05386e-7 0 1 -8.79906e-6 0 1 -1.93829e-5 0 1 5.82533e-6 0 1 9.48176e-7 0 1 2.68783e-6 0 1 -5.33004e-6 0 1 1.93434e-6 0 1 8.89819e-7 0 1 2.0669e-6 0 1 6.28348e-6 0 1 -2.53874e-5 0 1 2.26224e-5 0 1 -2.73573e-7 0 1 -1.43901e-5 0 1 3.23429e-7 0 1 -1.87487e-7 0 1 2.51396e-7 0 1 -1.5524e-6 0 1 -2.16277e-5 0 1 -2.0694e-6 0 1 -1.4176e-6 0 1 8.14874e-7 0 1 -2.50065e-6 0 1 -1.23362e-5 0 1 4.0663e-6 0 1 -1.06128e-5 0 1 -4.87307e-7 0 1 -2.54892e-7 0 1 -6.79127e-7 0 1 1.4398e-6 0 1 -2.69466e-6 0 1 -2.09221e-6 0 1 6.79964e-6 0 1 -4.40793e-6 0 1 -4.33564e-6 0 1 -7.4497e-7 0 1 -1.12219e-6 0 1 5.15251e-6 0 1 1.00497e-6 0 1 -5.12854e-7 0 1 -7.49384e-6 0 1 -1.26595e-5 0 1 -3.40604e-6 0 1 8.22466e-7 0 1 1.63015e-6 0 1 -1.70214e-6 0 1 3.08273e-6 0 1 -3.83869e-7 0 1 8.06639e-7 0 1 3.28844e-6 0 1 6.5033e-6 0 1 -8.22444e-7 0 1 1.74662e-6 0 1 8.50491e-7 0 1 -5.90026e-7 0 1 -8.06306e-7 0 1 2.09062e-6 0 1 -5.15113e-6 0 1 2.0099e-6 0 1 -7.72941e-6 0 1 3.10345e-6 0 1 -6.66063e-6 0 1 4.04138e-7 0 1 5.05477e-7 0 1 -1.9023e-5 0 1 9.53558e-7 0 1 -1.90456e-6 0 1 5.95092e-6 0 1 -3.15354e-6 0 1 3.81156e-6 0 1 4.79662e-6 0 1 -3.30513e-6 0 1 3.75733e-6 0 1 1.46955e-6 0 1 -1.51151e-6 0 1 2.94253e-7 0 1 1.2012e-6 0 1 -9.72592e-6 0 1 -3.31583e-7 0 1 0 0 1 8.63198e-7 0 1 -1.35477e-7 0 1 -5.67454e-7 0 1 6.75749e-7 0 1 -1.11299e-6 0 1 7.73587e-7 0 1 -9.28495e-7 0 1 -1.68918e-7 0 1 7.38848e-7 0 1 -5.90635e-7 0 1 -2.35051e-6 0 1 -1.10301e-6 0 1 1.3889e-7 0 1 4.52338e-7 0 1 -2.60757e-7 0 1 -8.1943e-6 0 1 -3.64184e-7 0 1 7.94006e-7 0 1 0 0 1 -1.75818e-7 0 1 -7.14384e-7 0 1 7.71389e-7 0 1 1.09008e-6 0 1 -6.33617e-6 0 1 1.43561e-6 0 1 7.93903e-5 0 1 -2.971e-5 0 1 -2.00668e-6 0 1 2.08154e-6 0 1 -4.16327e-6 0 1 1.71986e-6 0 1 -1.90696e-6 0 1 -1.60039e-6 0 1 -3.09294e-7 0 1 -1.43563e-6 0 1 1.58439e-6 0 1 -5.42182e-5 0 1 2.62865e-6 0 1 -1.68099e-6 0 1 1.73009e-6 0 1 -7.03786e-7 0 1 -3.47454e-6 0 1 2.74454e-6 0 1 -1.61385e-6 0 1 -6.46362e-6 0 1 1.0728e-5 0 1 -1.75961e-6 0 1 -3.3996e-6 0 1 4.17491e-6 0 1 -7.46175e-7 0 1 4.9433e-6 0 1 -3.73271e-6 0 1 -1.94759e-6 0 1 2.46075e-6 0 1 4.43928e-7 0 1 -1.98441e-6 0 1 -1.36703e-6 0 1 9.85717e-7 0 1 3.62317e-6 0 1 4.72622e-7 0 1 0 0 1 2.25415e-6 0 1 -4.16685e-7 0 1 6.41697e-7 0 1 -3.51839e-6 0 1 -1.61554e-6 0 1 2.61904e-6 0 1 -2.02948e-6 0 1 -6.06257e-7 0 1 3.01002e-6 0 1 -2.3265e-6 0 1 6.46474e-7 0 1 8.09758e-6 0 1 -2.20599e-6 0 1 7.61341e-7 0 1 -1.52259e-6 0 1 -9.99408e-7 0 1 4.23182e-7 0 1 -1.73352e-6 0 1 8.8956e-7 0 1 -1.61661e-6 0 1 2.22628e-6 0 1 -8.89376e-7 0 1 -3.46275e-6 0 1 4.9588e-7 0 1 1.0941e-6 0 1 2.20115e-7 0 1 -3.51282e-7 0 1 1.43877e-5 0 1 -7.30618e-7 0 1 -7.39472e-7 0 1 -7.30593e-7 0 1 -7.40019e-7 0 1 -1.48759e-6 0 1 -4.29304e-7 0 1 -6.91452e-7 0 1 -1.42524e-6 0 1 1.74652e-6 0 1 -4.96878e-7 0 1 3.06436e-6 0 1 -7.6619e-7 0 1 -3.09325e-7 0 1 -1.0928e-6 0 1 1.22589e-6 0 1 -7.66227e-7 0 1 -7.96838e-7 0 1 1.74858e-6 0 1 -2.73196e-7 0 1 -1.54328e-7 0 1 -1.05539e-5 0 1 1.70836e-6 0 1 -1.88053e-7 0 1 -2.39181e-7 0 1 -3.78219e-6 0 1 5.35181e-7 0 1 -4.52194e-7 0 1 -5.65387e-7 0 1 -6.28585e-7 0 1 2.22965e-6 0 1 1.21665e-7 0 1 2.46252e-6 0 1 -5.46373e-6 0 1 1.42645e-5 0 1 -4.99999e-7 0 1 3.06492e-7 0 1 2.15241e-6 0 1 4.75097e-7 0 1 -2.33033e-6 0 1 -2.47367e-7 0 1 5.23111e-6 0 1 -7.57125e-6 0 1 2.31911e-4 0 1 -4.04209e-6 0 1 2.48693e-6 0 1 -7.13633e-6 0 1 -7.53459e-7 0 1 5.60943e-7 0 1 -2.98432e-6 0 1 2.20587e-6 0 1 1.61541e-6 0 1 1.56622e-6 0 1 -4.71413e-6 0 1 1.77654e-6 0 1 -8.61891e-7 0 1 3.81968e-6 0 1 -2.52603e-6 0 1 7.80226e-6 0 1 7.80265e-7 0 1 0 0 1 -4.90346e-7 0 1 5.16942e-7 0 1 1.27489e-6 0 1 4.40283e-7 0 1 1.23476e-6 0 1 -1.0941e-6 0 1 7.35352e-6 0 1 2.16196e-6 0 1 3.29034e-6 0 1 7.39873e-7 0 1 1.87316e-6 0 1 1.0917e-5 0 1 -2.16521e-6 0 1 -8.50734e-7 0 1 -3.25775e-6 0 1 3.04522e-6 0 1 2.77303e-6 0 1 1.35127e-7 0 1 -9.53907e-6 0 1 -4.29243e-6 0 1 1.38675e-6 0 1 9.99424e-7 0 1 -1.11263e-6 0 1 1.61681e-6 0 1 -2.88349e-6 0 1 4.6996e-7 0 1 -9.40104e-7 0 1 9.39949e-7 0 1 9.40118e-7 0 1 0 0 1 1.35985e-6 0 1 1.52828e-5 0 1 -1.28204e-7 0 1 8.99488e-7 0 1 1.2746e-6 0 1 -0.9654216 -0.2606937 0 -0.9654344 0.2606461 0 -0.9654216 0.2606939 0 -0.7091472 0.7050605 0 -0.7089833 0.7052253 0 -0.7076399 0.7065732 0 -0.7076401 0.7065731 0 0.9649541 -0.2624189 0 0.9649541 -0.2624189 0 0.9665237 -0.2565777 0 0.9665236 -0.2565777 0 -3.35457e-7 0 -1 4.17865e-6 0 -1 -2.54557e-5 0 -1 1.26595e-5 0 -1 9.1567e-7 0 -1 -4.73637e-7 0 -1 -1.94607e-6 0 -1 1.48375e-6 0 -1 -3.0026e-7 0 -1 1.81412e-6 0 -1 -3.17654e-7 0 -1 -5.81785e-7 0 -1 9.57282e-7 0 -1 2.33697e-7 0 -1 -9.03858e-7 0 -1 -7.90516e-6 0 -1 -9.40486e-7 0 -1 4.23468e-7 0 -1 -3.02382e-7 0 -1 -2.38904e-6 0 -1 -3.83824e-7 0 -1 1.22664e-6 0 -1 -6.20446e-7 0 -1 3.02106e-6 0 -1 1.44634e-5 0 -1 -7.34426e-6 0 -1 -8.12353e-7 0 -1 3.12459e-7 0 -1 -6.62819e-7 0 -1 2.99397e-7 0 -1 -1.66195e-7 0 -1 -4.93722e-5 0 -1 -7.13878e-5 0 -1 -2.00292e-7 0 -1 5.17485e-7 0 -1 -1.79887e-6 0 -1 5.47157e-7 0 -1 -2.04523e-6 0 -1 7.22126e-7 0 -1 -3.84385e-6 0 -1 7.4529e-6 0 -1 5.17608e-7 0 -1 -3.53425e-6 0 -1 5.41702e-7 0 -1 3.98699e-6 0 -1 2.85284e-7 0 -1 8.17635e-7 0 -1 -9.39984e-7 0 -1 9.40048e-7 0 -1 -8.32287e-7 0 -1 -3.45239e-7 0 -1 2.70949e-7 0 -1 5.67476e-7 0 -1 0 0 -1 -5.05131e-7 0 -1 4.16154e-7 0 -1 2.10312e-7 0 -1 3.35742e-7 0 -1 -2.83736e-7 0 -1 3.31606e-6 0 -1 -3.46879e-7 0 -1 1.08313e-6 0 -1 1.79251e-6 0 -1 -3.31732e-6 0 -1 -5.12156e-7 0 -1 -1.8565e-6 0 -1 1.02361e-6 0 -1 8.73979e-7 0 -1 -1.94596e-7 0 -1 -4.80762e-7 0 -1 2.38699e-6 0 -1 -9.49339e-7 0 -1 5.97372e-6 0 -1 -1.66248e-6 0 -1 -6.53515e-7 0 -1 1.89463e-6 0 -1 -9.72611e-6 0 -1 1.65401e-6 0 -1 -5.42978e-7 0 -1 -1.81949e-7 0 -1 -3.13456e-7 0 -1 -2.1362e-6 0 -1 1.53398e-6 0 -1 3.43446e-6 0 -1 -6.11606e-7 0 -1 -3.31018e-6 0 -1 -6.12679e-7 0 -1 -2.18859e-6 0 -1 1.28161e-5 0 -1 -4.13935e-6 0 -1 -5.47154e-7 0 -1 7.18143e-6 0 -1 -2.58733e-7 0 -1 -8.01477e-7 0 -1 2.51327e-7 0 -1 -1.87538e-7 0 -1 0 0 -1 1.99876e-6 0 -1 2.9766e-6 0 -1 -1.93434e-6 0 -1 2.0858e-5 0 -1 -2.98116e-5 0 -1 4.91727e-6 0 -1 -7.51164e-6 0 -1 -1.08142e-6 0 -1 1.09649e-5 0 -1 7.79691e-6 0 -1 1.11739e-5 0 -1 -2.50065e-6 0 -1 2.09221e-6 0 -1 -6.04419e-6 0 -1 1.04019e-6 0 -1 9.05351e-7 0 -1 -1.19997e-6 0 -1 6.74034e-7 0 -1 -2.51242e-7 0 -1 3.1742e-6 0 -1 -1.74541e-6 0 -1 8.06306e-7 0 -1 -3.83949e-7 0 -1 9.72067e-7 0 -1 -8.51116e-7 0 -1 1.17949e-6 0 -1 -2.76924e-6 0 -1 -4.34861e-7 0 -1 2.688e-6 0 -1 5.22226e-6 0 -1 -2.06834e-5 0 -1 1.94757e-6 0 -1 -2.61327e-7 0 -1 -7.55753e-7 0 -1 4.04138e-7 0 -1 3.27586e-6 0 -1 -6.12382e-7 0 -1 6.44117e-6 0 -1 -2.11617e-6 0 -1 -1.90201e-5 0 -1 9.53558e-7 0 -1 -8.26282e-7 0 -1 4.79662e-6 0 -1 -7.88385e-7 0 -1 -9.93112e-7 0 -1 -1.57781e-6 0 -1 2.2942e-7 0 -1 0 0 -1 -2.28899e-6 0 -1 -7.23734e-7 0 -1 -5.55568e-7 0 -1 -5.21513e-7 0 -1 7.88373e-7 0 -1 -5.82243e-7 0 -1 0 0 -1 -1.41868e-7 0 -1 1.37468e-6 0 -1 -7.08609e-7 0 -1 4.07941e-7 0 -1 2.83727e-7 0 -1 1.58593e-6 0 -1 1.7264e-7 0 -1 -6.83105e-7 0 -1 -1.23019e-6 0 -1 3.24973e-6 0 -1 -1.77808e-7 0 -1 1.76844e-6 0 -1 6.00598e-7 0 -1 0 0 -1 0 0 -1 -2.20776e-7 0 -1 -8.16865e-7 0 -1 -5.15881e-7 0 -1 2.24867e-7 0 -1 -5.12816e-7 0 -1 1.30995e-5 0 -1 -9.72294e-7 0 -1 3.48893e-7 0 -1 -2.08623e-7 0 -1 -2.08153e-6 0 -1 -5.20404e-7 0 -1 1.9846e-5 0 -1 1.58446e-6 0 -1 -2.86643e-7 0 -1 2.29333e-6 0 -1 -9.45453e-7 0 -1 -2.971e-5 0 -1 -1.07295e-6 0 -1 3.81388e-6 0 -1 -9.94906e-6 0 -1 1.07179e-6 0 -1 -7.03786e-7 0 -1 -3.51913e-7 0 -1 -4.20248e-7 0 -1 -6.18637e-7 0 -1 3.37236e-6 0 -1 -2.53771e-6 0 -1 -9.8866e-6 0 -1 2.67793e-6 0 -1 -4.76251e-7 0 -1 1.41989e-6 0 -1 -1.88432e-6 0 -1 4.23774e-7 0 -1 7.17863e-7 0 -1 6.18607e-7 0 -1 -1.60041e-6 0 -1 -7.62474e-6 0 -1 -5.14926e-7 0 -1 -9.20878e-6 0 -1 2.10115e-6 0 -1 -4.55019e-7 0 -1 6.29824e-7 0 -1 2.18723e-6 0 -1 -3.05345e-6 0 -1 -8.33367e-7 0 -1 2.33214e-6 0 -1 -9.21052e-7 0 -1 6.66638e-7 0 -1 -9.92197e-7 0 -1 -7.679e-7 0 -1 -2.60521e-6 0 -1 -4.91221e-7 0 -1 -6.26639e-6 0 -1 2.01123e-6 0 -1 -1.30009e-7 0 -1 8.22444e-7 0 -1 2.31163e-7 0 -1 2.14622e-6 0 -1 9.53907e-6 0 -1 5.56572e-7 0 -1 -4.47048e-7 0 -1 1.44174e-6 0 -1 1.11263e-6 0 -1 3.25165e-6 0 -1 -9.15657e-7 0 -1 4.96694e-7 0 -1 8.50734e-7 0 -1 2.05527e-7 0 -1 5.96863e-7 0 -1 -1.49154e-7 0 -1 2.94237e-7 0 -1 -2.20911e-6 0 -1 1.03564e-6 0 -1 -1.44877e-6 0 -1 6.12314e-7 0 -1 4.42102e-7 0 -1 1.62556e-7 0 -1 -2.43329e-7 0 -1 -1.17853e-6 0 -1 4.69867e-6 0 -1 -3.27219e-7 0 -1 -1.20135e-4 0 -1 1.75003e-6 0 -1 1.47058e-7 0 -1 2.81453e-7 0 -1 -2.8983e-7 0 -1 4.46017e-7 0 -1 -1.95067e-7 0 -1 4.6327e-6 0 -1 -4.04165e-6 0 -1 2.1319e-7 0 -1 1.54169e-6 0 -1 4.78293e-7 0 -1 -4.90342e-7 0 -1 1.50445e-6 0 -1 4.81603e-6 0 -1 -5.464e-7 0 -1 -1.4247e-6 0 -1 -4.45341e-7 0 -1 -6.66297e-7 0 -1 4.07044e-6 0 -1 2.94988e-7 0 -1 -2.94984e-7 0 -1 -2.05406e-7 0 -1 -6.46663e-6 0 -1 8.80548e-7 0 -1 -1.23474e-6 0 -1 -9.2191e-7 0 -1 1.44342e-6 0 -1 -2.43375e-6 0 -1 7.39472e-7 0 -1 7.3061e-7 0 -1 4.94411e-7 0 -1 -7.40265e-7 0 -1 -7.30354e-7 0 -1 8.9953e-7 0 -1 2.56484e-7 0 -1 -8.22466e-7 0 -1 3.46702e-6 0 -1 -9.99337e-7 0 -1 -5.5657e-7 0 -1 -8.7991e-6 0 -1 -8.46364e-7 0 -1 -7.04334e-7 0 -1 2.37786e-6 0 -1 -3.96703e-6 0 -1 -1.29853e-6 0 -1 2.22344e-7 0 -1 1.11259e-6 0 -1 -0.6799162 -0.7332898 0 -0.6793475 -0.7338168 0 -0.6794624 -0.7337105 0 -0.9308539 -0.3653917 0 -0.9971553 0.07537472 0 -0.8664402 0.4992809 0 -0.8664667 0.4992351 0 -0.563691 0.8259858 0 -0.5637195 0.8259665 0 -0.1493232 0.9887885 0 0.2947888 0.9555625 0 0.2947651 0.9555698 0 0.2967494 0.9549554 0 -0.1493231 0.9887885 0 0.8659081 0.5002033 0 0.8659141 0.5001928 0 0.8663314 0.4994698 0 0.8663241 0.4994824 0 0.866212 0.4996767 0 0.8662003 0.499697 0 0.9627452 0.2704103 0 0.9616572 -0.2742543 0 0.9616441 -0.2743005 0 0.9615272 -0.2747097 0 0.9615197 -0.2747365 0 0.9616628 -0.2742347 0 0.9616532 -0.2742686 0 0.9456846 -0.3250857 0 0.9456493 -0.3251884 0 0.6754038 -0.737448 0 0.6753468 -0.7375004 0 0.2406362 -0.9706155 0 -0.8722184 0.4891169 0 -0.8705134 0.4921447 0 -0.8705165 0.4921392 0 -0.870599 0.4919932 0 -0.870599 0.4919934 0 -0.9780806 0.2082266 0 -0.9778286 0.2094074 0 -0.9778286 0.2094075 0 -0.2081355 -0.9781 0 -0.2081639 -0.9780941 0 -0.5780887 -0.815974 0 -0.5781543 -0.8159275 0 -0.852786 -0.5222605 0 -0.989812 -0.1423814 0 -0.9898316 -0.1422442 0 -0.006194114 -0.9999809 0 -0.006194174 -0.9999809 0 -0.006864666 -0.9999765 0 -0.006864786 -0.9999765 0 -0.492724 0.8701857 0 0.2586198 0.9659793 0 0.2586122 0.9659813 0 0.2587546 0.9659432 0 0.2587488 0.9659447 0 0.2588838 0.9659085 0 0.2588857 0.9659081 0 0.2583599 0.9660488 0 0.2583601 0.9660487 0 0.9662146 0.257739 0 0.7071252 -0.7070884 0 0.7071251 -0.7070885 0 0.9656779 -0.2597429 0 0.9656778 -0.259743 0 0.9669664 -0.2549041 0 0.9669045 -0.2551389 0 0.9662417 0.2576374 0 0.4999193 -0.8660721 0 0.5005038 -0.8657343 0 0.5005377 -0.8657149 0 0.2704045 -0.9627469 0 -0.2203233 -0.9754269 0 -0.2203233 -0.975427 0 -0.2230219 -0.9748135 0 0.2704043 -0.9627469 0 -0.2590897 -0.9658533 0 -0.2590987 -0.965851 0 -0.2583681 -0.9660466 0 -0.258368 -0.9660466 0 -0.258877 -0.9659103 0 -0.8660556 -0.4999478 0 -0.8660559 -0.4999474 0 -0.8659845 -0.500071 0 -0.8660131 -0.5000214 0 -0.8659929 -0.5000565 0 -0.8660496 -0.4999581 0 -0.8660497 -0.4999579 0 0.9658291 0.2591799 0 0.9658291 0.25918 0 0.7073782 -0.7068353 0 0.7073516 -0.7068619 0 0.2587561 -0.9659428 0 0.2587428 -0.9659463 0 -0.2587561 -0.9659428 0 -0.2587428 -0.9659463 0 -0.7073782 -0.7068353 0 -0.7073516 -0.7068619 0 0.8660283 0.499995 0 -0.9658254 -0.2591934 0 -0.9658254 -0.2591936 0 -0.9658262 0.2591912 0 -0.965826 0.2591912 0 -0.2592239 0.9658173 0 -0.2592236 0.9658173 0 0.2592107 0.9658209 0 0.2592236 0.9658173 0 0.2431836 0.9699803 0 0.2431837 0.9699803 0 0.2430786 0.9700067 0 0.2430785 0.9700067 0 0.2433103 0.9699486 0 0.243322 0.9699457 0 -0.8691038 0.4946299 0 -0.8691036 0.49463 0 -0.8691963 0.4944674 0 -0.619665 -0.7848665 0 -0.6195966 -0.7849205 0 -0.8778049 -0.4790185 0 -0.8778048 -0.4790186 0 -0.9960013 -0.08934009 0 -0.9960012 -0.08934015 0 -0.9514547 0.307789 0 -0.9514546 0.307789 0 -0.3076936 -0.9514855 0 -0.00890541 -0.9999604 0 -0.00890541 -0.9999604 0 -0.00925225 -0.9999572 0 -0.00925225 -0.9999572 0 -0.3076965 -0.9514846 0 0.9611453 0.2760431 0 0.9611762 0.2759352 0 0.9783365 -0.2070211 0 0.7677857 -0.6407068 0 0.7677282 -0.6407756 0 0.376633 -0.9263626 0 0.3766328 -0.9263626 0 0.8660258 0.4999995 0 0.8660221 0.5000059 0 0.9659253 -0.2588211 0 0.9659253 -0.2588212 0 0.9658831 -0.2589786 0 0.9658901 -0.2589526 0 -0.8660461 -0.4999641 0 -0.86605 -0.4999575 0 -0.9658513 0.2590971 0 -0.9658513 0.2590972 0 -0.9660501 0.2583552 0 -0.9660425 0.2583832 0 -0.9659086 0.2588835 0 -0.9659086 0.2588837 0 -0.5005142 0.8657283 0 -0.500514 0.8657285 0 -0.5000981 0.8659688 0 -0.5000935 0.8659715 0 0.7071088 0.7071049 0 0.7071086 0.7071051 0 0.259009 0.965875 0 0.259003 0.9658765 0 0.2585414 0.9660003 0 0.2585278 0.9660038 0 -0.2590126 0.965874 0 -0.2590125 0.965874 0 -0.2585015 0.9660109 0 -0.2585157 0.9660072 0 -0.7064228 0.7077902 0 -0.7064508 0.7077623 0 -0.7073718 0.7068417 0 -0.7073717 0.7068418 0 -0.9656872 0.2597082 0 -0.9656735 0.2597589 0 -0.9660106 0.2585027 0 -0.9660164 0.258481 0 -0.9658809 -0.2589868 0 -0.9658905 -0.2589509 0 -0.9659302 -0.2588026 0 -0.9659374 -0.2587762 0 -0.7070881 -0.7071256 0 -0.7071164 -0.7070972 0 -0.7076176 -0.7065956 0 -0.7032794 -0.7109136 0 -0.7031157 -0.7110755 0 -0.2590051 -0.9658761 0 -0.259005 -0.9658761 0 -0.2548372 -0.966984 0 -0.2549154 -0.9669635 0 -0.2593028 -0.9657962 0 -0.2593026 -0.9657962 0 0.2590164 -0.965873 0 0.2590221 -0.9658715 0 0.2584923 -0.9660134 0 0.2584782 -0.9660172 0 0.7071002 -0.7071135 0 0.7071 -0.7071136 0 0.7071185 -0.7070951 0 0.9657948 -0.2593079 0 0.9657948 -0.259308 0 0.9669896 -0.2548163 0 0.9658756 -0.2590065 0 0.9658756 -0.2590066 0 0.964958 0.2624043 0 0.9649581 0.2624044 0 0.9659457 0.258745 0 0.9659348 0.2587858 0 0.9659823 0.2586085 0 0.9659752 0.258635 0 0.7071165 0.7070971 0 0.7071021 0.7071114 0 -0.2597996 0.9656626 0 -0.2598241 0.9656561 0 -0.258523 0.9660051 0 -0.2584943 0.9660128 0 0.259202 0.9658232 0 0.7070745 0.7071391 0 0.7071274 0.7070862 0 0.965826 0.2591912 0 0.9658262 -0.2591912 0 0.7071108 -0.7071028 0 0.7071106 -0.707103 0 0.7070894 -0.7071242 0 -0.03046613 -0.9995359 0 -0.03046661 -0.9995359 0 -0.0305109 -0.9995345 0 -0.03051108 -0.9995344 0 -0.03034168 -0.9995397 0 -0.03034174 -0.9995397 0 -0.03048759 -0.9995352 0 -0.03048747 -0.9995352 0 0.4999997 -0.8660256 0 0.5000001 -0.8660254 0 0.8660882 0.4998913 0 0.8660548 0.4999492 0 0.8660126 0.5000224 0 0.8660124 0.5000225 0 0.8660553 0.4999485 0 0.8660502 0.4999572 0 0.8660192 0.5000107 0 0.8660536 0.4999511 0 0.8660487 0.4999596 0 0.8660242 0.5000021 0 0.8660225 0.5000052 0 0.8660237 0.5000028 0 0.8660238 0.500003 0 0.8660135 0.5000207 0 0.8660135 0.5000209 0 0.8660514 0.4999551 0 0.866068 0.4999263 0 0.4999999 0.8660255 0 0.4999995 0.8660257 0 -0.5000095 0.86602 0 -0.5000087 0.8660205 0 -0.8808602 0.4733766 0 -0.8808627 0.473372 0 -0.880864 0.4733694 0 -0.8808615 0.4733743 0 -0.72832 0.6852373 0 -0.7283198 0.6852374 0 -0.5261564 0.8503879 0 -0.5261567 0.8503876 0 -0.5261554 0.8503884 0 -0.5261547 0.850389 0 -0.5261549 0.8503889 0 -0.5261635 0.8503835 0 -0.526159 0.8503862 0 -0.361849 0.9322368 0 -0.3618555 0.9322343 0 -0.003197908 0.9999949 0 0.3560837 0.9344541 0 0.35609 0.9344517 0 0.4268454 0.9043247 0 0.4268537 0.9043207 0 0.2254735 0.9742493 0 0.2254711 0.97425 0 0.01391899 0.9999032 0 0.01391881 0.9999032 0 0.4733387 -0.8808805 0 0.4733368 -0.8808817 0 0.4733773 -0.8808599 0 0.4733775 -0.8808596 0 0.473384 -0.8808562 0 0.4733841 -0.8808562 0 0.4733778 -0.8808596 0 0.4733785 -0.8808592 0 0.9872968 -0.1588873 0 0.9872877 -0.158944 0 0.8643409 -0.5029065 0 0.8643492 -0.5028921 0 0.6267944 -0.7791847 0 0.6268133 -0.7791696 0 -0.5001104 0.8659617 0 -0.5000767 0.8659812 0 -0.5001038 0.8659656 0 -0.500097 0.8659695 0 -0.4999847 0.8660343 0 -0.4999788 0.8660377 0 -0.5000113 0.866019 0 -0.5000044 0.8660229 0 -0.8967779 0.4424809 0 -0.6579803 0.7530352 0 -0.6594709 0.7517302 0 -0.6594712 0.75173 0 -0.896778 0.4424809 0 -0.9659585 0.2586972 0 -0.9659585 0.2586973 0 -0.9659146 0.2588613 0 -0.9659145 0.2588614 0 -0.9978339 0.06578487 0 -0.9474763 -0.3198259 0 -0.9473185 -0.3202932 0 -0.9470285 -0.3211498 0 -0.9470167 -0.3211847 0 -0.9978362 0.06574887 0 -0.8658955 -0.5002249 0 -0.8658738 -0.5002626 0 -0.8657194 -0.5005299 0 -0.8657392 -0.5004957 0 -0.8660162 -0.500016 0 -0.8659347 -0.500157 0 -0.8659349 -0.5001569 0 -0.8661177 -0.4998401 0 -0.8661115 -0.4998509 0 -0.8660421 -0.4999712 0 -0.8660476 -0.4999616 0 -0.865876 -0.5002588 0 -0.8658978 -0.500221 0 -0.4424316 -0.8968023 0 -0.7548562 -0.6558904 0 -0.7548565 -0.6558901 0 -0.7514842 -0.6597512 0 -0.7515035 -0.6597293 0 -0.4424174 -0.8968094 0 -0.25878 -0.9659364 0 -0.2587823 -0.9659357 0 -0.2713642 -0.9624768 0 -0.2716371 -0.9623998 0 -0.2584653 -0.9660205 0 -0.2584594 -0.9660222 0 -0.2590018 -0.9658769 0 -0.2589992 -0.9658777 0 -0.2577874 -0.9662017 0 -0.257754 -0.9662106 0 -0.0657767 -0.9978344 0 0.3200898 -0.9473872 0 0.3202282 -0.9473405 0 0.3202281 -0.9473405 -3.13415e-7 0.3202282 -0.9473405 0 0.3211805 -0.947018 0 0.3211802 -0.9470182 0 0.4999245 -0.866069 0 0.4999415 -0.8660593 0 0.5000773 -0.8659808 0 0.5000804 -0.8659791 0 0.5000525 -0.8659951 0 0.5000538 -0.8659944 0 0.5000344 -0.8660056 0 0.6731739 -0.7394842 0 0.6731823 -0.7394766 0 0.996589 -0.08252668 0 0.9965878 -0.08254033 0 0.9965558 -0.08292496 0 0.9965535 -0.08295261 0 0.9563738 -0.2921461 0 0.9563798 -0.2921264 0 0.9565446 -0.2915859 0 0.9565468 -0.2915792 0 0.8727021 -0.4882531 0 0.8726919 -0.4882714 0 0.8730585 -0.4876155 0 0.8730498 -0.4876313 0 0.5000072 -0.8660213 0 0.5000045 -0.866023 0 0.4999988 -0.8660262 0 0.4999992 -0.8660259 0 0.4999888 -0.866032 0 0.4999862 -0.8660333 0 -0.866062 -0.4999368 0 -0.4999606 0.8660483 0 -0.4999604 0.8660483 0 -0.4999998 0.8660256 0 -0.4999983 0.8660265 0 -0.5000356 0.8660049 0 -0.5000328 0.8660065 0 0.8660485 0.4999603 0 0.9660236 0.2584539 0 0.9660249 -0.2584492 0 0.7068231 -0.7073904 0 0.7068742 -0.7073393 0 0.2589031 -0.9659034 0 0.2588647 -0.9659137 0 -0.2588775 -0.9659103 0 -0.2588774 -0.9659103 0 -0.7068487 -0.7073649 0 -0.9660376 -0.2584017 0 0.258848 0.9659182 0 0.2588861 0.9659079 0 -0.7080851 0.7061272 0 1.2012e-6 0 -1 -9.72592e-6 0 -1 2.48101e-6 0 -1 -3.1155e-6 0 -1 -1.39308e-6 0 -1 3.47578e-7 0 -1 -6.36552e-7 0 -1 -2.68457e-7 0 -1 -2.04107e-6 0 -1 -3.32348e-7 0 -1 -8.94217e-7 0 -1 1.63406e-6 0 -1 -1.62248e-7 0 -1 1.44367e-5 0 -1 -1.2979e-5 0 -1 6.28773e-5 0 -1 1.25244e-6 0 -1 -8.15868e-7 0 -1 5.61137e-6 0 -1 -2.99388e-7 0 -1 7.18102e-6 0 -1 6.80102e-7 0 -1 -1.43409e-5 0 -1 2.98476e-5 0 -1 1.26764e-7 0 -1 -4.1388e-6 0 -1 3.20045e-7 0 -1 9.10823e-7 0 -1 -5.90216e-6 0 -1 4.33433e-6 0 -1 2.41518e-7 0 -1 -2.81231e-7 0 -1 2.0427e-7 0 -1 1.63624e-6 0 -1 4.16167e-7 0 -1 -6.90501e-7 0 -1 -2.02069e-6 0 -1 8.32379e-7 0 -1 -1.65845e-6 0 -1 -2.70776e-7 0 -1 1.82095e-7 0 -1 -5.12157e-7 0 -1 -2.37154e-7 0 -1 -4.64253e-7 0 -1 1.16245e-6 0 -1 -2.20409e-6 0 -1 9.61487e-7 0 -1 -3.81773e-6 0 -1 2.53194e-7 0 -1 1.49693e-6 0 -1 -5.41285e-7 0 -1 2.32461e-7 0 -1 -1.61775e-7 0 -1 6.95945e-7 0 -1 1.15036e-6 0 -1 -9.51583e-6 0 -1 -8.99852e-7 0 -1 7.22065e-7 0 -1 4.65764e-6 0 -1 -4.0059e-7 0 -1 -1.19347e-6 0 -1 -1.03299e-6 0 -1 -4.23145e-6 0 -1 1.68445e-6 0 -1 4.58473e-7 0 -1 5.18167e-6 0 -1 -4.1394e-6 0 -1 7.08454e-6 0 -1 1.08261e-6 0 -1 -1.0917e-5 0 -1 2.29391e-6 0 -1 -1.24933e-6 0 -1 -7.3519e-7 0 -1 7.56155e-7 0 -1 2.56474e-7 0 -1 -1.56326e-6 0 -1 -1.27459e-7 0 -1 4.23228e-6 0 -1 -1.74542e-6 0 -1 2.64235e-7 0 -1 -1.28802e-6 0 -1 1.16494e-6 0 -1 1.40067e-7 0 -1 -1.02777e-6 0 -1 3.31621e-7 0 -1 -7.74118e-7 0 -1 8.73369e-7 0 -1 -6.92951e-7 0 -1 8.06597e-7 0 -1 8.69553e-7 0 -1 -1.33345e-6 0 -1 1.42594e-6 0 -1 -8.22607e-7 0 -1 1.62585e-6 0 -1 -2.10739e-5 0 -1 -1.64544e-5 0 -1 -2.61471e-7 0 -1 1.74747e-6 0 -1 -1.38205e-6 0 -1 -3.0595e-7 0 -1 7.92745e-7 0 -1 1.13348e-6 0 -1 -4.41052e-6 0 -1 3.9482e-6 0 -1 -3.71123e-7 0 -1 -2.1023e-6 0 -1 1.48336e-6 0 -1 0 0 -1 1.75821e-7 0 -1 4.29191e-7 0 -1 -1.40222e-6 0 -1 1.32633e-6 0 -1 -5.21466e-7 0 -1 3.15361e-7 0 -1 -2.11855e-7 0 -1 2.91661e-7 0 -1 -2.18653e-7 0 -1 2.61994e-7 0 -1 -2.06292e-6 0 -1 2.06726e-6 0 -1 -4.24603e-7 0 -1 9.28567e-7 0 -1 -5.31463e-7 0 -1 4.07963e-7 0 -1 0 0 -1 3.96498e-7 0 -1 -3.4524e-7 0 -1 0 0 -1 2.21051e-7 0 -1 0 0 -1 0 0 -1 7.71643e-7 0 -1 -2.06291e-6 0 -1 -2.24813e-7 0 -1 1.05647e-6 0 -1 -5.12539e-7 0 -1 -1.08864e-6 0 -1 6.49364e-7 0 -1 2.58211e-6 0 -1 -1.30096e-6 0 -1 1.43334e-6 0 -1 1.60047e-6 0 -1 -8.40494e-7 0 -1 -2.79757e-7 0 -1 1.01334e-6 0 -1 -1.29757e-6 0 -1 -2.74278e-6 0 -1 -9.86972e-6 0 -1 1.12845e-6 0 -1 1.73727e-6 0 -1 -2.19955e-6 0 -1 -9.88142e-6 0 -1 9.73892e-7 0 -1 1.68094e-6 0 -1 -2.85885e-6 0 -1 3.06463e-6 0 -1 -8.00195e-7 0 -1 6.18589e-7 0 -1 -1.80413e-6 0 -1 9.00512e-6 0 -1 -1.98738e-6 0 -1 -4.13682e-7 0 -1 7.71605e-7 0 -1 -1.82083e-6 0 -1 -1.80477e-6 0 -1 -2.3727e-6 0 -1 -3.9674e-6 0 -1 -8.33589e-7 0 -1 4.91224e-7 0 -1 2.71433e-6 0 -1 6.15193e-7 0 -1 9.9282e-7 0 -1 -2.37304e-6 0 -1 5.10104e-6 0 -1 -2.493e-6 0 -1 -1.59533e-6 0 -1 -2.13664e-7 0 -1 1.3162e-6 0 -1 1.28122e-7 0 -1 -6.60413e-7 0 -1 -4.11233e-7 0 -1 -4.62425e-7 0 -1 9.24843e-7 0 -1 -5.99635e-6 0 -1 1.27634e-6 0 -1 -7.7605e-7 0 -1 -6.04437e-7 0 -1 5.93475e-7 0 -1 -7.39873e-7 0 -1 -2.05822e-6 0 -1 9.00437e-7 0 -1 6.1865e-7 0 -1 1.21665e-7 0 -1 3.00344e-6 0 -1 1.97497e-6 0 -1 2.80471e-7 0 -1 -2.08891e-6 0 -1 4.41485e-6 0 -1 -4.92643e-6 0 -1 -4.46065e-7 0 -1 3.76737e-7 0 -1 6.4677e-7 0 -1 -1.75016e-6 0 -1 -3.35638e-7 0 -1 1.23518e-4 0 -1 1.7243e-6 0 -1 0 0 -1 -2.40361e-7 0 -1 4.70796e-7 0 -1 -1.69342e-7 0 -1 9.27412e-7 0 -1 -2.79972e-6 0 -1 7.43158e-6 0 -1 -2.8145e-7 0 -1 3.62136e-7 0 -1 -8.94887e-7 0 -1 -3.27401e-7 0 -1 -5.56793e-5 0 -1 5.39013e-7 0 -1 7.82052e-7 0 -1 -2.80776e-7 0 -1 1.07619e-6 0 -1 1.19801e-5 0 -1 -7.33361e-7 0 -1 7.51825e-7 0 -1 -8.74285e-7 0 -1 -2.41048e-6 0 -1 5.46393e-7 0 -1 -5.46431e-7 0 -1 3.66647e-7 0 -1 -7.33301e-7 0 -1 1.33291e-6 0 -1 2.94006e-7 0 -1 1.28401e-6 0 -1 0 0 -1 -9.22564e-7 0 -1 2.45117e-6 0 -1 7.4793e-7 0 -1 -8.91723e-7 0 -1 7.40017e-7 0 -1 7.3059e-7 0 -1 9.89135e-7 0 -1 -7.39719e-7 0 -1 -2.68407e-6 0 -1 6.8846e-7 0 -1 -7.61406e-7 0 -1 2.13766e-7 0 -1 -1.72182e-6 0 -1 1.49115e-6 0 -1 0.9660371 -0.2584038 0 0.966037 -0.2584039 0 0.7068787 -0.7073348 0 0.706853 -0.7073605 0 0.2588691 -0.9659125 0 0.2588691 -0.9659125 0 -0.2588819 -0.965909 0 -0.2588562 -0.9659159 0 -0.7080806 -0.7061317 0 -0.7080549 -0.7061574 0 -0.9649561 -0.2624117 0 -0.9649561 -0.2624116 0 -0.9656518 -0.2598395 0 -0.9656518 -0.2598395 0 -0.9654344 0.2606463 0 -0.7080595 0.7061529 0 -0.258848 0.9659182 0 0.7090653 0.7051429 0 0.7090652 0.705143 0 0.7058566 0.7083548 0 0.7058935 0.708318 0 9.0655e-7 0 1 -3.94995e-6 0 1 -4.81507e-7 0 1 -4.17865e-6 0 1 -7.01459e-5 0 1 1.68146e-6 0 1 2.04379e-6 0 1 2.52676e-6 0 1 -1.04687e-6 0 1 4.25206e-6 0 1 -1.80761e-6 0 1 6.65821e-7 0 1 -7.755e-7 0 1 4.64919e-7 0 1 7.04286e-7 0 1 -3.03606e-7 0 1 1.91073e-6 0 1 -1.94522e-5 0 1 2.96651e-6 0 1 -5.42978e-7 0 1 -5.6214e-7 0 1 2.45965e-7 0 1 1.63577e-6 0 1 -7.43278e-7 0 1 -2.06984e-6 0 1 2.06967e-6 0 1 1.30416e-5 0 1 -2.32392e-6 0 1 9.07563e-5 0 1 -4.09637e-7 0 1 -1.57287e-5 0 1 6.8022e-7 0 1 -2.50481e-6 0 1 -1.22559e-6 0 1 3.98765e-6 0 1 4.91283e-5 0 1 -1.78571e-6 0 1 1.14774e-5 0 1 -2.49714e-6 0 1 1.34305e-6 0 1 -4.75778e-6 0 1 -1.35388e-6 0 1 8.2971e-6 0 1 -4.51208e-7 0 1 3.69912e-6 0 1 4.84684e-6 0 1 -2.61492e-6 0 1 -2.53194e-7 0 1 6.53663e-7 0 1 9.47275e-7 0 1 -1.15945e-6 0 1 -3.89214e-6 0 1 1.99591e-6 0 1 -4.23749e-6 0 1 6.23659e-6 0 1 3.58356e-6 0 1 8.89528e-7 0 1 -1.92355e-6 0 1 -3.30613e-6 0 1 9.49399e-7 0 1 -1.55153e-5 0 1 -2.06579e-6 0 1 1.19347e-6 0 1 -4.67199e-7 0 1 8.27897e-6 0 1 -2.33617e-5 0 1 2.26696e-5 0 1 -1.09471e-6 0 1 -7.49834e-7 0 1 3.2032e-6 0 1 -1.00546e-6 0 1 -3.51519e-5 0 1 7.22132e-7 0 1 -4.08999e-6 0 1 5.05505e-6 0 1 -2.49865e-6 0 1 -9.93388e-7 0 1 1.14114e-6 0 1 8.188e-6 0 1 2.54073e-7 0 1 1.95241e-6 0 1 -5.09696e-7 0 1 3.38807e-7 0 1 2.88422e-6 0 1 -2.24853e-6 0 1 2.24347e-6 0 1 -2.97975e-6 0 1 4.76229e-6 0 1 2.57604e-6 0 1 -7.84414e-7 0 1 -1.47042e-6 0 1 -2.05164e-6 0 1 8.69166e-7 0 1 -1.85755e-6 0 1 9.73763e-7 0 1 -1.62892e-6 0 1 4.06462e-6 0 1 -1.70147e-6 0 1 1.64521e-6 0 1 -8.88036e-7 0 1 1.5358e-6 0 1 -1.32609e-6 0 1 3.22641e-6 0 1 2.77483e-6 0 1 -3.22587e-6 0 1 2.09331e-6 0 1 1.00494e-6 0 1 2.07307e-6 0 1 4.04217e-7 0 1 4.89564e-6 0 1 -4.83036e-7 0 1 7.41681e-7 0 1 -2.59562e-6 0 1 -1.40127e-6 0 1 -4.00764e-7 0 1 1.33291e-6 0 1 1.47017e-6 0 1 -5.28957e-6 0 1 8.11733e-7 0 1 -8.32408e-6 0 1 -5.12549e-7 0 1 1.7582e-7 0 1 -3.86767e-7 0 1 4.78139e-6 0 1 6.75755e-7 0 1 9.28567e-7 0 1 -9.00911e-7 0 1 3.69422e-6 0 1 -2.95322e-6 0 1 -1.38112e-6 0 1 2.08934e-6 0 1 -1.38891e-7 0 1 0 0 1 0 0 1 2.60733e-7 0 1 5.55523e-7 0 1 0 0 1 4.19961e-7 0 1 1.20706e-7 0 1 1.26844e-6 0 1 -1.43064e-7 0 1 6.00598e-7 0 1 -5.12465e-7 0 1 3.51639e-7 0 1 -7.14706e-7 0 1 2.17592e-6 0 1 6.9461e-5 0 1 -2.60202e-6 0 1 7.63196e-6 0 1 -1.6003e-6 0 1 -3.09319e-7 0 1 3.81241e-6 0 1 -8.40475e-7 0 1 -7.8964e-5 0 1 8.07504e-6 0 1 8.10688e-6 0 1 -1.9583e-6 0 1 1.7374e-6 0 1 -1.73726e-6 0 1 -1.31973e-6 0 1 3.2041e-6 0 1 4.94071e-6 0 1 -8.00205e-7 0 1 -8.06586e-6 0 1 -6.36997e-7 0 1 2.32657e-6 0 1 -1.57193e-5 0 1 -1.8334e-7 0 1 -2.6208e-6 0 1 1.64071e-6 0 1 3.28975e-7 0 1 5.4143e-7 0 1 -1.71917e-6 0 1 -2.54225e-7 0 1 1.00627e-5 0 1 1.73933e-4 0 1 2.86079e-6 0 1 5.81754e-7 0 1 0 0 1 7.83298e-6 0 1 -1.76542e-6 0 1 -4.12175e-7 0 1 2.46569e-6 0 1 -1.83455e-6 0 1 1.52258e-6 0 1 -3.04562e-6 0 1 1.99864e-6 0 1 3.18113e-6 0 1 -3.44363e-6 0 1 -1.61605e-6 0 1 1.61655e-6 0 1 4.13076e-6 0 1 7.67644e-7 0 1 1.53352e-6 0 1 -1.53395e-6 0 1 -1.56309e-7 0 1 -6.60417e-7 0 1 -3.98398e-7 0 1 -1.0755e-6 0 1 7.01769e-7 0 1 -6.04765e-7 0 1 -9.89315e-7 0 1 2.19255e-6 0 1 -2.9209e-6 0 1 1.47895e-6 0 1 -4.37744e-6 0 1 -5.72393e-7 0 1 -1.49921e-6 0 1 -7.33293e-7 0 1 -1.42549e-6 0 1 1.7474e-6 0 1 1.98738e-6 0 1 -3.60231e-5 0 1 1.53247e-6 0 1 -3.09304e-7 0 1 6.55715e-7 0 1 -2.45192e-6 0 1 9.5778e-7 0 1 3.18722e-7 0 1 2.73212e-7 0 1 -1.53244e-6 0 1 -1.5433e-7 0 1 6.57845e-7 0 1 1.46671e-6 0 1 -2.39188e-7 0 1 1.35659e-6 0 1 -1.80879e-6 0 1 5.65375e-7 0 1 -1.13076e-6 0 1 3.14347e-7 0 1 3.60272e-7 0 1 2.07586e-6 0 1 3.11143e-6 0 1 -1.73895e-6 0 1 7.53474e-7 0 1 1.42743e-5 0 1 -1.83896e-7 0 1 5.61553e-7 0 1 3.54844e-7 0 1 4.86656e-7 0 1 -6.82412e-7 0 1 6.82413e-7 0 1 -9.16322e-6 0 1 -4.69363e-6 0 1 -2.15428e-7 0 1 -1.26282e-6 0 1 7.80567e-6 0 1 0 0 1 -9.86912e-7 0 1 5.97597e-7 0 1 -4.40217e-7 0 1 5.23802e-6 0 1 1.53434e-6 0 1 -1.53384e-6 0 1 -8.51058e-7 0 1 1.87294e-6 0 1 -2.19298e-5 0 1 -9.99392e-7 0 1 -4.99668e-7 0 1 2.55383e-6 0 1 2.41775e-6 0 1 9.40175e-7 0 1 -1.84971e-6 0 1 9.24843e-7 0 1 -9.40543e-7 0 1 -8.33108e-7 0 1 4.16556e-7 0 1 1.03421e-5 0 1 -2.05015e-6 0 1 1.05647e-6 0 1 1.27496e-6 0 1 0.7517384 0.6594615 0 0.4449604 0.8955503 0 0.4447604 0.8956496 0 0.4439936 0.89603 0 0.7229875 0.6908612 0 0.7229898 0.6908588 4.3438e-5 0.7229934 0.690855 0 0.9818742 0.189534 0 0.9818742 0.189534 0 0.8410019 0.5410324 0 0.8408576 0.5412566 -3.5192e-5 0.8408237 0.5413092 0 0.7071068 -0.7071068 0 0.7071058 -0.7071079 0 0.8394553 0.5434289 0 0.8395074 0.5433483 -4.49408e-5 0.8395283 0.5433161 0 0.9952335 0.09752202 0 0.9952334 0.09752202 0 0.929027 -0.3700121 0 0.929027 -0.3700121 0 0.6556434 -0.7550707 0 0.6556431 -0.7550711 0 0.2361062 -0.9717273 0 0.2361268 -0.9717223 2.96935e-5 -0.839481 0.5433893 0 -0.8395174 0.543333 -3.21009e-5 -0.8395321 0.5433102 0 -0.9952319 0.09753829 0 -0.9952319 0.09753751 0 -0.9290291 -0.3700069 0 -0.9290289 -0.3700072 0 -0.6556513 -0.7550638 0 -0.655651 -0.7550642 0 -0.2361233 -0.9717231 0 -0.2361231 -0.9717231 0 0.2362443 -0.9716937 0 -0.7071076 -0.7071061 0 -0.7071074 -0.7071063 0 -0.8395173 -0.543333 0 -0.8395175 -0.5433327 0 -0.9952319 -0.09753829 0 -0.9952319 -0.09753751 0 -0.929029 0.3700069 0 -0.9290289 0.3700072 0 -0.6556513 0.7550638 0 -0.655651 0.7550642 0 -0.2361233 0.9717231 0 -0.2361232 0.9717231 0 0.2362443 0.9716937 0 0.2361268 0.9717223 3.21011e-5 0.2361062 0.9717273 0 0.6556431 0.7550711 0 0.6556434 0.7550707 0 0.929027 0.3700121 0 0.929027 0.3700121 0 0.9952335 -0.09752202 0 0.9952334 -0.09752202 0 0.8395074 -0.5433483 0 0.8395075 -0.5433483 0 0.7071058 0.7071079 0 0.7071068 0.7071068 0 0.8408237 -0.5413092 0 0.8408576 -0.5412566 -3.5192e-5 0.8410019 -0.5410324 0 0.9818742 -0.189534 0 0.9818742 -0.189534 0 0.7229934 -0.690855 0 0.7229874 -0.6908613 7.7665e-5 0.7229898 -0.6908588 2.89586e-5 0.7229875 -0.6908611 0 -0.7071074 0.7071063 0 -0.7071076 0.7071061 0 -0.7071081 0.7071055 0 -0.7071071 0.7071065 0 0.7071071 0.7071065 0 -0.7229895 0.690859 0 -0.7229907 0.6908578 -1.10009e-5 -0.7229916 0.6908568 0 0.971832 0.2356746 0 0.971834 0.2356666 0 0.7560544 0.6545088 0 0.7560545 0.6545089 0 0.3720215 0.9282242 0 0.3720245 0.928223 0 -0.09420967 0.9955524 0 -0.5398544 0.8417585 0 -0.5398543 0.8417585 0 -0.5398544 -0.8417585 0 -0.5398543 -0.8417585 0 -0.09420967 -0.9955524 0 0.3720245 -0.928223 0 0.3720215 -0.9282242 0 0.7560544 -0.6545088 0 0.7560545 -0.6545089 0 0.971834 -0.2356665 0 0.9718321 -0.2356747 0 -0.9659118 -0.2588717 0 -0.965912 0.258871 0 -0.9659166 0.2588535 0 -0.7071063 0.7071073 0 -0.7070983 0.7071152 -2.92851e-6 -0.7071311 0.7070826 0 -0.2588681 0.9659127 0 -0.2588634 0.965914 0 0.2588658 0.9659134 0 0.2588634 0.965914 0 0.707103 0.7071107 0 0.7071124 0.7071012 0 0.965912 0.258871 0 0.9659166 0.2588535 0 0.9659164 -0.2588542 0 0.9659118 -0.2588717 0 0.7071109 -0.7071027 0 0.7071015 -0.7071121 0 0.2588634 -0.965914 0 0.2588657 -0.9659134 0 -0.2588634 -0.965914 0 -0.258868 -0.9659127 0 -0.707137 -0.7070766 0 -0.7070968 -0.7071167 0 -0.7071025 -0.7071111 0 -0.9659164 -0.2588542 0 -0.9659119 -0.258871 0 -0.9659118 0.2588717 0 -0.9659164 0.2588542 0 -0.7071025 0.7071111 0 -0.7070968 0.7071167 -5.85703e-7 -0.707137 0.7070766 0 0.7071015 0.707112 0 0.7071108 0.7071027 0 0.9659118 0.2588717 0 0.9659164 0.2588542 0 0.9659166 -0.2588536 0 0.9659119 -0.258871 0 0.7071124 -0.7071013 0 0.707103 -0.7071106 0 -0.7071311 -0.7070826 0 -0.7070983 -0.7071153 -2.34281e-6 -0.7071063 -0.7071073 0 -0.9659166 -0.2588536 0 -0.9659122 0.2588703 0 -0.9659169 0.2588528 0 -0.7071045 0.7071092 0 -0.7070968 0.7071168 -4.68562e-6 0.9659122 0.2588703 0 0.9659169 0.2588528 0 -0.7071429 -0.7070707 0 -0.7070968 -0.7071168 4.68562e-6 -0.7071006 -0.707113 0 -0.9659122 -0.2588703 0 -0.7071006 0.707113 0 -0.7070968 0.7071168 4.68562e-6 -0.7071429 0.7070707 0 0.9659169 -0.2588528 0 0.9659122 -0.2588703 0 -0.7070968 -0.7071169 -4.68562e-6 -0.7071045 -0.7071092 0 -0.9659169 -0.2588528 0 0 -1 -2.0641e-6 -0.7071066 -0.707107 0 -0.7071049 -0.7071087 8.57476e-6 -0.7071119 -0.7071018 0 0.7071081 -0.7071055 0 0.7071071 -0.7071065 0 0.9659119 0.258871 0 0.7071025 -0.7071111 0 0.7070968 -0.7071167 -5.85703e-7 0.707137 -0.7070766 0 0.2588681 -0.9659127 0 0.2588634 -0.965914 0 -0.2588658 -0.9659134 0 -0.2588634 -0.965914 0 -0.7071015 -0.707112 0 -0.7071108 -0.7071027 0 -0.9659166 0.2588536 0 -0.9659119 0.258871 0 -0.7071124 0.7071013 0 -0.707103 0.7071106 0 -0.2588634 0.965914 0 -0.2588657 0.9659134 0 0.2588634 0.965914 0 0.258868 0.9659127 0 0.7071311 0.7070826 0 0.7070983 0.7071153 -2.34281e-6 0.7071063 0.7071073 0 0.9659166 0.2588536 0 -0.7071119 0.7071018 0 -0.7071049 0.7071087 8.57476e-6 -0.7071066 0.707107 0 -0.7229934 0.690855 0 -0.7229898 0.6908588 4.3438e-5 -0.7229875 0.6908612 0 0.7071074 -0.7071063 0 0.7071076 -0.7071061 0 0.839481 0.5433893 0 0.8395173 0.543333 -3.04959e-5 0.8395321 0.5433102 0 0.9952319 0.09753829 0 0.9952319 0.09753751 0 0.929029 -0.3700069 0 0.9290289 -0.3700072 0 0.6556513 -0.7550638 0 0.655651 -0.7550642 0 0.2361233 -0.9717231 0 0.2361232 -0.9717231 0 -0.2362443 -0.9716937 0 -0.2361268 -0.9717223 3.21011e-5 -0.8394553 0.5434289 0 -0.8395075 0.5433483 -4.49408e-5 -0.8395283 0.5433161 0 -0.9952334 0.09752202 0 -0.9952335 0.09752202 0 -0.929027 -0.3700121 0 -0.929027 -0.3700121 0 -0.6556434 -0.7550707 0 -0.6556431 -0.7550711 0 -0.2361062 -0.9717273 0 -0.7071058 -0.7071079 0 -0.7071068 -0.7071068 0 -0.8771582 0.4802016 0 -0.8771603 0.4801978 0 -0.9603019 0.278963 0 -0.9882226 -0.1530231 0 -0.9882235 -0.1530176 0 -0.8309588 -0.5563342 0 -0.830976 -0.5563084 -3.29155e-5 0.3223003 -0.9466375 0 0.3223072 -0.9466351 -5.60275e-6 0.3223099 -0.9466343 0 -0.1079728 -0.9941539 0 -0.1079728 -0.9941539 0 -0.5179765 -0.8553948 0 -0.517979 -0.8553935 0 -0.8310309 -0.5562264 0 0.5195269 -0.8544542 0 0.5195379 -0.8544474 0 0.5196542 -0.8543768 1.64319e-4 0.5195487 -0.8544409 0 0.5195506 -0.8544398 -2.52015e-5 0.5193766 -0.8545456 4.91183e-5 0 -1 -4.85063e-6 0 -1 -2.62025e-5 0 -1 -2.85331e-6 0 -1 -8.0844e-6 -0.5194932 -0.8544747 0 -0.5195488 -0.8544409 -2.26289e-5 -0.5195487 -0.8544409 -2.98975e-5 -0.5195546 -0.8544373 1.03643e-5 -0.5195466 -0.8544422 0 0.1080038 -0.9941506 -5.6291e-5 0.1079728 -0.9941539 0 -0.3223099 -0.9466343 0 -0.3223072 -0.9466351 -5.60275e-6 -0.3223003 -0.9466375 0 0.1079267 -0.9941589 0 0.5179765 -0.855395 0 0.517979 -0.8553934 0 0.8310309 -0.5562264 0 0.830976 -0.5563084 -3.36158e-5 0.8309588 -0.5563342 0 0.9882235 -0.1530176 0 0.9882227 -0.1530231 0 0.9603019 0.278963 0 0.8771604 0.4801977 0 0.8771582 0.4802017 0 0.7072834 0.7069302 0 0.7072951 0.7069185 0 0.9659138 0.2588641 0 0.9659143 -0.2588623 0 0.7071008 -0.7071128 0 0.7070891 -0.7071245 0 0.2588733 -0.9659114 0 0.2588733 -0.9659113 0 -0.2588733 -0.9659114 0 -0.2588733 -0.9659113 0 0.8771582 -0.4802016 0 0.8771603 -0.4801978 0 0.9603019 -0.278963 0 0.9882226 0.1530231 0 0.9882235 0.1530176 0 0.830976 0.5563085 0 0.8309733 0.5563123 0 0.517979 0.8553935 0 0.5179765 0.8553948 0 0.1079267 0.9941589 0 0.107973 0.9941539 -3.36157e-5 -0.3223003 0.9466375 0 -0.3223072 0.9466351 -5.60275e-6 -0.3223099 0.9466343 0 0.1080033 0.9941505 0 -0.5195464 0.8544422 0 -0.5195487 0.8544409 -3.26155e-5 -0.5195523 0.8544388 0 0 1 -8.0844e-6 0 1 -2.62025e-5 0 1 6.46753e-6 0 1 3.73897e-6 0 1 -4.85063e-6 0.5195269 0.8544542 0 0.5195487 0.8544409 -1.08718e-5 0.5195503 0.8544399 1.85925e-5 0.5195379 0.8544474 0 0.3223003 0.9466375 0 0.3223072 0.9466351 -5.60275e-6 0.3223099 0.9466343 0 -0.1079728 0.9941539 0 -0.1079728 0.9941539 0 -0.5179765 0.855395 0 -0.517979 0.8553934 0 -0.8309733 0.5563123 0 -0.830976 0.5563084 0 -0.9882235 0.1530176 0 -0.9882227 0.1530231 0 -0.9603019 -0.278963 0 -0.8771604 -0.4801977 0 -0.8771582 -0.4802017 0 0.2948569 -0.9555415 0 0.2948492 -0.9555438 0 -0.1491538 -0.988814 0 -0.1491498 -0.9888147 0 -0.5635716 -0.8260673 0 -0.563597 -0.8260499 0 -0.8659427 -0.5001432 0 -0.8659428 -0.5001432 0 -0.9972151 -0.07457911 0 -0.9972131 -0.07460623 0 -0.9308588 0.3653793 0 -0.9308402 0.3654265 0 -0.6803098 0.7329248 0 -0.6803234 0.7329121 0 -0.7229934 -0.690855 0 -0.7229874 -0.6908612 7.64123e-5 -0.7229898 -0.6908588 2.98636e-5 -0.7229875 -0.6908611 0 -0.9818742 -0.189534 0 -0.9818742 -0.189534 0 -0.8410019 -0.5410324 0 -0.8408576 -0.5412566 -3.5192e-5 -0.8408237 -0.5413092 0 -0.7071068 0.7071068 0 -0.7071058 0.7071079 0 -0.8395074 -0.5433483 0 -0.8395075 -0.5433483 0 -0.9952335 -0.09752202 0 -0.9952334 -0.09752202 0 -0.929027 0.3700121 0 -0.6556434 0.7550707 0 -0.6556431 0.7550711 0 -0.2361062 0.9717273 0 -0.2361268 0.9717223 2.96935e-5 -0.2362443 0.9716937 0 0.2361231 0.9717231 0 0.2361233 0.9717231 0 0.655651 0.7550642 0 0.6556513 0.7550638 0 0.9290289 0.3700072 0 0.9290291 0.3700069 0 0.9952319 -0.09753751 0 0.9952319 -0.09753829 0 0.8395175 -0.5433327 0 0.8395174 -0.543333 0 0.7071076 0.7071061 0 0.7071074 0.7071063 0 0.8735003 -0.4868239 0 0.8735007 -0.4868231 0 0.8735003 0.4868239 0 0.8735007 0.4868231 0 -0.971832 -0.2356746 0 -0.971834 -0.2356666 0 -0.7560544 -0.6545088 0 -0.7560545 -0.6545089 0 -0.3720215 -0.9282242 0 -0.3720245 -0.928223 0 0.09420967 -0.9955524 0 0.5398544 -0.8417585 0 0.5398543 -0.8417585 0 0.965912 -0.258871 0 0.9659166 -0.2588535 0 0.7071063 -0.7071073 0 0.7070983 -0.7071152 -2.92851e-6 0.7071311 -0.7070826 0 -0.707103 -0.7071107 0 -0.7071124 -0.7071012 0 -0.965912 -0.258871 0 -0.9659166 -0.2588535 0 -0.7071109 0.7071027 0 -0.7071015 0.7071121 0 0.707137 0.7070766 0 0.7070968 0.7071167 0 0 -1 -2.20484e-6 0.7071077 -0.7071059 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.8408237 0.5413092 0 -0.8408576 0.5412566 -3.5192e-5 -0.8410019 0.5410324 0 -0.9818742 0.189534 0 -0.9818742 0.189534 0 -0.2589706 -0.4831858 -0.8363407 0.2589627 -0.4831869 -0.8363426 0.2589399 -0.4831835 -0.8363515 0.7071245 -0.353722 -0.6122546 0.7071501 -0.3537029 -0.6122362 0.9659742 -0.1293801 -0.2239522 0.9659106 -0.1294235 -0.2242018 0.9658447 0.1295535 0.22441 0.9659095 0.1295067 0.2241587 0.7076157 0.3534735 0.6118306 0.7071509 0.3535243 0.6123383 0.2587713 0.4829462 0.8365408 0.2588086 0.4829555 0.8365238 -0.2588023 0.4829468 0.8365309 -0.2587779 0.4829533 0.8365346 -0.7076269 0.3532793 0.6119297 -0.7071273 0.353717 0.6122544 -0.9658502 0.1296035 0.2243578 -0.9659101 0.129449 0.2241889 -0.965975 -0.1293289 -0.2239786 -0.9659143 -0.129484 -0.2241509 -0.7071368 -0.3537154 -0.6122442 -0.7071273 -0.353717 -0.6122544 -0.2589306 -0.4831928 -0.8363491 -0.9848077 -0.08681988 -0.1503863 -0.9848076 -0.08682876 -0.1503827 0.9848071 0.08682537 0.1503875 0.9848082 0.08681595 0.1503858 0.9990462 -0.02182281 -0.03782248 0.9990459 -0.02184236 -0.03782051 0.8869839 -0.2308981 -0.3999321 0.8869913 -0.230885 -0.3999233 0.6089422 -0.3965941 -0.6869517 0.6089369 -0.3966075 -0.6869485 0.2154536 -0.4882462 -0.8456923 0.2165243 -0.4883723 -0.8453459 4.66587e-4 -0.8658328 0.5003334 -6.66453e-5 -0.8660033 0.5000383 -8.29299e-4 -0.8667786 0.4986924 -0.001216828 -0.8670673 0.4981896 2.81172e-4 -0.8658041 0.5003832 8.00216e-5 -0.8660166 0.5000152 -1.54655e-4 -0.8663028 0.4995194 2.30045e-5 -0.8660383 0.4999777 4.66245e-5 -0.8660355 0.4999826 3.55011e-5 -0.8659872 0.5000663 -1.10931e-5 -0.8660641 0.4999331 0 -0.866029 0.4999938 1.28135e-5 -0.8660522 0.4999538 -4.75096e-5 -0.8659932 0.5000559 -5.34576e-5 -0.8660134 0.5000211 -3.60633e-6 -0.8660266 0.499998 4.35076e-5 -0.8660284 0.4999949 5.55632e-5 -0.8660179 0.5000131 8.09791e-4 -0.8652958 0.5012609 9.68931e-5 -0.8660874 0.4998925 0 -0.8662373 0.4996331 -1.02501e-4 -0.8661172 0.499841 1.65556e-4 -0.8663727 0.4993982 -7.95825e-4 -0.8652706 0.5013045 2.26301e-4 -0.8661831 0.4997268 7.58558e-4 -0.8667809 0.4986885 1.96653e-5 -0.86602 0.5000096 4.10337e-5 -0.8660304 0.4999913 1.33297e-4 -0.8660416 0.4999723 -4.57867e-5 -0.8660262 0.4999986 -4.73971e-5 -0.8660266 0.4999979 4.25471e-5 -0.866033 0.4999868 -1.42149e-5 -0.8660327 0.4999874 1.02782e-4 -0.8659523 0.5001268 -1.41046e-5 -0.8660349 0.4999837 1.3915e-6 -0.8660171 0.5000146 1.77943e-4 -0.8660204 0.5000087 4.30911e-6 -0.8660284 0.499995 9.62908e-6 -0.8660277 0.4999961 -5.21991e-5 -0.8660326 0.4999877 4.49525e-5 -0.8660196 0.5000101 -1.33427e-4 -0.866036 0.4999817 -2.68362e-4 -0.8661718 0.4997462 6.6405e-4 -0.8650537 0.5016788 9.8372e-6 -0.8660148 0.5000184 -4.72162e-6 -0.8660303 0.4999916 3.6734e-5 -0.86601 0.5000268 -1.52241e-5 -0.8660442 0.4999675 -2.98316e-5 -0.8660272 0.4999969 -1.00024e-5 -0.86604 0.4999749 -7.97455e-5 -0.8660357 0.4999823 -1.43911e-5 -0.8660293 0.4999934 0.003495156 -0.8656275 0.5006765 -1.35762e-4 -0.8660383 0.4999778 -3.07201e-4 -0.8658594 0.5002873 -3.73389e-5 -0.8660297 0.4999925 -5.27768e-5 -0.8660337 0.4999857 -3.59213e-5 -0.8660362 0.4999814 -0.2587934 -0.4829789 -0.8365151 0.2587932 -0.4829802 -0.8365144 0.2587904 -0.4829764 -0.8365175 0.7071436 -0.3535447 -0.612335 0.7071429 -0.3535476 -0.6123342 0.9659137 -0.1294393 -0.2241795 0.9659144 -0.1294328 -0.2241801 0.9659119 0.1294409 0.2241857 0.9659123 0.129441 0.2241843 0.7071496 0.3535387 0.6123315 0.7071111 0.3535377 0.6123766 0.2587916 0.4829457 0.8365347 0.2588658 0.4829714 0.8364971 -0.2587926 0.4829816 0.8365138 -0.258867 0.4829344 0.836518 -0.7071502 0.3535177 0.6123429 -0.7071088 0.3535646 0.6123637 -0.9659142 0.1294345 0.2241796 -0.9659143 0.1294344 0.2241794 -0.9659147 -0.1294394 -0.2241746 -0.9659164 -0.1294261 -0.2241752 -0.7071436 -0.3535447 -0.612335 -0.7071446 -0.3535416 -0.6123356 -0.2587921 -0.4829778 -0.8365162 1.14148e-5 0.8660284 -0.4999949 -3.728e-5 0.8660045 -0.5000363 7.80886e-6 0.8660334 -0.4999862 -6.25089e-6 0.8660277 -0.4999963 -3.12637e-5 0.8660291 -0.4999938 3.73177e-5 0.8659745 -0.5000884 0 0.8660213 -0.5000072 -1.50614e-4 0.8660181 -0.5000127 9.92767e-5 0.86603 -0.4999923 1.31832e-4 0.8660354 -0.4999828 -3.36978e-5 0.8659822 -0.5000749 2.60313e-5 0.8660458 -0.499965 -2.549e-4 0.8657564 -0.5004658 -2.97179e-5 0.8660219 -0.5000061 1.20475e-4 0.8660315 -0.4999896 -5.19931e-5 0.8660114 -0.5000245 -9.15421e-5 0.8660214 -0.500007 4.72173e-5 0.8660309 -0.4999908 5.99306e-5 0.866024 -0.5000026 -9.6529e-4 0.8662785 -0.4995604 -1.60276e-4 0.8659182 -0.5001858 1.65371e-4 0.8662886 -0.4995439 -2.80697e-5 0.8660228 -0.5000048 -2.21934e-5 0.8660222 -0.5000056 -7.19957e-5 0.8660179 -0.5000131 -1.50289e-6 0.8660238 -0.5000029 0 0.8660236 -0.5000033 -0.00148499 0.8654827 -0.5009366 1.06479e-4 0.8660506 -0.4999564 0.001277089 0.8653261 -0.5012077 7.47449e-6 0.8660337 -0.4999858 -1.60671e-6 0.8660278 -0.4999959 -1.24135e-4 0.8660939 -0.4998813 3.56595e-5 0.865982 -0.5000752 -2.59293e-5 0.8660377 -0.4999786 -2.32206e-5 0.8660348 -0.4999839 -7.4492e-6 0.866014 -0.50002 -1.15209e-5 0.8660268 -0.4999977 1.34862e-4 0.8660299 -0.4999924 -1.15521e-4 0.8659943 -0.5000538 -9.29453e-5 0.8660129 -0.5000219 5.45856e-5 0.8659949 -0.5000529 -1.37363e-5 0.8660386 -0.4999772 0 0.8660312 -0.4999899 1.1892e-5 0.8660498 -0.4999579 -4.12068e-5 0.8659907 -0.5000602 9.40915e-5 0.8660392 -0.4999762 -4.667e-5 0.8660272 -0.4999969 9.8952e-5 0.8660281 -0.4999954 4.94241e-5 0.8660176 -0.5000135 -1.49296e-4 0.8660167 -0.5000153 7.21988e-6 0.8660293 -0.4999935 2.2569e-6 0.8660235 -0.5000034 1.27222e-5 0.8660408 -0.4999735 6.31314e-5 0.866025 -0.5000007 2.19592e-5 0.8660355 -0.4999824 6.45974e-5 0.8660845 -0.4998978 -3.98043e-5 0.8659623 -0.5001093 -0.2587538 -0.4829812 -0.836526 0.2587544 -0.482985 -0.8365237 0.2587563 -0.4829728 -0.83653 0.7071231 -0.3535534 -0.6123536 0.7071211 -0.3535555 -0.6123546 0.9659167 -0.1294277 -0.2241729 0.9659165 -0.1294274 -0.2241741 0.9659163 0.1294345 0.2241711 0.9659138 0.1294289 0.2241851 0.7071229 0.3535448 0.6123589 0.7071103 0.3535381 0.6123773 0.2587912 0.4829527 0.836531 0.2588636 0.4829636 0.8365021 -0.2587903 0.4829763 0.8365175 -0.2588675 0.4829453 0.8365115 -0.7071241 0.3535377 0.6123615 -0.7071082 0.3535481 0.612374 -0.9659191 0.1294158 0.224169 -0.9659138 0.1294412 0.2241776 -0.9659186 -0.1294211 -0.2241683 -0.965917 -0.1294345 -0.2241678 -0.7071205 -0.3535572 -0.6123544 -0.7071245 -0.3535487 -0.6123546 -0.2587578 -0.4829849 -0.8365225 -0.2587507 0.4829801 0.8365275 0.2588222 0.4829711 0.8365107 0.2587482 0.4829627 0.8365383 0.7071545 0.3535208 0.6123362 0.7071927 0.3535204 0.6122922 0.9659063 0.1294544 0.2242023 0.9659076 0.1294401 0.224205 0.9659169 -0.1294291 -0.2241714 0.965917 -0.1294289 -0.224171 0.7071177 -0.3535579 -0.6123571 0.7071223 -0.3535501 -0.6123564 0.2588846 -0.4829614 -0.836497 0.2588786 -0.482971 -0.8364933 -0.2588874 -0.4829701 -0.8364909 -0.258883 -0.4829568 -0.8365001 -0.7071205 -0.3535482 -0.6123596 -0.7071205 -0.3535566 -0.6123548 -0.9659188 -0.1294143 -0.2241714 -0.9659152 -0.1294435 -0.2241706 -0.9659056 0.1294612 0.2242013 -0.9659082 0.1294333 0.224206 -0.7071534 0.3535405 0.6123261 -0.7071958 0.3534942 0.612304 -0.2588255 0.482944 0.8365253 -0.2587482 0.4829829 0.8365268 0.258825 0.482967 0.8365122 0.2587508 0.48296 0.836539 0.9659082 0.1294398 0.2242028 0.9659057 0.1294547 0.2242046 0.9659159 -0.1294364 -0.2241712 0.9659179 -0.1294216 -0.2241712 0.2588886 -0.4829631 -0.8364948 0.2588821 -0.4829626 -0.8364971 -0.2588876 -0.4829688 -0.8364918 -0.2588796 -0.4829652 -0.8364963 -0.7071187 -0.353563 -0.6123532 -0.9659174 -0.1294252 -0.2241711 -0.965916 -0.1294362 -0.2241708 -0.9659075 0.1294467 0.2242017 -0.9659065 0.1294478 0.2242056 -0.7071939 0.3535006 0.6123024 -0.2588253 0.4829455 0.8365245 -0.2589717 -0.4831792 -0.8363441 0.2589634 -0.4831827 -0.8363448 0.2589388 -0.48319 -0.8363481 0.7071261 -0.3537164 -0.6122559 0.707148 -0.3537104 -0.6122343 0.965977 -0.1293805 -0.2239401 0.9659122 -0.1294323 -0.2241894 0.9658471 0.1295538 0.2243999 0.9659133 0.1294987 0.2241467 0.7076141 0.3534791 0.6118292 0.7071494 0.353515 0.6123454 0.2587698 0.4829552 0.8365361 0.2588097 0.482949 0.8365273 -0.258802 0.4829484 0.83653 -0.7076328 0.3532737 0.6119262 -0.7071309 0.3537189 0.6122491 -0.9658461 0.1296285 0.2243611 -0.9659119 0.1294237 0.2241957 -0.9659768 -0.1293036 -0.2239855 -0.9659097 -0.129509 -0.2241563 -0.7071405 -0.3537173 -0.6122389 -0.7071331 -0.3537114 -0.6122509 -0.2589302 -0.4831951 -0.8363478 -0.2587524 -0.4829785 -0.8365281 0.2587563 -0.4829851 -0.836523 0.258757 -0.4829809 -0.8365253 0.7071222 -0.3535564 -0.6123529 0.7071229 -0.3535495 -0.6123561 0.9659178 -0.1294279 -0.2241681 0.9659179 -0.1294276 -0.2241676 0.9659181 0.1294279 0.2241665 0.9659149 0.1294291 0.2241802 0.7071237 0.3535418 0.6123597 0.7071086 0.3535441 0.6123758 0.2588666 0.4829691 0.836498 -0.2587879 0.4829788 0.8365167 -0.2588669 0.4829374 0.8365163 -0.707125 0.3535348 0.6123622 -0.9659163 0.1294291 0.2241735 -0.9659135 0.1294343 0.2241827 -0.9659167 -0.1294277 -0.2241729 -0.9659155 -0.1294343 -0.2241743 -0.2587568 -0.4829796 -0.836526 0 -0.5002515 -0.8658802 0 -0.5002455 -0.8658837 0.9990462 -0.02183806 -0.03781485 0.9990466 -0.02182203 -0.03781354 0.8869826 -0.2308952 -0.3999366 0.8869866 -0.2308889 -0.3999314 0.608941 -0.3965983 -0.6869503 0.6089394 -0.396599 -0.6869513 0.2154508 -0.4882483 -0.8456918 0.2165214 -0.4883759 -0.8453447 0.9848075 0.0868225 0.1503864 0.9848079 0.08682346 0.1503834 0.9848079 0.08682423 0.1503832 0.9848074 0.0868234 0.1503862 -0.9848077 -0.08683085 -0.1503801 -0.984809 -0.08681589 -0.1503803 -0.9848063 -0.08683305 -0.1503881 -0.9848067 -0.08682066 -0.1503929 0 0.5000132 0.8660179 -0.9848079 -0.08681964 -0.1503858 -0.9848077 -0.08682167 -0.1503853 -0.230633 -0.4865408 -0.8426663 -0.230656 -0.4865041 -0.8426812 -0.2305836 -0.4865378 -0.8426816 -0.2304463 -0.4865344 -0.8427211 -0.6429131 -0.3829504 -0.663334 -0.6428465 -0.3830098 -0.6633642 -0.9181721 -0.1980967 -0.3431001 -0.9181909 -0.1980647 -0.3430685 0 -0.5000117 -0.8660187 0 -0.5000084 -0.8660207 -0.9659095 -0.1294425 -0.2241954 -0.9659098 -0.1294376 -0.2241966 -0.7071433 -0.3535421 -0.6123369 -0.7071387 -0.3535481 -0.6123387 -0.2587837 -0.4829688 -0.836524 -0.2587945 -0.4829934 -0.8365064 -1 -3.85852e-6 0 9.30673e-5 0.8660171 -0.5000145 0 0.865995 -0.5000529 0 0.8660171 -0.5000146 1.37622e-4 0.8660486 -0.4999599 -4.14539e-4 0.8659178 -0.5001863 -1.10527e-4 0.8660049 -0.5000355 1.7255e-4 0.8660464 -0.4999637 -1.51826e-5 0.8660309 -0.4999905 3.22352e-5 0.8659713 -0.5000938 0 0.8660373 -0.4999795 -6.1226e-5 0.8660046 -0.5000361 2.31104e-5 0.8660339 -0.4999853 -5.41823e-6 0.8660262 -0.4999986 7.28063e-5 0.8659985 -0.5000467 3.18925e-5 0.8660312 -0.4999899 -1.31118e-4 0.8660764 -0.4999117 -3.47368e-5 0.8660207 -0.5000082 2.89759e-5 0.8660059 -0.5000339 1.03584e-4 0.8659927 -0.5000569 -1.47353e-4 0.866066 -0.4999296 0 0.8660181 -0.5000129 0 0.8661285 -0.4998216 0 0.8661323 -0.499815 0 0.8660008 -0.5000428 -2.34068e-5 0.8660347 -0.4999841 -1.18909e-4 0.8659863 -0.500068 9.65795e-5 0.8660469 -0.4999629 1.26071e-4 0.8660663 -0.4999293 -1.35299e-4 0.8659783 -0.5000817 0 0.8660326 -0.4999878 5.63635e-5 0.8660028 -0.5000392 -1.38137e-4 0.8660804 -0.4999049 -1.26324e-5 0.8660261 -0.4999989 1.29991e-4 0.866038 -0.4999783 -1.15866e-4 0.8660145 -0.5000188 1.15356e-4 0.8660211 -0.5000077 -1.00928e-4 0.8660368 -0.4999804 -1.30319e-5 0.8660253 -0.5000003 9.7013e-5 0.8660234 -0.5000035 -6.91377e-5 0.8660343 -0.4999847 4.58594e-5 0.8660324 -0.4999881 5.75731e-5 0.8660247 -0.5000014 1.65372e-4 0.8662878 -0.4995453 -2.80697e-5 0.8660194 -0.5000107 -2.17195e-5 0.8660224 -0.5000054 -7.89163e-5 0.8660184 -0.5000124 -5.05448e-5 0.8660195 -0.5000101 -1.7298e-4 0.866028 -0.4999957 -2.24437e-5 0.8660249 -0.5000008 -5.85292e-5 0.8660218 -0.5000064 -3.12639e-5 0.8660414 -0.4999724 3.73177e-5 0.8659744 -0.5000886 0 0.8660207 -0.5000082 -3.36964e-5 0.8659551 -0.5001218 2.60314e-5 0.8660418 -0.4999716 -2.97178e-5 0.8660261 -0.4999989 -2.81175e-4 0.8658009 -0.5003888 -6.9207e-5 0.8660271 -0.4999973 0.001176357 0.8651267 -0.5015519 -1.08017e-4 0.8662579 -0.4995971 9.47372e-5 0.8660315 -0.4999894 3.05677e-4 0.865857 -0.5002915 1.83365e-4 0.8659966 -0.5000499 1.28311e-4 0.866039 -0.4999766 4.44698e-5 0.8660292 -0.4999935 -6.07599e-5 0.8660162 -0.5000161 1.03647e-4 0.8660389 -0.4999766 0 0.866023 -0.5000044 0 0.8660257 -0.4999997 -7.8368e-5 0.8659883 -0.5000643 7.84111e-5 0.8660501 -0.4999574 -4.17906e-6 0.8660258 -0.4999994 -3.90656e-6 0.8660236 -0.5000033 -1.20346e-5 0.8660324 -0.499988 4.15029e-5 0.866008 -0.5000302 -6.24957e-5 0.8660196 -0.5000101 8.71228e-6 0.8660119 -0.5000236 -6.07736e-6 0.8660238 -0.5000029 1.23779e-5 0.8660378 -0.4999787 -1.28405e-4 0.866028 -0.4999955 -1.8767e-5 0.8660316 -0.4999893 -8.38058e-6 0.866016 -0.5000163 -2.23602e-5 0.866033 -0.4999869 -2.62536e-5 0.8660407 -0.4999736 3.62252e-5 0.8659863 -0.5000678 4.93292e-5 0.8660199 -0.5000096 9.85895e-5 0.8660262 -0.4999986 -4.65657e-5 0.8660281 -0.4999954 -9.68084e-5 0.8660187 -0.5000119 1.49036e-4 0.8660182 -0.5000126 5.47541e-5 0.8659949 -0.5000529 0 0.8660334 -0.4999861 -2.63418e-5 0.8660223 -0.5000056 1.67162e-5 0.8660383 -0.4999775 -8.88317e-5 0.8660098 -0.5000273 6.04106e-5 0.8660314 -0.4999896 8.09092e-5 0.866052 -0.4999541 7.56136e-5 0.8660282 -0.4999952 -1.49034e-4 0.8660218 -0.5000063 6.82877e-4 0.8659568 -0.5001184 5.00996e-4 0.8659703 -0.5000954 0 0.8660351 -0.4999832 0 0.8660264 -0.4999983 4.35755e-6 0.8660246 -0.5000013 0 0.8660354 -0.4999828 4.81924e-5 0.8660134 -0.5000207 6.31329e-5 0.8660449 -0.4999663 -0.2587912 -0.4829814 -0.8365144 0.2587937 -0.4829776 -0.8365157 0.2587919 -0.4829791 -0.8365154 0.7071427 -0.3535476 -0.6123343 0.7071446 -0.3535416 -0.6123356 0.9659156 -0.1294327 -0.2241749 0.9659163 -0.1294263 -0.2241754 0.9659143 0.1294344 0.2241795 0.9659143 0.1294345 0.2241796 0.7071505 0.3535357 0.6123323 0.7071094 0.3535436 0.6123751 0.2587929 0.4829499 0.836532 0.2588667 0.4829661 0.8364998 -0.2587914 0.4829775 0.8365165 -0.2588661 0.4829396 0.8365152 -0.9659127 0.1294343 0.2241861 -0.9659124 0.129441 0.224184 -0.9659137 -0.1294393 -0.2241795 -0.9659144 -0.1294327 -0.2241799 -0.7071453 -0.3535386 -0.6123365 -0.7071412 -0.3535535 -0.6123327 -0.2587925 -0.4829751 -0.8365175 9.90702e-6 -0.8660325 0.4999877 0.003057777 -0.867923 0.4966895 0.003057777 -0.8679232 0.4966892 0.003057777 -0.867923 0.4966893 1.27954e-5 -0.8660491 0.4999589 0 -0.865995 0.5000529 1.67044e-5 -0.8660356 0.4999823 -1.86489e-4 -0.8658894 0.5002357 -1.3497e-4 -0.8659691 0.5000975 0 -0.8660326 0.4999878 2.25363e-5 -0.8660268 0.4999978 0 -0.8660353 0.4999829 7.41419e-5 -0.8659991 0.5000458 -1.86041e-6 -0.8660374 0.4999795 -2.40346e-5 -0.8660292 0.4999935 3.87016e-6 -0.8660272 0.4999968 -5.91701e-5 -0.8659987 0.5000464 -1.45761e-6 -0.8660287 0.4999943 4.65568e-4 -0.8659563 0.5001197 -2.37537e-5 -0.8660274 0.4999966 0 -0.8660256 0.4999997 1.74123e-5 -0.8660327 0.4999874 -3.84959e-5 -0.8660141 0.5000197 -1.81712e-6 -0.8660184 0.5000124 1.84792e-5 -0.8660497 0.4999581 -2.46052e-5 -0.8660122 0.5000231 -9.50333e-6 -0.8660057 0.5000342 1.87255e-5 -0.8660496 0.4999583 -3.34957e-5 -0.8660007 0.5000429 -1.08926e-4 -0.8660197 0.5000098 6.96169e-5 -0.8660402 0.4999743 0 -0.8660302 0.4999918 0 -0.8660385 0.4999776 0 -0.8659732 0.5000907 0 -0.8660212 0.5000073 2.51024e-4 -0.8660863 0.4998946 1.7376e-5 -0.8660277 0.4999961 1.07937e-4 -0.8660367 0.4999806 1.20918e-4 -0.8660303 0.4999917 0 -0.8660232 0.5000041 0 -0.8662489 0.4996126 0 -0.8662431 0.4996227 0 -0.8659679 0.5000997 0 -0.866025 0.5000008 -3.17726e-6 -0.8660253 0.5000002 0 -0.8660289 0.4999939 -4.50507e-5 -0.8659998 0.5000443 -3.26612e-5 -0.8660196 0.5000101 1.77915e-4 -0.8660663 0.4999291 6.38401e-6 -0.8660397 0.4999753 4.24997e-5 -0.8660343 0.4999845 -4.73975e-5 -0.8660244 0.5000019 -4.57341e-5 -0.8660281 0.4999954 -1.00898e-5 -0.8660275 0.4999964 -3.89685e-5 -0.8660352 0.4999831 6.75882e-5 -0.8660103 0.5000262 -4.87581e-5 -0.8660218 0.5000066 4.24996e-5 -0.8660317 0.4999891 -8.30727e-5 -0.8660316 0.4999892 -1.18411e-5 -0.866029 0.4999937 -1.07909e-5 -0.8660271 0.499997 3.51336e-6 -0.8660246 0.5000014 4.34848e-5 -0.866032 0.4999888 -6.5794e-5 -0.8660216 0.5000069 -1.04062e-5 -0.8660362 0.4999813 7.58318e-5 -0.8660078 0.5000306 -1.55931e-5 -0.8660439 0.4999681 0 -0.866029 0.4999939 1.28134e-5 -0.8660489 0.4999593 -4.62456e-5 -0.866007 0.5000321 -4.74504e-5 -0.8659901 0.5000613 7.42703e-5 -0.8660786 0.4999079 -7.81307e-5 -0.8659556 0.5001211 -5.57645e-5 -0.8660301 0.4999919 9.48669e-6 -0.866021 0.5000079 9.0931e-5 -0.8660225 0.500005 -7.31672e-5 -0.8660238 0.5000029 -9.61244e-5 -0.8660261 0.4999988 2.10043e-5 -0.8660162 0.500016 8.30712e-5 -0.8660368 0.4999803 4.02062e-5 -0.8660086 0.5000291 0 -0.8660267 0.4999977 0 -0.8660274 0.4999966 2.9409e-5 -0.8660249 0.5000008 1.46548e-4 -0.8660318 0.499989 0.003308534 -0.8655898 0.5007427 -8.29303e-4 -0.8667773 0.4986948 -1.86278e-4 -0.8659612 0.5001112 8.92844e-5 -0.8660515 0.4999549 -1.64626e-4 -0.8659871 0.5000666 0.001240432 -0.8663135 0.4994993 -5.43451e-5 -0.8661513 0.499782 -0.001220881 -0.8670636 0.4981961 -4.93928e-5 -0.8660376 0.499979 -3.50292e-5 -0.8660336 0.4999859 1.08331e-5 -0.8660276 0.4999963 4.32128e-5 -0.8660234 0.5000035 -1.32545e-4 -0.8660356 0.4999826 -2.68362e-4 -0.8661829 0.499727 6.64054e-4 -0.865047 0.5016906 8.09773e-4 -0.8652763 0.5012946 9.68923e-5 -0.8660899 0.4998885 0 -0.8662366 0.499634 -1.025e-4 -0.8661016 0.499868 1.65562e-4 -0.8664084 0.499336 -7.958e-4 -0.8652575 0.5013272 2.26308e-4 -0.8662051 0.4996886 7.58558e-4 -0.8667707 0.4987064 -3.04156e-4 -0.8658658 0.5002762 -1.35341e-4 -0.8660399 0.4999751 -0.258729 0.4829973 0.8365243 -0.2588407 0.4829257 0.8365311 -0.7071737 0.3535162 0.6123167 -0.7071254 0.3535446 0.612356 -0.9659119 0.1294316 0.2241913 -0.96591 0.1294456 0.2241914 0 0.3831374 0.9236914 0 -0.1301818 0.9914902 0 -0.6085823 0.7934907 0 -0.6085823 0.7934908 0 -0.9236913 0.3831377 0 -0.9236952 0.3831284 0 -0.991504 -0.1300765 0 -0.7935298 -0.6085314 0 -0.3831335 -0.923693 0 -0.3831374 -0.9236914 0 0.1301205 -0.9914982 0 0.1301219 -0.9914981 0 0.6085771 -0.7934948 0 0.6085823 -0.7934908 0 0.9236913 -0.3831377 0 0.9236952 -0.3831284 0 0.9915039 0.1300771 0 0.7935547 0.608499 0 0.3831335 0.923693 -0.6274505 0.3520196 0.6945416 -0.4600415 0.7703447 0.4415098 -0.4600098 0.7704364 0.4413828 -0.1684202 0.9833098 0.06882178 -0.1686564 0.9832249 0.06945478 0.1685263 0.9316174 -0.322006 0.1684834 0.9316639 -0.3218941 0.4598706 0.629688 -0.6261087 0.4599742 0.6293255 -0.6263971 0.6274402 0.1595298 -0.7621478 0.6274448 0.1595448 -0.7621408 0.6273829 -0.3521161 -0.6945539 0.6274256 -0.3520359 -0.6945559 0.4598629 -0.7705258 -0.4413799 0.4602801 -0.7701287 -0.441638 0.1688956 -0.9831901 -0.06936603 0.1682655 -0.9833255 -0.06897711 -0.1684569 -0.9316613 0.3219154 -0.1684709 -0.9316524 0.3219339 -0.4599505 -0.629424 0.6263154 -0.46004 -0.62933 0.6263441 -0.6273823 -0.1599591 0.7621054 -0.6275636 -0.159576 0.7620364 -0.6274713 0.3522963 0.6943826 -0.5047778 0.3638938 0.7828032 -0.3700124 0.7790152 0.506188 -0.3700359 0.7787807 0.5065315 -0.1355788 0.9863637 0.0933023 -0.1354565 0.9864361 0.09271192 0.1355007 0.9285299 -0.345647 0.1354923 0.9285337 -0.3456401 0.370052 0.6207919 -0.6911432 0.3700331 0.620917 -0.691041 0.5048522 0.1479104 -0.8504393 0.5048467 0.1478788 -0.850448 0.5048035 -0.3637198 -0.7828675 0.5048548 -0.3635839 -0.7828975 0.3702279 -0.7787241 -0.5064783 0.3700392 -0.7789117 -0.5063275 0.1353887 -0.9864514 -0.09264779 0.1354612 -0.9864348 -0.09271907 -0.1355173 -0.9285224 0.3456607 -0.1354786 -0.9285327 0.3456483 -0.370078 -0.6207941 0.6911273 -0.3701322 -0.6207415 0.6911456 -0.5048331 -0.1478978 0.8504528 -0.5047021 -0.1481932 0.850479 -0.5047436 0.363713 0.7829092 -0.3696557 0.3726593 0.8511638 -0.2710052 0.7853924 0.5565205 -0.2710201 0.7855297 0.5563194 -0.09919977 0.9888556 0.1110143 -0.09918963 0.988873 0.1108676 0.09921389 0.9261179 -0.3639538 0.09922337 0.9260568 -0.3641068 0.2709556 0.6142791 -0.7411102 0.2709587 0.6144914 -0.7409331 0.3697192 0.1389035 -0.9187021 0.3697366 0.1390365 -0.918675 0.3697031 -0.3726521 -0.8511463 0.3697063 -0.3726533 -0.8511444 0.271016 -0.7855014 -0.5563611 0.2708854 -0.7856426 -0.5562257 0.09909743 -0.9888576 -0.1110873 0.09944891 -0.9887752 -0.1115064 -0.09921115 -0.9261175 0.3639554 -0.09927207 -0.926081 0.3640316 -0.2710524 -0.614148 0.7411835 -0.270901 -0.6143538 0.7410682 -0.3696693 -0.1391359 0.918687 -0.3697576 -0.1389461 0.9186803 -0.3697053 0.372867 0.8510512 -0.2255998 0.3788585 0.897536 -0.1654509 0.7900461 0.5902994 -0.1654344 0.7899693 0.5904067 -0.06056541 0.9905173 0.1233186 -0.06048607 0.9904236 0.1241078 0.06073725 0.9244328 -0.3764774 0.06069648 0.924225 -0.3769938 0.1653149 0.6099669 -0.7749913 0.1653213 0.6100086 -0.7749571 0.2255465 0.1329115 -0.9651235 0.2255253 0.1328153 -0.9651417 0.2255973 -0.3787947 -0.8975637 0.2255684 -0.3788623 -0.8975424 0.1654137 -0.7901086 -0.5902259 0.1652738 -0.7902818 -0.5900333 0.0606352 -0.9904299 -0.1239839 0.060705 -0.990408 -0.1241254 -0.06054049 -0.9244337 0.3765066 -0.06081348 -0.9242478 0.3769188 -0.1654169 -0.6098778 0.7750396 -0.1653288 -0.6100054 0.7749581 -0.2255454 -0.1328359 0.9651342 -0.2255152 -0.1329044 0.9651318 -0.2255828 0.378808 0.8975616 -0.07576769 0.3820297 0.9210389 -0.0555337 0.7922457 0.60767 -0.05557596 0.7923294 0.6075569 -0.02040207 0.9912475 0.1304315 -0.02049505 0.9912951 0.1300542 0.02026253 0.9233981 -0.3833085 0.02032756 0.923504 -0.3830499 0.05552124 0.607716 -0.7922114 0.05549854 0.607642 -0.7922696 0.07578635 0.1296997 -0.9886529 0.07579642 0.1297454 -0.9886462 0.07577931 -0.3819628 -0.9210656 0.07575488 -0.3820307 -0.9210396 0.05546152 -0.7925476 -0.6072828 0.05560517 -0.7923026 -0.6075893 0.02043497 -0.9912479 -0.130423 0.02028208 -0.9912995 -0.1300544 -0.02045625 -0.9234068 0.3832772 -0.02036148 -0.9235026 0.3830515 -0.05554181 -0.6077321 0.7921975 -0.05558097 -0.6076337 0.7922702 -0.07580757 -0.1297839 0.9886402 -0.07579743 -0.1298088 0.9886377 -0.07573562 0.3819567 0.9210718 0.7066646 0.09280341 0.7014362 0.7070626 0.091829 0.7011633 0.7071864 0.09296911 0.7008882 0.7072014 0.09295487 0.7008748 0.7073161 0.09255874 0.7008116 0.7071631 0.09259754 0.7009608 0.7069954 0.09280019 0.7011032 0.7067992 0.09268373 0.7013164 0.7073396 0.09246838 0.7007998 0.707157 0.09209871 0.7010326 0.7072282 0.0921244 0.7009575 0.707222 0.09301334 0.7008464 0.7071419 0.09283888 0.7009503 0.7071436 0.09286791 0.7009449 0.7070726 0.09227156 0.7010951 0.7070721 0.09226632 0.7010962 0.7069923 0.09261208 0.7011312 0.707156 0.09259474 0.7009685 0.7073582 0.0923416 0.7007977 0.7075585 0.09246826 0.7005789 0.7067612 0.09274435 0.7013467 0.7066456 0.09242594 0.7015052 0.7071682 0.09266811 0.7009463 0.7071761 0.09243512 0.7009691 0.6274029 0.1599345 -0.7620937 0.4599977 0.6293593 -0.6263459 0.4599382 0.6295263 -0.6262217 0.1685862 0.9316498 -0.3218811 0.1688472 0.9314364 -0.3223614 -0.1685026 0.9832652 0.0692563 -0.168614 0.983229 0.06949883 -0.4600049 0.7702577 0.4416999 -0.4599157 0.7704455 0.441465 -0.6274305 0.3522154 0.6944605 -0.6274226 0.3523153 0.6944169 -0.6273898 -0.1600918 0.7620714 -0.6274504 -0.1599396 0.7620534 -0.4602433 -0.6290268 0.6264994 -0.459877 -0.6294772 0.626316 -0.168421 -0.9316211 0.3220505 -0.1688289 -0.9314532 0.3223224 0.168497 -0.9832665 -0.06925153 0.1687112 -0.9832189 -0.06940704 0.459837 -0.7705326 -0.4413949 0.4598931 -0.7704662 -0.4414527 0.627413 -0.3521507 -0.6945091 0.6273583 -0.3523179 -0.6944738 0.6274051 0.1600258 -0.7620727 0.5047979 0.1482925 -0.850405 0.3700492 0.620988 -0.6909686 0.3701842 0.620384 -0.6914387 0.1357017 0.9282824 -0.3462322 0.135483 0.9285438 -0.3456166 -0.1357323 0.9863539 0.09318184 -0.1356612 0.9863848 0.09295892 -0.3700313 0.7790014 0.5061955 -0.3700971 0.7788138 0.5064358 -0.5047854 0.3639054 0.7827928 -0.5047634 0.3634513 0.7830181 -0.5047299 -0.1482208 0.8504577 -0.5048691 -0.1478089 0.8504469 -0.3699976 -0.6209415 0.691038 -0.369864 -0.6211221 0.6909471 -0.135758 -0.9283015 0.3461591 -0.1359308 -0.9282076 0.3463431 0.135737 -0.9863522 -0.09319317 0.1355669 -0.9863932 -0.09300637 0.3699639 -0.7790336 -0.5061951 0.3703525 -0.7786037 -0.5065722 0.5048136 -0.3639051 -0.7827749 0.5048421 -0.363829 -0.7827918 0.5047888 0.1482254 -0.850422 0.3696946 0.1390147 -0.9186952 0.2710741 0.6137862 -0.7414751 0.2710438 0.6142538 -0.7410989 0.09923386 0.9261251 -0.3639301 0.09925395 0.92607 -0.3640648 -0.09936439 0.9888086 0.1112849 -0.099505 0.9886986 0.1121337 -0.2710249 0.7853752 0.5565351 -0.270951 0.7858374 0.5559184 -0.3697498 0.3725382 0.851176 -0.3697631 0.3727437 0.8510802 -0.3697356 -0.138876 0.9186998 -0.3696734 -0.1391084 0.9186895 -0.2709733 -0.6144676 0.7409474 -0.2711341 -0.6142001 0.7411103 -0.09968292 -0.9257984 0.364638 -0.09925651 -0.9260681 0.3640687 0.0993635 -0.9888077 -0.1112939 0.09929627 -0.9888241 -0.1112084 0.271192 -0.7852386 -0.5566465 0.2710753 -0.7853887 -0.5564915 0.3697054 -0.372793 -0.8510837 0.3697217 -0.3727314 -0.8511035 0.3697099 0.1392279 -0.9186568 0.2255676 0.1328507 -0.965127 0.1654092 0.6097754 -0.7751219 0.165389 0.6094487 -0.7753831 0.06057 0.924431 -0.3765087 0.06056344 0.9247216 -0.3757953 -0.06061285 0.9903488 0.1246411 -0.06059604 0.9904931 0.1234971 -0.165304 0.7903689 0.5899083 -0.1652833 0.7900908 0.5902864 -0.2255155 0.378845 0.897563 -0.2254893 0.3786954 0.8976327 -0.2255287 -0.1329308 0.965125 -0.2255504 -0.132847 0.9651315 -0.1653621 -0.609718 0.775177 -0.1652479 -0.6099776 0.7749972 -0.06050443 -0.9244212 0.3765432 -0.06059116 -0.924342 0.3767235 0.06059783 -0.9904706 -0.123677 0.06049937 -0.9905037 -0.1234591 0.1653633 -0.7898913 -0.5905311 0.1652311 -0.7900935 -0.5902974 0.2255024 -0.3788518 -0.8975634 0.2255479 -0.3786982 -0.8976168 0.2255725 0.1328547 -0.9651252 0.07578706 0.1297691 -0.9886437 0.05552291 0.6072255 -0.7925871 0.05564731 0.6077688 -0.7921618 0.02044743 0.923887 -0.3821188 0.02025955 0.923382 -0.3833476 -0.02046966 0.9913303 0.1297888 -0.02039039 0.9912573 0.1303585 -0.05556446 0.7924095 0.6074535 -0.05554175 0.7923358 0.6075518 -0.07579082 0.3817884 0.921137 -0.07583326 0.3820004 0.9210457 -0.07579511 -0.1297163 0.9886501 -0.07580065 -0.1296706 0.9886556 -0.05555778 -0.6077396 0.7921907 -0.0555365 -0.6078473 0.7921095 -0.02036219 -0.9235095 0.3830346 -0.02046275 -0.9233865 0.3833261 0.0202642 -0.9913352 -0.1297845 0.02043658 -0.9912565 -0.1303564 0.05559027 -0.7924014 -0.6074619 0.05564767 -0.7922998 -0.6075892 0.07583594 -0.3817889 -0.9211331 0.0757606 -0.3820853 -0.9210164 0.07577985 0.1297233 -0.9886503 0 0.1301413 -0.9914956 0 -0.3831907 -0.9236693 0 -0.7935218 -0.6085419 0 -0.9914616 -0.1303994 0 -0.9914658 -0.1303672 0 -0.9235821 0.3834007 0 -0.9235764 0.3834146 0 -0.6087654 0.7933503 0 -0.6087812 0.7933382 0 -0.1300464 0.991508 0 -0.1300423 0.9915084 0 0.383099 0.9237073 0 0.3831048 0.9237049 0 0.7935644 0.6084864 0 0.7935486 0.6085071 0 0.9914637 0.1303833 0 0.9914616 0.1303994 0 0.9235764 -0.3834146 0 0.6087143 -0.7933895 0 0.1301434 -0.9914952 -1 4.85201e-6 0 -1 7.27273e-6 0 -1 -4.09456e-6 0 -1 -2.18337e-5 0 -1 -3.63652e-6 0 -1 4.09452e-6 0 -1 1.4557e-5 0 -1 1.94104e-5 0 -1 -1.45505e-5 0 -0.5000032 0.8660236 0 -0.5000022 0.8660241 0 -0.5000062 0.8660218 0 -0.499997 0.8660272 0 -0.4999979 0.8660266 0 0.4999986 0.8660262 0 0.4999963 0.8660276 0 0.5000072 0.8660213 0 0.5000085 0.8660205 0 0.5000032 0.8660236 0 0.5000022 0.8660241 0 -0.5000013 0.8660247 0 -0.5000014 0.8660246 0 -0.5000002 0.8660253 0 -0.4999995 0.8660258 0 0.8660262 0.4999986 0 0.8660262 0.4999988 0 -0.8660268 0.4999977 0 -0.8660256 0.4999997 0 -0.4999997 -0.8660256 0 -0.4999988 -0.8660262 0 -0.4999928 -0.8660296 0 0.8503882 0.5261558 0 0.8503895 0.5261538 0 0.8503491 0.5262192 0 0.8503469 0.5262225 0 0.8503918 0.5261501 0 0.8503925 0.526149 0 -0.8503918 0.5261501 0 -0.8503925 0.526149 0 -0.850346 0.5262241 0 -0.85035 0.5262177 0 -0.8503882 0.5261558 0 -0.8503895 0.5261538 0 -0.4999996 0.8660258 0 -0.4999985 0.8660264 0 -0.5 0.8660254 0 -0.4999978 0.8660268 0 -0.4999842 0.8660346 0 -0.4999831 0.8660352 0 -0.4999959 0.8660278 0 -0.4999957 0.866028 0 -0.5000058 0.8660221 0 -0.4999979 0.8660266 0 -0.4999985 0.8660264 0 -0.5000118 0.8660187 0 -0.03047436 0.9995356 0 -0.03047448 0.9995356 0 -0.03046679 0.9995359 0 -0.03046685 0.9995359 0 -0.0304085 0.9995375 0 -0.03040897 0.9995375 0 -0.03048437 0.9995353 0 -0.03048449 0.9995353 0 -0.8660293 0.4999932 0 -0.8660315 0.4999895 0 -0.8660073 0.5000313 0 -0.8660081 0.5000301 0 -0.8660278 0.4999958 0 -0.8660302 0.4999917 0 -0.880858 -0.4733808 0 -0.880858 -0.4733806 0 -0.880858 -0.4733809 0 -0.8808597 -0.4733775 0 -0.8808673 -0.4733634 0 -0.8808748 -0.4733495 0 -0.5000018 -0.8660244 0 -0.500003 -0.8660237 0 -0.5000003 -0.8660253 0 0.4999976 -0.8660269 0 0.4999984 -0.8660263 0 0.4999125 -0.8660759 0 0.4999095 -0.8660776 0 0.5000278 -0.8660094 0 0.5000316 -0.8660072 0 0.8660265 -0.4999982 0 0.8660276 -0.4999963 0 0.8660315 -0.4999895 0 0.8660324 -0.4999879 0 0.8660269 -0.4999974 0 -0.499999 -0.8660261 0 -0.4999997 -0.8660256 0 -0.499997 -0.8660271 0 -0.4999958 -0.8660278 0 -0.5000011 -0.8660248 0 -0.5000002 -0.8660253 0 -0.5000048 -0.8660227 0 -0.5000028 -0.8660238 0 -0.4999998 -0.8660256 0 -0.4999936 -0.8660291 0 -0.4999908 -0.8660308 0 -0.5000031 -0.8660236 0 -0.5000017 -0.8660244 0 -0.8660269 -0.4999974 0 -0.8660315 -0.4999895 0 -0.8660324 -0.4999879 0 -0.8660265 -0.4999982 0 -0.8660276 -0.4999963 0 -0.5000295 -0.8660084 0 -0.50003 -0.8660081 0 -0.4999073 -0.866079 0 -0.4999148 -0.8660746 0 -0.4999976 -0.8660269 0 -0.4999984 -0.8660263 0 0.5000233 -0.8660121 0 0.5000299 -0.8660082 0 0.4999948 -0.8660284 0 0.4999946 -0.8660286 0 0.500003 -0.8660237 0 0.5000018 -0.8660244 0 0.8808739 -0.4733511 0 0.8808681 -0.4733617 0 0.8808594 -0.4733783 0 0.8808583 -0.4733802 0 0.8808572 -0.4733823 0 0.8808588 -0.4733791 0 0.8660296 0.4999927 0 0.8660284 0.4999949 0 0.8660073 0.5000313 0 0.8660081 0.5000301 0 0.8660303 0.4999915 0 0.8660305 0.4999912 0 0.03048437 0.9995353 0 0.03048449 0.9995353 0 0.03040891 0.9995375 0 0.03040856 0.9995375 0 0.03046679 0.9995359 0 0.03046685 0.9995359 0 0.03046739 0.9995357 0 0.03046756 0.9995357 0 0.03050041 0.9995348 0 0.03050071 0.9995348 0 0.4999849 0.8660342 0 0.4999823 0.8660357 0 0.4999974 0.8660269 0 0.4999942 0.8660288 0 0.5000058 0.8660221 0 0.4999987 0.8660262 0 0.4999977 0.8660267 0 0.5000118 0.8660187 0 -1.64875e-6 0 -1 -8.24484e-6 0 -1 6.28109e-6 0 -1 1.16719e-5 0 -1 7.11331e-7 0 -1 2.63629e-7 0 -1 -1.52683e-6 0 -1 2.17756e-6 0 -1 -2.00491e-6 0 -1 -8.36157e-7 0 -1 4.03148e-6 0 -1 -4.48846e-6 0 -1 -7.11327e-7 0 -1 4.00982e-6 0 -1 8.60073e-7 0 -1 9.8964e-7 0 -1 -1.57653e-6 0 -1 -1.84063e-6 0 -1 3.25478e-6 0 -1 -2.14223e-6 0 -1 1.47378e-6 0 -1 3.7465e-6 0 -1 6.97991e-7 0 -1 -7.14264e-6 0 -1 4.76076e-7 0 -1 -2.40536e-6 0 -1 -8.5437e-7 0 -1 1.71899e-6 0 -1 5.12101e-7 0 -1 8.80046e-7 0 -1 6.45891e-7 0 -1 -3.31079e-6 0 -1 1.12083e-6 0 -1 -1.53719e-6 0 -1 -1.54598e-5 0 -1 -1.2731e-6 0 -1 2.35347e-7 0 -1 -1.8221e-6 0 -1 2.28558e-5 0 -1 -2.02867e-7 0 -1 6.71909e-6 0 -1 -9.69764e-6 0 -1 6.78397e-6 0 -1 -2.30968e-5 0 -1 1.04595e-5 0 -1 -2.7826e-5 0 -1 -2.99262e-5 0 -1 1.60144e-5 0 -1 2.37147e-5 0 -1 -7.26737e-6 0 -1 -6.45997e-6 0 -1 1.64278e-5 0 -1 -2.58561e-7 0 -1 1.81614e-6 0 -1 1.0745e-6 0 -1 -3.31743e-7 0 -1 -2.38079e-7 0 -1 1.47305e-6 0 -1 1.30061e-6 0 -1 6.38961e-6 0 -1 -4.79106e-7 0 -1 1.36606e-5 0 -1 7.20134e-7 0 -1 1.3561e-6 0 -1 0 0 -1 2.85294e-7 0 -1 -2.5552e-7 0 -1 5.52652e-7 0 -1 9.429e-7 0 -1 2.58274e-7 0 -1 2.59488e-7 0 -1 3.23659e-7 0 -1 1.65522e-7 0 -1 -1.56121e-5 0 -1 1.06269e-5 0 -1 -1.54328e-6 0 -1 2.92391e-6 0 -1 -4.95261e-7 0 -1 -5.78273e-6 0 -1 2.40682e-5 0 -1 5.71246e-6 0 -1 -1.52677e-6 0 -1 -1.6368e-6 0 -1 1.26356e-7 0 -1 2.08721e-6 0 -1 2.64117e-6 0 -1 -2.4795e-6 0 -1 -1.67968e-6 0 -1 3.11661e-6 0 -1 3.35936e-6 0 -1 -8.55729e-7 0 -1 -2.30655e-6 0 -1 -3.37592e-7 0 -1 -3.01536e-6 0 -1 -4.60973e-7 0 -1 -8.55008e-6 0 -1 -3.88742e-6 0 -1 -8.53499e-7 0 -1 7.11569e-7 0 -1 -2.17867e-7 0 -1 3.21982e-7 0 -1 -1.29981e-6 0 -1 -1.81663e-7 0 -1 -3.48413e-6 0 -1 -2.96043e-6 0 -1 -1.01962e-6 0 -1 6.04496e-7 0 -1 4.17018e-7 0 -1 3.55821e-5 0 -1 -3.60068e-7 0 -1 -2.75002e-7 0 -1 -1.30372e-6 0 -1 -5.91741e-7 0 -1 1.48036e-6 0 -1 -5.94639e-7 0 -1 1.01173e-6 0 -1 1.01051e-6 0 -1 7.24468e-7 0 -1 -1.42314e-6 0 -1 7.35627e-7 0 -1 -1.30796e-7 0 -1 -8.62426e-7 0 -1 -1.57992e-7 0 -1 -4.82686e-6 0 -1 3.53448e-7 0 -1 5.8464e-6 0 -1 0.5000013 0.8660247 0 0.5000014 0.8660246 0 0.4999996 0.8660257 0 0.5000001 0.8660253 0 1.42083e-5 0 1 7.11327e-7 0 1 -1.61279e-5 0 1 1.11918e-6 0 1 -1.07509e-6 0 1 8.60052e-6 0 1 -7.11331e-7 0 1 8.98704e-7 0 1 -1.16892e-6 0 1 2.2265e-6 0 1 -1.62738e-6 0 1 -9.31672e-7 0 1 2.03715e-6 0 1 -6.98071e-6 0 1 2.15575e-6 0 1 1.14657e-6 0 1 1.32523e-6 0 1 -7.1793e-7 0 1 1.33135e-6 0 1 2.69599e-7 0 1 -6.01345e-7 0 1 -2.49766e-6 0 1 1.15697e-6 0 1 3.84076e-7 0 1 -5.15012e-6 0 1 4.26997e-7 0 1 6.73521e-7 0 1 2.8479e-7 0 1 -7.7004e-7 0 1 -6.97991e-7 0 1 -7.06421e-7 0 1 -7.51674e-7 0 1 4.84299e-6 0 1 -1.02583e-6 0 1 1.39365e-6 0 1 2.95106e-7 0 1 -2.14899e-6 0 1 2.02618e-6 0 1 -1.09519e-5 0 1 2.88711e-6 0 1 -1.72839e-5 0 1 3.11483e-6 0 1 -1.30164e-5 0 1 -9.35195e-7 0 1 1.43421e-6 0 1 -3.11483e-6 0 1 -1.174e-6 0 1 -1.93934e-5 0 1 7.52867e-6 0 1 8.56517e-6 0 1 -1.96023e-5 0 1 1.93798e-5 0 1 -4.12247e-6 0 1 2.86526e-6 0 1 -1.55872e-6 0 1 -2.0573e-6 0 1 4.24365e-7 0 1 6.07368e-7 0 1 -2.55438e-7 0 1 7.85146e-7 0 1 1.85506e-5 0 1 8.56626e-6 0 1 -1.88444e-6 0 1 4.77067e-7 0 1 3.79555e-7 0 1 -1.95399e-6 0 1 5.44748e-7 0 1 -2.17867e-7 0 1 3.00129e-6 0 1 1.3226e-6 0 1 7.26654e-7 0 1 -2.88935e-6 0 1 8.16395e-6 0 1 -2.18406e-6 0 1 -2.03923e-7 0 1 2.41798e-7 0 1 -2.72307e-7 0 1 -4.17018e-7 0 1 8.36157e-7 0 1 -2.2358e-7 0 1 2.75774e-7 0 1 5.90754e-7 0 1 2.59488e-7 0 1 -2.3665e-6 0 1 -2.58113e-7 0 1 -1.57529e-7 0 1 8.06181e-6 0 1 -1.94027e-6 0 1 2.57214e-6 0 1 -5.1548e-7 0 1 2.10597e-5 0 1 -1.55662e-5 0 1 5.91741e-7 0 1 -3.28556e-6 0 1 2.59962e-6 0 1 -6.56828e-6 0 1 2.9453e-6 0 1 3.93042e-7 0 1 8.06776e-7 0 1 -2.07825e-6 0 1 1.10565e-6 0 1 -2.32926e-7 0 1 2.59132e-7 0 1 -8.62426e-7 0 1 -1.98814e-7 0 1 -1.43758e-6 0 1 2.2744e-7 0 1 -6.44428e-7 0 1 3.81321e-6 0 1 -2.51438e-6 0 1 6.54724e-6 0 1 -3.63829e-6 0 1 -4.64433e-7 0 1 -5.2824e-6 0 1 1.11585e-6 0 1 -2.91071e-6 0 1 2.4502e-6 0 1 1.02556e-6 0 1 1.67968e-6 0 1 -1.15327e-6 0 1 -2.05112e-6 0 1 8.55729e-7 0 1 -4.3115e-6 0 1 -1.54538e-7 0 1 2.49588e-6 0 1 -1.65523e-7 0 1 -2.52712e-7 0 1 3.68435e-7 0 1 1.36799e-5 0 1 -5.87746e-6 0 1 -8.63844e-7 0 1 -9.99664e-6 0 1 7.88569e-7 0 1 1.33168e-6 0 1 -1.21275e-6 0 1 3.98511e-7 0 1 2.14801e-7 0 1 -4.87877e-6 0 1 7.38324e-6 0 1 -1.62292e-7 0 1 2.7633e-7 0 1 4.72831e-7 0 1 3.08045e-6 0 1 1.87261e-7 0 1 8.63266e-6 0 1 -7.59869e-7 0 1 0.4999997 -0.8660257 0 0.499999 -0.866026 0 0.499997 -0.8660271 0 0.4999958 -0.8660278 0 0.5000003 -0.8660253 0 0.500001 -0.8660249 0 0.5000019 -0.8660244 0 0.500003 -0.8660238 0 0.4999923 -0.8660299 0 0.4999921 -0.86603 0 0.500002 -0.8660243 0 0.5000028 -0.8660238 0 0.4999697 -0.8660429 0 0.4999675 -0.8660443 0 0.500001 -0.8660249 0 0.4999941 -0.8660288 0 0.4999954 -0.8660281 0 0.5000231 -0.866012 0 0.5000372 0.8660041 0 0.5000349 0.8660054 0 0.4999871 0.866033 0 0.4999876 0.8660326 0 -0.4999892 0.8660317 0 -0.4999882 0.8660323 0 -0.5000424 0.8660009 0 -0.500041 0.8660018 0 -0.9468491 -0.3216782 0 -0.9978471 0.06558364 0 -0.9978461 0.06559908 0 -0.8969252 0.4421825 0 -0.896919 0.4421949 0 -0.6593325 0.7518516 0 -0.6593402 0.7518447 0 -0.4999913 0.8660305 0 -0.5000059 0.8660221 0 -0.5000049 0.8660226 0 -0.4999949 0.8660284 0 -0.4999967 0.8660273 0 -0.6427844 0.7660472 0 -0.8659457 0.5001382 0 -0.9848269 0.1735395 0 -0.9659132 -0.2588664 0 -0.9659133 -0.2588658 0 -0.7071083 -0.7071053 0 -0.7071078 -0.7071058 0 -0.258867 -0.9659131 0 0.258869 -0.9659125 0 0.258867 -0.9659131 0 0.5000051 -0.8660225 0 0.5000057 -0.8660221 0 0.4999801 -0.8660369 0 0.4999806 -0.8660366 0 0.5000022 -0.8660241 0 0.500002 -0.8660243 0 0.5000099 -0.8660197 0 0.500007 -0.8660213 0 0.8660291 0.4999936 0 0.86603 0.4999921 0 0.8660231 0.5000041 0 -0.5000048 0.8660227 0 -0.5000046 0.8660229 0 -0.4998655 0.8661031 0 -0.5000579 0.8659921 0 -0.5000583 0.8659918 0 -0.2586861 0.9659615 0 -0.2586905 0.9659603 0 0.2586876 0.9659611 0 0.8660171 0.5000144 0 0.8660174 0.5000139 0 0.8660086 0.5000293 0 0.8660089 0.5000288 0 0.4999913 -0.8660305 0 0.4999909 -0.8660307 0 0.5000087 -0.8660203 0 0.5000079 -0.8660209 0 0.4999999 -0.8660256 0 0.4999966 -0.8660274 0 0.4999974 -0.8660268 0 0.4999862 -0.8660334 0 0.4999871 -0.866033 0 -0.2587459 0.9659455 0 -0.2587464 0.9659454 0 0.2587459 0.9659455 0 0.2587483 0.9659448 0 0.7071058 0.7071078 0 0.7071019 0.7071117 0 0.9659245 0.2588239 0 0.9659226 0.2588312 0 -0.5000076 0.866021 0 -0.5000094 0.86602 0 -0.5000008 0.866025 0 -0.5000004 0.8660253 0 -0.2493236 0.9684202 0 -0.2493237 0.9684203 0 -0.2492847 0.9684303 0 -0.2492856 0.9684301 0 -0.2493163 0.9684222 0 -0.2493157 0.9684223 0 -0.6859604 0.727639 0 -0.6859613 0.727638 0 -0.6859056 0.7276906 0 -0.6859056 0.7276905 0 -0.9520411 0.3059703 0 -0.9520408 0.3059711 0 -0.9520369 0.3059836 0 -0.5000016 -0.8660245 0 -0.5 -0.8660254 0 -0.8660261 -0.4999988 0 -0.8660251 -0.5000008 0 -0.8660348 -0.4999837 0 -0.8660326 -0.4999877 0 0.2588625 0.9659142 0 0.2588605 0.9659148 0 0.7071097 0.7071039 0 0.9659121 0.2588707 0 -0.9659291 0.2588069 0 -0.9659288 0.2588083 0 -0.7070724 0.7071412 0 -0.7070732 0.7071405 0 -0.2588625 0.9659142 0 -0.2588623 0.9659143 0 0.2588621 0.9659144 0 0.2588625 0.9659143 0 0.7070724 0.7071412 0 0.7070732 0.7071405 0 0.9659293 0.2588062 0 0.9659275 -0.2588132 0 0.9659273 -0.2588135 0 0.7070804 -0.7071332 0 0.7070797 -0.7071339 0 0.2588758 -0.9659106 0 -0.2588756 -0.9659107 0 -0.2588762 -0.9659105 0 -0.7070804 -0.7071332 0 -0.7070797 -0.7071339 0 -0.965927 -0.2588152 0 -0.9659272 -0.2588142 0 0.9659291 0.2588069 0 -0.9659293 0.2588062 0 -0.2588621 0.9659144 0 -0.2588625 0.9659143 0 0.258862 0.9659144 0 0.2588629 0.9659141 0 0.7070086 0.7072049 0 0.7070109 0.7072026 0 0.9659288 0.2588083 0 0.9659268 -0.2588156 0 0.9659273 -0.2588139 0 0.7070335 -0.7071802 0 0.7070312 -0.7071825 0 0.2588762 -0.9659105 0 0.2588756 -0.9659107 0 -0.2588758 -0.9659106 0 -0.9659275 -0.2588132 0 -0.9659273 -0.2588135 0 -0.2588798 -0.9659096 0 -0.2588597 0.965915 0 -0.2588538 0.9659165 0 0.2588538 0.9659165 0 -0.2588675 -0.9659129 0 -0.258873 -0.9659114 0 -0.9659137 -0.2588643 0 -0.9659138 -0.2588639 0 0.2588597 0.965915 0 0.2588798 -0.9659096 0 -0.7071127 -0.7071009 0 -0.9659171 -0.2588515 0 -0.9659171 0.2588515 0 -0.7071127 0.7071009 0 0.9659137 -0.2588643 0 0.9659138 -0.2588639 0 0.2588672 -0.9659129 0 -0.4999253 0.8660686 0 -0.4998884 0.8660899 0 -0.4999921 0.86603 0 -0.4999884 0.8660321 0 0.7071056 -0.707108 0 0.7071092 0.7071045 0 0.7071185 0.7070951 0 -0.7071092 0.7071045 0 -0.7071062 -0.7071074 0 -0.7071056 -0.707108 0 0.7071062 -0.7071074 0 -0.7071185 0.7070951 0 -0.707115 -0.7070986 0 -0.70712 0.7070937 0 -0.7070972 0.7071163 0 0.2588857 0.9659081 0 0.7070965 0.707117 0 0.7071207 0.7070929 0 -0.5000089 0.8660204 0 -0.5000115 0.8660189 0 -0.4999887 0.8660319 0 -0.4999901 0.8660311 0 -0.5000038 0.8660233 0 -0.5000046 0.8660228 0 0.5000038 -0.8660233 0 0.5000031 -0.8660237 0 0.4999935 -0.8660293 0 0.4999923 -0.8660299 0 0.5000101 -0.8660196 0 0.5000128 -0.866018 0 -0.4999879 0.8660324 0 -0.4999359 0.8660624 0 -0.4999366 0.8660621 0 0.4999762 0.8660392 0 -0.7070696 -0.707144 0 -0.9659273 -0.2588137 0 -0.9659255 0.2588207 0 -0.9659253 0.258821 0 -0.7070843 0.7071293 0 -0.7070836 0.7071301 0 -0.2588759 0.9659106 0 0.2588759 0.9659106 0 -0.5000128 -0.866018 0 -0.5000101 -0.8660196 0 0.4999994 0.8660258 0 0.499999 0.8660261 0 0.500011 0.8660191 0 0.5000093 0.86602 0 -0.2588857 0.9659081 0 0.6556442 -0.7550701 0 0.8395078 0.5433477 0 0.8395076 0.5433481 0 0.9952336 0.09752053 0 0.9952335 0.09752196 0 0.9290079 -0.3700602 0 0.9290097 -0.3700556 0 0.9290348 -0.3699926 0 0.9290349 -0.3699922 0 0.6556455 -0.7550689 0 0.2361736 -0.9717109 0 0.2361751 -0.9717105 0 0.2361137 -0.9717255 0 0.2361131 -0.9717256 0 -0.236129 -0.9717217 0 -0.2361286 -0.9717218 0 -0.6556447 -0.7550696 0 -0.6556447 -0.7550697 0 -0.9290269 -0.3700125 0 -0.9290278 -0.3700101 0 -0.9290307 -0.3700028 0 -0.9290325 -0.3699982 0 -0.9952319 0.09753799 0 -0.9952319 0.09753787 0 -0.8395171 0.5433335 0 -0.8395179 0.5433322 0 0.258872 -0.9659117 0 0.2588489 -0.9659179 0 -0.258872 -0.9659117 0 -0.2588607 -0.9659147 0 0.4999834 -0.8660351 0 0.4999829 -0.8660354 0 0.500005 -0.8660226 0 0.5000101 -0.8660197 0 0.5000202 -0.8660138 0 0.5000187 -0.8660147 0 -0.5000022 -0.8660243 0 -0.8808582 -0.4733804 0 -0.8808579 -0.4733809 0 -0.8808624 -0.4733726 0 -0.88086 -0.4733769 0 -0.8660357 0.4999822 0 -0.866036 0.4999817 0 -0.8660274 0.4999967 0 -0.8660269 0.4999973 0 -0.866024 0.5000024 0 -0.8660264 0.4999982 0 -0.5000175 0.8660153 0 -0.5000133 0.8660178 0 -0.4999464 0.8660565 0 -0.4999413 0.8660593 0 -0.500009 0.8660202 0 -0.5000085 0.8660205 0 -0.4999988 0.8660261 0 -0.4999995 0.8660258 0 -0.5000095 0.86602 0 -0.50001 0.8660197 0 -0.5000025 0.866024 0 -0.5000017 0.8660244 0 -0.4999991 0.8660259 0 -0.5000019 0.8660244 0 -0.4999574 0.86605 0 -0.5000255 0.8660108 0 -0.500025 0.866011 0 -0.499996 0.8660278 0 -0.5000071 0.8660213 0 -0.500009 0.8660203 0 -0.4999895 0.8660315 0 -0.4999884 0.8660321 0 -0.5000124 0.8660182 0 -0.5000117 0.8660187 0 -0.4999939 0.866029 0 -0.8660176 0.5000135 0 -0.8660184 0.5000123 0 -0.8660239 0.5000026 0 -0.8660237 0.5000032 0 -0.8660295 0.499993 0 -0.8660298 0.4999924 0 -0.8659969 0.5000494 0 -0.8659967 0.5000498 0 0.8503266 0.5262555 0 0.8503263 0.5262558 0 0.8504059 0.5261273 0 0.8503937 0.526147 0 0.8503932 0.5261477 0 0.8503783 0.5261718 0 0.8503768 0.5261743 0 0.5000054 0.8660224 0 0.4999991 0.8660259 0 0.4999975 0.8660269 0 0.4999977 0.8660268 0 0.5000107 0.8660193 0 0.4999574 0.86605 0 0.500025 0.866011 0 0.5000255 0.8660108 0 0.499996 0.8660278 0 0.500008 0.8660209 0 0.5000081 0.8660207 0 0.4999975 0.8660269 0 0.4999981 0.8660265 0 0.4999939 0.866029 0 0.4999814 0.8660362 0 0.5000085 0.8660205 0 0.4999983 0.8660264 0 0.5 0.8660255 0 0.03046911 0.9995357 0 0.03046905 0.9995358 0 0.03046441 0.9995359 0 0.03046441 0.9995359 0 0.03052002 0.9995342 0 0.8660184 0.5000123 0 0.8660165 0.5000154 0 0.8660274 0.4999967 0 0.8660269 0.4999973 0 0.8660199 0.5000097 0 0.8660179 0.5000129 0 0.8660168 -0.5000148 0 0.8660173 -0.5000141 0 0.8660293 -0.4999933 0 0.8660285 -0.4999948 0 0.5000026 -0.8660239 0 0.5000059 -0.8660221 0 0.5000004 -0.8660252 0 0.5000011 -0.8660249 0 -0.5000165 -0.866016 0 -0.4999834 -0.8660351 0 -0.4999829 -0.8660354 0 -0.655645 -0.7550693 0 0.8395174 0.5433329 0 0.8395175 0.5433328 0 0.9952319 0.09753799 0 0.9952319 0.09753787 0 0.9290325 -0.3699982 0 0.9290307 -0.3700028 0 0.9290277 -0.3700105 0 0.6556451 -0.7550693 0 0.236129 -0.9717217 0 0.2361286 -0.9717218 0 -0.2361134 -0.9717256 0 -0.2361134 -0.9717255 0 -0.2361751 -0.9717105 0 -0.2361736 -0.9717109 0 -0.9290348 -0.3699926 0 -0.9290349 -0.3699922 0 -0.9290097 -0.3700556 0 -0.9290079 -0.3700602 0 -0.9952334 0.09752213 0 -0.9952335 0.09752041 0 -0.8395071 0.5433488 0 -0.8395084 0.543347 0 -0.4999877 -0.8660325 0 -0.4999855 -0.8660337 0 -0.4999967 -0.8660272 0 -0.4999973 -0.866027 0 -0.5000013 -0.8660247 0 -0.5000011 -0.8660248 0 -0.5000082 -0.8660207 0 -0.5000034 -0.8660236 0 -0.4999676 -0.8660441 0 -0.4999681 -0.8660439 0 -0.2587479 0.965945 0 -0.7071058 0.7071078 0 -0.7071019 0.7071117 0 -0.9659245 0.2588239 0 -0.9659226 0.2588312 0 0.2588129 0.9659275 0 0.2588064 0.9659293 0 0.2587156 0.9659536 0 0.2587181 0.9659529 0 0.5000086 0.8660206 0 0.5000008 0.866025 0 0.9520369 0.3059836 0 0.9520408 0.3059711 0 0.9520411 0.3059703 0 0.6859285 0.7276691 0 0.2493234 0.9684203 0 0.2493239 0.9684202 0 0.2492852 0.9684302 0 0.2492852 0.9684302 0 0.2493157 0.9684223 0 0.2493163 0.9684222 0 0.6859272 0.7276703 0 0.8660326 -0.4999877 0 0.8660348 -0.4999837 0 0.8660254 -0.5 0 0.8660257 -0.4999995 0 0.5000005 -0.8660252 0 -0.9659121 0.2588707 0 -0.7071097 0.7071039 0 -0.2588605 0.9659148 0 -0.258869 -0.9659125 0 0.7071083 -0.7071053 0 0.7071078 -0.7071058 0 0.9659132 -0.2588664 0 0.9659133 -0.2588658 0 -0.5000057 -0.8660221 0 -0.5000051 -0.8660225 0 -0.4999797 -0.8660372 0 -0.4999811 -0.8660364 0 -0.5000028 -0.8660238 0 -0.5000032 -0.8660236 0 -0.8660287 0.4999942 0 -0.8660303 0.4999915 0 -0.8660231 0.5000041 0 0.2588618 0.9659144 0 -0.2588636 0.9659139 0 -0.2588618 0.9659144 0 -0.8660086 0.5000293 0 -0.8660089 0.5000288 0 -0.8660171 0.5000144 0 -0.8660174 0.5000139 0 -0.7071075 0.7071061 0 -0.2586876 0.9659611 0 0.2586905 0.9659603 0 0.2586861 0.9659615 0 0.5000048 0.8660227 0 0.5000046 0.8660229 0 0.4998655 0.8661031 0 0.5000583 0.8659918 0 0.5000579 0.8659921 0 0.9468721 -0.3216105 0 0.9468768 -0.3215966 0 0.9978451 0.06561535 0 0.997844 0.06563085 0 0.8969796 0.4420721 0 0.8969737 0.4420838 0 0.6591997 0.751968 0 0.659192 0.7519748 0 0.4999892 0.8660317 0 0.4999882 0.8660323 0 0.5000424 0.8660009 0 0.500041 0.8660018 0 -0.499988 0.8660324 0 -0.4999867 0.8660331 0 -0.5000349 0.8660054 0 -0.5000372 0.8660041 0 -0.5000231 -0.866012 0 -0.4999949 -0.8660285 0 -0.4999947 -0.8660284 0 -0.500001 -0.8660249 0 -0.4999675 -0.8660443 0 -0.4999697 -0.8660429 0 0.4999913 0.8660305 0 0.5000065 0.8660217 0 0.5000042 0.8660231 0 0.4999949 0.8660284 0 0.4999967 0.8660273 0 0.7070972 0.7071163 0 0.7071024 0.7071112 0 -0.5000019 -0.8660244 0 -0.5000032 -0.8660236 0 -0.4999992 -0.8660259 0 -0.4999952 -0.8660282 0 -0.4999977 -0.8660267 0 -0.8660928 0.4998835 0 -0.8660924 0.499884 0 -0.8660141 0.5000199 0 -0.8660133 0.5000212 0 0.5000002 0.8660253 0 0.8660243 -0.5000022 0 0.8660234 -0.5000035 0 0.8660248 -0.5000011 0 0.8660259 -0.4999992 0 -0.5000002 0.8660253 0 0.8660258 0.4999995 0 0.8660255 0.5 0 0.4999973 -0.8660271 0 0.5000001 -0.8660255 0 3.158e-6 0 1 7.79708e-7 0 1 -7.38614e-7 0 1 -4.37746e-7 0 1 3.59404e-7 0 1 3.41988e-6 0 1 3.05252e-7 0 1 2.54467e-6 0 1 1.14165e-6 0 1 -5.97731e-6 0 1 -4.87791e-6 0 1 2.13814e-6 0 1 -1.43631e-6 0 1 1.02777e-6 0 1 4.64511e-6 0 1 -1.87899e-6 0 1 1.20649e-6 0 1 -1.32666e-6 0 1 1.06137e-6 0 1 -1.16352e-6 0 1 -1.73623e-6 0 1 -2.29975e-6 0 1 -1.18683e-6 0 1 5.94895e-5 0 1 -1.35694e-6 0 1 2.1404e-6 0 1 -2.86479e-6 0 1 1.24257e-6 0 1 -1.02824e-6 0 1 -6.80993e-7 0 1 -4.73828e-7 0 1 -1.80492e-6 0 1 1.0214e-6 0 1 3.02493e-6 0 1 4.39431e-6 0 1 0 0 1 6.20662e-7 0 1 -1.49413e-6 0 1 -2.39831e-6 0 1 2.60083e-6 0 1 0 0 1 -2.4127e-6 0 1 1.67131e-5 0 1 -9.1539e-6 0 1 -3.80107e-6 0 1 3.54188e-6 0 1 -3.158e-6 0 1 4.39435e-6 0 1 2.63794e-6 0 1 2.57121e-6 0 1 -1.84367e-6 0 1 -6.12486e-7 0 1 1.20386e-6 0 1 1.71565e-6 0 1 2.20451e-6 0 1 -1.07009e-6 0 1 1.30867e-7 0 1 1.33416e-6 0 1 4.47246e-7 0 1 2.01472e-6 0 1 5.16751e-7 0 1 1.38909e-7 0 1 -2.68345e-6 0 1 1.15364e-6 0 1 -2.06266e-6 0 1 -5.10119e-7 0 1 2.05612e-6 0 1 -3.00822e-7 0 1 -8.58694e-7 0 1 4.39857e-6 0 1 -5.27667e-6 0 1 -4.54785e-5 0 1 1.65496e-7 0 1 1.26292e-6 0 1 5.60185e-6 0 1 5.95534e-6 0 1 1.21602e-6 0 1 -2.58422e-6 0 1 -1.25684e-6 0 1 -2.20684e-6 0 1 -3.06645e-6 0 1 8.73055e-7 0 1 -2.55567e-6 0 1 1.62131e-6 0 1 -1.6279e-7 0 1 0 0 1 -5.86703e-7 0 1 4.12368e-7 0 1 1.24854e-7 0 1 -7.11314e-7 0 1 -4.18893e-6 0 1 -2.76775e-5 0 1 1.58952e-5 0 1 -7.66801e-6 0 1 -8.40885e-6 0 1 4.72947e-6 0 1 -6.12272e-6 0 1 1.21265e-5 0 1 2.38449e-7 0 1 2.14694e-7 0 1 2.11322e-7 0 1 4.70331e-6 0 1 -6.00192e-6 0 1 1.20602e-6 0 1 -5.40033e-7 0 1 -5.16146e-6 0 1 -7.30574e-7 0 1 1.06756e-5 0 1 -8.18379e-7 0 1 -3.72358e-4 0 1 -1.34464e-7 0 1 1.2891e-5 0 1 3.72255e-7 0 1 -5.87501e-7 0 1 -2.06765e-6 0 1 -5.42698e-7 0 1 5.28231e-7 0 1 4.79184e-6 0 1 -1.06009e-6 0 1 -2.7385e-6 0 1 -3.31891e-6 0 1 7.5721e-7 0 1 -5.52213e-6 0 1 1.00306e-6 0 1 3.38245e-6 0 1 2.14131e-6 0 1 -1.38766e-5 0 1 -9.54376e-6 0 1 5.27482e-6 0 1 -4.88043e-7 0 1 -2.95542e-6 0 1 -2.94473e-7 0 1 3.51195e-7 0 1 -4.30757e-6 0 1 3.97047e-7 0 1 -4.46008e-7 0 1 7.26379e-7 0 1 3.40094e-6 0 1 -1.39559e-6 0 1 -8.07854e-7 0 1 1.16802e-6 0 1 6.03486e-6 0 1 1.10175e-6 0 1 -3.36038e-7 0 1 -4.57771e-7 0 1 -6.26745e-7 0 1 4.16934e-7 0 1 2.82305e-7 0 1 7.23578e-7 0 1 0 0 1 1.83055e-5 0 1 -3.13596e-6 0 1 2.79114e-6 0 1 0 0 1 1.60028e-6 0 1 -4.6863e-7 0 1 -3.89854e-7 0 1 1.35916e-7 0 1 1.77833e-6 0 1 1.43652e-6 0 1 -2.03186e-6 0 1 1.95274e-6 0 1 -2.10504e-7 0 1 2.48319e-7 0 1 3.34113e-7 0 1 -1.10792e-6 0 1 1.53721e-7 0 1 -9.52334e-7 0 1 6.03515e-6 0 1 4.64289e-6 0 1 2.18825e-7 0 1 -8.83556e-6 0 1 -7.71003e-7 0 1 7.71008e-7 0 1 1.47771e-6 0 1 -7.40122e-6 0 1 -6.66092e-6 0 1 3.69648e-7 0 1 4.41774e-6 0 1 3.78605e-7 0 1 0 0 1 0 0 1 -4.53725e-7 0 1 8.92506e-7 0 1 0 0 1 -1.46181e-7 0 1 0 0 1 -8.20455e-7 0 1 -1.58036e-6 0 1 1.81031e-7 0 1 5.94751e-7 0 1 4.36941e-6 0 1 9.50393e-7 0 1 2.76676e-7 0 1 2.74225e-6 0 1 2.30398e-6 0 1 6.08261e-6 0 1 6.86543e-6 0 1 -1.83351e-6 0 1 1.86732e-7 0 1 -2.40242e-7 0 1 5.20938e-6 0 1 7.18796e-7 0 1 -2.28358e-7 0 1 1.04161e-6 0 1 -1.81635e-7 0 1 1.87902e-6 0 1 8.68113e-7 0 1 7.58357e-6 0 1 -6.24563e-6 0 1 2.2669e-6 0 1 -1.51247e-6 0 1 6.48408e-7 0 1 -4.31246e-7 0 1 -3.41988e-6 0 1 7.96978e-6 0 1 -2.2833e-6 0 1 -1.55956e-6 0 1 -2.77564e-7 0 1 0 0 1 1.88123e-7 0 1 -4.75242e-7 0 1 6.94455e-7 0 1 -4.87702e-7 0 1 4.87791e-6 0 1 1.12553e-6 0 1 -2.13814e-6 0 1 -2.03029e-5 0 1 -2.0298e-5 0 1 -2.03525e-5 0 1 2.12903e-6 0 1 -1.10226e-6 0 1 -1.71565e-6 0 1 2.32056e-7 0 1 -1.01512e-6 0 1 -6.18027e-7 0 1 6.97394e-7 0 1 -2.19885e-6 0 1 -1.28561e-6 0 1 -1.31898e-6 0 1 5.41313e-7 0 1 -1.06289e-6 0 1 3.10007e-6 0 1 -3.57041e-6 0 1 5.38649e-6 0 1 3.5456e-6 0 1 -1.49024e-6 0 1 1.70043e-7 0 1 -5.0104e-7 0 1 -2.74225e-6 0 1 3.79338e-7 0 1 1.02872e-6 0 1 -4.47246e-7 0 1 -3.23357e-7 0 1 4.41425e-6 0 1 -0.8660262 -0.4999987 0 -0.8660246 -0.5000016 0 -0.8660231 -0.5000042 0 -0.8660245 -0.5000016 0 1.36044e-6 0 -1 1.70996e-6 0 -1 5.48384e-6 0 -1 3.15206e-6 0 -1 -6.11025e-7 0 -1 0 0 -1 1.06704e-6 0 -1 -1.81885e-6 0 -1 -3.15342e-6 0 -1 -9.65493e-7 0 -1 -7.67191e-7 0 -1 -7.86233e-7 0 -1 6.07864e-7 0 -1 4.28009e-7 0 -1 -3.46712e-6 0 -1 6.21454e-6 0 -1 -8.42171e-7 0 -1 -4.66731e-6 0 -1 1.28521e-5 0 -1 -1.3484e-6 0 -1 3.31786e-6 0 -1 -2.03226e-6 0 -1 -3.24204e-7 0 -1 2.15623e-7 0 -1 9.9608e-7 0 -1 1.19915e-6 0 -1 3.14539e-6 0 -1 -1.66924e-7 0 -1 -2.07937e-5 0 -1 1.85457e-6 0 -1 -9.59089e-7 0 -1 -5.3857e-7 0 -1 -7.08621e-7 0 -1 1.81031e-7 0 -1 8.32184e-7 0 -1 -4.96965e-7 0 -1 -2.20126e-6 0 -1 6.50209e-7 0 -1 -7.20726e-7 0 -1 1.73639e-6 0 -1 7.91254e-7 0 -1 2.79412e-7 0 -1 3.96173e-7 0 -1 -8.92503e-7 0 -1 -5.92527e-7 0 -1 -1.27794e-6 0 -1 6.62553e-7 0 -1 -3.31891e-6 0 -1 1.10443e-6 0 -1 7.82197e-6 0 -1 5.92098e-6 0 -1 7.86411e-7 0 -1 2.95542e-6 0 -1 1.07435e-6 0 -1 8.32599e-7 0 -1 -2.38594e-6 0 -1 -1.41187e-7 0 -1 4.00726e-6 0 -1 4.36873e-7 0 -1 5.47725e-7 0 -1 -1.70763e-7 0 -1 -6.56018e-6 0 -1 5.04456e-7 0 -1 -2.18899e-6 0 -1 6.14882e-7 0 -1 -8.42015e-7 0 -1 -1.53372e-7 0 -1 -7.42604e-7 0 -1 -1.35917e-7 0 -1 2.66479e-6 0 -1 3.02122e-6 0 -1 -1.70047e-6 0 -1 -1.38271e-6 0 -1 1.05031e-5 0 -1 -1.39559e-6 0 -1 -7.63308e-7 0 -1 7.5681e-7 0 -1 -5.13296e-7 0 -1 1.06203e-6 0 -1 -6.03588e-7 0 -1 2.2157e-6 0 -1 -2.56641e-7 0 -1 1.25978e-6 0 -1 -2.13532e-7 0 -1 4.2506e-7 0 -1 -7.15211e-7 0 -1 -6.89944e-7 0 -1 1.61275e-7 0 -1 2.32444e-6 0 -1 -1.03025e-6 0 -1 -1.14834e-6 0 -1 1.26452e-6 0 -1 4.46008e-7 0 -1 -7.94115e-7 0 -1 -2.5309e-7 0 -1 -3.28883e-6 0 -1 3.02064e-6 0 -1 -1.94927e-7 0 -1 1.75632e-7 0 -1 -1.94834e-7 0 -1 -3.37125e-7 0 -1 2.20469e-7 0 -1 -2.00349e-7 0 -1 3.55446e-7 0 -1 -2.6746e-7 0 -1 -2.02685e-6 0 -1 1.89787e-7 0 -1 0 0 -1 -2.39738e-7 0 -1 5.42398e-7 0 -1 -3.57673e-7 0 -1 9.70875e-7 0 -1 2.44346e-6 0 -1 -2.23724e-6 0 -1 2.62982e-5 0 -1 -3.09549e-7 0 -1 0 0 -1 4.20544e-7 0 -1 2.18994e-7 0 -1 -2.00363e-6 0 -1 7.82203e-6 0 -1 -1.47771e-6 0 -1 2.81637e-7 0 -1 -7.91762e-7 0 -1 6.09162e-6 0 -1 5.33079e-7 0 -1 0 0 -1 2.72077e-6 0 -1 -5.73929e-6 0 -1 2.92418e-6 0 -1 -6.15341e-7 0 -1 -7.49408e-7 0 -1 -1.7188e-5 0 -1 -1.71664e-6 0 -1 5.6317e-7 0 -1 0 0 -1 -5.69365e-5 0 -1 6.18316e-7 0 -1 -3.04344e-6 0 -1 -6.73644e-7 0 -1 -3.7578e-7 0 -1 -8.12208e-7 0 -1 4.27023e-5 0 -1 -2.30398e-6 0 -1 1.46456e-6 0 -1 -1.74732e-6 0 -1 -2.28848e-6 0 -1 -5.49294e-7 0 -1 -1.31898e-6 0 -1 -4.28036e-6 0 -1 -1.10226e-6 0 -1 6.86266e-6 0 -1 -1.11708e-6 0 -1 -5.11222e-7 0 -1 7.8399e-7 0 -1 2.28817e-6 0 -1 -5.15274e-7 0 -1 1.6958e-7 0 -1 -4.00988e-6 0 -1 1.95125e-6 0 -1 2.03007e-7 0 -1 5.02814e-7 0 -1 2.85651e-5 0 -1 -1.62782e-7 0 -1 -1.33051e-5 0 -1 5.65816e-7 0 -1 2.43155e-7 0 -1 -2.5699e-7 0 -1 1.05171e-5 0 -1 -7.08942e-7 0 -1 -5.40333e-6 0 -1 1.39552e-5 0 -1 -1.19288e-6 0 -1 5.16839e-6 0 -1 -2.355e-7 0 -1 1.62035e-7 0 -1 3.74472e-7 0 -1 -4.20554e-7 0 -1 -1.08701e-6 0 -1 1.02873e-6 0 -1 -6.19586e-6 0 -1 -3.03811e-7 0 -1 -9.91338e-6 0 -1 4.4472e-6 0 -1 -1.02872e-6 0 -1 2.01259e-6 0 -1 1.02024e-6 0 -1 1.59012e-7 0 -1 -1.69579e-7 0 -1 -3.05722e-6 0 -1 6.03008e-7 0 -1 -2.08218e-7 0 -1 1.65588e-7 0 -1 -4.58047e-6 0 -1 4.79545e-7 0 -1 -2.93891e-7 0 -1 5.0807e-7 0 -1 -3.40496e-6 0 -1 -2.39831e-6 0 -1 -1.26447e-6 0 -1 -1.43886e-6 0 -1 1.99626e-7 0 -1 5.00108e-6 0 -1 4.02162e-7 0 -1 -1.32666e-6 0 -1 1.56139e-6 0 -1 8.37921e-6 0 -1 -3.85612e-6 0 -1 4.36379e-7 0 -1 -2.00535e-6 0 -1 -1.24257e-6 0 -1 1.02824e-6 0 -1 -2.7923e-6 0 -1 -5.14637e-7 0 -1 1.28081e-7 0 -1 -1.85192e-6 0 -1 7.86233e-7 0 -1 5.43134e-7 0 -1 9.02462e-7 0 -1 -5.10698e-7 0 -1 2.08934e-7 0 -1 -3.41993e-6 0 -1 1.61987e-6 0 -1 -1.02777e-6 0 -1 1.30298e-6 0 -1 -1.06704e-6 0 -1 -3.39524e-6 0 -1 2.03412e-5 0 -1 1.708e-7 0 -1 7.56233e-7 0 -1 -7.20113e-6 0 -1 6.91754e-7 0 -1 -3.71944e-6 0 -1 -6.86266e-6 0 -1 3.29615e-6 0 -1 -1.90582e-6 0 -1 -2.00467e-6 0 -1 3.04688e-7 0 -1 2.63794e-6 0 -1 -1.84367e-6 0 -1 1.25957e-6 0 -1 -5.12403e-7 0 -1 1.90868e-6 0 -1 1.02851e-5 0 -1 -1.17519e-6 0 -1 6.77736e-6 0 -1 -3.37756e-6 0 -1 -1.46668e-7 0 -1 -3.37683e-6 0 -1 3.52314e-6 0 -1 5.84178e-7 0 -1 -2.34826e-6 0 -1 2.35008e-6 0 -1 2.34098e-6 0 -1 -1.17349e-6 0 -1 4.66401e-6 0 -1 -6.75488e-6 0 -1 5.87064e-7 0 -1 6.79108e-6 0 -1 -4.0894e-6 0 -1 -1.68782e-6 0 -1 -1.17507e-6 0 -1 1.69423e-6 0 -1 5.81568e-7 0 -1 -1.68873e-6 0 -1 -1.1735e-6 0 -1 1.70425e-6 0 -1 2.3501e-6 0 -1 -1.17337e-6 0 -1 3.37829e-6 0 -1 -3.52646e-6 0 -1 3.38258e-6 0 -1 -2.34398e-6 0 -1 6.84013e-6 0 -1 -1.16331e-6 0 -1 -8.81714e-7 0 -1 -2.05735e-6 0 -1 6.76553e-6 0 -1 -6.84023e-6 0 -1 -2.34629e-6 0 -1 6.81459e-6 0 -1 -1.17504e-6 0 -1 1.17446e-6 0 -1 -0.6045993 0.7965299 0 -0.3875608 0.9218441 0 -0.3875806 0.9218358 0 -0.1459475 0.9892924 0 -0.1459557 0.9892912 0 0.1043123 0.9945446 0 0.1043239 0.9945434 0 0.3487296 0.9372235 0 0.5705842 0.8212391 0 0.5705839 0.8212394 0 0.7569675 0.6534526 0 0.7569956 0.65342 0 0.8958415 0.4443739 0 0.8958191 0.4444189 0 0.9781556 0.2078741 0 0.9781557 0.207874 0 0.9991332 -0.04163002 0 0.9991332 -0.04163008 0 0.9572868 -0.2891402 0 0.8552786 -0.5181684 0 0.8553037 -0.518127 0 0.6998366 -0.7143031 0 0.6998927 -0.714248 0 0.4999466 -0.8660563 0 0.2689986 -0.9631406 0 0.2690282 -0.9631324 0 0.02063047 -0.9997872 0 0.02062928 -0.9997873 0 -0.2281202 -0.973633 0 -0.228133 -0.97363 0 -0.463474 -0.8861106 0 -0.4634972 -0.8860984 0 -0.6689481 -0.7433091 0 -0.668976 -0.7432841 0 -0.8328844 -0.5534469 0 -0.9443698 -0.3288856 0 -0.9443523 -0.3289358 0 -0.9964921 -0.08368754 0 -0.9964921 -0.08368748 0 -0.98596 0.1669821 0 -0.9859601 0.1669819 0 -0.9135194 0.4067953 0 -0.9135406 0.4067476 0 -0.7837361 0.6210939 0 -0.7837641 0.6210588 0 -0.6045995 0.7965296 0 2.0051e-6 0 -1 -2.57793e-6 0 -1 -4.28178e-7 0 -1 8.57229e-7 0 -1 -1.14572e-6 0 -1 1.7132e-6 0 -1 -3.90576e-7 0 -1 -1.14546e-6 0 -1 -1.56273e-6 0 -1 7.90619e-7 0 -1 2.28056e-6 0 -1 -1.14392e-6 0 -1 -3.12469e-6 0 -1 1.14567e-6 0 -1 -3.13724e-6 0 -1 -5.66688e-7 0 -1 -3.16608e-6 0 -1 2.29172e-6 0 -1 6.24816e-6 0 -1 -3.43224e-6 0 -1 6.30581e-6 0 -1 -5.72433e-7 0 -1 -1.14439e-6 0 -1 1.13791e-6 0 -1 1.14498e-6 0 -1 -2.29097e-6 0 -1 3.12523e-6 0 -1 1.13459e-6 0 -1 4.295e-7 0 -1 -6.24803e-6 0 -1 4.29132e-7 0 -1 -3.12474e-6 0 -1 -5.72688e-7 0 -1 -0.569645 0.8218908 0 -0.4269082 0.9042951 0 -0.4269088 0.9042947 0 -0.2719189 0.9623202 0 -0.2719317 0.9623166 0 -0.1100111 0.9939305 0 -0.1100112 0.9939303 0 0.0549876 0.9984871 0 0.05498486 0.9984873 0 0.2187202 0.9757877 0 0.218731 0.9757852 0 0.3762221 0.9265296 0 0.3762227 0.9265292 0 0.5236777 0.8519166 0 0.5237007 0.8519024 0 0.6567405 0.7541167 0 0.7719287 0.6357092 0 0.8660331 0.4999866 0 0.8660336 0.4999859 0 0.9364947 0.3506819 0 0.9364788 0.3507243 0 0.9814534 0.1917007 0 0.9814443 0.1917473 0 0.9996217 0.02750468 0 0.9905412 -0.1372159 0 0.9905347 -0.1372635 0 0.9544093 -0.2985011 0 0.9544234 -0.2984561 0 0.8922398 -0.4515619 0 0.8922595 -0.451523 0 0.8057253 -0.5922893 0 0.805702 -0.5923211 0 0.6972083 -0.7168687 0 0.6971838 -0.7168924 0 0.569925 -0.8216969 0 0.4268029 -0.9043447 0 0.4268218 -0.9043358 0 0.2719873 -0.962301 0 0.2719866 -0.9623011 0 0.1099937 -0.9939324 0 0.1099883 -0.9939329 0 -0.05499428 -0.9984867 0 -0.05499696 -0.9984866 0 -0.2187219 -0.9757872 0 -0.2187114 -0.9757897 0 -0.3762221 -0.9265296 0 -0.3762227 -0.9265292 0 -0.5236996 -0.8519032 0 -0.5236788 -0.8519158 0 -0.6567405 -0.7541167 0 -0.6567648 -0.7540956 0 -0.7719047 -0.6357384 0 -0.7719527 -0.63568 0 -0.866012 -0.5000234 0 -0.8660336 -0.4999859 0 -0.9364963 -0.3506779 0 -0.9364958 -0.3506788 0 -0.9814442 -0.1917479 0 -0.9814443 -0.1917473 0 -0.9996217 -0.02750468 0 -0.9996231 -0.0274558 0 -0.9905079 0.1374561 0 -0.9905013 0.1375036 0 -0.9544093 0.2985011 0 -0.9544234 0.2984561 0 -0.8922576 0.4515267 0 -0.8922376 0.4515662 0 -0.8058226 0.5921571 0 -0.8058453 0.5921261 0 -0.6973341 0.7167463 0 -0.5696221 0.8219068 0 -0.4938817 0.5076124 -0.7059821 -0.4938432 0.5078075 -0.7058687 -0.5708121 0.4194519 -0.7058568 -0.5707994 0.4195767 -0.7057929 -0.6320925 0.3198691 -0.7057924 -0.632059 0.3197554 -0.7058739 -0.6760504 0.2113712 -0.7058882 -0.6760808 0.2114828 -0.7058256 -0.7016531 0.09742182 -0.7058271 -0.7016186 0.09731 -0.705877 -0.7080788 -0.0194481 -0.7058656 -0.7080184 -0.01953202 -0.7059238 -0.6951505 -0.1358224 -0.7059165 -0.6951286 -0.1358097 -0.7059405 -0.6632992 -0.2484048 -0.7059243 -0.6633278 -0.2483846 -0.7059046 -0.6134161 -0.3541414 -0.7059069 -0.6134662 -0.3541229 -0.7058726 -0.546777 -0.4502823 -0.7058901 -0.5466428 -0.4503215 -0.705969 -0.4651293 -0.5340949 -0.7059726 -0.4650878 -0.5340912 -0.7060028 -0.3708873 -0.6033354 -0.705995 -0.3709764 -0.6033432 -0.7059417 -0.266463 -0.656233 -0.7059432 -0.266493 -0.6562284 -0.7059361 -0.1549139 -0.6911471 -0.705916 -0.1549844 -0.6911877 -0.7058608 -0.03895694 -0.7072783 -0.705861 -0.03890985 -0.7072606 -0.7058815 0.07790708 -0.7040209 -0.7058931 0.0778163 -0.7041056 -0.7058186 0.1926684 -0.6816855 -0.7058215 0.1928464 -0.68142 -0.7060291 0.3022685 -0.6404653 -0.7060014 0.3021795 -0.6406365 -0.7058843 0.4036818 -0.5820311 -0.7058901 0.4036331 -0.5822038 -0.7057755 0.4939183 -0.5078516 -0.7057843 0.4939278 -0.5077128 -0.7058776 0.5707075 -0.4195358 -0.7058914 0.5707151 -0.4193708 -0.7059834 0.6319094 -0.3198007 -0.7059873 0.631917 -0.3197519 -0.7060026 0.675935 -0.2113611 -0.7060018 0.6759406 -0.2114133 -0.7059808 0.7015415 -0.09722477 -0.7059652 0.7016113 -0.09733653 -0.7058805 0.7080785 0.01947408 -0.7058652 0.7080257 0.01956123 -0.7059157 0.6951498 0.1357963 -0.7059222 0.6951366 0.1358402 -0.7059268 0.6633036 0.2483804 -0.7059289 0.6633299 0.2483604 -0.7059112 0.6134105 0.3541641 -0.7059004 0.6134694 0.3541248 -0.705869 0.5467783 0.4502834 -0.7058885 0.5466499 0.4502984 -0.7059783 0.4651143 0.5341037 -0.7059758 0.4652632 0.534081 -0.705895 0.3709265 0.6033992 -0.7059201 0.371005 0.6034075 -0.7058717 0.266485 0.6562871 -0.7058845 0.2665094 0.6562688 -0.7058925 0.1549245 0.6911655 -0.7058957 0.1549994 0.6912224 -0.7058236 0.03895193 0.7072784 -0.7058612 0.03888982 0.7072391 -0.705904 -0.07791846 0.7040266 -0.7058862 -0.07781952 0.7041054 -0.7058185 -0.1926296 0.681707 -0.7058113 -0.1926914 0.6816448 -0.7058545 -0.3023889 0.6405469 -0.7058759 -0.3024125 0.6405042 -0.7059044 -0.4034943 0.5821638 -0.7058879 -0.4035128 0.5820726 -0.7059525 0.3873033 0.9219524 0 0.6047616 0.7964067 0 0.7835956 0.6212714 0 0.9135354 0.4067592 0 0.9135328 0.4067651 0 0.9860023 0.1667317 0 0.9860023 0.1667319 0 0.9964918 -0.08369088 0 0.9964919 -0.08369082 0 0.9443551 -0.3289279 0 0.8330436 -0.5532073 0 0.8330434 -0.5532078 0 0.6690784 -0.743192 0 0.6690781 -0.7431921 0 0.4631955 -0.8862562 0 0.4631985 -0.8862547 0 0.2284643 -0.9735523 0 0.2284657 -0.9735521 0 -0.02102649 -0.999779 0 -0.2689223 -0.963162 0 -0.2689241 -0.9631615 0 -0.5000963 -0.8659698 0 -0.6994742 -0.7146579 0 -0.6994773 -0.7146549 0 -0.8553924 -0.5179806 0 -0.8553893 -0.5179858 0 -0.9573976 -0.288773 0 -0.9991163 -0.0420323 0 -0.97816 0.2078539 0 -0.97816 0.2078536 0 -0.8955892 0.4448821 0 -0.895592 0.4448764 0 -0.75716 0.6532295 0 -0.7571568 0.6532333 0 -0.5708546 0.8210512 0 -0.5708516 0.8210534 0 -0.3484053 0.9373441 0 -0.1046636 0.9945077 0 0.1463227 0.9892369 0 0.1463236 0.9892368 0 0.3873037 0.9219522 0 2.57145e-6 0 -1 -6.33328e-6 0 -1 -6.25e-6 0 -1 1.7179e-6 0 -1 -2.5756e-6 0 -1 3.00541e-6 0 -1 -6.28479e-6 0 -1 6.25094e-6 0 -1 1.14348e-6 0 -1 -3.39945e-6 0 -1 1.43225e-6 0 -1 -1.56258e-6 0 -1 -2.29129e-6 0 -1 2.5781e-6 0 -1 -6.25798e-6 0 -1 1.14432e-6 0 -1 7.88464e-7 0 -1 -3.12422e-6 0 -1 2.2912e-6 0 -1 -2.27925e-6 0 -1 3.43284e-6 0 -1 7.81641e-7 0 -1 -7.83758e-7 0 -1 -1.14017e-6 0 -1 1.14581e-6 0 -1 1.14085e-6 0 -1 4.5693e-6 0 -1 -2.28423e-6 0 -1 -1.14582e-6 0 -1 -2.2835e-6 0 -1 1.14286e-6 0 -1 -1.13615e-6 0 -1 1.14516e-6 0 -1 1.71747e-6 0 -1 -2.28938e-6 0 -1 -1.1373e-6 0 -1 0.426609 0.9044361 0 0.5699196 0.8217005 0 0.5699225 0.8216985 0 0.6972012 0.7168756 0 0.8058334 0.5921424 0 0.8058363 0.5921384 0 0.8922473 0.4515473 0 0.8922497 0.4515424 0 0.9544211 0.2984638 0 0.9544207 0.2984647 0 0.9905013 0.1375041 0 0.9905021 0.1374977 0 0.9996149 -0.02775007 0 0.9996148 -0.02775627 0 0.9814446 -0.1917461 0 0.9366082 -0.3503785 0 0.9366085 -0.350378 0 0.8659697 -0.5000966 0 0.771925 -0.6357137 0 0.6567375 -0.7541193 0 0.6567345 -0.7541219 0 0.5237089 -0.8518974 0 0.5237073 -0.8518983 0 0.3763405 -0.9264814 0 0.3763383 -0.9264823 0 0.2187254 -0.9757865 0 0.2187258 -0.9757865 0 0.05500566 -0.9984861 0 0.05500555 -0.9984861 0 -0.1099964 -0.9939321 0 -0.1099957 -0.9939321 0 -0.2722072 -0.9622387 0 -0.2722048 -0.9622393 0 -0.426653 -0.9044154 0 -0.4266524 -0.9044158 0 -0.5698614 -0.8217409 0 -0.56986 -0.8217419 0 -0.6973052 -0.7167745 0 -0.6973036 -0.716776 0 -0.8057751 -0.5922219 0 -0.8057736 -0.5922238 0 -0.8922682 -0.4515059 0 -0.9544078 -0.298506 0 -0.9544084 -0.2985041 0 -0.9905192 -0.137375 0 -0.9905188 -0.1373776 0 -0.9996197 0.02757579 0 -0.9996198 0.02757591 0 -0.9814492 0.1917225 0 -0.9814486 0.1917255 0 -0.9365408 0.3505589 0 -0.9365395 0.350562 0 -0.8659804 0.5000782 0 -0.8659816 0.5000759 0 -0.7719429 0.635692 0 -0.7719465 0.6356875 0 -0.6566989 0.754153 0 -0.6567013 0.7541508 0 -0.5237294 0.8518848 0 -0.5237332 0.8518823 0 -0.3763917 0.9264606 0 -0.3763906 0.9264611 0 -0.2187313 0.9757851 0 -0.218731 0.9757852 0 -0.05500286 0.9984863 0 0.1099904 0.9939327 0 0.109991 0.9939326 0 0.2722192 0.9622353 0 0.2722201 0.962235 0 0.426606 0.9044376 0 0.1928313 0.6816192 -0.705841 0.1926775 0.6815811 -0.7059197 0.07790243 0.7039627 -0.7059517 0.07798057 0.7040261 -0.7058799 -0.03896111 0.7072685 -0.7058706 -0.03909844 0.7070865 -0.7060453 -0.1549145 0.6910948 -0.7059671 -0.1547904 0.6911907 -0.7059006 -0.2665988 0.6562116 -0.7059118 -0.2666641 0.656162 -0.7059333 -0.3709453 0.6033661 -0.7059384 -0.3708891 0.6035463 -0.705814 -0.4651947 0.5342262 -0.7058302 -0.4651976 0.5341545 -0.7058826 -0.5467973 0.4502845 -0.7058729 -0.5467861 0.4503125 -0.7058638 -0.6134065 0.3542243 -0.7058737 -0.6134017 0.3541743 -0.705903 -0.6633761 0.248311 -0.7058852 -0.6633685 0.2483414 -0.7058816 -0.6951931 0.1358028 -0.7058783 -0.6951978 0.1357876 -0.7058766 -0.708034 0.01953303 -0.7059081 -0.7080462 0.01953113 -0.705896 -0.701596 -0.0973066 -0.7058998 -0.7016203 -0.09728056 -0.7058792 -0.6760383 -0.2114424 -0.7058784 -0.6760538 -0.211456 -0.7058596 -0.632033 -0.3198194 -0.7058682 -0.6319924 -0.3198426 -0.7058941 -0.5707674 -0.4194973 -0.7058659 -0.5706827 -0.4194917 -0.7059378 -0.4939069 -0.5076982 -0.7059026 -0.4938942 -0.5076854 -0.7059208 -0.4036269 -0.5820233 -0.7059279 -0.4036946 -0.5820514 -0.705866 -0.3022173 -0.6406387 -0.705866 -0.3022274 -0.6406183 -0.7058802 -0.1928156 -0.6816025 -0.7058613 -0.1926785 -0.6815117 -0.7059864 -0.07790708 -0.7039721 -0.7059417 -0.07799375 -0.7040216 -0.7058829 0.03896206 -0.7072506 -0.7058885 0.03909683 -0.7071155 -0.7060163 0.1549128 -0.6911033 -0.7059592 0.1548041 -0.691191 -0.7058972 0.2665703 -0.6562485 -0.7058882 0.2666287 -0.6561369 -0.7059699 0.3709237 -0.6033667 -0.7059493 0.370872 -0.603493 -0.7058684 0.4651788 -0.5341605 -0.7058904 0.4651831 -0.534196 -0.7058607 0.546785 -0.4502981 -0.7058738 0.5467936 -0.4502426 -0.7059026 0.6133573 -0.3542153 -0.7059209 0.613367 -0.3542559 -0.7058922 0.6634064 -0.2481777 -0.7059036 0.6634488 -0.2483406 -0.7058064 0.6952682 -0.1358337 -0.7057985 0.6952739 -0.1358642 -0.705787 0.7081623 -0.01966011 -0.7057759 0.7079285 -0.01935011 -0.7060191 0.7014741 0.09737747 -0.7060112 0.7017154 0.09713661 -0.7058045 0.6761175 0.2114322 -0.7058057 0.6760963 0.2114647 -0.7058162 0.632057 0.3198705 -0.7058235 0.631904 0.3199431 -0.7059276 0.570787 0.4194241 -0.7058935 0.5706457 0.4194538 -0.7059902 0.4937804 0.5077112 -0.7059818 0.4939439 0.5077114 -0.7058674 0.4036791 0.5820146 -0.7059053 0.4037053 0.5820169 -0.7058884 0.3021781 0.6406385 -0.705883 0.3022758 0.6406629 -0.705819 1.56352e-6 0 -1 3.13621e-6 0 -1 1.56512e-6 0 -1 3.12609e-6 0 -1 -1.17284e-6 0 -1 -1.17388e-6 0 -1 1.16502e-6 0 -1 -6.24877e-6 0 -1 -8.81092e-7 0 -1 -1.16758e-6 0 -1 2.34998e-6 0 -1 -1.17283e-6 0 -1 3.1257e-6 0 -1 -2.34834e-6 0 -1 -1.17482e-6 0 -1 -8.04297e-7 0 -1 4.54787e-6 0 -1 -1.1682e-6 0 -1 7.81172e-7 0 -1 -1.96749e-7 0 -1 6.25704e-6 0 -1 -1.1754e-6 0 -1 -2.34135e-6 0 -1 -2.34471e-6 0 -1 5.85809e-7 0 -1 2.64328e-6 0 -1 -6.24875e-6 0 -1 -8.00193e-7 0 -1 -1.17548e-6 0 -1 -6.25688e-6 0 -1 5.86177e-7 0 -1 -1.16563e-6 0 -1 1.17538e-6 0 -1 -0.9991841 0.04038965 0 -0.9991832 -0.0404098 0 -0.9991881 0.04028934 0 -0.9870299 0.1605367 0 -0.987026 0.1605606 0 -0.9485585 0.3166021 0 -0.9485508 0.3166252 0 -0.8854485 0.4647376 0 -0.8854588 0.4647179 0 -0.7994133 0.6007816 0 -0.7994139 0.6007808 0 -0.6927343 0.7211929 0 -0.69271 0.7212163 0 -0.5681398 0.8229321 0 -0.5681174 0.8229476 0 -0.4286841 0.9034545 0 -0.4286938 0.9034498 0 -0.2780601 0.9605637 0 -0.2780802 0.9605579 0 -0.1206569 0.9926944 0 -0.1206541 0.9926947 0 0.04039615 0.9991838 0 0.1998437 0.9798279 0 0.3547262 0.9349702 0 0.4999546 0.8660517 0 0.632479 0.7745775 0 0.6324667 0.7745876 0 0.7485287 0.6631024 0 0.8452015 0.5344478 0 0.8451902 0.5344657 0 0.9199923 0.3919364 0 0.9200016 0.3919146 0 0.970898 0.2394937 0 0.9709039 0.2394697 0 0.996773 0.0802738 0 0.9967749 0.08024883 0 0.9967733 -0.08026891 0 0.9967712 -0.08029389 0 0.9709188 -0.2394095 0 0.9709131 -0.2394324 0 0.9199631 -0.3920052 0 0.9199538 -0.392027 0 0.8451871 -0.5344707 0 0.8451989 -0.5344521 0 0.7485328 -0.6630977 0 0.6324611 -0.7745922 0 0.6324734 -0.7745822 0 0.4999546 -0.8660517 0 0.3547262 -0.9349702 0 0.2000938 -0.9797767 0 0.04013615 -0.9991942 0 0.04013603 -0.9991943 0 -0.1204067 -0.9927247 0 -0.1204099 -0.9927243 0 -0.2783112 -0.960491 0 -0.2782918 -0.9604966 0 -0.4286938 -0.9034498 0 -0.4286841 -0.9034545 0 -0.5681163 -0.8229483 0 -0.5681409 -0.8229314 0 -0.6927092 -0.721217 0 -0.6927351 -0.7211922 0 -0.7994173 -0.6007763 0 -0.8854588 -0.4647179 0 -0.8854485 -0.4647376 0 -0.9485498 -0.316628 0 -0.9485574 -0.3166055 0 -0.9870259 -0.1605611 0 -0.98703 -0.1605362 0 -0.9991873 -0.04030954 0 0.6876039 0.1695679 -0.7060083 0.687747 0.1695101 -0.7058827 0.6516763 0.2776088 -0.7058693 0.6516633 0.2776069 -0.705882 0.5986659 0.3785725 -0.7058909 0.5984668 0.3786405 -0.7060233 0.530095 0.4696124 -0.7060195 0.5301882 0.4695903 -0.7059643 0.4479414 0.5485787 -0.7059816 0.4480805 0.5485989 -0.7058776 0.3541253 0.6134462 -0.7058888 0.3541094 0.6134434 -0.7058992 0.2512705 0.6622614 -0.7058846 0.2511769 0.6622387 -0.7059391 0.1415452 0.6940122 -0.7059122 0.1416761 0.6940356 -0.705863 0.02861547 0.7078041 -0.705829 0.02845793 0.707654 -0.7059859 -0.08545303 0.7030779 -0.7059599 -0.08536356 0.7031691 -0.7058799 -0.1969604 0.6803957 -0.7058812 -0.1970751 0.6802094 -0.7060288 -0.3036035 0.6398918 -0.7059487 -0.3035864 0.6398882 -0.7059592 -0.402391 0.5828568 -0.7059457 -0.4024107 0.5827603 -0.7060142 -0.4906105 0.5107724 -0.7059838 -0.4905511 0.5110154 -0.705849 -0.566266 0.4255733 -0.7058543 -0.5662668 0.4252668 -0.7060383 -0.62707 0.329117 -0.7060207 -0.6270834 0.3291972 -0.7059715 -0.671826 0.2242355 -0.7059522 -0.6718277 0.2243906 -0.7059012 -0.6991134 0.1136633 -0.7059187 -0.6990559 0.1136381 -0.7059797 -0.7068066 0.02848201 -0.7068333 -0.7068065 0.02859717 -0.7068288 -0.7068119 -0.02854996 -0.7068252 -0.7068012 -0.02853655 -0.7068365 -0.6990609 -0.1137348 -0.7059592 -0.6991348 -0.1135936 -0.7059086 -0.6718689 -0.2242787 -0.7058976 -0.6717808 -0.2243463 -0.7059599 -0.6271114 -0.3291387 -0.7059739 -0.6271548 -0.3291272 -0.7059406 -0.566197 -0.4255151 -0.7059447 -0.5663335 -0.4254736 -0.7058601 -0.490714 -0.5108474 -0.7058575 -0.4906115 -0.5108948 -0.7058944 -0.4024144 -0.5828963 -0.7059 -0.4023067 -0.5829064 -0.7059529 -0.3036161 -0.6398811 -0.705953 -0.3035611 -0.6398803 -0.7059773 -0.1971025 -0.6802282 -0.706003 -0.1970623 -0.6802123 -0.7060295 -0.08527439 -0.7030353 -0.7060239 -0.08535283 -0.7030804 -0.7059695 0.02842783 -0.7076745 -0.7059665 0.02845674 -0.707654 -0.7059859 0.1417165 -0.6939015 -0.7059867 0.1416539 -0.6939933 -0.7059089 0.251246 -0.6622058 -0.7059454 0.2512015 -0.662279 -0.7058927 0.354119 -0.6134346 -0.7059021 0.3541243 -0.6134692 -0.7058694 0.4479904 -0.548674 -0.7058764 0.4480313 -0.5485089 -0.7059788 0.5301285 -0.4696376 -0.7059775 0.5301545 -0.4695539 -0.7060138 0.598551 -0.3784775 -0.7060394 0.5985797 -0.3787417 -0.7058734 0.6516237 -0.2776617 -0.705897 0.6516222 -0.2775893 -0.7059268 0.6876879 -0.1695967 -0.7059195 0.6876327 -0.1694233 -0.7060149 0.7059122 -0.05687272 -0.7060123 0.7059553 -0.05690634 -0.7059665 0.7059555 0.05683529 -0.7059721 0.7059131 0.05691683 -0.706008 0.6045993 -0.7965299 0 0.3875608 -0.9218441 0 0.3875806 -0.9218358 0 0.1459475 -0.9892924 0 0.1459557 -0.9892912 0 -0.1043123 -0.9945446 0 -0.1043239 -0.9945434 0 -0.3487296 -0.9372235 0 -0.5705842 -0.8212391 0 -0.5705839 -0.8212394 0 -0.7569675 -0.6534526 0 -0.7569956 -0.65342 0 -0.8958415 -0.4443739 0 -0.8958191 -0.4444189 0 -0.9781556 -0.2078741 0 -0.9781557 -0.207874 0 -0.9991332 0.04163002 0 -0.9991332 0.04163008 0 -0.9572868 0.2891402 0 -0.8552786 0.5181684 0 -0.8553037 0.518127 0 -0.6998366 0.7143031 0 -0.6998927 0.714248 0 -0.4999466 0.8660563 0 -0.2689986 0.9631406 0 -0.2690282 0.9631324 0 -0.02063047 0.9997872 0 -0.02062928 0.9997873 0 0.2281202 0.973633 0 0.228133 0.97363 0 0.463474 0.8861106 0 0.4634972 0.8860984 0 0.6689481 0.7433091 0 0.668976 0.7432841 0 0.8328844 0.5534469 0 0.9443698 0.3288856 0 0.9443523 0.3289358 0 0.9964921 0.08368754 0 0.9964921 0.08368748 0 0.98596 -0.1669821 0 0.9859601 -0.1669819 0 0.9135194 -0.4067953 0 0.9135406 -0.4067476 0 0.7837361 -0.6210939 0 0.7837641 -0.6210588 0 0.6045995 -0.7965296 0 -6.24816e-6 0 -1 3.43224e-6 0 -1 -6.30581e-6 0 -1 3.90576e-7 0 -1 1.14546e-6 0 -1 1.14439e-6 0 -1 6.24803e-6 0 -1 -4.29132e-7 0 -1 3.12474e-6 0 -1 5.72688e-7 0 -1 -1.14498e-6 0 -1 5.72433e-7 0 -1 -2.843e-7 0 -1 -4.295e-7 0 -1 3.12469e-6 0 -1 -1.14567e-6 0 -1 3.13724e-6 0 -1 1.56273e-6 0 -1 -7.90619e-7 0 -1 2.29097e-6 0 -1 -3.12523e-6 0 -1 -1.13459e-6 0 -1 1.14572e-6 0 -1 -2.28054e-6 0 -1 1.14392e-6 0 -1 -2.0051e-6 0 -1 -5.70518e-7 0 -1 5.66688e-7 0 -1 3.16608e-6 0 -1 2.57793e-6 0 -1 4.28178e-7 0 -1 -8.57229e-7 0 -1 -2.29172e-6 0 -1 -1.7132e-6 0 -1 0.569645 -0.8218908 0 0.4269082 -0.9042951 0 0.4269088 -0.9042947 0 0.2719189 -0.9623202 0 0.2719317 -0.9623166 0 0.1100111 -0.9939305 0 0.1100112 -0.9939303 0 -0.0549876 -0.9984871 0 -0.05498486 -0.9984873 0 -0.2187202 -0.9757877 0 -0.218731 -0.9757852 0 -0.5236777 -0.8519166 0 -0.5237007 -0.8519024 0 -0.7719287 -0.6357092 0 -0.8660331 -0.4999866 0 -0.9364947 -0.3506819 0 -0.9364788 -0.3507243 0 -0.9814534 -0.1917007 0 -0.9905412 0.1372159 0 -0.9905347 0.1372635 0 -0.8922398 0.4515619 0 -0.8922595 0.451523 0 -0.8057253 0.5922893 0 -0.805702 0.5923211 0 -0.6972083 0.7168687 0 -0.6971838 0.7168924 0 -0.569925 0.8216969 0 -0.4268029 0.9043447 0 -0.4268218 0.9043358 0 -0.2719873 0.962301 0 -0.2719866 0.9623011 0 -0.1099937 0.9939324 0 -0.1099883 0.9939329 0 0.05499428 0.9984867 0 0.05499696 0.9984866 0 0.2187219 0.9757872 0 0.2187114 0.9757897 0 0.5236996 0.8519032 0 0.5236788 0.8519158 0 0.6567648 0.7540956 0 0.7719047 0.6357384 0 0.7719527 0.63568 0 0.866012 0.5000234 0 0.9364963 0.3506779 0 0.9364958 0.3506788 0 0.9814442 0.1917479 0 0.9996231 0.0274558 0 0.9905079 -0.1374561 0 0.9905013 -0.1375036 0 0.8922576 -0.4515267 0 0.8922376 -0.4515662 0 0.8058226 -0.5921571 0 0.8058453 -0.5921261 0 0.6973341 -0.7167463 0 0.5696221 -0.8219068 0 0.4938817 -0.5076124 -0.7059821 0.4938432 -0.5078075 -0.7058687 0.5708121 -0.4194519 -0.7058568 0.5707994 -0.4195767 -0.7057929 0.6320925 -0.3198691 -0.7057924 0.632059 -0.3197554 -0.7058739 0.6760504 -0.2113712 -0.7058882 0.6760808 -0.2114828 -0.7058256 0.7016531 -0.09742182 -0.7058271 0.7016186 -0.09731 -0.705877 0.7080788 0.0194481 -0.7058656 0.7080184 0.01953202 -0.7059238 0.6951505 0.1358224 -0.7059165 0.6951286 0.1358097 -0.7059405 0.6632992 0.2484048 -0.7059243 0.6633278 0.2483846 -0.7059046 0.6134161 0.3541414 -0.7059069 0.6134662 0.3541229 -0.7058726 0.546777 0.4502823 -0.7058901 0.5466428 0.4503215 -0.705969 0.4651293 0.5340949 -0.7059726 0.4650878 0.5340912 -0.7060028 0.3708873 0.6033354 -0.705995 0.3709764 0.6033432 -0.7059417 0.266463 0.656233 -0.7059432 0.266493 0.6562284 -0.7059361 0.1549139 0.6911471 -0.705916 0.1549844 0.6911877 -0.7058608 0.03895694 0.7072783 -0.705861 0.03890985 0.7072606 -0.7058815 -0.07790708 0.7040209 -0.7058931 -0.0778163 0.7041056 -0.7058186 -0.1926684 0.6816855 -0.7058215 -0.1928464 0.68142 -0.7060291 -0.3022685 0.6404653 -0.7060014 -0.3021795 0.6406365 -0.7058843 -0.4036818 0.5820311 -0.7058901 -0.4036331 0.5822038 -0.7057755 -0.4939183 0.5078516 -0.7057843 -0.4939278 0.5077128 -0.7058776 -0.5707075 0.4195358 -0.7058914 -0.5707151 0.4193708 -0.7059834 -0.6319094 0.3198007 -0.7059873 -0.631917 0.3197519 -0.7060026 -0.675935 0.2113611 -0.7060018 -0.6759406 0.2114133 -0.7059808 -0.7015415 0.09722477 -0.7059652 -0.7016113 0.09733653 -0.7058805 -0.7080785 -0.01947408 -0.7058652 -0.7080257 -0.01956123 -0.7059157 -0.6951498 -0.1357963 -0.7059222 -0.6951366 -0.1358402 -0.7059268 -0.6633036 -0.2483804 -0.7059289 -0.6633299 -0.2483604 -0.7059112 -0.6134105 -0.3541641 -0.7059004 -0.6134694 -0.3541248 -0.705869 -0.5467783 -0.4502834 -0.7058885 -0.5466499 -0.4502984 -0.7059783 -0.4651143 -0.5341037 -0.7059758 -0.4652632 -0.534081 -0.705895 -0.3709265 -0.6033992 -0.7059201 -0.371005 -0.6034075 -0.7058717 -0.266485 -0.6562871 -0.7058845 -0.2665094 -0.6562688 -0.7058925 -0.1549245 -0.6911655 -0.7058957 -0.1549994 -0.6912224 -0.7058236 -0.03895193 -0.7072784 -0.7058612 -0.03888982 -0.7072391 -0.705904 0.07791846 -0.7040266 -0.7058862 0.07781952 -0.7041054 -0.7058185 0.1926296 -0.681707 -0.7058113 0.1926914 -0.6816448 -0.7058545 0.3023889 -0.6405469 -0.7058759 0.3024125 -0.6405042 -0.7059044 0.4034943 -0.5821638 -0.7058879 0.4035128 -0.5820726 -0.7059525 -1.17497e-6 0 -1 -3.12438e-6 0 -1 -1.17444e-6 0 -1 1.96828e-7 0 -1 1.16596e-6 0 -1 -1.17497e-6 0 -1 -2.64308e-6 0 -1 1.17546e-6 0 -1 7.31193e-7 0 -1 1.46705e-7 0 -1 -1.17567e-6 0 -1 -5.85809e-7 0 -1 2.34476e-6 0 -1 -1.56301e-6 0 -1 -3.13566e-6 0 -1 1.16924e-6 0 -1 1.17389e-6 0 -1 2.34126e-6 0 -1 -1.56514e-6 0 -1 -3.12609e-6 0 -1 1.17284e-6 0 -1 -1.17126e-6 0 -1 2.34478e-6 0 -1 -3.51486e-6 0 -1 -4.66653e-6 0 -1 2.05594e-6 0 -1 -1.17363e-6 0 -1 6.31213e-6 0 -1 -2.69149e-6 0 -1 1.17284e-6 0 -1 1.17475e-6 0 -1 -1.1739e-6 0 -1 -1.16502e-6 0 -1 0.9991853 -0.04035967 0 0.9991853 0.04035967 0 0.9870364 -0.1604968 0 0.9870404 -0.1604722 0 0.9485246 -0.3167034 0 0.9485324 -0.3166804 0 0.8854485 -0.4647376 0 0.7995079 -0.6006556 0 0.7994953 -0.6006725 0 0.6927343 -0.7211929 0 0.69271 -0.7212163 0 0.5681398 -0.8229321 0 0.5681409 -0.8229314 0 0.4284721 -0.9035551 0 0.4284811 -0.9035508 0 0.2783139 -0.9604902 0 0.2783005 -0.9604941 0 0.1206539 -0.9926947 0 0.120657 -0.9926943 0 -0.04039716 -0.9991837 0 -0.04039412 -0.9991839 0 -0.2001037 -0.9797748 0 -0.2000938 -0.9797767 0 -0.3544991 -0.9350564 0 -0.3544984 -0.9350566 0 -0.4999546 -0.8660517 0 -0.6324611 -0.7745922 0 -0.6324488 -0.7746023 0 -0.7485328 -0.6630977 0 -0.7485578 -0.6630696 0 -0.8452506 -0.5343702 0 -0.8452728 -0.534335 0 -0.9199617 -0.3920086 0 -0.9199613 -0.3920091 0 -0.9709045 -0.2394672 0 -0.9708985 -0.2394915 0 -0.9967749 -0.08024883 0 -0.996773 -0.0802738 0 -0.996773 0.08027303 0 -0.996775 0.08024805 0 -0.970898 0.2394937 0 -0.9709039 0.2394697 0 -0.9199617 0.3920086 0 -0.9199613 0.3920091 0 -0.8452759 0.5343301 0 -0.8452528 0.5343667 0 -0.7485537 0.6630743 0 -0.7485287 0.6631024 0 -0.6324544 0.7745977 0 -0.6324667 0.7745876 0 -0.4999546 0.8660517 0 -0.3544991 0.9350564 0 -0.3544984 0.9350566 0 -0.2000938 0.9797767 0 -0.2001037 0.9797748 0 -0.04038453 0.9991843 0 -0.04038757 0.9991841 0 0.1206569 0.9926944 0 0.1206541 0.9926947 0 0.2783005 0.9604941 0 0.2783139 0.9604902 0 0.4284818 0.9035505 0 0.4284714 0.9035553 0 0.5681345 0.8229358 0 0.5681334 0.8229365 0 0.6927149 0.7212116 0 0.69274 0.7211874 0 0.7994959 0.6006717 0 0.7995073 0.6006564 0 0.8854461 0.4647421 0 0.8854465 0.4647415 0 0.9485322 0.3166809 0 0.9485248 0.316703 0 0.9870406 0.1604704 0 0.9870367 0.1604954 0 -0.6876047 -0.1696182 -0.7059954 -0.6877076 -0.1695211 -0.7059185 -0.6515997 -0.2776291 -0.705932 -0.651736 -0.2775819 -0.7058248 -0.5987628 -0.3785241 -0.7058348 -0.5984731 -0.3786445 -0.7060158 -0.5301135 -0.4696229 -0.7059986 -0.5301898 -0.4695554 -0.7059863 -0.4479209 -0.548615 -0.7059664 -0.4478864 -0.5485823 -0.7060137 -0.3540652 -0.6133422 -0.7060093 -0.3540543 -0.6133317 -0.7060239 -0.2510579 -0.6622201 -0.705999 -0.2511787 -0.6622533 -0.7059249 -0.1417288 -0.6939536 -0.705933 -0.1416479 -0.6939342 -0.7059683 -0.0286082 -0.7076507 -0.7059831 -0.02866405 -0.7076573 -0.7059742 0.08545303 -0.7030779 -0.7059599 0.08555036 -0.7029865 -0.7060391 0.1970906 -0.6802176 -0.7060166 0.1969255 -0.6804168 -0.7058707 0.303506 -0.6400161 -0.7058778 0.3035703 -0.6399154 -0.7059415 0.4023925 -0.5828855 -0.7059213 0.4024309 -0.5827193 -0.7060366 0.4905853 -0.5107729 -0.7060009 0.4905828 -0.5108352 -0.7059575 0.5662585 -0.425454 -0.7059323 0.5662719 -0.4253947 -0.7059573 0.6271172 -0.3291418 -0.7059672 0.6271256 -0.3291416 -0.7059598 0.671789 -0.2243122 -0.705963 0.6718109 -0.2242969 -0.7059469 0.6990892 -0.1136834 -0.7059393 0.6990774 -0.1136141 -0.7059623 0.7068269 -0.02855044 -0.7068102 0.7068092 -0.02859723 -0.7068259 0.706813 0.02849674 -0.7068263 0.7068015 0.02865552 -0.7068313 0.6990751 0.1136534 -0.7059583 0.6991134 0.1136509 -0.7059206 0.6718088 0.2242921 -0.7059504 0.6717838 0.2243164 -0.7059666 0.6271088 0.3291409 -0.7059752 0.6271322 0.3291451 -0.7059524 0.5662627 0.4254292 -0.7059438 0.5662706 0.4254235 -0.7059409 0.490643 0.5107933 -0.705946 0.4905416 0.5108259 -0.7059928 0.4023462 0.5828072 -0.7060123 0.4024673 0.5828072 -0.7059432 0.3034855 0.6399462 -0.7059502 0.3036096 0.6400123 -0.7058368 0.1971405 0.6803363 -0.7058883 0.1970962 0.6803718 -0.7058663 0.08546268 0.7031306 -0.7059062 0.08535194 0.7031028 -0.7059473 -0.02860397 0.7076576 -0.7059764 -0.02865397 0.7076575 -0.7059745 -0.1417165 0.6939015 -0.7059867 -0.141659 0.6939703 -0.7059307 -0.2510823 0.6622757 -0.7059381 -0.2511461 0.6621624 -0.7060217 -0.3540658 0.6133137 -0.7060338 -0.3540455 0.6133657 -0.7059989 -0.4479185 0.5485501 -0.7060182 -0.4479013 0.5486509 -0.7059509 -0.530147 0.4696066 -0.7059843 -0.5301335 0.469575 -0.7060156 -0.5986177 0.3783984 -0.7060253 -0.5986363 0.3787776 -0.7058061 -0.6516813 0.2776891 -0.7058331 -0.6516407 0.27751 -0.705941 -0.6876803 0.1696126 -0.7059231 -0.6876172 0.1695295 -0.7060045 -0.7059273 0.05683225 -0.7060006 -0.7059651 0.0569204 -0.7059558 -0.7059688 -0.05683636 -0.7059588 -0.7059112 -0.05691665 -0.7060099 7.81817e-7 0 -1 -1.17477e-6 0 -1 -7.34637e-7 0 -1 -1.46122e-7 0 -1 2.6419e-6 0 -1 3.12477e-6 0 -1 -1.17515e-6 0 -1 -5.86172e-7 0 -1 -6.59939e-7 0 -1 -7.82835e-7 0 -1 -1.17322e-6 0 -1 1.17505e-6 0 -1 1.17368e-6 0 -1 -1.16372e-6 0 -1 1.17124e-6 0 -1 -2.91976e-6 0 -1 2.34238e-6 0 -1 -1.17286e-6 0 -1 3.9042e-7 0 -1 -7.88047e-7 0 -1 3.12406e-6 0 -1 -1.1752e-6 0 -1 6.25731e-6 0 -1 -1.17165e-6 0 -1 -1.98012e-6 0 -1 -2.35113e-6 0 -1 2.34887e-6 0 -1 -2.04053e-6 0 -1 1.17507e-6 0 -1 0.4645203 -0.8855625 0 0.5345876 -0.8451132 0 0.4645196 -0.8855628 0 0.3544991 -0.9350564 0 0.3544984 -0.9350566 0 0.04038655 -0.9991841 0 0.04038757 -0.9991841 0 -0.1206569 -0.9926944 0 -0.1206541 -0.9926947 0 -0.2783005 -0.9604941 0 -0.2783139 -0.9604902 0 -0.4285693 -0.9035089 0 -0.4285784 -0.9035046 0 -0.5680053 -0.823025 0 -0.5680043 -0.8230257 0 -0.69274 -0.7211874 0 -0.6927149 -0.7212116 0 -0.79952 -0.6006396 0 -0.7995073 -0.6006564 0 -0.8854461 -0.4647421 0 -0.8854465 -0.4647415 0 -0.9485322 -0.3166809 0 -0.9485248 -0.316703 0 -0.9870367 -0.1604949 0 -0.9870327 -0.1605198 0 -0.9870325 0.1605213 0 -0.9870365 0.1604966 0 -0.9485246 0.3167034 0 -0.9485324 0.3166804 0 -0.7995079 0.6006556 0 -0.7995194 0.6006403 0 -0.6927092 0.721217 0 -0.6927351 0.7211922 0 -0.5680106 0.8230212 0 -0.5680117 0.8230205 0 -0.428579 0.9035043 0 -0.4285687 0.9035092 0 -0.2783139 0.9604902 0 -0.2783005 0.9604941 0 -0.1206539 0.9926947 0 -0.120657 0.9926943 0 0.04039716 0.9991837 0 0.2000938 0.9797767 0 0.3544991 0.9350564 0 0.3544984 0.9350566 0 0.4999763 0.8660392 0 0.6324488 0.7746023 0 0.6324611 0.7745922 0 0.7485328 0.6630977 0 0.8451485 0.5345317 0 0.845148 0.5345324 0 0.9200432 0.3918172 0 0.9200611 0.3917753 0 0.9709045 0.2394672 0 0.9708985 0.2394915 0 0.9967527 0.08052331 0 0.9967547 0.08049839 0 0.9967549 -0.08049762 0 0.9967529 -0.08052259 0 0.970898 -0.2394937 0 0.9709039 -0.2394697 0 0.9200612 -0.3917747 0 0.9200429 -0.3918178 0 0.8451511 -0.5345274 0 0.8451508 -0.5345281 0 0.7485287 -0.6631024 0 0.6324667 -0.7745876 0 0.6324544 -0.7745977 0 0.5346329 -0.8450844 0 -0.490592 0.5107532 -0.7060105 -0.4906145 0.5106596 -0.7060625 -0.5661796 0.425368 -0.7060474 -0.5661727 0.4255585 -0.705938 -0.6271409 0.3291542 -0.7059404 -0.6271285 0.3291134 -0.7059705 -0.671789 0.2243122 -0.705963 -0.6718064 0.2243251 -0.7059422 -0.6990872 0.1137098 -0.7059372 -0.6990761 0.1135841 -0.7059684 -0.7082417 0 -0.7059701 -0.7082378 0 -0.705974 -0.6990684 -0.1136523 -0.7059649 -0.6991153 -0.1136512 -0.7059187 -0.6718088 -0.2242921 -0.7059504 -0.6717792 -0.2243446 -0.7059619 -0.6271088 -0.3291409 -0.7059752 -0.5662681 -0.4254332 -0.7059371 -0.5660716 -0.4254825 -0.706065 -0.4905781 -0.510699 -0.7060593 -0.4906506 -0.5107309 -0.7059858 -0.4022607 -0.5828701 -0.706009 -0.4023634 -0.5828652 -0.7059546 -0.3035457 -0.6399397 -0.7059301 -0.3035867 -0.6399342 -0.7059175 -0.1971276 -0.6803186 -0.7059089 -0.1971612 -0.6803279 -0.7058905 -0.08546185 -0.7031508 -0.7058863 -0.08535373 -0.7030878 -0.705962 0.02860289 -0.7076842 -0.7059497 0.02865457 -0.7076426 -0.7059893 0.141659 -0.6939703 -0.7059307 0.2510775 -0.6622632 -0.7059515 0.2511461 -0.6621624 -0.7060217 0.3285598 -0.6263859 -0.706887 0.3284021 -0.6265461 -0.7068184 0.3781699 -0.5978372 -0.7068085 0.3782984 -0.5977036 -0.7068527 0.447927 -0.5485605 -0.7060049 0.4479086 -0.5486301 -0.7059624 0.5301337 -0.4696481 -0.7059666 0.5301224 -0.4697439 -0.7059115 0.5986257 -0.3786169 -0.7059013 0.5986336 -0.3785375 -0.7059371 0.6516365 -0.2775099 -0.7059448 0.6516407 -0.27751 -0.705941 0.6876803 -0.1696126 -0.7059231 0.6876207 -0.1695006 -0.7060081 0.7059009 -0.0569902 -0.7060143 0.7059575 -0.05712825 -0.7059464 0.7059546 0.05702203 -0.705958 0.7058938 0.05709391 -0.7060129 0.6876047 0.1696182 -0.7059954 0.6877111 0.1694921 -0.705922 0.6516484 0.2775164 -0.7059313 0.6516249 0.2775048 -0.7059577 0.5985907 0.3786021 -0.7059388 0.5986714 0.3785614 -0.7058923 0.5301847 0.469686 -0.7059033 0.5300803 0.4696967 -0.7059745 0.4479296 0.548599 -0.7059733 0.4478959 0.5485938 -0.7059987 0.3540777 0.6133372 -0.7060075 0.3540478 0.6133503 -0.706011 0.2510579 0.6622201 -0.705999 0.2511734 0.6622393 -0.7059398 0.1417262 0.6939405 -0.7059464 0.1416479 0.6939342 -0.7059683 0.02860927 0.7076508 -0.705983 0.02866256 0.7076796 -0.7059519 -0.08545541 0.703071 -0.7059665 -0.08554857 0.7030016 -0.7060243 -0.1970978 0.680189 -0.7060422 -0.1969701 0.6803923 -0.7058817 -0.3035485 0.6399458 -0.7059234 -0.3035703 0.6399154 -0.7059415 -0.4023019 0.5829144 -0.7059491 -0.4023327 0.5828154 -0.7060133 -4.69572e-6 0 -1 1.17281e-6 0 -1 1.17115e-6 0 -1 -2.64156e-6 0 -1 1.45599e-7 0 -1 7.34582e-7 0 -1 -5.87748e-7 0 -1 7.33313e-7 0 -1 -6.2502e-6 0 -1 2.35024e-6 0 -1 -3.52285e-6 0 -1 6.2977e-6 0 -1 -1.16798e-6 0 -1 1.17238e-6 0 -1 -1.75769e-6 0 -1 -1.17542e-6 0 -1 3.13676e-6 0 -1 -1.16889e-6 0 -1 1.17491e-6 0 -1 -1.16747e-6 0 -1 2.34954e-6 0 -1 1.17513e-6 0 -1 -1.56188e-6 0 -1 1.17351e-6 0 -1 -1.57796e-6 0 -1 -1.16396e-6 0 -1 -7.81875e-7 0 -1 1.16283e-6 0 -1 -1.56438e-6 0 -1 1.17177e-6 0 -1 1.17235e-6 0 -1 0.1971551 0.6803717 -0.70585 0.1968882 0.6802444 -0.7060471 0.08543407 0.7029954 -0.7060443 0.08556926 0.7030826 -0.7059412 -0.02860862 0.7076802 -0.7059535 -0.02865117 0.7076224 -0.7060098 -0.1417408 0.6939093 -0.7059742 -0.1416585 0.6939766 -0.7059245 -0.2510581 0.6622989 -0.7059249 -0.2511514 0.6621884 -0.7059955 -0.3540756 0.6133616 -0.7059873 -0.3540616 0.6132851 -0.7060608 -0.4479442 0.5485603 -0.7059941 -0.4479043 0.5486615 -0.7059407 -0.5301095 0.4696403 -0.70599 -0.5301513 0.4696385 -0.7059599 -0.5986304 0.3784852 -0.705968 -0.5986423 0.378619 -0.705886 -0.6515907 0.2776575 -0.7059291 -0.6515696 0.2775318 -0.705998 -0.6876499 0.1694909 -0.7059819 -0.6876819 0.1695343 -0.7059404 -0.705961 0.05698835 -0.7059543 -0.7059541 0.05698496 -0.7059615 -0.7059609 -0.05699002 -0.7059543 -0.7059504 -0.05698156 -0.7059653 -0.6876851 -0.169502 -0.7059449 -0.6876547 -0.1695276 -0.7059684 -0.651542 -0.2776296 -0.705985 -0.6516587 -0.2775698 -0.7059009 -0.5987041 -0.3785304 -0.7058812 -0.5985754 -0.3785748 -0.7059665 -0.5301342 -0.4696537 -0.7059627 -0.5301433 -0.4696409 -0.7059642 -0.4479486 -0.5485913 -0.7059672 -0.4478696 -0.5486145 -0.7059993 -0.3780373 -0.5978222 -0.7068921 -0.3782737 -0.5977801 -0.7068014 -0.328694 -0.6264104 -0.7068029 -0.3285179 -0.626439 -0.7068595 -0.2510298 -0.6622239 -0.7060055 -0.2511638 -0.6622607 -0.7059231 -0.1417552 -0.6939877 -0.7058941 -0.1416436 -0.6939038 -0.7059991 -0.02860647 -0.7076268 -0.7060071 -0.02865362 -0.7076818 -0.70595 0.08545523 -0.7030875 -0.70595 0.08536529 -0.7031545 -0.7058942 0.1971253 -0.6803091 -0.7059187 0.1971322 -0.6803444 -0.7058827 0.303541 -0.6399982 -0.7058791 0.3035754 -0.6399164 -0.7059385 0.402332 -0.5829123 -0.7059337 0.4023519 -0.5827817 -0.7060301 0.4906504 -0.5107416 -0.7059783 0.4906053 -0.5107483 -0.7060047 0.5662245 -0.4254505 -0.7059616 0.5662227 -0.425503 -0.7059314 0.6271278 -0.3291375 -0.7059599 0.6271541 -0.3291354 -0.7059375 0.6717805 -0.2243129 -0.7059708 0.6717851 -0.2242507 -0.7059861 0.6990612 -0.113596 -0.7059811 0.6990867 -0.1136363 -0.7059494 0.7082617 0 -0.70595 0.708249 0 -0.7059628 0.6990893 0.1136001 -0.7059527 0.6990575 0.1136292 -0.7059794 0.6717571 0.2243032 -0.7059961 0.6718051 0.2242633 -0.7059632 0.6271399 0.3291334 -0.705951 0.6271343 0.3291251 -0.7059599 0.5662273 0.4254668 -0.7059496 0.5662015 0.4254838 -0.70596 0.490648 0.5107325 -0.7059864 0.4906024 0.5107496 -0.7060058 0.4022796 0.5828413 -0.7060222 0.402414 0.5828672 -0.7059241 0.3035067 0.6399256 -0.7059596 0.3036144 0.6399676 -0.7058752 7.82561e-7 0 -1 -1.17546e-6 0 -1 1.1739e-6 0 -1 -2.34476e-6 0 -1 -1.17284e-6 0 -1 1.17126e-6 0 -1 -1.46705e-7 0 -1 2.64308e-6 0 -1 -1.16746e-6 0 -1 -1.17475e-6 0 -1 1.17444e-6 0 -1 -1.96828e-7 0 -1 -2.34126e-6 0 -1 1.17497e-6 0 -1 -1.16596e-6 0 -1 1.17497e-6 0 -1 3.12438e-6 0 -1 -1.16289e-6 0 -1 1.17567e-6 0 -1 -2.34478e-6 0 -1 3.51486e-6 0 -1 1.17129e-6 0 -1 -1.17284e-6 0 -1 1.56301e-6 0 -1 3.13566e-6 0 -1 -1.16924e-6 0 -1 -1.17389e-6 0 -1 4.66653e-6 0 -1 -2.05594e-6 0 -1 1.17363e-6 0 -1 -6.31213e-6 0 -1 2.69149e-6 0 -1 -0.9991853 0.04035967 0 -0.9991853 -0.04035967 0 -0.9870364 0.1604968 0 -0.9870404 0.1604722 0 -0.7994953 0.6006725 0 -0.5681409 0.8229314 0 -0.4284721 0.9035551 0 -0.4284811 0.9035508 0 0.04039412 0.9991839 0 0.2001037 0.9797748 0 0.7485578 0.6630696 0 0.8452506 0.5343702 0 0.8452728 0.534335 0 0.9199617 0.3920086 0 0.9199613 0.3920091 0 0.996773 -0.08027303 0 0.996775 -0.08024805 0 0.9199617 -0.3920086 0 0.9199613 -0.3920091 0 0.8452759 -0.5343301 0 0.8452528 -0.5343667 0 0.7485537 -0.6630743 0 0.2001037 -0.9797748 0 0.04038453 -0.9991843 0 -0.4284818 -0.9035505 0 -0.4284714 -0.9035553 0 -0.5681345 -0.8229358 0 -0.5681334 -0.8229365 0 -0.7994959 -0.6006717 0 -0.9870406 -0.1604704 0 -0.9870367 -0.1604954 0 0.6877076 0.1695211 -0.7059185 0.6515997 0.2776291 -0.705932 0.651736 0.2775819 -0.7058248 0.5987628 0.3785241 -0.7058348 0.5984731 0.3786445 -0.7060158 0.5301135 0.4696229 -0.7059986 0.5301898 0.4695554 -0.7059863 0.4479209 0.548615 -0.7059664 0.4478864 0.5485823 -0.7060137 0.3540652 0.6133422 -0.7060093 0.3540543 0.6133317 -0.7060239 0.2511787 0.6622533 -0.7059249 0.1417288 0.6939536 -0.705933 0.0286082 0.7076507 -0.7059831 0.02866405 0.7076573 -0.7059742 -0.08555036 0.7029865 -0.7060391 -0.1970906 0.6802176 -0.7060166 -0.1969255 0.6804168 -0.7058707 -0.303506 0.6400161 -0.7058778 -0.4023925 0.5828855 -0.7059213 -0.4024309 0.5827193 -0.7060366 -0.4905853 0.5107729 -0.7060009 -0.4905828 0.5108352 -0.7059575 -0.5662585 0.425454 -0.7059323 -0.5662719 0.4253947 -0.7059573 -0.6271172 0.3291418 -0.7059672 -0.6271256 0.3291416 -0.7059598 -0.6718109 0.2242969 -0.7059469 -0.6990892 0.1136834 -0.7059393 -0.6990774 0.1136141 -0.7059623 -0.7068269 0.02855044 -0.7068102 -0.7068092 0.02859723 -0.7068259 -0.706813 -0.02849674 -0.7068263 -0.7068015 -0.02865552 -0.7068313 -0.6990751 -0.1136534 -0.7059583 -0.6991134 -0.1136509 -0.7059206 -0.6717838 -0.2243164 -0.7059666 -0.6271322 -0.3291451 -0.7059524 -0.5662627 -0.4254292 -0.7059438 -0.5662706 -0.4254235 -0.7059409 -0.490643 -0.5107933 -0.705946 -0.4905416 -0.5108259 -0.7059928 -0.4023462 -0.5828072 -0.7060123 -0.4024673 -0.5828072 -0.7059432 -0.3034855 -0.6399462 -0.7059502 -0.3036096 -0.6400123 -0.7058368 -0.1971405 -0.6803363 -0.7058883 -0.1970962 -0.6803718 -0.7058663 -0.08546268 -0.7031306 -0.7059062 -0.08535194 -0.7031028 -0.7059473 0.02860397 -0.7076576 -0.7059764 0.02865397 -0.7076575 -0.7059745 0.2510823 -0.6622757 -0.7059381 0.3540658 -0.6133137 -0.7060338 0.3540455 -0.6133657 -0.7059989 0.4479185 -0.5485501 -0.7060182 0.4479013 -0.5486509 -0.7059509 0.530147 -0.4696066 -0.7059843 0.5301335 -0.469575 -0.7060156 0.5986177 -0.3783984 -0.7060253 0.5986363 -0.3787776 -0.7058061 0.6516813 -0.2776891 -0.7058331 0.6876172 -0.1695295 -0.7060045 0.7059273 -0.05683225 -0.7060006 0.7059651 -0.0569204 -0.7059558 0.7059688 0.05683636 -0.7059588 0.7059112 0.05691665 -0.7060099 6.59939e-7 0 -1 7.82835e-7 0 -1 1.17235e-6 0 -1 -1.17368e-6 0 -1 1.16372e-6 0 -1 -1.17538e-6 0 -1 7.34637e-7 0 -1 -3.9042e-7 0 -1 7.88047e-7 0 -1 -3.12406e-6 0 -1 1.1752e-6 0 -1 1.98012e-6 0 -1 -2.6419e-6 0 -1 1.17477e-6 0 -1 1.16643e-6 0 -1 -1.17505e-6 0 -1 7.82585e-7 0 -1 1.17265e-6 0 -1 -1.17124e-6 0 -1 2.35113e-6 0 -1 -6.25731e-6 0 -1 1.17165e-6 0 -1 -2.34887e-6 0 -1 2.04053e-6 0 -1 1.17322e-6 0 -1 -3.12477e-6 0 -1 1.17515e-6 0 -1 1.16842e-6 0 -1 2.91976e-6 0 -1 -2.34238e-6 0 -1 1.17286e-6 0 -1 -0.4645203 0.8855625 0 -0.5345876 0.8451132 0 -0.4645196 0.8855628 0 -0.04038655 0.9991841 0 0.4285693 0.9035089 0 0.4285784 0.9035046 0 0.5680053 0.823025 0 0.5680043 0.8230257 0 0.79952 0.6006396 0 0.9870367 0.1604949 0 0.9870327 0.1605198 0 0.9870325 -0.1605213 0 0.9870365 -0.1604966 0 0.7995194 -0.6006403 0 0.6927092 -0.721217 0 0.6927351 -0.7211922 0 0.5680106 -0.8230212 0 0.5680117 -0.8230205 0 0.428579 -0.9035043 0 0.4285687 -0.9035092 0 -0.04039615 -0.9991838 0 -0.4999763 -0.8660392 0 -0.8451485 -0.5345317 0 -0.845148 -0.5345324 0 -0.9200432 -0.3918172 0 -0.9200611 -0.3917753 0 -0.9967527 -0.08052331 0 -0.9967547 -0.08049839 0 -0.9967549 0.08049762 0 -0.9967529 0.08052259 0 -0.9200612 0.3917747 0 -0.9200429 0.3918178 0 -0.8451511 0.5345274 0 -0.8451508 0.5345281 0 -0.5346329 0.8450844 0 0.490592 -0.5107532 -0.7060105 0.4906145 -0.5106596 -0.7060625 0.5661796 -0.425368 -0.7060474 0.5661727 -0.4255585 -0.705938 0.6271409 -0.3291542 -0.7059404 0.6271285 -0.3291134 -0.7059705 0.6718064 -0.2243251 -0.7059422 0.6990872 -0.1137098 -0.7059372 0.6990761 -0.1135841 -0.7059684 0.7082417 0 -0.7059701 0.7082378 0 -0.705974 0.6990684 0.1136523 -0.7059649 0.6991153 0.1136512 -0.7059187 0.6717792 0.2243446 -0.7059619 0.6271548 0.3291272 -0.7059406 0.5662681 0.4254332 -0.7059371 0.5660716 0.4254825 -0.706065 0.4905781 0.510699 -0.7060593 0.4906506 0.5107309 -0.7059858 0.4022607 0.5828701 -0.706009 0.4023634 0.5828652 -0.7059546 0.3035457 0.6399397 -0.7059301 0.3035867 0.6399342 -0.7059175 0.1971276 0.6803186 -0.7059089 0.1971612 0.6803279 -0.7058905 0.08546185 0.7031508 -0.7058863 0.08535373 0.7030878 -0.705962 -0.02860289 0.7076842 -0.7059497 -0.02865457 0.7076426 -0.7059893 -0.2510775 0.6622632 -0.7059515 -0.3285598 0.6263859 -0.706887 -0.3284021 0.6265461 -0.7068184 -0.3781699 0.5978372 -0.7068085 -0.3782984 0.5977036 -0.7068527 -0.447927 0.5485605 -0.7060049 -0.4479086 0.5486301 -0.7059624 -0.5301337 0.4696481 -0.7059666 -0.5301224 0.4697439 -0.7059115 -0.5986257 0.3786169 -0.7059013 -0.5986336 0.3785375 -0.7059371 -0.6516365 0.2775099 -0.7059448 -0.6876207 0.1695006 -0.7060081 -0.7059009 0.0569902 -0.7060143 -0.7059575 0.05712825 -0.7059464 -0.7059546 -0.05702203 -0.705958 -0.7058938 -0.05709391 -0.7060129 -0.6877111 -0.1694921 -0.705922 -0.6516484 -0.2775164 -0.7059313 -0.6516249 -0.2775048 -0.7059577 -0.5985907 -0.3786021 -0.7059388 -0.5986714 -0.3785614 -0.7058923 -0.5301847 -0.469686 -0.7059033 -0.5300803 -0.4696967 -0.7059745 -0.4479296 -0.548599 -0.7059733 -0.4478959 -0.5485938 -0.7059987 -0.3540777 -0.6133372 -0.7060075 -0.3540478 -0.6133503 -0.706011 -0.2511734 -0.6622393 -0.7059398 -0.1417262 -0.6939405 -0.7059464 -0.02860927 -0.7076508 -0.705983 -0.02866256 -0.7076796 -0.7059519 0.08545541 -0.703071 -0.7059665 0.08554857 -0.7030016 -0.7060243 0.1970978 -0.680189 -0.7060422 0.1969701 -0.6803923 -0.7058817 0.3035485 -0.6399458 -0.7059234 0.4023019 -0.5829144 -0.7059491 0.4023327 -0.5828154 -0.7060133 -0.9921199 -0.1252927 0 -0.9921137 0.1253413 0 -0.9921208 0.1252856 0 -0.9297758 0.3681264 0 -0.9297369 0.3682246 0 -0.8089896 0.587823 0 -0.8089626 0.5878601 0 -0.6374116 0.7705236 0 -0.6374394 0.7705006 0 -0.4257458 0.9048429 0 -0.4257676 0.9048326 0 -0.1871785 0.982326 0 -0.1871995 0.9823219 0 0.0626598 0.998035 0 0.06265616 0.9980352 0 0.308984 0.9510672 0 0.3089842 0.9510672 0 0.5359438 0.8442537 0 0.5359694 0.8442375 0 0.7289708 0.6845448 0 0.7289423 0.6845751 0 0.8762363 0.4818819 0 0.8762121 0.4819258 0 0.9685913 0.2486584 0 0.9685913 0.2486581 0 0.9685922 -0.2486547 0 0.9685921 -0.248655 0 0.8762122 -0.4819254 0 0.876236 -0.4818823 0 0.7289355 -0.6845824 0 0.728964 -0.6845521 0 0.5359694 -0.8442375 0 0.5359438 -0.8442537 0 0.308984 -0.9510672 0 0.3089842 -0.9510672 0 0.0626707 -0.9980343 0 0.06267416 -0.9980341 0 -0.1872133 -0.9823194 0 -0.1871926 -0.9823232 0 -0.4257676 -0.9048326 0 -0.4257458 -0.9048429 0 -0.6374394 -0.7705006 0 -0.6374116 -0.7705236 0 -0.8090929 -0.5876808 0 -0.8091198 -0.5876438 0 -0.9296859 -0.3683534 0 -0.9297246 -0.3682557 0 -0.9921269 -0.125237 0 -1.14486e-6 0 -1 6.88135e-7 0 -1 -7.82267e-7 0 -1 1.56508e-6 0 -1 -2.2916e-6 0 -1 6.25172e-6 0 -1 -2.28655e-6 0 -1 -2.28827e-6 0 -1 2.27028e-6 0 -1 1.14523e-6 0 -1 -3.14957e-6 0 -1 -1.13609e-6 0 -1 1.14537e-6 0 -1 6.25118e-6 0 -1 1.1457e-6 0 -1 -6.25438e-6 0 -1 2.28559e-6 0 -1 -1.1455e-6 0 -1 -1.14519e-6 0 -1 1.14415e-6 0 -1 1.14533e-6 0 -1 -1.13871e-6 0 -1 -6.26881e-6 0 -1 2.28569e-6 0 -1 -3.12821e-6 0 -1 1.14568e-6 0 -1 -3.13197e-6 0 -1 1.14104e-6 0 -1 -1.14329e-6 0 -1 -2.26425e-6 0 -1 -0.9965922 -0.08248585 0 -0.9965941 0.08246475 0 -0.996594 0.08246499 0 -0.9693937 0.2455114 0 -0.9693935 0.2455121 0 -0.9157999 0.4016349 0 -0.9158176 0.4015944 0 -0.8372102 0.5468813 0 -0.8372098 0.546882 0 -0.7356549 0.6773566 0 -0.7356298 0.6773838 0 -0.6141049 0.7892245 0 -0.6141039 0.7892252 0 -0.4760553 0.8794154 0 -0.4760354 0.8794263 0 -0.3246899 0.9458206 0 -0.3246892 0.9458209 0 -0.1644807 0.9863803 0 0.1645204 0.9863738 0 0.3246899 0.9458206 0 0.3246741 0.9458259 0 0.4760553 0.8794154 0 0.4760354 0.8794263 0 0.6141049 0.7892245 0 0.6141276 0.7892067 0 0.7356549 0.6773566 0 0.7356298 0.6773838 0 0.8372326 0.5468471 0 0.8371874 0.5469164 0 0.9157999 0.4016349 0 0.9157996 0.4016355 0 0.9694054 0.2454654 0 0.9693935 0.2455121 0 0.9965699 0.0827564 0 0.9965699 0.08275663 0 0.996568 -0.08277755 0 0.9693937 -0.2455114 0 0.9694052 -0.2454661 0 0.9157999 -0.4016349 0 0.9157996 -0.4016355 0 0.8371846 -0.5469205 0 0.8372294 -0.5468519 0 0.7356305 -0.6773831 0 0.7356542 -0.6773573 0 0.6142858 -0.7890837 0 0.614263 -0.7891013 0 0.4758384 -0.8795328 0 0.4758589 -0.8795217 0 0.3246824 -0.9458231 0 0.324698 -0.9458178 0 0.1647671 -0.9863325 0 0.1647675 -0.9863325 0 -0.1647273 -0.9863392 0 -0.1647277 -0.9863391 0 -0.3246974 -0.945818 0 -0.324698 -0.9458178 0 -0.4758384 -0.8795328 0 -0.4758589 -0.8795217 0 -0.6142621 -0.7891022 0 -0.614263 -0.7891013 0 -0.7356305 -0.6773831 0 -0.7356542 -0.6773573 0 -0.837207 -0.5468863 0 -0.9158179 -0.4015939 0 -0.9157996 -0.4016355 0 -0.9693937 -0.2455114 0 -0.9693935 -0.2455121 0 -0.6866111 -0.1738746 -0.7059269 -0.6865939 -0.1739101 -0.705935 -0.6486604 -0.2844508 -0.7059231 -0.6486077 -0.2844926 -0.7059547 -0.5929644 -0.3873455 -0.7059439 -0.5929713 -0.3873277 -0.7059479 -0.5210374 -0.4797535 -0.7059438 -0.5212109 -0.4797211 -0.7058377 -0.435118 -0.5589731 -0.7058479 -0.4350924 -0.5589655 -0.7058699 -0.3370617 -0.6230199 -0.7058582 -0.3371379 -0.6230092 -0.7058312 -0.2300124 -0.670009 -0.7058202 -0.2299767 -0.6700049 -0.7058358 -0.1166923 -0.6986912 -0.7058424 -0.1165038 -0.6985806 -0.705983 0 -0.7082499 -0.705962 0 -0.7082523 -0.7059594 0.1166949 -0.6985668 -0.7059652 0.1164945 -0.6987494 -0.7058176 0.2300209 -0.6700336 -0.7057941 0.2300462 -0.6699801 -0.7058367 0.337089 -0.6230407 -0.7058267 0.3371121 -0.6229648 -0.7058826 0.4351167 -0.5589641 -0.705856 0.4350939 -0.5589721 -0.7058637 0.5210979 -0.4798367 -0.7058426 0.5211381 -0.4796251 -0.7059568 0.5929633 -0.3873479 -0.7059435 0.5929676 -0.3873229 -0.7059537 0.6486256 -0.2844875 -0.7059404 0.6487039 -0.2847074 -0.7057797 0.6867324 -0.1739321 -0.7057948 0.6866533 -0.173693 -0.7059307 0.7058635 -0.05861306 -0.7059188 0.7058864 -0.05870556 -0.7058882 0.705884 0.05862647 -0.705897 0.7058567 0.05865657 -0.705922 0.6866108 0.1738502 -0.7059333 0.6867447 0.1738256 -0.7058091 0.6487259 0.2844795 -0.7058513 0.6485629 0.284616 -0.7059461 0.5929688 0.3873181 -0.7059553 0.5929585 0.3873484 -0.7059472 0.5210404 0.4797303 -0.7059575 0.5211957 0.4797395 -0.7058365 0.4350117 0.559062 -0.7058431 0.4351564 0.5590522 -0.7057617 0.3372521 0.6230214 -0.7057659 0.337151 0.6230133 -0.7058213 0.2300051 0.6699901 -0.7058406 0.2300483 0.6700313 -0.7057874 0.1165458 0.6987546 -0.7058038 0.1164897 0.6987207 -0.7058467 0 0.7083929 -0.7058184 0 0.7083829 -0.7058284 -0.1165159 0.6987058 -0.7058572 -0.1165277 0.6987456 -0.7058158 -0.2299896 0.6699875 -0.7058481 -0.2299844 0.6700246 -0.7058146 -0.337218 0.6229732 -0.7058247 -0.3371842 0.6230846 -0.7057425 -0.4350596 0.5591205 -0.7057673 -0.4351028 0.5589835 -0.7058491 -0.5211044 0.4798167 -0.7058514 -0.5211255 0.4796425 -0.7059542 -0.5929582 0.3873133 -0.7059668 -0.5929639 0.3873496 -0.7059421 -0.6486351 0.2844397 -0.7059508 -0.6486178 0.2844063 -0.7059801 -0.6865685 0.1738907 -0.7059645 -0.6865918 0.1739329 -0.7059314 -0.7058943 0.0584191 -0.705904 -0.7058949 0.05845689 -0.7059003 -0.7059007 -0.05846041 -0.7058942 -0.7058845 -0.05844384 -0.7059118 7.81797e-7 0 -1 1.1737e-6 0 -1 1.16367e-6 0 -1 -1.17479e-6 0 -1 -2.33329e-6 0 -1 1.17502e-6 0 -1 3.89347e-6 0 -1 -6.2736e-6 0 -1 -1.46135e-7 0 -1 3.81627e-6 0 -1 5.85442e-7 0 -1 5.84309e-6 0 -1 -5.25671e-6 0 -1 -1.45935e-7 0 -1 3.90566e-7 0 -1 -7.88067e-7 0 -1 -1.17381e-6 0 -1 -3.12555e-6 0 -1 1.17111e-6 0 -1 6.25586e-6 0 -1 5.85908e-7 0 -1 -1.17218e-6 0 -1 -2.34969e-6 0 -1 -5.86128e-7 0 -1 -6.11054e-7 0 -1 -7.82855e-7 0 -1 1.17046e-6 0 -1 -8.06675e-7 0 -1 3.48857e-6 0 -1 -2.35051e-6 0 -1 4.67482e-6 0 -1 -1.17428e-6 0 -1 -2.04035e-6 0 -1 -1.46894e-7 0 -1 0.4645055 -0.8855702 0 0.534601 -0.8451047 0 0.4645049 -0.8855705 0 0.04013502 -0.9991943 0 -0.1204037 -0.992725 0 -0.1204129 -0.992724 0 -0.2783045 -0.960493 0 -0.2782986 -0.9604947 0 -0.4287911 -0.9034037 0 -0.5680106 -0.8230212 0 -0.5680117 -0.8230205 0 -0.6927343 -0.7211929 0 -0.69271 -0.7212163 0 -0.7994053 -0.6007924 0 -0.9870299 -0.1605367 0 -0.987034 -0.1605117 0 -0.9870339 0.1605122 0 -0.98703 0.1605362 0 -0.7994012 0.6007976 0 -0.4287911 0.9034037 0 -0.2780668 0.9605618 0 -0.2780735 0.9605598 0 -0.1206599 0.9926939 0 -0.1206511 0.992695 0 0.04039514 0.9991838 0 0.1998535 0.9798258 0 0.6324544 0.7745977 0 0.7485537 0.6630743 0 0.7485163 0.6631165 0 0.8450881 0.5346272 0 0.8450767 0.5346451 0 0.9199833 0.3919577 0 0.9200107 0.3918933 0 0.9709622 0.2392333 0 0.9709623 0.2392329 0 0.9967508 0.08054828 0 0.9967491 -0.08056843 0 0.9967511 -0.08054351 0 0.9709771 -0.2391728 0 0.9709772 -0.239172 0 0.9199722 -0.3919839 0 0.9199447 -0.3920482 0 0.8450736 -0.5346501 0 0.8450854 -0.5346314 0 0.7485204 -0.6631118 0 0.7485578 -0.6630696 0 0.6324488 -0.7746023 0 0.5346021 -0.845104 0 -0.4906172 0.5107527 -0.7059934 -0.4905753 0.5108618 -0.7059434 -0.5661635 0.425523 -0.7059668 -0.5661749 0.4254063 -0.7060279 -0.6270818 0.3291232 -0.7060074 -0.6270702 0.3291903 -0.7059864 -0.6718323 0.2243623 -0.7059059 -0.6991112 0.1136896 -0.7059166 -0.6990699 0.1135808 -0.7059751 -0.7082364 0 -0.7059754 -0.6990651 -0.1136821 -0.7059634 -0.6991362 -0.1136236 -0.7059025 -0.6717852 -0.2243181 -0.7059646 -0.6271417 -0.3291203 -0.7059556 -0.5661852 -0.425533 -0.7059434 -0.5661464 -0.4255415 -0.7059694 -0.4906403 -0.5107974 -0.7059449 -0.4907228 -0.5107724 -0.7059056 -0.4023264 -0.5829823 -0.705879 -0.4022295 -0.5829434 -0.7059663 -0.3036947 -0.6398334 -0.7059623 -0.3035292 -0.6398131 -0.706052 -0.1970878 -0.6802042 -0.7060303 -0.1971193 -0.6802004 -0.7060251 -0.08527278 -0.703022 -0.7060372 -0.08535462 -0.7030951 -0.7059546 0.02842622 -0.7076878 -0.7059532 0.02845734 -0.7076391 -0.7060008 0.1417166 -0.6939284 -0.7059603 0.1416568 -0.693978 -0.7059236 0.2512505 -0.6621908 -0.7059579 0.2511665 -0.6623654 -0.7058241 0.3286205 -0.6265867 -0.7066808 0.3288779 -0.6263102 -0.7068061 0.3782005 -0.5978112 -0.7068141 0.3780514 -0.5979594 -0.7067685 0.4479754 -0.5486823 -0.7058795 0.4480386 -0.5484881 -0.7059903 0.530136 -0.469746 -0.7058998 0.5985764 -0.3786802 -0.7059091 0.5985639 -0.3785233 -0.7060039 0.6515084 -0.2776393 -0.7060123 0.651492 -0.2775338 -0.7060688 0.6875963 -0.1693607 -0.7060655 0.6876292 -0.1694523 -0.7060114 0.7058914 -0.05705785 -0.7060182 0.705947 -0.05711418 -0.7059581 0.7059479 0.05702149 -0.7059646 0.7058935 0.05712372 -0.7060108 0.687642 0.1694172 -0.7060073 0.6876131 0.1694474 -0.7060282 0.6515474 0.2775539 -0.7060098 0.6515346 0.2775818 -0.7060106 0.5984826 0.3786435 -0.7060083 0.5986651 0.3785575 -0.7058997 0.530189 0.469669 -0.7059112 0.5300675 0.4697217 -0.7059674 0.447948 0.54856 -0.7059919 0.4480732 0.5486197 -0.705866 0.3542302 0.6134738 -0.7058122 0.2512915 0.6622901 -0.7058502 0.2511155 0.6622555 -0.7059453 0.1415479 0.6940253 -0.7058988 0.02861493 0.7077907 -0.7058424 0.02845793 0.7076838 -0.7059561 -0.08536177 0.7031543 -0.7058948 -0.196964 0.6803814 -0.705894 -0.1971116 0.6801866 -0.7060406 -0.3036615 0.6397741 -0.7060303 -0.3035807 0.6399058 -0.7059458 -0.4022942 0.5829034 -0.7059626 -0.4023307 0.5828232 -0.7060079 0.3872452 0.9219769 0 0.6046695 0.7964766 0 0.7837852 0.6210321 0 0.9133907 0.4070841 0 0.9133881 0.40709 0 0.9860349 0.1665391 0 0.9860337 0.1665461 0 0.9964924 -0.08368378 0 0.9443529 -0.3289342 0 0.8330078 -0.5532613 0 0.8330075 -0.5532618 0 0.6691558 -0.7431222 0 0.6691555 -0.7431224 0 0.463181 -0.8862638 0 0.4631781 -0.8862652 0 0.2284234 -0.9735619 0 0.2284216 -0.9735624 0 -0.02102667 -0.999779 0 -0.2689645 -0.9631501 0 -0.2689626 -0.9631507 0 -0.5000779 -0.8659805 0 -0.6995131 -0.7146198 0 -0.6995162 -0.7146168 0 -0.855408 -0.5179547 0 -0.9573213 -0.289026 0 -0.9573232 -0.2890195 0 -0.9991247 -0.04183441 0 -0.9991241 -0.04184854 0 -0.9781513 0.2078945 0 -0.9781513 0.2078943 0 -0.8956682 0.4447231 0 -0.8956654 0.4447287 0 -0.757006 0.6534081 0 -0.7570062 0.6534078 0 -0.5708878 0.8210282 0 -0.5708914 0.8210257 0 -0.3483799 0.9373535 0 -0.1046673 0.9945074 0 0.1463627 0.9892311 0 0.1463626 0.9892311 0 0.3872506 0.9219746 0 2.57164e-6 0 -1 -6.33513e-6 0 -1 -6.24953e-6 0 -1 1.71788e-6 0 -1 -1.14596e-6 0 -1 2.57796e-6 0 -1 -6.25696e-6 0 -1 2.85599e-6 0 -1 -2.28436e-6 0 -1 -2.57536e-6 0 -1 3.00591e-6 0 -1 -6.28585e-6 0 -1 2.29133e-6 0 -1 -2.27919e-6 0 -1 3.43293e-6 0 -1 7.81602e-7 0 -1 -1.14014e-6 0 -1 -2.28352e-6 0 -1 1.14273e-6 0 -1 6.25125e-6 0 -1 1.14342e-6 0 -1 -3.39957e-6 0 -1 1.43222e-6 0 -1 -2.29137e-6 0 -1 -1.13624e-6 0 -1 1.14514e-6 0 -1 1.14434e-6 0 -1 1.71733e-6 0 -1 -2.28934e-6 0 -1 -1.13723e-6 0 -1 0.4266374 0.9044229 0 0.5698738 0.8217324 0 0.5698724 0.8217333 0 0.6973052 0.7167745 0 0.6973036 0.716776 0 0.8057751 0.5922219 0 0.8057736 0.5922238 0 0.8922682 0.4515059 0 0.9544062 0.2985112 0 0.9544067 0.2985093 0 0.9905192 0.137375 0 0.9905188 0.1373776 0 0.9996197 -0.02757579 0 0.9996198 -0.02757591 0 0.9814492 -0.1917225 0 0.9814486 -0.1917255 0 0.936543 -0.3505529 0 0.9365422 -0.350555 0 0.8659804 -0.5000782 0 0.8659816 -0.5000759 0 0.7719355 -0.635701 0 0.7719385 -0.6356973 0 0.6567103 -0.7541431 0 0.6567118 -0.7541418 0 0.5237294 -0.8518848 0 0.5237332 -0.8518823 0 0.3763917 -0.9264606 0 0.3763906 -0.9264611 0 0.2187313 -0.9757851 0 0.218731 -0.9757852 0 0.05500286 -0.9984863 0 -0.1099904 -0.9939327 0 -0.109991 -0.9939326 0 -0.2722192 -0.9622353 0 -0.2722201 -0.962235 0 -0.4266223 -0.9044299 0 -0.426624 -0.9044291 0 -0.5699072 -0.821709 0 -0.5699101 -0.8217071 0 -0.6972012 -0.7168756 0 -0.8058334 -0.5921424 0 -0.8058363 -0.5921384 0 -0.8922473 -0.4515473 0 -0.8922497 -0.4515424 0 -0.9544226 -0.2984586 0 -0.9544224 -0.2984595 0 -0.9905013 -0.1375041 0 -0.9905021 -0.1374977 0 -0.9996149 0.02775007 0 -0.9996148 0.02775627 0 -0.9814446 0.1917461 0 -0.9366061 0.3503845 0 -0.9366058 0.350385 0 -0.8659697 0.5000966 0 -0.7719324 0.6357047 0 -0.771933 0.6357039 0 -0.6567262 0.7541292 0 -0.656724 0.754131 0 -0.5237089 0.8518974 0 -0.5237073 0.8518983 0 -0.3763405 0.9264814 0 -0.3763383 0.9264823 0 -0.2187254 0.9757865 0 -0.2187258 0.9757865 0 -0.05500566 0.9984861 0 -0.05500555 0.9984861 0 0.1099964 0.9939321 0 0.1099957 0.9939321 0 0.2722072 0.9622387 0 0.2722048 0.9622393 0 0.4266368 0.9044232 0 0.1928156 0.6816025 -0.7058613 0.1926724 0.6815415 -0.7059593 0.07790708 0.7039721 -0.7059417 0.0779969 0.7040504 -0.7058538 -0.03896206 0.7072506 -0.7058885 -0.03909683 0.7071155 -0.7060163 -0.1549128 0.6911033 -0.7059592 -0.1547963 0.6912208 -0.7058696 -0.2665703 0.6562485 -0.7058882 -0.2666549 0.656161 -0.7059378 -0.3709101 0.6033445 -0.7059754 -0.3708796 0.6035054 -0.7058539 -0.4651857 0.5341834 -0.7058686 -0.4651737 0.5341851 -0.7058753 -0.546774 0.4502784 -0.7058948 -0.5468049 0.4502518 -0.705888 -0.6133347 0.3542023 -0.7059471 -0.613367 0.3542559 -0.7058922 -0.6633991 0.2481799 -0.7059097 -0.663461 0.2483506 -0.7057914 -0.6952937 0.1358387 -0.7057723 -0.6952775 0.1358649 -0.7057833 -0.7081493 0.01965975 -0.705789 -0.7079358 0.01935029 -0.7060118 -0.701487 -0.09737926 -0.7059981 -0.7017174 -0.09713441 -0.7058028 -0.6761183 -0.2114284 -0.705806 -0.6760815 -0.2114646 -0.7058304 -0.6320541 -0.3198691 -0.7058268 -0.6319063 -0.3199369 -0.7059285 -0.5707845 -0.4194222 -0.7058968 -0.5706242 -0.4194487 -0.7060106 -0.493785 -0.5077159 -0.7059753 -0.4939345 -0.5076869 -0.7058914 -0.4036793 -0.5820337 -0.7058894 -0.4037097 -0.5820441 -0.7058634 -0.3021899 -0.640636 -0.7058802 -0.3022758 -0.6406629 -0.705819 -0.1928348 -0.6816317 -0.7058279 -0.1926915 -0.6815792 -0.7059177 -0.07789957 -0.7039369 -0.7059778 -0.07798057 -0.7040261 -0.7058799 0.03896111 -0.7072685 -0.7058706 0.03909844 -0.7070865 -0.7060453 0.1549145 -0.6910948 -0.7059671 0.1548045 -0.6911891 -0.705899 0.2665891 -0.6561875 -0.7059379 0.2666544 -0.6561783 -0.7059218 0.3709453 -0.6033661 -0.7059384 0.3708814 -0.6035339 -0.7058285 0.4652048 -0.534223 -0.705826 0.4651976 -0.5341545 -0.7058826 0.5467882 -0.4502878 -0.7058779 0.5467973 -0.4503218 -0.7058492 0.6134065 -0.3542243 -0.7058737 0.6134017 -0.3541743 -0.705903 0.663359 -0.2482997 -0.7059052 0.6633902 -0.2483441 -0.7058603 0.6951931 -0.1358028 -0.7058783 0.6951729 -0.1357827 -0.7059021 0.70806 -0.01953375 -0.705882 0.7080426 -0.01953101 -0.7058997 0.701596 0.0973066 -0.7058998 0.7016326 0.09728479 -0.7058663 0.6760375 0.2114462 -0.7058781 0.6760548 0.2114517 -0.7058599 0.6320359 0.3198208 -0.7058649 0.6319901 0.3198488 -0.7058932 0.5707739 0.4195021 -0.7058578 0.5707159 0.4195054 -0.7059028 0.4939024 0.5076936 -0.7059092 0.4938832 0.507689 -0.7059258 0.4036416 0.5820256 -0.7059177 0.4036985 0.5820361 -0.7058765 0.3021944 0.6406177 -0.7058949 0.3022336 0.6406315 -0.7058656 6.50034e-6 0 -1 -1.14411e-6 0 -1 6.55669e-6 0 -1 -2.27295e-6 0 -1 -2.29012e-6 0 -1 1.62824e-6 0 -1 1.13304e-6 0 -1 1.14549e-6 0 -1 1.14321e-6 0 -1 -6.50022e-6 0 -1 2.2907e-6 0 -1 -2.27932e-6 0 -1 1.14411e-6 0 -1 -1.62811e-6 0 -1 -1.1456e-6 0 -1 1.1441e-6 0 -1 1.13647e-6 0 -1 -1.14535e-6 0 -1 -5.66308e-7 0 -1 -1.14329e-6 0 -1 1.13468e-6 0 -1 -1.14549e-6 0 -1 1.1456e-6 0 -1 1.14507e-6 0 -1 -1.13968e-6 0 -1 -1.1441e-6 0 -1 0.9927074 0.1205489 0 0.9927074 -0.1205489 0 0.9927004 -0.1206069 0 0.9350228 -0.3545877 0 0.9350032 -0.3546392 0 0.8229849 -0.5680633 0 0.8229852 -0.5680629 0 0.6629028 -0.7487056 0 0.6629022 -0.7487061 0 0.4646027 -0.8855194 0 0.464603 -0.8855191 0 0.2396023 -0.9708712 0 0.2395889 -0.9708744 0 -0.2395887 -0.9708746 0 -0.2395889 -0.9708744 0 -0.4646027 -0.8855194 0 -0.464603 -0.8855191 0 -0.6629028 -0.7487056 0 -0.6629022 -0.7487061 0 -0.8231776 -0.5677841 0 -0.8231504 -0.5678235 0 -0.9350423 -0.3545362 0 -0.9350228 -0.3545877 0 -0.9927004 -0.1206069 0 -0.9927004 0.1206069 0 -0.9350739 0.3544529 0 -0.9350935 0.3544015 0 -0.8230189 0.5680142 0 -0.8230465 0.5679742 0 -0.6631307 0.7485037 0 -0.4646149 0.8855129 0 -0.2395746 0.970878 0 0.2395746 0.970878 0 0.2395883 0.9708747 0 0.4646149 0.8855129 0 0.6631307 0.7485037 0 0.8228537 0.5682535 0 0.9350544 0.3545044 0 0.9350739 0.3544529 0 0.9927004 0.1206069 0 -0.9991861 -0.04033869 0 -0.9991812 0.04045993 0 -0.9870336 0.1605136 0 -0.9870258 0.1605624 0 -0.9485583 0.3166026 0 -0.7993891 0.6008136 0 -0.6926966 0.7212291 0 -0.6927477 0.7211801 0 -0.4286744 0.9034591 0 -0.2783274 0.9604863 0 -0.1204001 0.9927256 0 -0.1203942 0.9927262 0 0.04013413 0.9991944 0 0.04013603 0.9991943 0 0.354718 0.9349734 0 0.7485454 0.6630837 0 0.8451871 0.5344707 0 0.8451876 0.53447 0 0.970907 0.2394568 0 0.9709073 0.2394561 0 0.9967753 0.08024394 0 0.9967769 -0.08022314 0 0.9708921 -0.2395174 0 0.9708923 -0.239517 0 0.9200015 -0.3919152 0 0.9200016 -0.3919146 0 0.8451876 -0.53447 0 0.7485454 -0.6630837 0 0.632479 -0.7745775 0 0.354718 -0.9349734 0 0.1998531 -0.979826 0 0.199863 -0.9798239 0 -0.1206508 -0.992695 0 -0.120657 -0.9926943 0 -0.2780869 -0.9605559 0 -0.2780601 -0.9605637 0 -0.4286744 -0.9034591 0 -0.6927525 -0.7211754 0 -0.6927024 -0.7212236 0 -0.7994133 -0.6007816 0 -0.7993897 -0.6008129 0 -0.9991821 -0.04043889 0 -1.17347e-6 0 -1 1.70393e-6 0 -1 -1.17518e-6 0 -1 6.77727e-6 0 -1 2.35049e-6 0 -1 -2.34664e-6 0 -1 2.35051e-6 0 -1 -3.37664e-6 0 -1 3.52295e-6 0 -1 5.84058e-7 0 -1 2.3406e-6 0 -1 -1.17347e-6 0 -1 -6.75215e-6 0 -1 5.87218e-7 0 -1 6.79385e-6 0 -1 -4.08825e-6 0 -1 3.37911e-6 0 -1 -3.52588e-6 0 -1 3.38268e-6 0 -1 -2.34458e-6 0 -1 6.8377e-6 0 -1 -2.92067e-7 0 -1 1.17445e-6 0 -1 -1.68791e-6 0 -1 -1.17355e-6 0 -1 -1.4667e-7 0 -1 -2.05677e-6 0 -1 6.76288e-6 0 -1 -1.16333e-6 0 -1 -8.81474e-7 0 -1 3.86238e-6 0 -1 7.33155e-7 0 -1 6.31868e-6 0 -1 -3.9043e-7 0 -1 7.87948e-7 0 -1 -4.65147e-6 0 -1 2.35115e-6 0 -1 -6.25735e-6 0 -1 3.20641e-6 0 -1 -1.17507e-6 0 -1 1.17514e-6 0 -1 -1.16833e-6 0 -1 1.17418e-6 0 -1 7.82914e-7 0 -1 -1.17317e-6 0 -1 -7.82331e-7 0 -1 1.17545e-6 0 -1 2.34577e-6 0 -1 -1.171e-6 0 -1 -3.12492e-6 0 -1 1.17509e-6 0 -1 1.17242e-6 0 -1 1.17478e-6 0 -1 7.34423e-7 0 -1 1.46121e-7 0 -1 -2.64186e-6 0 -1 1.17221e-6 0 -1 1.17001e-6 0 -1 1.17502e-6 0 -1 2.32749e-6 0 -1 -1.17552e-6 0 -1 2.92119e-6 0 -1 -2.34234e-6 0 -1 1.17285e-6 0 -1 -0.4647474 0.8854433 0 -0.5343608 0.8452566 0 -0.4647262 0.8854545 0 -0.3544158 0.9350879 0 -0.3544151 0.9350882 0 -0.200143 0.9797668 0 -0.200148 0.9797658 0 0.1206238 0.9926983 0 0.120624 0.9926984 0 0.2783072 0.9604922 0 0.428579 0.9035043 0 0.5679989 0.8230293 0 0.5680117 0.8230205 0 0.6928598 0.7210724 0 0.6928606 0.7210716 0 0.7993753 0.6008322 0 0.7993746 0.6008329 0 0.8854588 0.4647179 0 0.8854485 0.4647376 0 0.9485246 0.3167034 0 0.9870802 0.1602277 0 0.9870762 0.1602519 0 0.9870761 -0.1602522 0 0.9870801 -0.1602275 0 0.9485248 -0.316703 0 0.8854588 -0.4647179 0 0.7993753 -0.6008322 0 0.7993746 -0.6008329 0 0.6928598 -0.7210724 0 0.6928606 -0.7210716 0 0.568 -0.8230286 0 0.4285784 -0.9035046 0 0.2783072 -0.9604922 0 0.1206238 -0.9926983 0 0.120624 -0.9926984 0 -0.200148 -0.9797658 0 -0.200143 -0.9797668 0 -0.3544158 -0.9350879 0 -0.3544151 -0.9350882 0 -0.4999584 -0.8660495 0 -0.4999475 -0.8660557 0 -0.6325898 -0.774487 0 -0.7483958 -0.6632525 0 -0.7484207 -0.6632243 0 -0.8452619 -0.5343523 0 -0.8452615 -0.534353 0 -0.9199631 -0.3920052 0 -0.9199628 -0.3920057 0 -0.9709622 -0.2392333 0 -0.9709564 -0.2392566 0 -0.9967508 -0.08054828 0 -0.9967508 0.08054751 0 -0.970957 0.239254 0 -0.9709627 0.2392311 0 -0.9199602 0.392012 0 -0.91996 0.3920125 0 -0.8452619 0.5343523 0 -0.8452615 0.534353 0 -0.7484207 0.6632243 0 -0.7483958 0.6632525 0 -0.6325898 0.774487 0 0.4906942 -0.5106728 -0.7059976 0.490669 -0.5107461 -0.7059621 0.5661773 -0.425553 -0.7059378 0.5661763 -0.4255463 -0.7059425 0.6271263 -0.3291599 -0.7059507 0.6271351 -0.3291168 -0.705963 0.6717846 -0.2242974 -0.7059717 0.6717402 -0.2241094 -0.7060737 0.6990053 -0.1134831 -0.7060547 0.69907 -0.1136129 -0.7059698 0.6990909 0.1134969 -0.7059677 0.6989744 0.1135985 -0.7060668 0.6716866 0.2242646 -0.7060754 0.6718482 0.2241442 -0.7059599 0.627113 0.329153 -0.7059658 0.627148 0.3291295 -0.7059456 0.5661784 0.4255443 -0.705942 0.5661803 0.4255558 -0.7059335 0.4907157 0.5107094 -0.7059562 0.4906651 0.5107234 -0.7059811 0.4022644 0.5828658 -0.7060105 0.4023599 0.5828751 -0.7059485 0.3035508 0.6399239 -0.7059422 0.303593 0.6399476 -0.7059025 0.08543777 0.7031525 -0.7058873 0.08535641 0.7031099 -0.7059397 -0.02860313 0.7076776 -0.7059563 -0.02864587 0.7076351 -0.7059972 -0.1417523 0.693903 -0.705978 -0.1416665 0.6940068 -0.7058933 -0.2510368 0.6623157 -0.7059168 -0.251146 0.6621471 -0.7060361 -0.3287053 0.626317 -0.7068804 -0.3285644 0.6264693 -0.706811 -0.3780002 0.5979418 -0.7068109 -0.3782575 0.5976092 -0.7069544 -0.4479495 0.5484279 -0.7060936 -0.4478704 0.5487769 -0.7058725 -0.5301187 0.469789 -0.7058843 -0.5301508 0.4695655 -0.7060089 -0.5986186 0.3784298 -0.7060075 -0.5986328 0.378544 -0.7059344 -0.6515546 0.277638 -0.7059701 -0.6515831 0.2777088 -0.7059159 -0.6877219 0.1694611 -0.705919 -0.6877508 0.1695178 -0.7058773 -0.7060456 0.05704188 -0.7058655 -0.7059635 0.05689048 -0.7059597 -0.7060602 -0.05691379 -0.705861 -0.68777 -0.169462 -0.7058718 -0.6877152 -0.1695211 -0.7059111 -0.6515935 -0.277637 -0.7059347 -0.6515381 -0.2777029 -0.7059598 -0.5986733 -0.3784633 -0.7059432 -0.5985698 -0.3785042 -0.706009 -0.5300287 -0.4697079 -0.7060058 -0.5302623 -0.4696643 -0.7058594 -0.4480832 -0.5485789 -0.7058914 -0.4477286 -0.5486134 -0.7060896 -0.3540257 -0.6132718 -0.7060903 -0.3541301 -0.6133069 -0.7060075 -0.2510005 -0.6622289 -0.7060111 -0.251197 -0.6622867 -0.705887 -0.1417673 -0.6939682 -0.7059109 -0.1416552 -0.6939334 -0.7059676 -0.02860903 -0.7076441 -0.7059897 -0.02864736 -0.7076871 -0.705945 0.08543211 -0.7030929 -0.7059475 0.08554857 -0.7029867 -0.7060391 0.1970996 -0.6802089 -0.7060224 0.1969629 -0.6803782 -0.7058975 0.3035625 -0.639962 -0.7059026 0.3035772 -0.6398835 -0.7059674 0.4022911 -0.5829122 -0.7059571 0.4023349 -0.5828294 -0.7060005 -0.1242468 -0.9922513 0 -0.2660012 0.9639728 0 -0.2660033 0.9639722 0 -0.52985 0.8480914 0 -0.7497426 0.6617297 0 -0.7497425 0.6617298 0 -0.9073513 0.4203733 0 -0.9073529 0.4203698 0 -0.9895641 0.1440939 0 -0.9895642 0.1440929 0 -0.9895641 -0.1440939 0 -0.9895642 -0.1440929 0 -0.9073519 -0.4203718 0 -0.9073523 -0.4203713 0 -0.7497417 -0.6617307 0 -0.7497434 -0.6617288 0 -0.52985 -0.8480914 0 -0.2660017 -0.9639727 0 -0.2660028 -0.9639723 0 0.1242468 -0.9922513 0 3.67501e-6 0 1 1.95643e-6 0 1 -1.21061e-6 0 1 1.84974e-6 0 1 1.84191e-6 0 1 1.8419e-6 0 1 -3.67501e-6 0 1 1.89599e-6 0 1 -5.36453e-7 0 1 -1.84192e-6 0 1 1.2106e-6 0 1 1.21806e-6 0 1 2.45271e-6 0 1 4.8909e-7 0 1 2.65311e-7 0 1 0 0 1 -2.44551e-6 0 1 1.85717e-6 0 1 -2.04186e-7 0 1 2.38313e-6 0 1 -3.68384e-6 0 1 1.25633e-6 0 1 -1.85979e-6 0 1 -3.05752e-7 0 1 3.05755e-7 0 1 6.07353e-7 0 1 -2.42967e-6 0 1 -4.90634e-6 0 1 1.0729e-6 0 1 -3.7198e-6 0 1 -1.22304e-6 0 1 3.6749e-6 0 1 1.19157e-6 0 1 4.58986e-7 0 1 -5.86663e-7 0 1 4.90629e-6 0 1 1.22303e-6 0 1 6.11971e-7 0 1 -1.82225e-6 0 1 2.42943e-6 0 1 2.27288e-6 0 1 -2.38418e-6 0 1 -1.24376e-6 0 1 -7.57768e-7 0 1 2.38418e-6 0 1 1.01014e-6 0 1 8.5286e-7 0 1 0.9471237 -0.3208687 0 0.9471325 -0.3208426 0 0.9834671 -0.1810877 0 0.983462 -0.1811148 0 0.9993004 -0.03740066 0 0.9993025 -0.03734463 0 0.9942797 0.1068084 0 0.9942767 0.1068357 0 0.9684644 0.249152 0 0.9684715 0.2491249 0 0.9224338 0.3861554 0 0.9224448 0.3861291 0 0.8570992 0.5151516 0 0.8570749 0.5151919 0 0.7741757 0.6329709 0 0.774149 0.6330036 0 0.6745542 0.7382254 0 0.6745422 0.7382364 0 0.5612319 0.8276587 0 0.561246 0.827649 0 0.4361876 0.8998558 0 0.4361985 0.8998505 0 0.3017979 0.953372 0 0.3017906 0.9533743 0 0.1614884 0.9868747 0 0.1614794 0.9868761 0 0.01729995 0.9998504 0 0.01730048 0.9998504 0 -0.1268777 0.9919185 0 -0.1268715 0.9919192 0 -0.2682828 0.9633403 0 -0.2682844 0.9633398 0 -0.4046362 0.9144779 0 -0.4046487 0.9144723 0 -0.5319274 0.8467901 0 -0.5319287 0.8467893 0 -0.6486933 0.7610499 0 -0.6487082 0.7610373 0 -0.7514964 0.6597374 0 -0.7515249 0.6597049 0 -0.921442 0.3885161 0 -0.921442 0.3885159 0 0.1242468 0.9922513 0 -0.1242468 0.9922513 0 -2.45271e-6 0 1 2.68227e-7 0 1 -1.83473e-6 0 1 1.19156e-6 0 1 1.84192e-6 0 1 -1.2106e-6 0 1 -1.21806e-6 0 1 3.68384e-6 0 1 1.83471e-6 0 1 -5.02457e-6 0 1 -1.83471e-6 0 1 5.05039e-7 0 1 3.53538e-6 0 1 -5.05039e-7 0 1 -4.04047e-6 0 1 0.9214426 0.3885147 0 0.9214414 0.3885173 0 1.51309e-5 0 1 -5.83765e-6 0 1 -3.83293e-7 0 1 -6.11971e-7 0 1 -3.05755e-7 0 1 3.05752e-7 0 1 -5.86661e-7 0 1 -1.25633e-6 0 1 1.85979e-6 0 1 -2.42943e-6 0 1 -1.65862e-6 0 1 1.8374e-6 0 1 -3.06642e-6 0 1 1.46713e-6 0 1 1.24376e-6 0 1 7.57768e-7 0 1 -2.38418e-6 0 1 -2.76319e-6 0 1 3.08029e-6 0 1 -3.6749e-6 0 1 2.44606e-6 0 1 1.8599e-6 0 1 -1.0729e-6 0 1 -2.27288e-6 0 1 2.38418e-6 0 1 -0.3227248 0.946493 0 -0.4702916 0.8825111 0 -0.470302 0.8825055 0 -0.6053848 0.795933 0 -0.7251026 0.6886409 0 -0.725117 0.6886258 0 -0.8270325 0.5621543 0 -0.8270173 0.5621767 0 -0.9062449 0.4227532 0 -0.9062589 0.4227232 0 -0.9620386 0.2729136 0 -0.9620306 0.2729418 0 -0.9935481 0.1134117 0 -0.993548 0.1134127 0 -0.9989432 -0.04596346 0 -0.9784459 -0.2065036 0 -0.9784525 -0.2064723 0 -0.9326102 -0.3608856 0 -0.8630357 -0.5051429 0 -0.8630522 -0.505115 0 -0.770883 -0.6369768 0 -0.7708797 -0.6369808 0 -0.6583147 -0.752743 0 -0.6583008 -0.7527551 0 -0.5285453 -0.8489051 0 -0.5285306 -0.8489143 0 -0.3862439 -0.9223967 0 -0.2336376 -0.9723238 0 -0.2336227 -0.9723273 0 -0.0743193 -0.9972346 0 -0.07432222 -0.9972343 0 0.08651274 -0.9962508 0 0.0865156 -0.9962505 0 0.2457084 -0.9693438 0 0.2457162 -0.9693418 0 0.397351 -0.9176667 0 0.3973237 -0.9176787 0 0.5402836 -0.841483 0 0.5402687 -0.8414926 0 0.6675404 -0.7445737 0 0.6675566 -0.7445591 0 0.7786224 -0.6274929 0 0.869071 -0.4946873 0 0.8690691 -0.4946909 0 0.937322 -0.3484647 0 0.9373327 -0.3484359 0 0.980887 -0.1945783 0 0.9808999 -0.1945137 0 0.9994297 -0.03377121 0 0.9994297 -0.03377151 0 0.9919024 0.1270031 0 0.9918984 0.1270343 0 0.9589312 0.2836388 0 0.9589402 0.2836087 0 0.9005591 0.4347335 0 0.9005335 0.4347866 0 0.8198075 0.5726394 0 0.8197894 0.5726652 0 0.7165131 0.6975737 0 0.5954503 0.8033923 0 0.5954686 0.8033787 0 0.4590541 0.8884084 0 0.4590573 0.8884068 0 0.3109461 0.9504276 0 0.3109576 0.9504238 0 0.1538765 0.9880901 0 0.1538725 0.9880908 0 -0.005396604 0.9999855 0 -0.005396246 0.9999855 0 -0.1674646 0.9858781 0 -0.16747 0.9858772 0 -0.3227029 0.9465003 0 0.4724535 -0.8813557 0 0.3207879 -0.9471511 0 0.320774 -0.9471558 0 0.1604658 -0.9870414 0 0.1604657 -0.9870414 0 -0.004549205 -0.9999897 0 -0.004549384 -0.9999898 0 -0.1692994 -0.9855648 0 -0.1692917 -0.9855661 0 -0.3289314 -0.9443538 0 -0.3289309 -0.944354 0 -0.4795873 -0.8774943 0 -0.479587 -0.8774944 0 -0.6172893 -0.7867363 0 -0.6173107 -0.7867195 0 -0.7388904 -0.6738257 0 -0.7389116 -0.6738023 0 -0.8392086 -0.5438097 0 -0.8392083 -0.5438103 0 -0.9175836 -0.3975429 0 -0.9175674 -0.3975805 0 -0.9705886 -0.2407442 0 -0.9705783 -0.2407861 0 -0.9968944 -0.07875096 0 -0.9968909 -0.07879483 0 -0.9961372 0.08781158 0 -0.9961372 0.08781164 0 -0.9687017 0.248228 0 -0.9687016 0.2482283 0 -0.9140505 0.4056005 0 -0.914083 0.4055271 0 -0.8343515 0.5512328 0 -0.8343715 0.5512028 0 -0.7330622 0.6801617 0 -0.7330838 0.6801384 0 -0.6103459 0.792135 0 -0.6103666 0.7921191 0 -0.4724898 0.8813362 0 -0.4724895 0.8813363 0 -0.3207644 0.9471591 0 -0.3207641 0.9471592 0 -0.1604658 0.9870414 0 -0.1604726 0.9870403 0 0.00454235 0.9999897 0 0.00454235 0.9999897 0 0.1695494 0.9855217 0 0.1695417 0.9855231 0 0.3284761 0.9445124 0 0.3284621 0.9445172 0 0.4802365 0.877139 0 0.4802363 0.8771392 0 0.6172893 0.7867363 0 0.6172679 0.786753 0 0.7389342 0.6737776 0 0.7389116 0.6738023 0 0.8392052 0.543815 0 0.8391848 0.5438464 0 0.9175853 0.3975389 0 0.9175692 0.3975762 0 0.9705879 0.240747 0 0.9705879 0.2407473 0 0.9968909 0.07879483 0 0.9968909 0.07879483 0 0.9962671 -0.08632379 0 0.9962672 -0.08632391 0 0.9683399 -0.2496353 0 0.9683293 -0.2496769 0 0.9140687 -0.4055597 0 0.9140685 -0.4055598 0 0.8343682 -0.5512075 0 0.834368 -0.5512079 0 0.7338302 -0.679333 0 0.7338079 -0.6793571 0 0.6096291 -0.7926868 0 0.60965 -0.7926709 0 0.4724721 -0.8813456 0 -0.622247 0.7828209 0 -0.9297562 0.368176 0 -0.9297559 0.3681766 0 -0.9892159 -0.1464647 0 -0.989172 -0.1467614 9.74611e-5 0.3682023 0.9297457 0 -0.1461086 0.9892686 0 -0.1468295 0.9891619 1.94918e-4 -0.1481399 0.9889665 0 -0.6222476 0.7828205 0 0.9299445 -0.3677 0 0.9891543 0.1468804 0 0.9891718 0.1467627 0 0.7808545 0.6247131 0 0.7827991 0.6222744 -4.86807e-4 0.7839158 0.6208672 0 0.3681825 0.9297536 0 -0.9890433 -0.1476261 0 -0.7835874 -0.6212817 0 -0.7835581 -0.6213185 0 -0.3676695 -0.9299566 0 -0.3676481 -0.929965 0 0.1468294 -0.9891619 0 0.1468381 -0.9891606 0 0.6220827 -0.7829516 0 0.621279 -0.7835894 -1.49929e-4 0.6209269 -0.7838685 0 0.929965 -0.3676481 0 1.86679e-7 0 -1 -7.05991e-7 0 -1 8.1877e-7 0 -1 -1.41198e-6 0 -1 6.66508e-7 0 -1 -3.9977e-6 0 -1 -0.775626 -0.3364967 -0.5340171 -0.650097 -0.282085 -0.705551 -0.6503884 -0.281961 -0.7053318 -0.4887848 -0.2117574 -0.8463146 -0.4885745 -0.211788 -0.8464282 -0.3057252 -0.1325264 -0.9428514 -0.2383257 -0.1385468 -0.9612522 -0.10532 -0.03424054 -0.9938488 -0.03092002 -0.01341849 -0.9994318 -0.7769548 -0.3357028 0.5325833 -0.8673709 -0.3746091 0.3276216 -0.8675301 -0.3751986 0.3265236 -0.9121136 -0.3945482 0.1112686 -0.9119526 -0.3955194 0.1091194 -0.9111217 -0.3957151 -0.115181 -0.9117973 -0.3947632 -0.1130827 -0.8676511 -0.3756959 -0.3256294 -0.865128 -0.3773538 -0.3303905 -0.7792941 -0.3353915 -0.5293517 -0.7754869 -0.3363565 -0.5343074 -0.4851818 -0.2198345 0.8463283 -0.5232823 -0.2220006 0.8227341 -0.6471796 -0.2861019 0.7066147 -0.6581869 -0.285472 0.6966318 -0.7778272 -0.3374357 0.5302096 -0.1013738 -0.04391789 0.9938786 -0.1004975 -0.04395645 0.9939659 -0.3012348 -0.130698 0.9445505 -0.3281436 -0.1292199 0.9357478 -0.3269127 -0.128713 0.9362485 -0.3269127 -0.128713 0.9362485 -0.3269127 -0.128713 0.9362484 -0.03754895 -0.3265044 0.9444496 -0.01245737 -0.1091949 0.9939423 -0.01253396 -0.1089675 0.9939663 -0.003877818 -0.0336619 -0.9994258 -0.001645863 -0.1370382 -0.9905645 -0.06309658 -0.2676435 -0.9614499 -0.04084759 -0.3563945 -0.9334424 -0.06065738 -0.5291931 -0.8463306 -0.06030881 -0.5298548 -0.8459414 -0.08048194 -0.7041075 -0.7055178 -0.08127641 -0.7028621 -0.7066676 -0.09703934 -0.8391102 -0.5352361 -0.09573739 -0.8407003 -0.5329704 -0.1071713 -0.9381104 -0.3293376 -0.1083192 -0.9371759 -0.331615 -0.1140516 -0.9868346 -0.114673 -0.1139475 -0.9868671 -0.1144958 -0.1138754 -0.987721 0.1069568 -0.113605 -0.987693 0.1075014 -0.1079249 -0.9383283 0.3284696 -0.1078286 -0.9382576 0.3287031 -0.09654498 -0.841759 0.5311506 -0.09602665 -0.8411805 0.5321601 -0.08013814 -0.7019912 0.7076626 -0.08102768 -0.7032629 0.7062973 -0.06089383 -0.5276156 0.847298 -0.06022042 -0.5264515 0.8480697 -0.03739941 -0.3269661 0.9442958 6.61629e-6 0 -1 -5.81605e-6 0 -1 -6.40697e-6 0 -1 0.09733587 0.8435285 0.5281907 0.1081446 0.9372363 0.3315012 0.1079788 0.9374153 0.3310487 0.1137678 0.9876334 0.1078759 0.1139767 0.9875673 0.1082603 0.1137983 0.9866374 -0.1166054 0.1142235 0.9866927 -0.1157169 0.1084809 0.9371585 -0.3316113 0.1085042 0.9371498 -0.3316281 0.09668207 0.8402105 -0.5335719 0.09721302 0.84062 -0.5328299 0.08143174 0.7041931 -0.7053233 0.08053213 0.7032988 -0.7063182 0.06028741 0.5287953 -0.8466056 0.06054282 0.5291395 -0.8463723 0.03778439 0.3301799 -0.9431616 -9.9976e-4 0.2754672 -0.96131 0.02266401 0.1073125 -0.993967 0.003893971 0.03380453 -0.9994209 0.01261323 0.109846 0.9938686 0.01227664 0.1093253 0.9939302 0.03689962 0.3254201 0.9448494 0.03793227 0.326983 0.9442686 0.0613026 0.5284425 0.8467529 0.06073629 0.5275087 0.8473758 0.08111 0.7009433 0.7085899 0.08114582 0.7009947 0.708535 0.09759759 0.8431123 0.5288066 -0.2246863 0.8876475 -0.4019926 -0.493765 0.7700312 -0.4040398 -0.803424 -0.4011341 -0.4400015 -0.8145152 -0.3930616 -0.4266939 -0.803315 -0.4319308 -0.4100257 -0.8166064 -0.3895686 -0.4258995 -0.8256225 -0.379731 -0.4173153 -0.8256226 -0.3797309 -0.4173153 -0.8336126 -0.3694125 -0.4106392 -0.8439179 -0.3511696 -0.4055647 -0.8439179 -0.3511695 -0.4055647 -0.8439179 -0.3511696 -0.4055647 -0.8409408 -0.3646455 -0.3998151 -0.8397341 -0.3708342 -0.3966466 -0.8390233 -0.3854071 -0.3840591 -0.8427852 -0.403923 -0.3557516 -0.8447282 -0.4074329 -0.3470342 -0.7499414 -0.5244829 -0.4031199 -0.7497569 -0.5245632 -0.4033586 -0.7949007 -0.4522741 -0.4044514 -0.6559252 -0.6380946 -0.4032338 -0.6549823 -0.6388826 -0.4035184 -0.7537377 -0.5187967 -0.4033975 -0.5449239 -0.7348874 -0.4037308 -0.5450271 -0.7348572 -0.4036464 -0.6559967 -0.6377556 -0.4036534 -0.2842472 -0.8697121 -0.4034904 -0.420125 -0.8128424 -0.4034628 -0.4201211 -0.8128522 -0.4034472 -0.4200824 -0.8128364 -0.4035195 -0.5446627 -0.7352246 -0.4034693 -0.10275 -0.9074487 -0.4074055 -0.1102315 -0.911109 -0.3971518 -0.1213671 -0.9137583 -0.3877061 -0.1438657 -0.9216958 -0.3602491 -0.1564967 -0.9375884 -0.3105427 -0.1378204 -0.9207465 -0.3650088 -0.1146597 -0.9038785 -0.412137 -0.1318579 -0.8967904 -0.4223512 -0.1392483 -0.8922213 -0.4295942 -0.1604807 -0.8940009 -0.41834 -0.1803022 -0.8939788 -0.4102356 -0.2016705 -0.8920305 -0.4044881 -0.2017083 -0.8919312 -0.4046882 -0.2843105 -0.8696261 -0.4036313 -0.2893259 -0.8759665 -0.3859707 -0.2077451 -0.889703 -0.4065349 -0.207745 -0.889703 -0.4065349 -0.207745 -0.889703 -0.4065349 -0.2074323 -0.8898194 -0.4064397 -0.6560847 -0.638103 -0.402961 -0.5449974 -0.7351663 -0.4031233 -0.5447887 -0.7344781 -0.404657 -0.41995 -0.8124873 -0.4043595 -0.4199739 -0.8125281 -0.4042524 -0.2841601 -0.8694982 -0.4040123 -0.7965309 -0.4490975 -0.4047841 -0.7882364 -0.4635164 -0.4047664 -0.7556595 -0.5286747 -0.3866286 -0.7483282 -0.5268691 -0.4030062 -0.6560782 -0.6380884 -0.4029948 0.05804479 0.8975755 -0.4370231 0.03383511 0.8863332 -0.4618104 0.06750494 0.905125 -0.4197523 0.005485832 0.9146066 -0.4043078 0.07444155 0.9027307 -0.4237168 0.0896756 0.9057313 -0.4142576 0.09569621 0.9063987 -0.411441 0.1083539 0.9093481 -0.4016784 0.1047536 0.9105712 -0.3998584 0.09713131 0.9136897 -0.3946347 0.08839058 0.9183579 -0.3857539 0.07978153 0.9248015 -0.3719907 0.06936299 0.9360985 -0.3448314 0.06984251 0.9353011 -0.3468917 -0.3974197 0.8234756 -0.4049022 -0.3687399 0.8510416 -0.3738436 -0.3303202 0.8531025 -0.4038621 -0.2247967 0.8871464 -0.4030356 -0.2245398 0.8870439 -0.4034045 -0.07972645 0.9115031 -0.4034921 -0.07911676 0.9114598 -0.4037101 -0.07893747 0.9115754 -0.4034837 -0.07470571 0.9120687 -0.4031744 -0.6722983 0.6200404 -0.4044316 -0.6111388 0.6810038 -0.4034146 -0.6107537 0.6810806 -0.4038678 -0.6115202 0.6801726 -0.4042381 -0.4935832 0.7700267 -0.4042705 -0.7361338 0.5410094 -0.4067136 -0.7337822 0.5508748 -0.3976188 -0.7308707 0.5605193 -0.3894178 -0.7262574 0.5856078 -0.3600192 -0.7336289 0.6041995 -0.3110172 -0.7284777 0.5804544 -0.3638583 -0.7261103 0.5504106 -0.4120826 -0.7092383 0.5634609 -0.4236662 -0.7032737 0.5666345 -0.4293386 -0.695815 0.5825583 -0.4200802 -0.6821777 0.6061965 -0.4088513 -0.6138363 0.6885143 -0.3862035 -0.6634205 0.6288884 -0.405429 -0.6680768 0.6238663 -0.4055419 -0.6106348 0.6803418 -0.4052904 -0.4935138 0.7695918 -0.4051824 -0.4939365 0.769927 -0.4040285 -0.3639363 0.8393729 -0.403737 -0.3497052 0.7261517 -0.5919544 -0.3299684 0.8536447 -0.4030033 0.009813845 0.9143298 -0.4048517 -0.01251637 0.914242 -0.4049754 -0.08020359 0.9181991 -0.3879147 -0.08191347 0.9122863 -0.401278 -0.2248778 0.8879088 -0.4013079 0.8291181 -0.3870237 -0.4034549 0.7899632 -0.4607716 -0.4045339 0.7501789 -0.5105322 -0.4202242 0.7507281 -0.4740819 -0.4600584 0.7486274 -0.4981312 -0.4375184 0.7442136 -0.5177316 -0.4220193 0.7405682 -0.5284107 -0.4151396 0.7354524 -0.5400153 -0.4092594 0.7354524 -0.5400154 -0.4092594 0.7354524 -0.5400153 -0.4092594 0.7322355 -0.5495122 -0.4023277 0.7370598 -0.5453082 -0.3992264 0.742913 -0.540695 -0.3946255 0.7510625 -0.5356159 -0.3860324 0.7620921 -0.5309571 -0.3705407 0.7745461 -0.5280998 -0.3481223 0.7753989 -0.5280917 -0.3462308 0.8804811 -0.2490563 -0.4033907 0.8803586 -0.2486181 -0.4039281 0.8288091 -0.3872002 -0.4039203 0.908894 -0.1044023 -0.4037475 0.9088966 -0.1044104 -0.4037393 0.8799962 -0.2503899 -0.4036233 0.909001 -0.1046038 -0.4034541 0.9140262 0.04260659 -0.4034115 0.9138759 0.0423724 -0.4037767 0.8940646 0.1941982 -0.403653 0.8954187 0.1884235 -0.4033881 0.8954591 0.1885613 -0.4032341 0.8413419 0.3640753 -0.3994911 0.8622288 0.3442525 -0.3715532 0.8536643 0.3505813 -0.3851624 0.8462761 0.3579648 -0.3945606 0.8360338 0.3687647 -0.4062762 0.8398028 0.3537808 -0.4117894 0.8409023 0.3477633 -0.4146613 0.8423908 0.333062 -0.4236124 0.8422107 0.3165367 -0.4364467 0.8433172 0.3260871 -0.427181 0.8638724 0.2922506 -0.4102612 0.8735282 0.2710772 -0.4043088 0.9030406 0.1871232 -0.3866557 0.8758713 0.2606282 -0.4061067 0.8758712 0.2606284 -0.4061067 0.8758712 0.2606282 -0.4061067 0.8527857 0.3297994 -0.4049556 0.9090808 0.3267822 -0.2584294 0.8749132 0.3382014 -0.3466221 0.8806467 -0.2488017 -0.4031863 0.909201 -0.1044746 -0.4030368 0.9085148 -0.1046373 -0.4045391 0.9136069 0.04267817 -0.4043526 0.9135957 0.04266339 -0.4043796 0.894962 0.1883533 -0.4044332 0.7874376 -0.4640682 -0.4056884 0.795748 -0.4496758 -0.4056809 0.8350101 -0.3900064 -0.3881407 0.8293378 -0.384122 -0.4057698 0.8795701 -0.2488809 -0.4054811 -0.7364088 0.5451089 -0.4006973 -0.7408906 0.5360522 -0.4046346 -0.7952249 0.4524128 -0.4036586 -0.7952617 0.4522764 -0.4037389 -0.8574929 0.3189429 -0.4037097 -0.857423 0.3194448 -0.403461 -0.897653 0.1773168 -0.4034575 -0.8976547 0.1772989 -0.4034615 -0.9144634 0.03120887 -0.4034633 -0.9144263 0.03100574 -0.4035631 -0.9075961 -0.115773 -0.4035667 -0.9075971 -0.1157633 -0.4035672 -0.8771488 -0.2602286 -0.4035978 -0.877258 -0.2600316 -0.4034876 -0.843183 -0.3542073 -0.40445 -0.8350514 -0.3673042 -0.4096058 0.8386209 0.3678888 -0.4017124 0.8346204 0.3738796 -0.4045034 0.7893859 0.4626269 -0.4035424 0.7896144 0.4623814 -0.4033765 0.7052969 0.5829576 -0.4033819 0.7049572 0.5832254 -0.4035883 0.6022058 0.6888249 -0.4035698 0.6022449 0.6887993 -0.4035552 0.4843724 0.7762314 -0.4035448 0.4841997 0.7762938 -0.4036317 0.3534052 0.843907 -0.4036407 0.3532194 0.8439428 -0.4037285 0.2130911 0.8897125 -0.4037374 0.2133999 0.8897112 -0.4035773 0.1154778 0.9071969 -0.4045477 0.1096547 0.9070951 -0.4063919 -0.09999513 -0.9101392 -0.4020543 -0.0937196 -0.9097188 -0.4045103 0.005749225 -0.9149438 -0.4035402 0.005788266 -0.9149346 -0.4035608 0.1524398 -0.9021636 -0.4035627 0.1524294 -0.9021714 -0.4035495 0.2951523 -0.8660368 -0.4035658 0.2951686 -0.8660255 -0.4035782 0.4302807 -0.8074491 -0.4035896 0.4301851 -0.8075286 -0.4035324 0.5543365 -0.7279244 -0.4035308 0.5544099 -0.7278442 -0.4035748 0.6638137 -0.6296713 -0.4035661 0.6636829 -0.6298895 -0.4034407 0.7283255 -0.5531711 -0.4044053 0.7334861 -0.543848 -0.4077102 6.4699e-6 0 1 5.65841e-6 0 1 2.83579e-6 0 1 -2.84796e-6 0 1 -2.86074e-6 0 1 -3.12531e-6 0 1 1.45298e-6 0 1 3.10528e-6 0 1 -1.82744e-6 0 1 -8.08216e-7 0 1 -2.94513e-6 0 1 6.19709e-6 0 1 -6.4754e-6 0 1 -6.64894e-6 0 1 6.736e-6 0 1 -5.42146e-6 0 1 5.29425e-6 0 1 -2.32709e-7 0 1 6.13732e-7 0 1 -0.05550813 -0.8726797 0.4851278 0.7682507 0.4972581 0.4031441 0.6759755 0.6168686 0.4031507 0.6760834 0.616904 0.4029155 0.5652377 0.7197672 0.4030405 0.5651156 0.7197048 0.4033228 0.4389376 0.8028916 0.4033598 0.4392663 0.8031966 0.4023934 0.3009451 0.8644316 0.4027285 0.3007057 0.8641401 0.403532 0.1047245 0.9097942 0.4016309 0.1105613 0.8958633 0.430355 0.1175915 0.8475633 0.5175026 0.0907287 0.8459546 0.5254799 0.102899 0.7420261 0.6624267 0.09516513 0.9098581 0.403859 0.09516507 0.909858 0.4038589 0.09516513 0.9098581 0.403859 0.1041588 0.9043619 0.4138605 0.09815734 0.9076372 0.4081175 0.09314024 0.9091724 0.4058701 0.1194507 0.911328 0.3939706 0.138606 0.918486 0.3703671 0.1604097 0.9363538 0.3122667 0.1829812 0.9129337 0.3647877 0.2156857 0.8886522 0.4046939 -0.7300509 0.5485269 0.4076076 -0.7284341 0.5516523 0.4062802 -0.7853387 0.5233833 0.3306254 -0.7666177 0.5268994 0.3669803 -0.7512884 0.5331822 0.3889507 -0.7445486 0.5376995 0.3956344 -0.7359161 0.5453166 0.4013195 -0.7322583 0.5491661 0.4027586 -0.7322583 0.5491661 0.4027585 -0.7322583 0.5491662 0.4027585 -0.7283955 0.5534232 0.4039342 -0.7313048 0.5447372 0.4104323 -0.7306948 0.5345801 0.4246284 -0.7059247 0.4984853 0.5031728 -0.6784031 0.5188212 0.5201862 -0.6203659 0.4371006 0.6512215 -0.825197 0.5191854 0.2224783 -0.7865533 0.5184784 0.3354316 -0.7960438 0.4507057 0.403954 -0.8364981 0.3715962 0.4027251 -0.8356251 0.3707337 0.4053238 -0.8853124 0.2279824 0.4052729 -0.8859555 0.2284345 0.4036094 -0.9113892 0.07951027 0.4037918 -0.9113022 0.07948446 0.4039933 -0.9118512 -0.07160663 0.4042276 -0.9122478 -0.07151651 0.4033477 -0.8908049 -0.2087584 0.4035924 -0.9133956 -0.2270656 0.3378605 -0.8695128 -0.282397 0.4052152 -0.7815108 -0.3502438 0.5163045 -0.614747 -0.2696549 0.7411966 -0.8102169 -0.370201 0.4544226 -0.8194362 -0.3817211 0.4275669 -0.8216204 -0.3880969 0.4175174 -0.8242673 -0.3980566 0.4026592 -0.8242673 -0.3980566 0.4026592 -0.8242673 -0.3980566 0.4026591 -0.8328177 -0.3879953 0.3948094 -0.8363559 -0.3844181 0.3908089 -0.8452229 -0.3770761 0.3786978 -0.8544072 -0.3716682 0.3631132 -0.8559675 -0.3710893 0.3600174 -0.8602782 -0.3210004 0.396081 -0.864055 -0.2986216 0.4052582 -0.06654375 -0.9106832 0.4077108 -0.1545306 -0.9017716 0.4036437 -0.1403036 -0.9222607 0.3602086 -0.1490035 -0.9135307 0.3784968 -0.1740983 -0.9006819 0.3980727 -0.1663543 -0.8972389 0.4090093 -0.1520417 -0.8872873 0.4354361 -0.16496 -0.8884641 0.4282755 -0.1488474 -0.8835787 0.4439971 -0.1513773 -0.8854154 0.4394595 -0.08808594 -0.9102014 0.4046905 -0.07348453 -0.9114842 0.4047179 -0.05622905 -0.9152073 0.3990414 -0.069754 -0.9117958 0.4046762 -0.07187175 -0.9115544 0.4048496 0.559094 -0.7249026 0.4024057 0.4323303 -0.8069757 0.4023444 0.4322855 -0.806694 0.4029569 0.2931473 -0.8668439 0.4032942 0.2931491 -0.8665304 0.4039662 0.1467751 -0.9029449 0.4039155 0.1466795 -0.9033973 0.4029373 0.03331077 -0.9143574 0.4035356 -0.003930687 -0.9600179 0.2799112 -0.02155059 -0.9407267 0.3384804 -0.04177021 -0.9229424 0.3826653 0.7025434 -0.594165 0.391664 0.7012936 -0.6271692 0.3388895 0.7033361 -0.6531047 0.2806648 0.6439821 -0.6489764 0.4051133 0.5588561 -0.7241116 0.4041563 0.7711801 -0.4952889 0.3999629 0.77118 -0.4952889 0.3999629 0.7711802 -0.4952889 0.3999629 0.7692396 -0.506623 0.389363 0.7691901 -0.5074892 0.3883316 0.7250366 -0.5573192 0.40462 0.7112204 -0.57486 0.4046005 0.6775024 -0.5584021 0.4787252 0.713256 -0.5725426 0.4043031 0.7638795 -0.5040715 0.4029889 0.7356778 -0.4988127 0.4582186 0.7494951 -0.4935387 0.4412217 0.7546848 -0.4941784 0.4315538 0.7440539 -0.4962593 0.4473371 0.8483546 0.3316307 0.4126932 0.8526061 0.341302 0.3956965 0.8523194 0.3516739 0.3871396 0.7868759 0.5241878 0.3256589 0.7999985 0.4426232 0.4050767 0.8392802 0.3638445 0.4040124 0.8648622 0.3935706 0.3116343 0.8539248 0.3663114 0.369633 0.855805 0.3241487 0.4031447 0.8420524 0.3356206 0.4222638 0.8206161 0.3385133 0.4604324 0.7206096 0.3087952 0.6207798 0.08722418 0.9104757 0.40426 0.08895105 0.9101445 0.4046292 0.003951489 0.9149819 0.4034757 0.003956377 0.91498 0.40348 -0.1468489 0.90314 0.4034523 -0.1466948 0.9031544 0.4034761 -0.1467604 0.9031294 0.4035082 0.8547097 0.3254836 0.4043909 0.8881435 0.2200632 0.4034516 0.8879346 0.2207309 0.4035469 0.9121869 0.0717653 0.4034415 0.9121664 0.07164674 0.4035088 0.9121736 0.07156962 0.4035061 0.8879366 0.2208434 0.4034811 0.7671509 -0.4920501 0.4115413 0.7723543 -0.4900816 0.4040903 0.8362708 -0.3711206 0.4036347 0.836298 -0.3710948 0.4036017 0.8859655 -0.2284207 0.4035954 0.8861073 -0.2281953 0.4034113 0.9117186 -0.07786822 0.4033682 0.9115162 -0.07952022 0.4035032 0.9115158 -0.07954084 0.4035 0.9110438 -0.08636498 0.403163 -0.1549514 -0.9087657 0.3874726 -0.1690797 -0.8990746 0.4038282 -0.3007004 -0.8641967 0.4034146 -0.3011273 -0.8638783 0.403778 -0.43884 -0.8027392 0.4037688 -0.5648552 -0.7197622 0.4035852 -0.5650352 -0.7195119 0.4037796 -0.5671086 -0.7180235 0.4035222 -0.4386898 -0.8029043 0.4036039 -0.8223001 -0.3971568 0.4075403 -0.8220273 -0.4009991 0.4043151 -0.7680575 -0.4973571 0.4033902 -0.7681315 -0.4970992 0.4035671 -0.6764139 -0.6160867 0.4036105 -0.6759015 -0.6167615 0.4034383 -0.6755975 -0.616967 0.4036333 -0.5664343 -0.7183798 0.4038349 -0.7246672 0.5578182 0.4045941 -0.6703982 0.622738 0.40344 -0.6705051 0.6225746 0.4035145 -0.6704102 0.6226511 0.403554 -0.5589099 0.7244047 0.4035561 -0.5588203 0.7244912 0.4035249 -0.5589064 0.7244544 0.4034718 -0.5587798 0.7245281 0.4035147 -0.4319857 0.8065772 0.4035116 -0.4319842 0.8065846 0.4034985 -0.2933627 0.866675 0.4035006 -0.2933436 0.8666754 0.4035136 -0.1467567 0.9031254 0.4035184 6.29094e-7 0 1 2.52707e-6 0 1 8.5728e-6 0 1 -3.84618e-6 0 1 -6.32687e-6 0 1 2.22104e-6 0 1 7.62242e-6 0 1 -3.45913e-6 0 1 -3.12086e-6 0 1 1.25121e-6 0 1 -1.90024e-6 0 1 3.03045e-7 0 1 3.40608e-6 0 1 8.69384e-6 0 1 6.15764e-6 0 1 -2.14854e-6 0 1 -9.08073e-6 0 1 1.21265e-5 0 1 -2.20264e-6 0 1 -1.73025e-6 0 1 -1.61417e-5 0 1 1.13082e-6 0 1 3.39916e-6 0 1 -1.37058e-6 0 1 4.18639e-6 0 1 -4.79393e-6 0 1 -7.4387e-7 0 1 -1.56606e-6 0 1 -6.14885e-6 0 1 9.05272e-6 0 1 3.19032e-6 0 1 7.57044e-7 0 1 -3.05537e-6 0 1 1.63433e-5 0 1 -2.84631e-6 0 1 3.49413e-6 0 1 -9.09223e-6 0 1 9.35104e-6 0 1 -4.30219e-6 0 1 2.01081e-6 0 1 -3.20357e-6 0 1 -1.89288e-6 0 1 3.92761e-6 0 1 2.96002e-6 0 1 -8.37061e-7 0 1 -1.94691e-6 0 1 -9.59619e-6 0 1 -1.61547e-6 0 1 1.09151e-6 0 1 1.14497e-6 0 1 -1.70666e-6 0 1 -1.21333e-6 0 1 -1.07021e-6 0 1 1.76741e-6 0 1 -2.70352e-6 0 1 1.46023e-6 0 1 -1.91953e-5 0 1 2.66786e-6 0 1 -2.97941e-6 0 1 2.60024e-6 0 1 1.62519e-5 0 1 -1.35631e-6 0 1 3.37728e-6 0 1 1.06067e-5 0 1 8.43865e-7 0 1 -2.60173e-6 0 1 2.38914e-6 0 1 4.61418e-7 0 1 2.10155e-6 0 1 -1.82765e-6 0 1 4.3631e-6 0 1 -1.28183e-6 0 1 1.45339e-6 0 1 3.56789e-5 0 1 -1.62841e-6 0 1 -4.41287e-6 0 1 1.69145e-5 0 1 -2.89519e-5 0 1 -3.89837e-7 0 1 -1.70726e-6 0 1 4.52474e-6 0 1 -1.54842e-6 0 1 -4.89033e-6 0 1 7.54262e-6 0 1 -4.79089e-7 0 1 0 0 1 2.96376e-6 0 1 -1.57322e-6 0 1 -2.9568e-6 0 1 1.43766e-6 0 1 1.31834e-6 0 1 2.10766e-6 0 1 -2.98562e-6 0 1 7.92477e-7 0 1 -2.67202e-6 0 1 -3.2089e-6 0 1 8.20608e-7 0 1 2.96951e-6 0 1 3.57058e-6 0 1 1.5977e-5 0 1 -2.8925e-6 0 1 2.97607e-6 0 1 -2.23454e-6 0 1 5.40891e-6 0 1 1.26604e-6 0 1 5.63357e-7 0 1 2.24694e-6 0 1 7.52124e-7 0 1 1.14012e-6 0 1 -2.00075e-6 0 1 3.3368e-6 0 1 6.18108e-6 0 1 7.6476e-6 0 1 -2.33554e-7 0 1 -1.31333e-6 0 1 3.25835e-6 0 1 1.11883e-6 0 1 3.6956e-6 0 1 -3.07186e-6 0 1 -5.88945e-7 0 1 9.06546e-7 0 1 -3.04601e-6 0 1 -1.98972e-6 0 1 8.80827e-7 0 1 6.98293e-7 0 1 -3.77632e-6 0 1 9.59335e-7 0 1 -1.0724e-6 0 1 -2.4572e-6 0 1 2.46073e-5 0 1 -4.18718e-6 0 1 2.14011e-6 0 1 -5.63579e-6 0 1 1.70631e-7 0 1 1.25422e-6 0 1 7.09876e-7 0 1 -2.99178e-7 0 1 6.79172e-6 0 1 -3.24117e-6 0 1 -5.50544e-7 0 1 -3.34833e-6 0 1 1.164e-6 0 1 2.1883e-6 0 1 -8.82606e-7 0 1 -1.4699e-5 0 1 8.85771e-7 0 1 -2.7571e-6 0 1 -9.86291e-6 0 1 6.87947e-5 0 1 -2.34063e-6 0 1 -1.64149e-7 0 1 -1.44788e-6 0 1 1.28153e-5 0 1 4.50847e-6 0 1 -1.62779e-6 0 1 2.05373e-6 0 1 2.63595e-6 0 1 0.9865263 -0.163603 0 0.971617 -0.2350051 -0.02707457 0.8763532 0.4805817 -0.03234726 0.9176748 0.3973325 0 0.9912955 0.131656 0 0.9736966 0.2193377 -0.06169253 0.9992392 0.03900361 0 0.6437504 0.7646391 -0.03020679 0.7113795 0.7028081 0 0.8280243 0.5606921 0 -0.1447722 -0.9894649 5.76836e-4 -0.1547471 -0.9879542 0 -0.4919326 -0.8706334 0 -0.4919145 -0.8706436 0 -0.7738095 -0.6334186 0 -0.7737888 -0.6334438 0 -0.950318 -0.3112808 0 -0.9503054 -0.3113193 0 -0.9985771 0.05332839 0 -0.9985748 0.05337071 0 -0.9121885 0.409771 0 -0.9119663 0.4102652 2.1115e-4 -0.9116796 0.410902 0 -0.7027487 0.7114382 0 -0.7027276 0.7114591 0 -0.3977206 0.9175066 0 -0.3977355 0.9175002 0 -0.03914338 0.9992336 0 -0.03914505 0.9992336 0 0.3056609 0.9521405 0 0.3243741 0.9458667 -0.01085019 0.4801892 0.8771651 0 0.5702397 0.8214783 0 0.9398811 -0.341502 0 0.8206637 -0.5714116 0 0.8206632 -0.5714122 0 0.5597127 -0.8286868 0 0.2220085 -0.9750448 0 0.2219997 -0.9750468 0 -0.1437667 -0.9896117 0 -0.5486769 0.8359866 0.008957982 -0.4709948 0.8820179 -0.01443296 -0.5470984 0.8370205 0.008942484 -0.6050948 0.7959605 -0.01752972 -0.6410049 0.7675113 0.006266534 -0.7261825 0.6874268 -0.01017516 -0.7236212 0.690158 -0.007372975 -0.6353431 0.7722046 0.006262481 -0.826308 0.5629138 -0.01852697 -0.7974792 0.603321 0.005541801 -0.7961105 0.6051257 0.005567014 -0.7961105 0.6051257 0.005567073 -0.7961105 0.6051257 0.005567073 -0.9615021 0.2747871 0.002438127 -0.9615021 0.274787 0.002438008 -0.9615021 0.274787 0.002437949 -0.9129013 0.408175 -0.002097427 -0.9058012 0.4234918 -0.01337552 -0.8630598 0.5050472 0.007432937 -0.8607991 0.508891 0.007426142 -0.9537592 0.3005622 0.002445161 -0.9621637 0.2720386 -0.01536548 -0.9815607 0.1909418 0.008942186 -0.9817712 0.1898564 0.008942484 -0.9933668 0.1137019 -0.01715731 -0.9970496 0.07668888 0.003319442 -0.9988617 -0.04623049 -0.01175189 -0.9993042 -0.03693127 -0.005236208 -0.9976752 0.06806695 0.003320097 -0.9648877 -0.2625386 0.008077383 -0.9643222 -0.2646084 0.008073568 -0.9783438 -0.2061883 -0.01816719 -0.9886991 -0.1497076 0.007861733 -0.9878672 -0.1551023 0.007854282 -0.9282569 -0.3716644 -0.01431119 -0.9326258 -0.3608152 -0.00466305 -0.8874994 -0.4608025 0.002476871 -0.8798503 -0.4752446 0.002468943 -0.8631623 -0.5046529 -0.01662248 -0.8196389 -0.572801 0.009549558 -0.8207236 -0.5712457 0.009557783 -0.770065 -0.6377614 -0.01613372 -0.7496253 -0.6618586 0.002278506 -0.7511462 -0.660132 0.002288281 -0.6586754 -0.7524168 -0.003960907 -0.6690675 -0.7430347 -0.01575034 -0.5290255 -0.8484198 -0.01777291 -0.5799911 -0.8145834 0.008013665 -0.5811592 -0.8137506 0.00800848 -0.2746606 -0.9615305 0.004556894 -0.3804759 -0.9247694 -0.006308436 -0.3861841 -0.9223583 -0.01082873 -0.4880116 -0.8728054 0.007445573 -0.4828008 -0.8756985 0.007462024 -0.2722487 -0.962216 0.004586577 -0.2322055 -0.972509 -0.0175212 -0.1623757 -0.9866979 0.007849752 -0.1617658 -0.9867981 0.007829904 -0.07496625 -0.9970552 -0.01616168 -0.0469551 -0.9988964 0.001124382 -0.06624877 -0.9978026 0.001106381 0.08738553 -0.9961735 -0.001473486 0.06684809 -0.9975746 -0.01939964 0.2448419 -0.9694023 -0.0176534 0.1801557 -0.9836053 0.008044898 0.1792859 -0.983764 0.008065462 0.4979123 -0.8672033 0.006471395 0.3979453 -0.917374 -0.008042871 0.3970575 -0.917752 -0.008761644 0.2904877 -0.9568602 0.005957901 0.2901953 -0.9569488 0.005981326 0.5004178 -0.8657598 0.006497979 0.5404197 -0.8412224 -0.01707226 0.5949521 -0.8037146 0.008653938 0.5963636 -0.8026673 0.008696377 0.6678568 -0.744164 -0.01369017 0.6829527 -0.7304624 -5.23848e-4 0.7784513 -0.6275153 -0.01543068 0.761828 -0.6477791 7.16829e-4 0.7398964 -0.6727205 7.46287e-4 0.7398961 -0.6727209 7.46439e-4 0.7398968 -0.6727201 7.46308e-4 0.8690243 -0.4944512 -0.01774042 0.8296276 -0.5582456 0.008938431 0.830805 -0.556492 0.008933603 0.9689103 -0.247321 0.006735742 0.9351899 -0.353963 -0.01141196 0.937224 -0.3486601 -0.006874799 0.8873915 -0.4609898 0.004972755 0.8893516 -0.4571972 0.004980802 0.9692629 -0.2459351 0.006741762 0.9808946 -0.1936726 -0.01835 0.9911995 -0.1321431 0.007861614 0.9912455 -0.131798 0.007859051 0.999349 -0.0336883 -0.01291298 0.9998077 -0.01935315 -0.003164529 0.9918727 0.1261169 -0.01682627 0.9956163 0.09350329 0.002312898 0.9957459 0.09211319 0.002312481 0.9584111 0.2848746 -0.01716572 0.9784958 0.2060634 0.009156107 0.977804 0.2093216 0.009159266 0.8533958 0.5212023 0.007999062 0.9053287 0.4245025 -0.01332795 0.9013038 0.4331536 -0.005454778 0.9468992 0.3215212 0.002452075 0.9480829 0.3180139 0.002459645 0.8517793 0.5238398 0.007996141 0.819238 0.5731759 -0.01784986 0.7853481 0.6190031 0.007983863 0.786997 0.6169056 0.007965803 0.7163296 0.6976751 -0.01101714 0.7106211 0.7035564 -0.005119204 0.5948963 0.8036087 -0.01765114 0.6261586 0.7796856 0.003984272 0.6281553 0.7780779 0.003974258 0.4595998 0.8879856 -0.01580131 0.5306865 0.8475305 0.007993817 0.5326246 0.8463136 0.008030891 0.2205547 0.9753412 0.008082926 0.3272513 0.9447835 -0.01705396 0.3109754 0.9504153 -0.002280533 0.4189333 0.9080158 0.001464605 0.4338153 0.9010007 0.001468777 0.21719 0.976096 0.008068919 0.1536339 0.9879626 -0.01807492 0.1051746 0.9944379 0.005631268 -0.006241261 0.9999468 -0.008215427 -0.008800685 0.9999098 -0.01016134 0.09951412 0.9950203 0.00563097 -0.1662032 0.9859381 -0.01739674 -0.1243005 0.9922342 0.004539132 -0.1179459 0.9930097 0.004528105 -0.450743 0.8926538 0 -0.3435647 0.939129 0 -0.3221839 0.9465695 -0.01428031 -0.2354586 0.9718413 0.00915426 -0.2361904 0.9716637 0.009160697 -4.29812e-6 0 1 -1.60839e-6 0 1 -1.08707e-6 0 1 3.03302e-6 0 1 6.13301e-6 0 1 -8.64846e-6 0 1 6.01323e-6 0 1 3.73072e-6 0 1 4.28758e-6 0 1 -6.124e-6 0 1 2.14836e-6 0 1 6.11471e-6 0 1 -6.10359e-6 0 1 1.47608e-6 0 1 6.13346e-6 0 1 5.38162e-7 0 1 -6.45106e-6 0 1 -6.13196e-6 0 1 4.31734e-6 0 1 4.35176e-6 0 1 6.06105e-6 0 1 6.13738e-6 0 1 -2.15733e-6 0 1 3.04938e-6 0 1 -6.12235e-6 0 1 8.68674e-6 0 1 1.21242e-5 0 1 -6.10352e-6 0 1 -5.89762e-6 0 1 -3.4488e-6 0 1 -2.25958e-6 0 1 1.52517e-6 0 1 -5.8972e-6 0 1 3.03236e-6 0 1 -4.5544e-6 0 1 -2.2996e-6 0 1 3.05146e-6 0 1 -8.76609e-6 0 1 1.03055e-5 0 1 -6.13663e-6 0 1 -0.5386754 0.8202193 0.1925337 -0.5363633 0.820685 0.1969532 -0.6269977 0.7537592 0.1967763 -0.6293645 0.753592 0.1897359 -0.6231814 0.7575463 0.1943419 -0.7098906 0.6768757 0.1946657 -0.709737 0.6769134 0.1950942 -0.780997 0.5933543 0.19487 -0.7822672 0.591017 0.196868 -0.7816702 0.5912753 0.1984577 -0.8438977 0.4983958 0.1985908 -0.8434851 0.4985125 0.2000453 -0.8465686 0.4954603 0.1945267 -0.8959414 0.3993697 0.1944039 -0.8948246 0.4000169 0.1981801 -0.9424578 0.269545 0.1977846 -0.9355555 0.2956125 0.1932597 -0.9362369 0.2950438 0.1908133 -0.9635135 0.187429 0.1910814 -0.9633377 0.1860979 0.1932563 -0.9632471 0.1862338 0.1935771 -0.9781935 0.07518953 0.1936084 -0.9778959 0.07466238 0.1953078 -0.9790968 0.06725186 0.1919547 -0.98061 -0.03814721 0.1922206 -0.9793797 -0.03632408 0.1987358 -0.9683261 -0.1520844 0.198028 -0.9699276 -0.1477422 0.1934238 -0.9696112 -0.1468181 0.1957002 -0.9458793 -0.2590488 0.1954641 -0.9460688 -0.2595568 0.1938669 -0.9462221 -0.2573465 0.1960526 -0.9462221 -0.2573465 0.1960526 -0.9462221 -0.2573464 0.1960526 -0.9107859 -0.3632652 0.1962334 -0.9111405 -0.3648036 0.191681 -0.8710243 -0.4521287 0.192085 -0.862822 -0.4653089 0.1975499 -0.862926 -0.4661224 0.1951636 -0.8043638 -0.5611351 0.1952599 -0.8043542 -0.5621063 0.1924868 -0.8048839 -0.5601922 0.1958229 -0.735125 -0.6490292 0.1958377 -0.7356698 -0.6489133 0.1941689 -0.7366977 -0.6475647 0.1947732 -0.6561332 -0.729207 0.1942842 -0.656227 -0.7287524 0.1956683 -0.5699182 -0.7980148 0.1958718 -0.5692083 -0.7982978 0.1967806 -0.5688792 -0.7989347 0.1951408 -0.4743742 -0.8583697 0.195373 -0.4738456 -0.8594475 0.1918868 -0.4783284 -0.8557687 0.1971341 -0.3733549 -0.906442 0.197406 -0.3730906 -0.9068152 0.1961879 -0.2693079 -0.9428732 0.1961208 -0.2674797 -0.9431516 0.197281 -0.2670131 -0.9436812 0.1953713 -0.1578485 -0.9678282 0.1959397 -0.1590538 -0.9666429 0.200757 -0.1585247 -0.9668738 0.2000627 -0.04601472 -0.9788436 0.1993691 -0.04696881 -0.9794462 0.1961605 -0.06512689 -0.9780907 0.1977301 0.06415933 -0.9780115 0.1984371 0.06560122 -0.9789152 0.1934462 0.1758798 -0.9651753 0.1936566 0.1756565 -0.9652817 0.193329 0.1768392 -0.9655526 0.1908829 0.2868538 -0.9387529 0.1909398 0.2844312 -0.9379663 0.1982879 0.2847275 -0.937914 0.1981102 0.38902 -0.8996288 0.1983219 0.390354 -0.8999128 0.1943728 0.4886083 -0.8505107 0.1946626 0.4898915 -0.8494853 0.1959112 0.4909747 -0.849488 0.1931686 0.58366 -0.7885869 0.1935765 0.5837502 -0.7885813 0.1933274 0.5853744 -0.7878972 0.1911936 0.5853744 -0.7878971 0.1911936 0.5853743 -0.7878971 0.1911936 0.6711291 -0.7163475 0.1908717 0.6698857 -0.7165099 0.194594 0.7256646 -0.6598877 0.1948308 0.7256652 -0.6598871 0.194831 0.7256643 -0.659888 0.1948309 0.7464721 -0.6354016 0.1975961 0.7470342 -0.6352317 0.1960117 0.8148009 -0.5457853 0.1954939 0.814442 -0.5469915 0.1936092 0.8136224 -0.5475768 0.1953931 0.8723056 -0.4484054 0.1949757 0.872331 -0.4482454 0.19523 0.8698011 -0.4521169 0.1975767 0.8698011 -0.4521168 0.1975767 0.9165655 -0.3479222 0.1971242 0.9174448 -0.3472515 0.1941948 0.950457 -0.2426596 0.1942878 0.9505642 -0.2411187 0.1956771 0.95056 -0.2411313 0.1956816 0.9719856 -0.1303913 0.195556 0.9726577 -0.1296774 0.1926671 0.9727482 -0.129585 0.192272 0.981117 -0.01902234 0.1924777 0.9811874 -0.01904588 0.1921162 0.9771925 0.09072262 0.1920009 0.9767319 0.09382438 0.1928521 0.9755222 0.09165483 0.1998899 0.9582505 0.2050093 0.1993169 0.9592825 0.2033321 0.1960437 0.9590868 0.2019072 0.1984588 0.929259 0.3116883 0.1983138 0.9299269 0.3111278 0.1960501 0.9288228 0.3153061 0.194603 0.8887655 0.4148095 0.1950103 0.88908 0.4168877 0.1890544 0.8380714 0.5117575 0.1890522 0.8350242 0.5149867 0.1937091 0.8351637 0.5135915 0.1967878 0.7708112 0.6058082 0.1970959 0.7706292 0.6074787 0.1926145 0.7719501 0.6050281 0.1950236 0.697858 0.6891956 0.1949449 0.6976245 0.6907312 0.1902906 0.6165015 0.7640137 0.1902868 0.6132757 0.7661663 0.1920472 0.6139266 0.7643908 0.1969798 0.5224275 0.8296238 0.1969619 0.5223476 0.8299536 0.1957804 0.5207381 0.8317611 0.1923681 0.425756 0.8842409 0.1919631 0.4246615 0.884087 0.1950715 0.4108387 0.8911595 0.1924741 0.3212217 0.9272127 0.1925968 0.3211737 0.927233 0.1925786 0.2164371 0.9571172 0.1925662 0.2136385 0.957041 0.1960389 0.2130494 0.9574968 0.1944475 0.1026012 0.975547 0.1943739 0.1031259 0.9750585 0.1965349 0.09766131 0.976513 0.192054 -0.00868231 0.9812936 0.1923214 -0.008637249 0.9812729 0.1924287 -0.1157904 0.974432 0.1925483 -0.121627 0.9729754 0.1962796 -0.121895 0.9730876 0.1955563 -0.2308806 0.9530993 0.1956937 -0.2317578 0.9534163 0.1930952 -0.231002 0.9533738 0.1942076 -0.3371807 0.9211608 0.1943503 -0.3369983 0.9211115 0.1948994 -0.4414008 0.8759056 0.19482 -0.4423652 0.8760259 0.192072 -0.538596 0.8203797 0.1920718 -0.1958407 0.80835 0.5551728 -0.1967216 0.8094643 0.5532343 -0.1032964 0.826413 0.5535084 -0.1017005 0.8240913 0.5572527 -0.007347345 0.8302863 0.5572889 -0.00749576 0.8305361 0.5569146 0.08685147 0.8257933 0.5572453 0.08678424 0.8258772 0.5571314 0.1809396 0.8105416 0.5570307 0.1811422 0.8098961 0.5579032 0.2716441 0.7841193 0.5580023 0.2712563 0.7868126 0.5543882 0.3603503 0.7502362 0.5543405 0.3603134 0.7506933 0.5537453 0.443867 0.7048265 0.553355 0.4436531 0.7030341 0.5558013 0.5195785 0.6490758 0.5556429 0.518932 0.6460067 0.5598081 0.5895114 0.5822309 0.5598959 0.590984 0.5864402 0.5539187 0.6544492 0.5144551 0.554105 0.6537384 0.512788 0.5564841 0.7068653 0.4359123 0.5570656 0.7067213 0.4357002 0.557414 0.7522037 0.3511493 0.5575695 0.7525691 0.3515878 0.5567996 0.7876059 0.2635401 0.5569773 0.7899245 0.2657934 0.5526059 0.8154202 0.1728298 0.552467 0.8157131 0.1730799 0.5519562 0.8300663 0.07978773 0.5519276 0.8268228 0.07775443 0.5570622 0.8305709 -0.01624608 0.5566759 0.8329294 -0.01497083 0.5531768 0.825496 -0.110809 0.5534237 0.8249185 -0.1109763 0.5542507 0.8069368 -0.2046459 0.5540515 0.8075629 -0.2045482 0.5531747 0.7785136 -0.2954854 0.5537192 0.7784613 -0.2954568 0.5538081 0.7406051 -0.3805859 0.5537675 0.7386947 -0.3806422 0.5562748 0.6899373 -0.4633691 0.5561255 0.6916739 -0.463613 0.55376 0.6341022 -0.5396931 0.5537562 0.6345837 -0.5398496 0.5530517 0.5694503 -0.6078302 0.5534156 0.5684511 -0.607408 0.5549045 0.4947987 -0.668571 0.555146 0.4946011 -0.6684788 0.5554331 0.4152708 -0.7200891 0.5558974 0.4143576 -0.7195401 0.557288 0.3295411 -0.762038 0.5574056 0.3316068 -0.7638269 0.5537198 0.2433687 -0.7964042 0.5536354 0.2412504 -0.7942277 0.5576743 0.1485678 -0.8164012 0.5580474 0.1498401 -0.8181024 0.5552085 0.05445742 -0.83004 0.5550387 0.05567342 -0.832147 0.5517537 -0.03993672 -0.8327882 0.5521495 -0.04052495 -0.8314316 0.5541474 -0.1339855 -0.8215625 0.5541509 -0.1336269 -0.8228087 0.5523856 -0.2274035 -0.8018587 0.552549 -0.2279595 -0.7993806 0.5559003 -0.2279594 -0.7993807 0.5559003 -0.2279595 -0.7993807 0.5559003 -0.316433 -0.7682488 0.5564747 -0.3163709 -0.7691733 0.5552314 -0.4022034 -0.7277927 0.555473 -0.4022366 -0.7294525 0.5532674 -0.4835815 -0.6782175 0.5533263 -0.4834835 -0.6771296 0.5547426 -0.5562737 -0.6183164 0.5551976 -0.556056 -0.6174756 0.5563502 -0.6231164 -0.5496582 0.5564187 -0.6241234 -0.5521019 0.5528594 -0.6833278 -0.4767066 0.5530045 -0.6827584 -0.475698 0.5545741 -0.7323092 -0.3948878 0.5547854 -0.7320261 -0.394498 0.555436 -0.7721883 -0.3079742 0.5557672 -0.7733554 -0.3093674 0.5533655 -0.8032101 -0.2199571 0.5535995 -0.8019084 -0.2188819 0.555908 -0.8217834 -0.1251635 0.5558832 -0.8227757 -0.125863 0.5542553 -0.8319792 -0.03238201 0.5538611 -0.8303104 -0.0314871 0.5564112 -0.82837 0.06326681 0.5565972 -0.8291009 0.06291323 0.5555481 -0.8162395 0.1576606 0.5557845 -0.817075 0.1574354 0.5546194 -0.7935044 0.250711 0.5545222 -0.7939875 0.2506575 0.5538547 -0.7606759 0.3391119 0.553512 -0.7592993 0.3391266 0.5553898 -0.7159671 0.4228367 0.555518 -0.7168453 0.4228887 0.5543447 -0.6640828 0.5017358 0.5543061 -0.6639433 0.5017284 0.5544798 -0.6022961 0.5743313 0.5544214 -0.6030504 0.5745441 0.55338 -0.5326522 0.6403828 0.5533457 -0.5342095 0.6409923 0.5511344 -0.4580388 0.6974508 0.5511469 -0.4562813 0.6963784 0.5539536 -0.3746446 0.7434145 0.5540546 -0.3723469 0.7416739 0.5579227 -0.2852978 0.7794537 0.557725 -0.2868251 0.7808584 0.55497 -0.1315122 0.5411124 0.8306034 -0.1305258 0.5395929 0.8317466 -0.06802213 0.5511785 0.8316101 -0.06936448 0.5538747 0.8297057 -0.005035161 0.5580697 0.8297787 -0.005165219 0.5583976 0.8295574 0.05836516 0.555447 0.8295012 0.05876451 0.553622 0.8306922 0.1215258 0.5433793 0.8306446 0.1212172 0.5459417 0.829008 0.1822996 0.5287911 0.8289432 0.1822848 0.5252721 0.8311808 0.2405192 0.5010839 0.8313035 0.2404319 0.5003722 0.8317574 0.2963342 0.4695192 0.8317078 0.2972053 0.4732714 0.8292667 0.3499389 0.435659 0.8293033 0.3500843 0.4360155 0.8290545 0.3969371 0.3939389 0.8290073 0.3948972 0.3897681 0.8319478 0.4364995 0.3424019 0.8320031 0.4383532 0.345318 0.8298205 0.4750317 0.292869 0.8298027 0.4739683 0.2915798 0.8308642 0.5043853 0.2356446 0.8307029 0.5054977 0.2367395 0.8297147 0.5290153 0.1780104 0.829732 0.5258862 0.1756398 0.8322227 0.5422804 0.1150692 0.8322808 0.542198 0.1150078 0.8323429 0.5519729 0.05187165 0.8322472 0.5562918 0.05388367 0.8292383 0.5584393 -0.01009732 0.8294839 0.55465 -0.01127892 0.8320073 0.5498394 -0.07399344 0.8319866 0.5497776 -0.07394969 0.8320313 0.5376385 -0.136214 0.8321001 0.5398687 -0.1359279 0.8307018 0.5207543 -0.1976696 0.8305069 0.5216395 -0.1977241 0.8299383 0.4958015 -0.2554243 0.8300238 0.4938918 -0.255172 0.831239 0.4618086 -0.3095659 0.8312051 0.4641891 -0.3101382 0.8296642 0.4251999 -0.3617483 0.8296646 0.4244261 -0.3614319 0.8301985 0.3810447 -0.4071921 0.8300601 0.3776641 -0.4053652 0.8324956 0.3296707 -0.4455621 0.8323411 0.3330569 -0.4478331 0.8297702 0.2785569 -0.4836918 0.8297279 0.279556 -0.4846014 0.8288607 0.2228268 -0.5131822 0.82885 0.2210204 -0.5112375 0.8305337 0.1617881 -0.5326666 0.8307173 0.1617467 -0.5325717 0.830786 0.100304 -0.5476366 0.8306825 0.09989237 -0.5468453 0.8312532 0.03711062 -0.5547158 0.8312119 0.03703975 -0.5545186 0.8313466 -0.02707076 -0.5554081 0.8311372 -0.02683287 -0.5561862 0.8306245 -0.08928316 -0.5497747 0.8305277 -0.08962041 -0.5479868 0.8316723 -0.1522243 -0.533836 0.8317734 -0.151991 -0.5376296 0.8293692 -0.2125622 -0.5168544 0.829264 -0.2124252 -0.5145576 0.8307263 -0.268868 -0.4875322 0.8306758 -0.2687878 -0.4871199 0.8309438 -0.3233543 -0.4528559 0.8308812 -0.3236293 -0.4539261 0.8301899 -0.3730615 -0.4143208 0.8301588 -0.3722267 -0.4122828 0.8315469 -0.4162178 -0.3681822 0.8313873 -0.4169189 -0.36947 0.8304641 -0.4569886 -0.3183681 0.830544 -0.4560188 -0.317071 0.8315725 -0.488816 -0.2634363 0.8316611 -0.4908085 -0.2655208 0.8298228 -0.5181449 -0.2073001 0.8297907 -0.5163593 -0.2056815 0.8313051 -0.5364894 -0.1464261 0.8311069 -0.5367421 -0.146569 0.8309185 -0.5500072 -0.08414489 0.8309103 -0.5507962 -0.08456492 0.8303448 -0.5567711 -0.02114534 0.8303968 -0.5554967 -0.02060431 0.8312634 -0.5541604 0.04208171 0.8313456 -0.553855 0.04212379 0.8315469 -0.545538 0.1051387 0.831465 -0.5459002 0.1050356 0.8312404 -0.5301263 0.1673707 0.831236 -0.5318769 0.1673072 0.8301297 -0.509052 0.2273931 0.8301557 -0.5096486 0.22743 0.8297794 -0.4807825 0.2836216 0.8297029 -0.4789158 0.2832312 0.8309151 -0.444028 0.335484 0.8308367 -0.4438607 0.3355076 0.8309167 -0.4028424 0.3838574 0.830886 -0.4018493 0.383327 0.8316115 -0.3556045 0.4267255 0.8315352 -0.3538542 0.4256224 0.8328461 -0.3033954 0.4631036 0.8327583 -0.3044446 0.4638334 0.8319689 -0.248906 0.4958429 0.831977 -0.2510327 0.4978872 0.8301151 -0.1921712 0.5232101 0.8302539 -0.1917648 0.5227081 0.8306639 -0.04595559 0.1900164 0.9807049 -0.04620367 0.1904216 0.9806146 -0.02433729 0.1943834 0.9806237 -0.02381461 0.19319 0.9808724 -0.001802027 0.1947646 0.9808483 -0.001866161 0.1949917 0.9808032 0.02058988 0.1939483 0.9807956 0.02056419 0.1940692 0.9807723 0.04228961 0.1904708 0.9807816 0.04235947 0.1894784 0.9809707 0.06366306 0.1834572 0.9809641 0.06367176 0.183963 0.9808688 0.08435273 0.1755313 0.9808535 0.08441692 0.175918 0.9807786 0.1037673 0.1652231 0.9807822 0.103628 0.1647543 0.9808758 0.1218754 0.151786 0.9808709 0.1217356 0.1515457 0.9809253 0.1383851 0.1365526 0.9809195 0.1391622 0.1380511 0.9805997 0.1540214 0.1213241 0.9805906 0.1529492 0.119834 0.9809417 0.165541 0.1018482 0.9809298 0.1657086 0.1020277 0.9808828 0.1762744 0.08254098 0.9808743 0.1766486 0.08291578 0.9807754 0.1851481 0.06182783 0.9807637 0.1858369 0.06231254 0.9806029 0.1917362 0.04068279 0.980603 0.1912328 0.0404281 0.9807119 0.1945886 0.01883882 0.9807041 0.1941439 0.01867711 0.9807953 0.1950671 -0.003987312 0.9807818 0.1957791 -0.003748536 0.9806409 0.1940829 -0.02612149 0.9806373 0.1936796 -0.02616775 0.9807158 0.1895434 -0.04774296 0.980711 0.18919 -0.04775518 0.9807786 0.1824526 -0.06914526 0.9807803 0.1823462 -0.06912606 0.9808015 0.1733545 -0.08955067 0.9807798 0.1729939 -0.08948653 0.9808493 0.1619564 -0.1082155 0.9808464 0.1609206 -0.1078905 0.9810526 0.1475309 -0.125616 0.9810481 0.1483232 -0.1259777 0.9808822 0.1326775 -0.1423948 0.9808774 0.1335662 -0.1429243 0.9806797 0.1167791 -0.1570183 0.9806671 0.1162683 -0.1566424 0.9807878 0.09749561 -0.1689593 0.9807892 0.09722566 -0.1687132 0.9808584 0.07728046 -0.1787259 0.9808592 0.07797175 -0.1795604 0.9806522 0.05688226 -0.1873776 0.9806396 0.05633115 -0.1864909 0.9808405 0.03500819 -0.1916705 0.9808348 0.0350731 -0.1917331 0.9808202 0.01299113 -0.1945646 0.9808037 0.01308321 -0.1947699 0.9807617 -0.009402155 -0.1949359 0.980771 -0.009338319 -0.195161 0.9807268 -0.03153955 -0.1928269 0.9807258 -0.0316621 -0.1918225 0.9809189 -0.05291092 -0.1871711 0.9809014 -0.05289947 -0.1873996 0.9808584 -0.07432496 -0.1800031 0.9808542 -0.07436627 -0.1805048 0.9807588 -0.09432989 -0.1709486 0.980754 -0.09412181 -0.1700337 0.9809331 -0.1128162 -0.1582101 0.9809395 -0.1128247 -0.158242 0.9809334 -0.1302585 -0.144307 0.9809221 -0.1307826 -0.1454037 0.9806904 -0.1462796 -0.1296195 0.9807146 -0.1455632 -0.1284983 0.9809687 -0.1594453 -0.1108515 0.9809635 -0.160403 -0.1120444 0.9806717 -0.1720502 -0.09308999 0.9806799 -0.1713235 -0.09235823 0.9808763 -0.1808365 -0.07204359 0.980871 -0.1815561 -0.07263362 0.9806945 -0.1886065 -0.05149137 0.980702 -0.1878579 -0.0510798 0.9808671 -0.1924911 -0.0295692 0.9808531 -0.1933711 -0.02997875 0.9806677 -0.19546 -0.007236421 0.9806851 -0.1950085 -0.007097065 0.9807759 -0.1946116 0.01479566 0.9807689 -0.194096 0.01490384 0.9808694 -0.1911577 0.03677517 0.9808701 -0.1907218 0.03681159 0.9809538 -0.1853036 0.05828404 0.9809514 -0.1860429 0.05828791 0.9808112 -0.1779707 0.07941722 0.9808259 -0.178304 0.07946449 0.9807615 -0.1680719 0.09938997 0.9807515 -0.16754 0.09925568 0.9808561 -0.155288 0.1173952 0.980869 -0.1554777 0.1174504 0.9808324 -0.1410331 0.1345264 0.9808223 -0.1415203 0.134777 0.9807177 -0.1248977 0.150252 0.9807268 -0.1246972 0.1501013 0.9807754 -0.1070862 0.1631728 0.9807687 -0.1072407 0.1633095 0.9807291 -0.08798778 0.1745239 0.9807139 -0.08805799 0.174625 0.9806895 -0.06737124 0.1836186 0.9806863 -0.0672537 0.1834608 0.9807237 -0.3265824 -0.9451687 0 0.3272798 0.9449276 0 -0.9133071 0.4072716 0 0.407221 0.9132993 0.007448971 0.979639 -0.2007673 0 0.9996177 -0.02764976 0 0.9892243 0.1464082 0 0.9892243 0.1464084 0 0.9484466 0.3169373 0 0.9484627 0.3168891 0 0.8791719 0.4765048 0 0.8791605 0.4765259 0 0.7836734 0.6211731 0 0.7836732 0.6211736 0 0.6631498 0.7484867 0 0.6631361 0.7484989 0 0.5239619 0.8517417 0 0.5239735 0.8517346 0 0.3676111 0.9299797 0 0.913345 -0.4071867 0 -0.4080446 -0.9129304 0.007608592 -0.9796333 0.2007947 0 -0.9996476 0.02654993 0 -0.9996483 0.02652305 0 -0.9892244 -0.146407 0 -0.9892168 -0.1464596 0 -0.9488002 -0.315877 0 -0.9488 -0.3158774 0 -0.8791626 -0.476522 0 -0.8791738 -0.4765012 0 -0.7836702 -0.6211772 0 -0.7836829 -0.6211611 0 -0.6631498 -0.7484867 0 -0.6631361 -0.7484989 0 -0.5234591 -0.8520508 0 -0.5234708 -0.8520437 0 -0.3676126 -0.9299791 0 -0.3265394 -0.9451836 0 -0.1996569 -0.979866 0 -0.199657 -0.9798659 0 -0.02767896 -0.9996169 0 -0.02767705 -0.9996169 0 0.1464257 -0.9892217 0 0.1464257 -0.9892217 0 0.3158829 -0.9487982 0 0.3158934 -0.9487947 0 0.4765096 -0.8791694 0 0.4764954 -0.879177 0 0.621888 -0.7831063 0 0.6218715 -0.7831193 0 0.7479889 -0.6637114 0 0.747972 -0.6637304 0 0.8520669 -0.523433 0 0.8520518 -0.5234577 0 0.9133037 -0.4072791 0 0.9303753 -0.3665887 0.003826737 0.9456402 -0.3252147 0 0.9796338 -0.2007929 0 0.3272777 0.9449282 0 0.1994444 0.9799093 0 0.02770066 0.9996163 0 -0.1464306 0.989221 0 -0.1464257 0.9892217 0 -0.315865 0.9488041 0 -0.3158752 0.9488008 0 -0.4765096 0.8791694 0 -0.4765098 0.8791692 0 -0.6218766 0.7831153 0 -0.6218934 0.7831019 0 -0.7479718 0.6637305 0 -0.7480059 0.6636921 0 -0.8520517 0.5234578 0 -0.8520365 0.5234825 0 -0.9133518 0.4071716 0 -0.9299724 0.3676105 0.003733634 -0.9449469 0.327224 0 -0.979644 0.2007432 0 3.65764e-6 0 1 1.24274e-6 0 1 1.29143e-6 0 1 -1.6287e-6 0 1 0.27239 0.6556493 0.7042214 0.2897905 0.5978499 0.7473935 0.6399089 -0.2397951 0.7300788 0.6761868 -0.209564 0.7062963 0.7060887 -0.07567656 0.7040681 0.7060468 -0.07553011 0.7041259 0.70591 -0.0756762 0.7042473 0.701756 0.1081961 0.7041535 0.7022267 0.107497 0.7037912 0.7017325 0.1064485 0.7044432 0.6511325 0.2825748 0.7043991 0.6514543 0.2831455 0.7038722 0.6512223 0.2814725 0.7047573 0.5575395 0.4385306 0.7048693 0.5576655 0.4392238 0.7043379 0.5575983 0.4395652 0.7041779 0.4279098 0.5666543 0.7041279 0.4279374 0.5658447 0.7047619 0.4271942 0.567124 0.7041843 2.74036e-6 0 1 -2.03553e-6 0 1 4.97156e-6 0 1 -1.45607e-5 0 1 0.3974864 -0.9176082 0 0.3977589 -0.91749 -5.88003e-5 0.3977009 -0.9175152 5.12357e-5 0.3974965 -0.9176038 0 -0.2891872 -0.5985701 0.7470507 -0.2690848 -0.6483244 0.7122281 -0.6399118 0.239797 0.7300756 -0.6757412 0.2099546 0.7066067 -0.674921 0.2116171 0.7068945 -0.7054649 0.07520812 0.7047433 -0.7057104 0.07549291 0.7044669 -0.7060282 0.0734384 0.7043656 -0.701862 -0.1070936 0.7042164 -0.7021981 -0.1068859 0.7039129 -0.7014812 -0.1108897 0.7040082 -0.7014813 -0.1108898 0.7040082 -0.7014813 -0.1108896 0.7040082 -0.6517379 -0.2828018 0.7037478 -0.6514955 -0.2823941 0.7041358 -0.5546141 -0.4436905 0.7039474 -0.5546141 -0.4436905 0.7039474 -0.5546142 -0.4436904 0.7039474 -0.5581405 -0.439032 0.704081 -0.5581223 -0.4389783 0.704129 -0.4270634 -0.5673388 0.7040905 -0.4279978 -0.5667678 0.703983 -0.4279471 -0.5671462 0.7037092 -0.3108836 -0.6363438 0.7059872 -0.3974965 0.9176038 0 -0.3977567 0.917491 -5.88e-5 -0.3977004 0.9175153 4.65779e-5 -2.45306e-6 0 1 -1.10625e-6 0 1 -8.38184e-7 0 1 -8.42477e-7 0 1 -1.0499e-6 0 1 -1.05536e-6 0 1 8.59623e-6 0 1 3.34377e-6 0 1 2.1256e-6 0 1 1.23665e-6 0 1 1.67374e-6 0 1 -4.24567e-6 0 1 -0.7191023 -0.6949042 0 -0.9981053 -0.06152963 0 -0.9909244 0.1344116 -0.001563847 -0.9505636 0.310418 0.008347988 -0.9468113 0.3217096 0.007168292 -0.9015578 0.43264 -0.004059851 -0.8662502 0.4996105 0 -0.6965714 0.7174875 0 -0.7406787 0.6714953 -0.02212023 -0.5442407 0.8370289 0.05643373 -0.5442407 0.8370289 0.05643373 -0.5442408 0.8370289 0.05643373 -0.9506107 0.3103858 0 -0.976424 0.2063351 -0.06341958 -0.9419597 0.3351497 -0.01966285 -0.9419597 0.3351496 -0.01966291 -0.9419597 0.3351497 -0.01966285 -0.5809054 -0.8139498 0.005896389 -0.7391262 -0.6735119 -0.008621215 -0.7947568 -0.6055013 -0.04159229 -0.8682084 -0.4962 0 -0.9859461 -0.1670634 0 -0.9551785 -0.2832832 -0.08593422 -0.9984847 -0.05502796 4.65253e-4 -0.5844507 -0.8114077 0.005905151 -0.4234835 -0.9054576 -0.02843326 -0.3988875 -0.9167929 -0.01948338 0.2527499 -0.9656263 0.06069201 -0.01808589 -0.9995739 -0.02291166 0.04736459 -0.9988777 0 -0.2352589 -0.9719328 0 -0.2968174 -0.9549282 -0.003414332 -0.3016424 -0.9534202 0.001372635 -0.2329583 -0.9724868 0 0.0473634 -0.9988778 0 -0.42363 -0.9058353 0 -0.5449415 -0.838185 0.02201831 -0.4104105 -0.9118738 0.007035136 -0.9905919 0.1368404 -0.001564145 -0.9965699 -0.08272254 0.002370595 -0.9858964 -0.1670577 0.01000553 -0.955658 -0.2944791 0 -0.7954525 -0.6060159 0 -0.8665724 -0.4985893 0.02147144 -0.7246086 -0.6891607 1.40213e-4 0.04736047 -0.998878 0 0.505263 -0.8629654 0 0.8483958 -0.5293625 0 0.9972671 -0.07388067 0 0.9972733 -0.073798 0 0.9586483 0.2845939 0 0.9178392 0.3969138 -0.005538523 0.8637483 0.5039237 0 0.6270902 0.7789468 0 0.6270694 0.7789634 0 0.1934368 0.9811128 0 0.1934366 0.9811128 0 -0.2842798 0.9587414 0 -0.2842686 0.9587448 0 -0.6965948 0.7174648 0 -0.6965716 0.7174874 0 -0.8662549 0.4996024 0 -0.9031559 0.4293102 0.001514494 -0.3673772 0.8477381 0.3825888 0.3198784 -0.7376551 -0.5945947 0.3673671 -0.8471618 -0.3838729 0.3285615 -0.7203431 0.6108626 0.1517955 -0.3928647 0.9069815 0.2450471 -0.5577813 0.7929893 0.1675797 -0.3789666 0.9101107 0.1522566 -0.3514852 0.9237295 0.05326777 -0.1221976 0.9910753 0.05190175 -0.1197175 0.9914504 0.398654 -0.9078572 0.1298858 0.3581379 -0.8345176 0.4187096 0.3676953 -0.8479169 0.3818862 0.3198214 -0.7375439 0.5947633 0.2457969 -0.6084077 0.7546019 0.3962185 -0.9146811 -0.07980877 0.3962276 -0.9146748 0.07983583 0.3771558 -0.8919254 0.249445 0.4150686 -0.9007618 -0.1278532 0.3379579 -0.8477662 -0.4087507 0.3773268 -0.8921716 -0.2483029 0.2330332 -0.5853846 -0.776544 0.3305506 -0.7189741 -0.6114022 0.2498842 -0.572111 -0.7811831 0.2424408 -0.5592434 -0.7927606 0.1527695 -0.3524031 -0.923295 0.1520005 -0.3510273 -0.9239457 0.05322927 -0.1222266 -0.9910738 -0.301025 0.7319905 -0.6112069 -0.1835669 0.3812579 -0.9060605 -0.2393621 0.5593104 -0.7936484 -0.1622892 0.3817672 -0.909899 -0.1526984 0.3517904 -0.9235403 -0.05263429 0.1219239 -0.9911429 -0.05195742 0.119855 -0.9914309 0.0521205 -0.1202637 -0.9913729 -0.3901862 0.9115843 -0.1294943 -0.3638343 0.8302656 -0.4222366 -0.3673517 0.8477011 -0.3826952 -0.3200463 0.7385499 -0.5933924 -0.2756402 0.5938498 -0.7558869 -0.3966119 0.9147667 0.07681822 -0.3966078 0.9147676 -0.07682806 -0.3932912 0.8858272 -0.2462365 -0.3738133 0.9183406 0.1300544 -0.3875932 0.8253042 0.4106636 -0.3932515 0.8856769 0.2468397 -0.05207592 0.120131 0.9913913 -0.05273514 0.1221438 0.9911105 -0.1526539 0.351511 0.9236541 -0.1533278 0.3535858 0.9227501 -0.2416643 0.5573167 0.7943529 -0.2465093 0.5732823 0.7813966 -0.2989273 0.7339934 0.6098329 -0.2679629 0.5704595 0.7763839 -0.3195326 0.7373389 0.5951726 -0.4350636 -0.9003998 0 -0.2919632 -0.9544444 -0.06159001 -0.3355464 -0.9420238 0 -0.06738507 -0.997727 0 -0.06900751 -0.9976159 -7.47774e-4 0.9551889 -0.2959972 0 -0.06983083 -0.9975588 0 0.2034612 -0.9790831 0 0.2034569 -0.979084 0 0.4592297 -0.8883177 0 0.4592209 -0.8883222 0 0.682076 -0.7312814 0 0.6820837 -0.7312741 0 0.8538063 -0.5205909 0 0.8538438 -0.5205295 4.27347e-5 0.8538514 -0.5205171 0 0.9263104 -0.3767617 0 0.9624904 -0.2701836 -0.02476412 0.9664105 -0.2568496 -0.008900344 0.9942518 -0.1066185 0.009799242 0.3539686 0.9229655 -0.1511327 0.4798222 0.8773658 0 0.4361395 0.89977 -0.01401382 0.4606749 0.8875691 0 0.2038171 0.9790091 0 0.2041581 0.9789378 -4.27465e-4 0.2060308 0.9785456 0 -0.06754344 0.9977164 0 -0.06754022 0.9977167 0 -0.3342465 0.9424858 0 -0.3342417 0.9424875 0 -0.5758807 0.8175339 0 -0.5758789 0.8175351 0 -0.7749934 0.6319694 0 -0.775386 0.6314875 5.66309e-4 -0.776194 0.6304942 0 -0.8974968 0.441021 0 -0.9160318 0.3989619 -0.04141485 -0.9488846 0.3156234 0 0.793296 0.6077356 0.03659284 0.7640939 0.6446151 0.02513825 0.7103382 0.7036587 0.01685541 0.629188 0.7771878 0.01008296 0.7981522 0.6024551 -0.001022875 0.7969673 0.6040219 -8.65002e-4 0.8183482 0.5746797 -0.007029533 0.9798448 0.1996653 -0.006175816 0.9705629 0.2399672 -0.02057754 0.8369904 0.5469002 -0.01863551 0.8640199 0.5007247 -0.05238908 0.8545623 0.5183278 -0.0325517 0.9047006 0.426048 0 0.9630387 0.2693631 0 0.9282696 0.3517612 -0.1207458 0.9563939 0.2874468 -0.05181813 0.9845509 0.1750885 -0.001938462 0.9876284 0.156812 -5.13917e-4 0.9970353 -0.07628059 0.01010519 0.9992458 0.03490978 0.01700162 0.9992458 0.03490978 0.01700168 0.9992459 0.03490978 0.01700168 0.9925174 0.1193333 0.02586263 0.9862625 0.1611829 0.03614479 0.9758683 0.2090604 0.06304585 0.9886841 0.1499695 -0.003600955 0.9514104 0.3079251 7.0584e-4 0.9155995 0.3979499 0.05756288 0.9300853 0.3578821 0.08283603 0.9147669 0.3953724 0.08295959 0.9020817 0.4300822 0.03574824 0.7820808 0.615979 -0.09444344 0.8443863 0.521955 0.1207261 0.8190914 0.5703603 0.06147068 0.9942551 -0.1065872 0.009799838 0.9999355 -8.46425e-4 -0.01132905 0.9883258 0.1523248 0.003045737 0.9999476 0 0.01024526 0.9999476 0 0.01024776 -0.42193 -0.9066256 0.002237141 -0.4389228 -0.898522 0.002235352 -0.5775492 -0.816337 -0.005565464 -0.6023277 -0.7982417 0.003398895 -0.7763975 -0.6302351 0.003285229 -0.601217 -0.798666 -0.02589958 -0.7758281 -0.6309328 -0.003826856 -0.7860108 -0.6182117 0.00125122 -0.7807188 -0.6248815 0.001248836 -0.7807187 -0.6248814 0.001248836 -0.7807187 -0.6248816 0.001248896 -0.9173413 -0.3980995 -0.001306533 -0.9175173 -0.3976943 -0.001157641 -0.9877359 -0.156129 0.001271486 -0.987736 -0.1561282 0.001271665 -0.9877358 -0.1561297 0.001271605 -0.9909031 -0.1345715 0.001270413 -0.9885525 -0.1508592 -0.00233674 -0.9907082 -0.135954 -0.003726184 -0.9945768 0.103954 0.003286361 -0.9943602 0.1060045 0.003286957 -0.9905976 0.1366871 -0.005746364 -0.954195 0.2991765 0.002292692 -0.9549835 0.2966504 0.002294421 0.6816139 0.7316409 0.01020801 0.685018 0.7284562 0.01009404 0.7853259 0.6190751 0.003093481 0.6827279 0.7305882 -0.0111131 0.6031756 0.79755 0.009652614 0.6016423 0.7987074 0.009651422 0.9542589 0.2989816 0 0.9999537 -0.009632647 0 0.9999542 -0.009578824 0 0.909283 -0.4161784 0 0.9092932 -0.4161562 0 0.6618301 -0.7496539 0 0.6618034 -0.7496775 0 0.3003324 -0.9538346 0 -0.1142544 -0.9934516 0 -0.1142509 -0.993452 0 -0.5086542 -0.860971 0 -0.5086554 -0.8609703 0 -0.8150398 -0.579405 0 -0.8150133 -0.5794424 0 -0.9801166 -0.1984228 0 -0.9801217 -0.1983976 0 -0.97605 0.2175466 0 -0.8034337 0.5953944 0 -0.8034582 0.5953612 0 -0.4904337 0.8714786 0 -0.490435 0.8714779 0 -0.09497725 0.9954794 0 -0.0949794 0.9954792 0 0.3187553 0.9478372 0 0.3187487 0.9478394 0 0.6763851 0.7365482 0 0.6763717 0.7365606 0 0.8702838 0.4925507 0 0.9168766 0.3977276 -0.03391402 -0.8142404 -0.5805279 0 -0.8146238 -0.5799897 -3.3505e-4 -0.5091737 -0.8606638 0 -0.5098844 -0.8602429 3.82614e-4 -0.507238 -0.861806 -2.51226e-4 -0.5077547 -0.8615018 0 -0.1142601 -0.9934509 0 0.2992399 -0.954178 0 0.2992415 -0.9541774 0 0.6618435 -0.7496421 0 0.66179 -0.7496892 0 0.9096271 -0.4154258 0 0.9094908 -0.4157242 -8.4054e-5 0.9093776 -0.4159716 0 0.999929 -0.01192313 0 0.999929 -0.01192313 0 0.999929 -0.01192313 0 0.9999541 -0.009590387 1.39537e-4 0.9999556 -0.009422779 0 0.9546447 0.2977476 0 0.9537099 0.300728 -5.41867e-4 0.9168567 0.3977728 -0.03392338 0.8703297 0.4924696 0 0.6770402 0.7359461 0 0.6770133 0.7359707 0 0.3178005 0.9481576 0 0.3183814 0.9479628 -1.8828e-4 0.3189499 0.9477717 0 -0.09498351 0.9954789 0 -0.09498816 0.9954785 0 -0.4918518 0.870679 0 -0.8034558 0.5953644 0 -0.8160391 -0.5779968 0 -0.9801162 -0.1984248 0 -0.976188 0.2169266 0 -0.976039 0.2175957 -3.00217e-4 -0.975674 0.2192267 0 -0.8034546 0.595366 0 0.9999542 -0.009578883 0 -0.5086715 -0.8609607 3.76906e-4 -0.5104635 -0.8598995 0 -0.1142575 -0.9934512 0 0.3003248 -0.953837 0 0.3003233 -0.9538375 0 0.6617957 -0.7496842 0 0.6618473 -0.7496387 0 0.9095864 -0.415515 0 0.9093016 -0.4161377 -2.49079e-4 0.9089294 -0.41695 0 0.9999536 -0.009632647 0 0.9542894 0.2988841 0 0.9168764 0.3977275 -0.03391736 0.8713531 0.4906561 -7.18608e-4 0.8695247 0.4938895 0 0.676976 0.7360051 0 0.677041 0.7359454 -2.60809e-5 0.6773356 0.7356742 0 0.3177657 0.9481694 0 0.3173108 0.9483217 1.47999e-4 0.3168876 0.9484631 0 -0.09378099 0.9955929 0 -0.4918352 0.8706884 0 -0.4918825 0.8706616 0 -0.5079499 -0.8613867 0 -0.8150293 -0.5794197 0 -0.9801257 -0.1983772 0 -0.9801162 -0.1984248 1.68271e-5 -0.9801001 -0.1985039 0 -0.9763043 0.2164025 0 -0.9761879 0.2169265 1.74763e-4 -0.975844 0.2184684 -1.3829e-4 -0.9756312 0.2194174 0 -0.8146234 -0.5799905 0 -0.5081061 -0.8612945 0 -0.5081296 -0.8612806 0 -0.1142662 -0.9934502 0 0.2995861 -0.9540694 0 0.2995706 -0.9540742 0 0.661208 -0.7502028 0 0.6612328 -0.7501808 0 0.909938 -0.4147445 0 0.9099583 -0.4147 0 0.9999414 -0.01082551 0 0.8702538 0.492601 -0.001650154 0.8714492 0.490483 -0.001652836 0.9167593 0.3980523 -0.03326952 0.9535623 0.3011957 0 0.9999415 -0.01082557 0 0.9225898 0.3857825 0 0.6761626 0.7367525 0 0.6761608 0.7367542 0 0.3184256 0.9479479 0 -0.09474021 0.9955021 0 -0.09473466 0.9955026 0 -0.4916031 0.8708194 0 -0.49158 0.8708324 0 -0.8028633 0.5961631 0 -0.802888 0.5961301 0 -0.976045 0.2175693 0 -0.9760563 0.217518 0 -0.9797437 -0.2002558 0 -0.9797644 -0.2001546 0 -0.9805011 -0.1965135 0 -0.9804799 -0.1966193 0 -0.1142597 -0.9934509 5.38514e-5 -0.1143072 -0.9934455 0 0.2992323 -0.9541804 0 0.662482 -0.7490779 0 0.6625087 -0.7490543 0 0.9091117 -0.4165523 0 0.9092934 -0.4161559 2.08684e-4 0.909823 -0.4149966 0 0.9168574 0.3977703 -0.03393447 0.8689189 0.4949538 8.37376e-4 0.8711538 0.4910103 0 0.676189 0.7367283 0 0.6767103 0.7362493 -4.00633e-4 0.681169 0.7321262 0 0.31788 0.948131 0 0.3181808 0.9480301 -5.38011e-5 0.3182549 0.9480053 0 -0.09486186 0.9954905 0 -0.09486395 0.9954903 0 -0.4915686 0.870839 0 -0.110257 -0.9939031 0 -0.5086479 -0.8609747 0 -0.8150421 -0.5794019 0 -0.9801135 -0.1984382 0 -0.9763312 0.2162809 0 -0.976039 0.2175957 3.46469e-4 -0.9758442 0.2184678 0 -0.8132244 0.5819503 1.64541e-7 -0.8132258 0.5819485 1.65327e-6 -0.8132231 0.5819522 0 -0.8032711 0.5956137 -1.21218e-4 -0.8031706 0.5957491 0 -0.8144586 -0.5802218 2.62209e-4 -0.8147728 -0.5797804 0 -0.5077607 -0.8614982 0 -0.5077683 -0.8614937 6.73442e-6 -0.5077343 -0.8615137 0 -0.1142627 -0.9934507 5.38529e-5 -0.1143041 -0.9934459 0 0.2995937 -0.9540669 0 0.2995798 -0.9540712 0 0.6612157 -0.7501959 0 0.9100005 -0.4146073 0 0.9095009 -0.4157015 -5.68211e-4 0.9079159 -0.4191524 0 0.9999534 -0.009644269 -6.29496e-4 0.9999427 -0.01071304 0 0.9530984 0.3026608 0 0.9542644 0.2989632 7.31964e-4 0.9168884 0.3977596 -0.03321164 0.8713156 0.4907231 0 0.6764369 0.7365007 0 0.6764235 0.736513 0 0.3162773 0.9486668 0 0.3176512 0.9482077 -2.28971e-4 0.318129 0.9480475 0 -0.09378725 0.9955924 0 -0.09378767 0.9955922 0 -0.4918634 0.8706725 0 -0.8133465 -0.5817797 0 -0.9803512 -0.1972605 0 -0.9803459 -0.1972864 0 -0.9762957 0.2164416 0 -0.9763013 0.216416 0 -0.758772 0.6513565 0 -0.7587718 0.6513565 0 -0.758772 0.6513563 0 -0.8028878 0.59613 4.84352e-4 -0.8033444 0.5955148 0 4.40259e-6 0 1 -1.47255e-6 0 1 3.67196e-6 0 1 -7.51649e-7 0 1 3.15812e-6 0 1 -2.69849e-6 0 1 5.99743e-6 0 1 1.57277e-6 0 1 -0.9571047 -0.2897427 0 -0.9571049 -0.2897418 0 -0.7769981 -0.629503 0 -0.7769992 -0.6295016 0 -0.4793738 -0.8776108 0 -0.4794203 -0.8775855 0 -0.4813325 -0.8765382 0 -0.4816901 -0.8763417 2.92406e-5 -0.4817097 -0.8763309 0 -0.1141881 -0.9934592 0 -0.1141937 -0.9934586 0 0.2691895 -0.9630873 0 0.2695682 -0.9629814 3.48847e-5 0.2696201 -0.9629668 0 0.6300334 -0.7765681 0 0.6137436 -0.7895054 1.86056e-4 0.6135342 -0.7896682 0 0.8662973 -0.499529 0 0.8663173 -0.4994941 0 -0.9949863 -0.1000112 0 -0.9949895 -0.09997987 -6.66953e-6 -0.9953663 -0.09613108 0.002166748 -0.9950863 -0.09901219 0 0.1248129 -0.6970589 0.706067 0.1247349 -0.6970523 0.7060874 0.1247783 -0.6970561 0.706076 0.1248356 -0.6970545 0.7060674 0.2307071 -0.6695041 0.7060727 0.2306323 -0.6695478 0.7060557 0.4233248 -0.5677059 0.7060496 0.4235637 -0.5676174 0.7059777 0.4235196 -0.5676617 0.7059684 0.4233557 -0.5677422 0.706002 0.3312203 -0.6259636 0.7060189 0.3309766 -0.6260187 0.7060844 0.3310073 -0.6259657 0.706117 0.2305172 -0.6695623 0.7060794 0.7531409 0.6578592 0 0.7527978 0.658252 -1.15701e-4 0.7526491 0.6584219 0 0.7529059 0.6581282 -1.58738e-4 0.5184385 -0.8551151 0 -0.2285847 -0.973524 0 -0.2285751 -0.9735264 0 0.1567261 -0.9876422 0 0.1568132 -0.9876284 7.97377e-5 0.1641422 -0.9864367 0 0.5184797 -0.85509 0 0.8019411 -0.5974033 0 0.8035448 -0.5952443 -2.74836e-4 0.8034104 -0.5954256 -3.14495e-4 0.8030748 -0.5958783 0 0.9687506 -0.248037 0 0.9687365 -0.2480919 0 0.9695397 -0.2449348 0 0.9695117 -0.2450454 0 0.9695117 -0.2450453 0 0.9695117 -0.2450453 0 0.9907017 0.136052 0 0.9907079 0.1360064 0 0.8657242 0.5005214 0 0.8657451 0.5004853 0 -0.4108527 -0.9117017 0 -0.4101917 -0.9119994 0 -0.4104342 -0.9118902 6.38078e-5 -0.4103347 -0.911935 9.00647e-5 -0.4108287 -0.9117125 3.39511e-4 0.6656134 -0.2411739 0.7062535 0.6680209 -0.2368906 0.7054297 0.6660755 -0.240601 0.7060132 0.7034572 0.0828973 0.7058866 0.7034403 0.08285307 0.7059088 0.7031659 0.08387464 0.7060616 0.7076272 -0.02624231 0.7060985 0.7076953 -0.02649688 0.7060208 0.7077524 -0.02621328 0.7059742 0.7077325 -0.02595388 0.7060037 0.6949065 -0.1370354 0.7059223 0.6950436 -0.1350858 0.7061631 0.6953229 -0.1347328 0.7059556 0.6950289 -0.1366186 0.7058826 0.6663169 -0.2404263 0.7058449 -1.52512e-6 0 1 5.52146e-7 0 1 1.28816e-6 0 1 -1.13646e-4 0 1 1.01316e-6 0 1 -1.57128e-6 0 1 -0.001036703 0.9999995 0 0.7290841 -0.6844242 0 0.9338836 -0.3575772 0 0.933903 -0.3575263 0 0.9325966 -0.3609205 0 0.9325971 -0.3609194 0 0.9997624 0.02180111 0 0.9997614 0.02184748 0 0.9174305 0.3978961 0 0.917414 0.3979341 0 0.6987541 0.715362 0 0.3762951 0.9264999 0 0.3761469 0.9265601 0 0.3775898 0.9259731 0 0.3776106 0.9259645 0 -0.001036703 0.9999995 0 0.584022 -0.8117378 0 0.5840454 -0.811721 2.03706e-4 0.5838674 -0.811849 3.57418e-4 0.5842191 -0.8115961 0 0.5410286 0.4568459 0.7061019 0.5413709 0.4566957 0.7059367 0.5411082 0.4570841 0.7058867 0.4646059 0.5347536 0.7058186 0.4648533 0.5342896 0.7060072 0.4646754 0.5344106 0.7060327 0.4643983 0.5346641 0.706023 0.3765118 0.5998071 0.7060243 0.3765458 0.5998038 0.706009 0.3764406 0.5997965 0.7060713 0.2789431 0.6507988 0.7061528 0.2799169 0.6504242 0.7061125 0.2800904 0.6504552 0.7060151 0.3758662 0.6002332 0.7060062 -0.9477314 0.3190694 0 -0.9463914 0.3230214 7.42774e-4 -0.9459269 0.3243802 0 -0.946336 0.3231841 5.88674e-4 -0.866245 0.4996196 0 0.9571395 0.2896274 0 0.9571336 0.2896472 0 0.7769981 0.629503 0 0.7770106 0.6294875 0 0.480952 0.8767469 0 0.4809706 0.8767368 0 0.1147574 0.9933935 0 0.1146307 0.9934082 -8.91045e-5 0.1104305 0.9938836 -7.50534e-4 0.1133598 0.993554 0 -0.2690935 0.9631141 0 -0.6644619 0.7473222 0 -0.6138645 0.7894113 -6.16219e-4 -0.6132284 0.7899057 0 0.9950323 0.09955281 0 0.9950373 0.09950274 -4.5599e-4 0.9949529 0.1003395 -9.19609e-4 0.9950773 0.09910279 0 -0.1247408 0.696965 0.7061725 -0.1250726 0.6970425 0.7060374 -0.1240776 0.6970251 0.70623 -0.1250275 0.6972241 0.7058659 -0.2305921 0.6697874 0.7058414 -0.2308421 0.6695898 0.7059472 -0.4238853 0.5673822 0.7059736 -0.4232221 0.567667 0.7061425 -0.4234175 0.5674538 0.7061968 -0.4236862 0.5673598 0.7061111 -0.3310464 0.6259407 0.7061209 -0.3309135 0.6259613 0.7061649 -0.3306769 0.6262149 0.7060509 -0.2306036 0.6695984 0.706017 2.42554e-6 0 1 2.24804e-6 0 1 -7.36238e-7 0 1 3.68089e-7 0 1 -6.98285e-6 0 -1 3.48955e-6 0 -1 3.49401e-6 0 -1 1.75493e-6 0 -1 3.68759e-6 0 -1 -2.19984e-6 0 -1 3.67798e-6 0 -1 -1.10225e-6 0 -1 -1.77421e-6 0 -1 4.553e-7 0 -1 1.81723e-6 0 -1 -1.80992e-6 0 -1 3.56934e-6 0 -1 3.55331e-6 0 -1 -7.3568e-6 0 -1 7.0325e-6 0 -1 -7.4082e-6 0 -1 6.99396e-6 0 -1 -7.503e-6 0 -1 -6.86186e-6 0 -1 -1.95075e-6 0 -1 -9.84159e-7 0 -1 1.65445e-6 0 -1 4.07055e-7 0 -1 8.07629e-7 0 -1 -8.28555e-6 0 -1 3.17759e-6 0 -1 3.14695e-6 0 -1 3.12133e-6 0 -1 -3.09425e-6 0 -1 0.9997869 -0.00435549 -0.02018457 0.9992012 -0.03739327 0.01410096 0.9992294 -0.03663176 0.01410108 0.9855686 -0.1685336 -0.01584565 0.9815837 -0.1907925 0.009578943 0.9811967 -0.1927729 0.009577155 0.9443252 -0.3288668 -0.009831964 0.9406334 -0.3394041 0.003721117 0.9426483 -0.3337669 0.003724575 0.8775426 -0.4794807 -0.00416404 0.8760029 -0.4823059 0 0.7863946 -0.6177245 0 0.7864019 -0.6177152 0 0.6962805 -0.7177698 0 0.6737996 -0.7384563 -0.02600765 0.5975958 -0.8014552 0.02343118 0.5432583 -0.8392404 0.02336686 0.5966681 -0.7997595 -0.06612217 0.4675653 -0.8836257 0.02425664 0.467306 -0.883763 0.02425247 0.3976402 -0.9171161 -0.02793902 0.3254345 -0.9452494 0.02441626 0.3257022 -0.9451568 0.02442598 0.2411753 -0.9700945 -0.02740919 0.1762295 -0.9840732 0.02330642 0.1761087 -0.9840949 0.0233075 0.07828086 -0.9965918 -0.02602088 0.04780161 -0.9988569 0 -0.08690017 -0.996217 0 -0.08690172 -0.996217 0 -0.2467694 -0.9690743 0 -0.2496409 -0.9683308 -0.00386846 -0.3908207 -0.92046 0.003555476 -0.3953354 -0.9185301 0.003545105 -0.4056679 -0.9139644 -0.01014208 -0.5304077 -0.8476921 0.009273946 -0.5320079 -0.8466887 0.009269833 -0.5503749 -0.8347762 -0.01537114 -0.6553725 -0.7551696 0.01434814 -0.655826 -0.754776 0.01433765 -0.6803725 -0.7325938 -0.01998919 -0.764932 -0.6438491 0.01837021 -0.7640369 -0.6449107 0.01838332 -0.7916787 -0.610483 -0.02356624 -0.8264099 -0.5630691 0 -0.8814357 -0.472304 0 -0.9472337 -0.3205437 0 -0.9472383 -0.3205303 0 -0.9758023 -0.2186551 0 -0.9867881 -0.160259 -0.02379822 -0.9929755 -0.1169838 0.01773422 -0.9930183 -0.1166201 0.01773488 -0.9997916 0.003908038 -0.02003985 -0.9991927 0.03739291 0.0146963 -0.9992209 0.03663074 0.01469755 -0.9855017 0.1689699 -0.01535445 -0.9815838 0.1907924 0.009570419 -0.9819927 0.1886771 0.009569168 -0.944329 0.3288384 -0.01039499 -0.9404801 0.3398283 0.00372374 -0.9425098 0.334158 0.003721177 -0.8775364 0.4794923 -0.004167735 -0.8760029 0.4823059 0 -0.7863626 0.6177653 0 -0.6963258 0.7177259 0 -0.6739199 0.7383502 -0.02590698 -0.5983103 0.8009296 0.02316766 -0.5431538 0.8393142 0.02314609 -0.5966837 0.7997052 -0.06663548 -0.4673835 0.8837306 0.0239368 -0.4668289 0.8840239 0.02393162 -0.3975996 0.9171344 -0.02791345 -0.3255166 0.9452222 0.02437168 -0.3254364 0.9452499 0.02436834 -0.2412183 0.9700874 -0.02728229 -0.1764574 0.9840323 0.02330994 -0.1765676 0.9840127 0.02330553 -0.07836753 0.9965799 -0.02621436 -0.04766279 0.9988635 0 0.08711922 0.9961979 0 0.08711946 0.9961979 0 0.2464686 0.9691509 0 0.2495986 0.9683404 -0.004197597 0.3938795 0.9191558 0.003389656 0.3954967 0.9184611 0.003401994 0.4055925 0.9139993 -0.009997844 0.5307264 0.8474904 0.009471237 0.5316587 0.8469057 0.009477853 0.5504149 0.8347445 -0.01565533 0.6556398 0.7549412 0.01415586 0.6563079 0.7543604 0.01415646 0.6803585 0.7326208 -0.0194717 0.7637465 0.6452549 0.01837831 0.7639173 0.6450525 0.01837736 0.7916584 0.6105033 -0.02372175 0.8265764 0.5628246 0 0.8814341 0.4723071 0 0.8814357 0.472304 0 0.9472383 0.3205303 0 0.9472342 0.3205425 0 0.9761229 0.2172191 0 0.9868015 0.1602614 -0.02321892 0.9929627 0.1170036 0.01831096 0.99279 0.1184604 0.01831126 -3.14911e-6 0 1 1.44259e-6 0 1 -3.68274e-6 0 1 -0.8037188 0.5950093 0 0.2283372 0.9735822 0 0.2283468 0.9735798 0 -0.1567182 0.9876434 0 -0.1568168 0.9876277 -6.97494e-5 -0.1647393 0.9863371 0 -0.5190025 0.8547728 0 -0.5184638 0.8550996 -4.21607e-4 -0.5144742 0.8575059 0 -0.803731 0.5949929 0 -0.9685102 0.2489742 0 -0.968655 0.2484098 -2.76308e-4 -0.9689356 0.2473137 0 -0.9907016 -0.1360528 0 -0.9907079 -0.1360072 0 -0.8658043 -0.5003829 0 -0.8657943 -0.5004004 0 0.4108527 0.9117017 0 0.4108359 0.9117093 3.49217e-4 0.4120975 0.9111392 0.00107634 0.4106785 0.9117802 0 -0.665763 0.2408177 0.706234 -0.6684252 0.2370567 0.7049908 -0.6660291 0.2406461 0.7060416 -0.7032344 -0.08285403 0.7061138 -0.7032113 -0.08281177 0.7061417 -0.703277 -0.08264744 0.7060955 -0.7076223 0.02627032 0.7061025 -0.7076956 0.02648133 0.7060211 -0.7077459 0.02624243 0.7059796 -0.7077398 0.02595359 0.7059963 -0.6949032 0.1370295 0.7059267 -0.6950485 0.1350724 0.7061609 -0.6953209 0.1347324 0.7059575 -0.6954769 0.1336475 0.7060102 -0.6660158 0.2406628 0.7060486 0.1917113 -0.9814514 0 0.1936033 -0.9810799 -3.40898e-4 0.194236 -0.9809549 0 0.1935823 -0.9810841 -2.73322e-4 0.001036763 -0.9999995 0 -0.7290725 0.6844366 0 -0.7290957 0.6844118 0 -0.9338951 0.3575474 0 -0.9339045 0.3575226 0 -0.9341794 0.3568037 0 -0.9341798 0.3568026 0 -0.9997842 -0.02077895 0 -0.9997846 -0.02075558 0 -0.9174135 -0.3979352 0 -0.917414 -0.3979341 0 -0.6987511 -0.7153649 0 -0.6987496 -0.7153664 0 -0.3762866 -0.9265033 0 -0.3762881 -0.9265027 0 -0.3775817 -0.9259763 0 -0.3775922 -0.925972 0 0.001036703 -0.9999995 0 -0.989066 -0.1474742 0 -0.784379 -0.6202819 0 -0.3672018 -0.9301414 0 -0.3672402 -0.9301262 0 0.147154 -0.9891137 0 0.1471532 -0.9891138 0 0.6214556 -0.7834494 0 0.9293097 -0.3693016 0 0.9293101 -0.3693004 0 0.9891183 0.1471226 0 0.9891183 0.1471231 0 0.7822367 0.6229814 0 0.7822907 0.6229137 0 0.3693242 0.9293007 0 0.3692857 0.9293161 0 -0.1475165 0.9890597 0 -0.1474999 0.9890621 0 -0.6217353 0.7832275 0 -0.6217858 0.7831874 0 -0.9301588 0.3671576 0 -0.9301218 0.3672512 0 0.7835587 0.6213178 0 0.7862823 0.6178674 0 0.7835955 0.6212714 0 0.3663907 0.9304612 0 0.3664105 0.9304533 0 -0.1475086 0.9890608 0 -0.1475157 0.9890598 0 -0.6202448 0.7844084 0 -0.9301241 0.3672454 0 -0.9301245 0.3672443 0 -0.9889468 -0.1482706 0 -0.9889693 -0.1481204 0 -0.9894618 -0.1447943 0 -0.9894619 -0.1447935 0 -0.7834487 -0.6214566 0 -0.78345 -0.6214549 0 -0.3684728 -0.9296386 0 -0.3684713 -0.9296392 0 0.1475086 -0.9890608 0 0.1475078 -0.9890609 0 0.6217492 -0.7832165 0 0.6217776 -0.783194 0 0.9301241 -0.3672454 0 0.930143 -0.3671975 0 0.989058 0.1475272 0 0.989066 0.1474742 0 0.784379 0.6202819 0 0.7844053 0.6202487 0 0.3672018 0.9301414 0 0.3672402 0.9301262 0 -0.147154 0.9891137 0 -0.1471611 0.9891126 0 -0.6214293 0.7834703 0 -0.9301426 0.3671987 0 -0.930143 0.3671975 0 -0.9894615 -0.1447964 0 -0.9894615 -0.1447969 0 -0.7822631 -0.6229484 0 -0.7822907 -0.6229137 0 -0.3693056 -0.929308 0 -0.3693227 -0.9293012 0 0.6229067 -0.7822962 0 0.6229614 -0.7822527 0 0.9301057 -0.3672922 0 -0.146442 0.9892193 -6.75143e-6 -0.1465 0.9892107 0 -0.622764 0.7824099 0 -0.6228146 0.7823695 0 -0.9301057 0.3672922 0 -0.989403 -0.1451957 0 -0.9894108 -0.1451427 0 -0.7824228 -0.6227477 0 -0.7825111 -0.6226369 0 -0.7835211 -0.6213652 0 -0.7835579 -0.6213189 0 -0.3672179 -0.930135 0 -0.3672548 -0.9301204 0 0.1475181 -0.9890594 0 0.1475339 -0.9890571 0 0.6153516 -0.7882528 0 0.6202448 -0.7844083 -5.13285e-4 0.6219832 -0.7830306 0 0.9894503 0.1448729 0 0.9894613 0.144798 0 0.9882975 0.1525387 0 0.9882706 0.1527135 0 0.7838168 0.6209923 0 0.7838445 0.6209574 0 0.3676228 0.9299751 0 0.3676598 0.9299604 0 -0.1464549 0.9892174 0 -6.38537e-6 0 -1 6.39812e-6 0 -1 3.60191e-6 0 -1 3.60633e-6 0 -1 -3.54524e-6 0 -1 2.18724e-7 0 -1 6.5241e-7 0 -1 -4.03382e-6 0 -1 -3.20453e-5 0 -1 2.18723e-7 0 -1 -6.52404e-7 0 -1 3.54521e-6 0 -1 -2.89714e-5 0 -1 -1.25008e-5 0 -1 4.11292e-6 0 -1 4.19163e-6 0 -1 -2.73993e-6 0 -1 -1.05501e-6 0 -1 6.34655e-6 0 -1 -1.35487e-6 0 -1 -3.54668e-6 0 -1 1.40697e-5 0 -1 -2.35889e-6 0 -1 -1.58294e-6 0 -1 3.56092e-6 0 -1 4.80543e-6 0 -1 -3.46443e-6 0 -1 1.47796e-6 0 -1 1.722e-6 0 -1 7.35121e-6 0 -1 -2.41057e-6 0 -1 1.43367e-6 0 -1 -2.95351e-6 0 -1 -7.67201e-6 0 -1 1.80337e-6 0 -1 -6.92406e-6 0 -1 7.02721e-6 0 -1 5.3227e-6 0 -1 -1.35077e-6 0 -1 9.66322e-6 0 -1 5.26316e-6 0 -1 -1.07949e-5 0 -1 2.01371e-5 0 -1 9.01437e-6 0 -1 1.17025e-5 0 -1 -2.33693e-6 0 -1 -2.68109e-6 0 -1 2.20798e-6 0 -1 -1.46524e-6 0 -1 1.70251e-6 0 -1 7.14596e-7 0 -1 -2.50642e-6 0 -1 1.23269e-6 0 -1 -1.31845e-6 0 -1 1.65696e-6 0 -1 1.34708e-6 0 -1 1.05677e-6 0 -1 1.24565e-6 0 -1 -6.41961e-6 0 -1 3.54022e-6 0 -1 -1.84186e-6 0 -1 -2.92694e-6 0 -1 2.93572e-6 0 -1 -1.43447e-5 0 -1 3.64575e-6 0 -1 -1.77489e-6 0 -1 4.30037e-6 0 -1 2.64884e-6 0 -1 1.28175e-6 0 -1 -2.74608e-6 0 -1 -2.58904e-6 0 -1 -5.42029e-6 0 -1 4.13767e-6 0 -1 -1.35199e-6 0 -1 3.03706e-6 0 -1 3.39572e-6 0 -1 7.11035e-6 0 -1 4.67412e-6 0 -1 -1.29493e-6 0 -1 1.48941e-6 0 -1 -1.62667e-4 0 -1 -1.62645e-4 0 -1 -1.6275e-4 0 -1 3.76631e-6 0 -1 5.01288e-6 0 -1 -2.62181e-6 0 -1 9.97877e-6 0 -1 -5.449e-5 0 -1 4.55083e-5 0 -1 -9.69744e-5 0 -1 -1.11074e-5 0 -1 5.39174e-6 0 -1 5.05766e-6 0 -1 -1.21999e-5 0 -1 -7.4618e-6 0 -1 -1.21336e-5 0 -1 -7.59315e-7 0 -1 3.25892e-5 0 -1 1.19922e-6 0 -1 -3.31038e-6 0 -1 7.83199e-6 0 -1 -2.21666e-6 0 -1 4.74003e-6 0 -1 -4.4018e-5 0 -1 2.63047e-6 0 -1 3.09471e-6 0 -1 1.02394e-4 0 -1 1.02352e-4 0 -1 1.02362e-4 0 -1 4.5688e-6 0 -1 -8.0966e-7 0 -1 -2.86293e-6 0 -1 -1.02775e-5 0 -1 1.19689e-5 0 -1 -2.75749e-5 0 -1 3.94471e-6 0 -1 -3.10574e-6 0 -1 3.7461e-6 0 -1 -2.07759e-6 0 -1 5.05712e-6 0 -1 -7.48867e-6 0 -1 -3.37662e-6 0 -1 -6.10926e-6 0 -1 9.7947e-6 0 -1 5.93542e-6 0 -1 5.39072e-6 0 -1 3.90031e-6 0 -1 -1.64374e-5 0 -1 6.26994e-6 0 -1 1.0881e-6 0 -1 -3.76642e-6 0 -1 3.75402e-7 0 -1 -2.33594e-6 0 -1 7.47518e-6 0 -1 1.21473e-5 0 -1 -4.4603e-5 0 -1 -2.83647e-5 0 -1 8.4717e-5 0 -1 -6.28097e-6 0 -1 9.26718e-6 0 -1 -2.06515e-5 0 -1 4.02891e-6 0 -1 1.91241e-6 0 -1 -2.63269e-6 0 -1 -1.42418e-5 0 -1 6.04171e-6 0 -1 -1.26134e-6 0 -1 -1.04892e-5 0 -1 1.68379e-5 0 -1 1.02045e-5 0 -1 3.42517e-6 0 -1 -1.05245e-5 0 -1 1.27346e-6 0 -1 -4.22846e-6 0 -1 1.1619e-6 0 -1 3.26879e-6 0 -1 2.52725e-5 0 -1 1.37467e-6 0 -1 -1.06288e-6 0 -1 3.59244e-6 0 -1 5.68861e-6 0 -1 -1.81686e-6 0 -1 -3.76483e-6 0 -1 -4.75475e-6 0 -1 1.7324e-5 0 -1 -9.46199e-6 0 -1 1.7438e-6 0 -1 -1.14183e-5 0 -1 -1.05606e-6 0 -1 4.15538e-6 0 -1 2.82072e-6 0 -1 -2.52505e-5 0 -1 -3.83686e-6 0 -1 1.82695e-6 0 -1 6.95517e-6 0 -1 7.77389e-7 0 -1 -8.82208e-6 0 -1 -1.42189e-6 0 -1 -7.85257e-6 0 -1 -2.02387e-6 0 -1 2.30475e-6 0 -1 -2.81773e-6 0 -1 1.48792e-5 0 -1 -6.5879e-7 0 -1 -5.50394e-6 0 -1 -5.46857e-7 0 -1 -3.56593e-6 0 -1 2.11058e-6 0 -1 -1.36766e-6 0 -1 2.11007e-6 0 -1 -4.05218e-6 0 -1 -9.71213e-6 0 -1 5.24989e-6 0 -1 6.47078e-7 0 -1 -3.23868e-6 0 -1 0 0 -1 6.42079e-6 0 -1 -0.7818383 -0.6234813 0 -0.7862599 -0.6178961 0 -0.7819135 -0.623387 0 0.1475007 -0.989062 0 0.1475157 -0.9890598 0 0.6202974 -0.7843669 0 0.6202448 -0.7844084 0 0.9301615 -0.3671507 0 0.9889699 0.1481169 0 0.98897 0.1481162 0 0.9894606 0.1448024 0 0.9894785 0.1446806 0 0.9894784 0.1446807 0 0.9894785 0.1446807 0 0.7834487 0.6214566 0 0.7835027 0.6213884 0 0.3684728 0.9296386 0 0.3684713 0.9296392 0 -0.622933 0.7822752 0 -0.6229351 0.7822736 0 -0.9292725 0.3693949 0 -0.9293472 0.369207 0 -0.7862588 -0.6178975 0 6.46095e-6 0 1 1.44857e-6 0 1 -6.44828e-6 0 1 -3.07958e-5 0 1 -4.35225e-6 0 1 2.16117e-6 0 1 -4.08871e-6 0 1 -4.85286e-6 0 1 2.19037e-6 0 1 2.37557e-6 0 1 9.28251e-6 0 1 -1.45404e-5 0 1 7.50948e-6 0 1 -1.0116e-5 0 1 -1.70184e-6 0 1 -1.96387e-4 0 1 -1.96384e-4 0 1 -1.96398e-4 0 1 3.99754e-6 0 1 -4.14504e-6 0 1 1.42625e-5 0 1 -5.22724e-6 0 1 1.16398e-5 0 1 -1.75119e-5 0 1 -7.22794e-7 0 1 1.76044e-5 0 1 -9.92725e-7 0 1 -1.98761e-6 0 1 1.65418e-6 0 1 1.99569e-6 0 1 3.79708e-6 0 1 -2.52461e-5 0 1 1.82929e-5 0 1 4.49002e-6 0 1 2.58117e-5 0 1 5.65185e-5 0 1 2.88961e-6 0 1 -3.01943e-6 0 1 -6.94715e-6 0 1 1.03619e-6 0 1 -2.61654e-6 0 1 -1.79789e-6 0 1 1.6547e-6 0 1 -1.0998e-6 0 1 1.46223e-6 0 1 -1.86997e-6 0 1 -6.04127e-6 0 1 -6.9403e-6 0 1 -5.48639e-6 0 1 -1.24553e-5 0 1 5.72037e-6 0 1 -5.87034e-6 0 1 2.2972e-6 0 1 2.9541e-6 0 1 -2.46521e-6 0 1 -2.20848e-6 0 1 -2.89218e-6 0 1 8.78457e-6 0 1 -3.74122e-6 0 1 2.15908e-5 0 1 1.32018e-6 0 1 2.22717e-6 0 1 5.73289e-6 0 1 8.06335e-6 0 1 -1.07149e-5 0 1 1.94511e-6 0 1 3.41434e-6 0 1 -2.97924e-6 0 1 5.496e-6 0 1 -6.58803e-7 0 1 -9.37699e-6 0 1 -4.84696e-5 0 1 -7.32502e-7 0 1 4.75118e-6 0 1 -2.39856e-6 0 1 2.10102e-5 0 1 -2.65043e-6 0 1 6.09756e-6 0 1 -1.4017e-7 0 1 1.94643e-6 0 1 -1.9293e-6 0 1 1.47358e-5 0 1 -2.49581e-6 0 1 8.43341e-6 0 1 5.39479e-6 0 1 -1.14153e-5 0 1 -6.3192e-6 0 1 7.16112e-6 0 1 4.49208e-6 0 1 2.1564e-5 0 1 -1.05497e-5 0 1 1.174e-5 0 1 2.42342e-6 0 1 4.7478e-6 0 1 -1.13647e-5 0 1 3.36836e-6 0 1 -6.04164e-6 0 1 -5.7258e-6 0 1 -6.83882e-6 0 1 -8.0177e-6 0 1 5.35488e-7 0 1 1.56475e-6 0 1 9.73035e-7 0 1 3.36441e-6 0 1 -3.79708e-6 0 1 1.28662e-6 0 1 1.44684e-6 0 1 3.6808e-6 0 1 -2.58104e-6 0 1 7.33654e-6 0 1 -5.67666e-6 0 1 -3.86481e-6 0 1 1.44877e-6 0 1 1.99972e-6 0 1 2.79336e-6 0 1 -1.52778e-6 0 1 -4.05834e-6 0 1 -1.02847e-5 0 1 2.10084e-5 0 1 -1.01974e-5 0 1 2.09674e-5 0 1 7.88917e-6 0 1 3.37662e-6 0 1 8.41567e-6 0 1 -9.84667e-6 0 1 9.71949e-6 0 1 -2.07342e-6 0 1 4.99426e-6 0 1 -3.95498e-6 0 1 2.21351e-6 0 1 1.35913e-6 0 1 -2.01369e-6 0 1 -3.90028e-6 0 1 -5.28765e-6 0 1 -1.31898e-6 0 1 -1.71045e-6 0 1 -1.06608e-5 0 1 5.33291e-6 0 1 1.43887e-5 0 1 7.49677e-6 0 1 1.19014e-5 0 1 -8.75887e-6 0 1 -1.03008e-5 0 1 -4.40925e-6 0 1 6.58441e-6 0 1 5.9566e-6 0 1 7.60757e-6 0 1 -1.29271e-6 0 1 6.83604e-6 0 1 -6.04122e-6 0 1 1.79779e-6 0 1 1.3072e-6 0 1 -5.09996e-6 0 1 1.01904e-5 0 1 -5.49535e-6 0 1 2.63491e-6 0 1 -2.54563e-6 0 1 3.42774e-7 0 1 2.65449e-6 0 1 -1.0181e-5 0 1 1.30576e-5 0 1 -4.21563e-6 0 1 3.26437e-6 0 1 1.58806e-6 0 1 -1.3781e-6 0 1 -1.10292e-6 0 1 -5.16657e-6 0 1 -7.80354e-6 0 1 4.03758e-6 0 1 -2.92737e-6 0 1 2.35707e-4 0 1 1.02695e-5 0 1 -9.90795e-6 0 1 1.91877e-5 0 1 -4.38462e-6 0 1 9.11278e-6 0 1 -3.24408e-6 0 1 5.56558e-6 0 1 -8.61905e-6 0 1 7.16551e-6 0 1 -3.05653e-6 0 1 6.9457e-6 0 1 -1.97173e-6 0 1 -2.36796e-6 0 1 7.19217e-6 0 1 -1.13817e-5 0 1 2.95648e-6 0 1 -1.37787e-5 0 1 -1.22097e-5 0 1 3.66161e-6 0 1 -4.67128e-6 0 1 3.30443e-6 0 1 3.86698e-6 0 1 -5.32422e-7 0 1 -2.14428e-6 0 1 4.1862e-6 0 1 3.00192e-6 0 1 4.90215e-6 0 1 -1.70707e-5 0 1 3.79524e-6 0 1 4.18554e-6 0 1 3.89787e-7 0 1 2.33828e-6 0 1 -3.73619e-6 0 1 -2.27339e-6 0 1 -3.3067e-6 0 1 -5.75374e-6 0 1 1.06335e-5 0 1 -1.26256e-5 0 1 6.98129e-6 0 1 1.21799e-5 0 1 -9.33184e-6 0 1 -2.71156e-6 0 1 6.871e-7 0 1 8.97682e-6 0 1 -1.93843e-5 0 1 1.35018e-5 0 1 -2.74925e-6 0 1 9.42427e-6 0 1 -1.57025e-6 0 1 -8.74073e-6 0 1 2.86238e-6 0 1 -2.86166e-6 0 1 1.74279e-6 0 1 -0.5411533 -0.4567814 0.7060482 -0.5412705 -0.4567207 0.7059976 -0.5417348 -0.4559826 0.7061185 -0.4645269 -0.5343856 0.7061493 -0.4644615 -0.5345349 0.7060794 -0.4646447 -0.5344298 0.7060384 -0.4642059 -0.5348871 0.7059807 -0.3760889 -0.6001896 0.7059247 -0.3767675 -0.5996249 0.7060427 -0.3766632 -0.5996339 0.7060907 -0.3756304 -0.6003822 0.706005 -0.2798208 -0.6505764 0.7060104 -0.2799523 -0.6504435 0.7060808 -0.279838 -0.6504244 0.7061437 -0.2764861 -0.6512324 0.7067191 -0.2801698 -0.6505111 0.7059322 0.9464816 -0.3227578 4.52048e-5 0.9464142 -0.3229554 0 0.9460409 -0.3240468 -7.0458e-4 0.9461568 -0.323708 -7.15249e-4 0.9461568 -0.323708 -7.15205e-4 0.9461568 -0.3237081 -7.15238e-4 0.9465929 -0.3224312 0 0.4367709 -0.8995728 0 -0.8000673 0.5999104 0 -0.8000673 0.5999104 0 -0.8000671 0.5999105 0 -0.9335843 0.3583578 0 -0.9743402 -0.2250806 0 -0.9743402 -0.2250807 1.92974e-7 -0.9743403 -0.2250804 0 -0.7675473 -0.6409924 0 -0.4268684 -0.9043138 0 0.9164748 -0.4000927 0 0.9826772 0.1853253 0 0.7956801 0.6057172 0 0.8071125 0.5903979 0 0.9860147 0.1666591 0 0.8568775 0.5155202 0 0.9173384 0.3981084 0 0.9173333 0.3981204 0 0.9672554 0.2538051 0 0.8122545 -0.5827235 -0.02599996 0.7849417 -0.6195696 0 0.8830922 -0.4691997 0 0.7317607 -0.6815617 0 0.6604162 -0.7507985 0.01233899 0.6934278 -0.7205259 -5.85926e-4 0.7318562 -0.6814591 0 0.7578967 -0.6523747 0 0.7578867 -0.6523863 0 0.05243182 -0.9982661 -0.02675509 0.005241632 -0.9999864 0 0.1835407 -0.9830121 0 0.08589154 -0.9947532 0.05557703 0.1862757 -0.9824976 0 -0.07671827 -0.9970528 0 -0.3449145 -0.9385634 0.01152092 -0.2915866 -0.9565444 0 -0.1754182 -0.984494 0 -0.1735951 -0.9848166 -0.001027822 -0.07672715 -0.9970521 0 -0.03853815 -0.9992572 0 -0.03853791 -0.9992572 0 -0.8214321 -0.5688247 0.0410822 -0.7481212 -0.6630316 -0.02653133 -0.8320052 -0.554768 0 -0.8320052 -0.5547679 0 -0.8320052 -0.554768 0 -0.948974 -0.3153529 -0.001014709 -0.9495382 -0.3136516 0 -0.8788571 -0.4770851 0 -0.8780403 -0.4785858 -9.52372e-4 -0.831967 -0.5548253 0 -0.8051599 -0.5930578 0 -0.8051427 -0.5930814 0 -0.9833369 -0.181793 0 -0.9744561 -0.2245785 0 -0.974456 -0.2245784 0 -0.9744561 -0.2245784 0 -0.9833337 -0.1818102 0 -0.9775193 -0.210668 0.008669435 -0.9955773 -0.09300798 -0.01324367 -0.9925448 -0.1218813 0 -0.9536103 0.301044 0 -0.9536102 0.3010442 0 -0.9536103 0.3010441 0 -0.838278 0.5452426 -7.20543e-4 -0.8375822 0.5463114 0 -0.9207437 0.3901682 0 -0.7552593 0.655426 0 -0.5900633 0.807357 0 -0.8001106 0.5998526 0 -0.8001106 0.5998526 0 -0.8001105 0.5998526 0 -0.7552372 0.6554515 0 -0.7261461 0.6874227 -0.01272886 -0.6933653 0.7205862 0 -0.6576554 0.7533189 0 -0.5918666 0.8060349 0.001327216 -0.5900377 0.8073757 7.72091e-5 -0.1417255 0.989906 0 -0.09647107 0.9953354 -9.93944e-4 -0.05244201 0.9983351 0.02402257 0.0413841 0.9991434 0 0.2610792 0.9652981 0.006111741 0.2489863 0.968507 0 0.1308305 0.9914048 0 0.08447694 0.9963443 -0.01271939 0.04138505 0.9991434 0 -0.005029737 0.9999874 0 -0.005026102 0.9999874 0 -0.7675409 -0.6410001 0 -0.6531738 -0.7572082 0 -0.653994 -0.7564997 -9.96012e-5 -0.4709144 -0.8821789 0 -0.4709289 -0.8821713 0 -0.4268972 -0.9043002 0 -0.3770356 -0.9261987 -5.50488e-4 -0.3755391 -0.9268066 0 -0.6541721 -0.7563458 0 -0.5084441 -0.861095 0 -0.5475929 -0.8367272 -0.005466341 -0.5082965 -0.8610993 -0.01195269 -0.5055527 -0.8627212 -0.01134771 0.18608 -0.9825347 1.10688e-4 0.1865628 -0.982443 0 0.3120599 -0.9500625 0 0.3561064 -0.9343671 -0.01209545 0.6252095 -0.7804571 0 0.6251949 -0.7804688 0 0.5167969 -0.8561081 0 0.5187695 -0.8549143 -7.97468e-5 0.5173354 -0.8557823 -9.11705e-4 0.4369773 -0.8994726 0 0.3962459 -0.9181445 0 0.3962469 -0.9181441 0 0.9649153 -0.2625614 0 0.9915173 -0.1299715 -9.88691e-4 0.9918615 -0.127321 -6.20141e-4 0.8771724 -0.4801242 0.007039368 0.9164728 -0.400097 0 0.9373447 -0.3484035 0 0.9525443 -0.304159 -0.01211589 0.964908 -0.2625886 0 0.9743741 -0.2249336 0 0.9744656 -0.2245367 0 0.9918645 0.1272988 0 0.9622057 0.2722202 -0.00751698 0.9815598 0.1911382 0.002577006 0.986014 0.1666629 0 0.9919053 0.1269801 0 0.9987458 0.0500645 -7.81758e-4 0.9988193 0.04857957 -2.69635e-4 0.9987463 0.05005788 0 0.9916573 -0.1289025 0 0.719185 0.6948181 -9.12185e-4 0.7180535 0.6959878 -3.40029e-4 0.8468252 0.5318455 -0.005235254 0.7945708 0.6071437 0.005838215 0.8071013 0.5904131 0 0.7782955 0.6278983 0 0.7783572 0.6278217 0 0.5127652 0.8585289 0 0.3350974 0.9421835 0 0.3351116 0.9421785 0 0.4293057 0.9031593 0 0.3867578 0.9218429 -0.02498275 0.7193859 0.6946107 0 0.5834015 0.812184 0 0.5847846 0.8111884 -6.62445e-4 0.5836259 0.8120223 -8.61112e-4 0.512523 0.8586735 0 0.4678038 0.8838323 0 0.467796 0.8838366 0 -0.3562138 0.9344045 0 -0.4797848 0.8770287 -0.02504885 -0.4385267 0.8987182 0 -0.5897895 0.8075571 0 -0.1417348 0.9899047 0 -0.2711217 0.9625452 0 -0.2693349 0.9630467 -6.16426e-5 -0.2709884 0.9625822 -9.14036e-4 -0.355897 0.9345253 0 -0.3993096 0.9168161 0 -0.3993112 0.9168155 0 -0.9767883 0.2138149 -0.0129593 -0.9767885 0.2138136 -0.01296514 -0.9767885 0.2138137 -0.0129652 -0.976051 0.2172094 -0.01202356 -0.9850419 0.1722247 -0.005589306 -0.8971322 0.4406739 0.03099006 -0.9335525 0.3584405 -6.22295e-4 -0.9536408 0.3009476 0 -0.9536408 0.3009476 0 -0.9536408 0.3009476 0 -0.9658868 0.2589646 0 -0.9659085 0.2588839 0 -0.9758234 0.2185607 0 -0.9992019 0.03994435 0 -0.9992173 0.03956025 1.67345e-4 -0.9992893 0.03769683 0 -0.9925467 -0.1218654 0 -0.3972693 0.9177021 -5.24491e-5 -0.3972588 0.9177066 0 -0.3985258 0.9171569 -7.20483e-4 -0.3978942 0.9174313 0 -0.9472346 -0.3205411 0 -0.8814384 -0.4722993 0 -0.8814329 -0.4723095 0 -0.791889 -0.6106652 0 -0.7918953 -0.6106569 0 -0.6805036 -0.7327448 0 -0.6805164 -0.7327328 0 -0.5504398 -0.8348749 0 -0.4056846 -0.9140132 0 -0.4056849 -0.914013 0 -0.2496432 -0.968338 0 -0.2496466 -0.9683371 0 -0.08690112 -0.996217 0 -0.08690005 -0.9962171 0 0.07830798 -0.9969293 0 0.07830703 -0.9969293 0 0.2412643 -0.9704595 0 0.2412614 -0.9704602 0 0.3977922 -0.9174757 0 0.3977971 -0.9174736 0 0.5434141 -0.8394648 0 0.5434027 -0.8394722 0 0.6740299 -0.7387042 0 0.6740235 -0.73871 0 0.7863995 -0.6177183 0 0.7863933 -0.6177263 0 0.87755 -0.479485 0 0.8775395 -0.4795047 0 0.9443742 -0.3288733 0 0.9443741 -0.3288731 0 0.9856926 -0.1685535 0 0.9856905 -0.1685659 0 0.9999905 -0.004368126 0 0.9999905 -0.004355192 0 0.9870669 0.1603096 0 0.987069 0.1602969 0 0.9472389 0.3205286 0 0.947235 0.3205401 0 0.8814321 0.4723108 0 0.8814375 0.4723008 0 0.7918782 0.6106791 0 0.7918785 0.6106787 0 0.6804828 0.7327642 0 0.5504811 0.8348477 0 0.5504693 0.8348554 0 0.4056095 0.9140466 0 0.4056143 0.9140444 0 0.2496007 0.9683489 0 0.2495977 0.9683497 0 0.08712011 0.9961979 0 0.08711904 0.9961979 0 -0.07839506 0.9969224 0 -0.07839411 0.9969225 0 -0.2413071 0.9704489 0 -0.2413073 0.9704489 0 -0.397751 0.9174934 0 -0.3977514 0.9174934 0 -0.5432871 0.839547 0 -0.543293 0.8395432 0 -0.6741484 0.738596 0 -0.6741422 0.7386017 0 -0.786361 0.6177673 0 -0.7863674 0.6177593 0 -0.8775447 0.4794951 0 -0.8775395 0.4795047 0 -0.9443781 0.3288617 0 -0.9443741 0.3288731 0 -0.9856195 0.1689802 0 -0.9856151 0.1690052 0 -0.9999924 0.003915846 0 -0.9999923 0.00392878 0 -0.987069 -0.1602964 0 -0.987067 -0.160309 0 -0.9472386 -0.3205297 0 0.8806294 0.4738059 0 0.9479221 0.3185023 0 0.9479221 0.3185024 0 0.9881227 0.1536669 0 0.9881207 0.1536797 0 0.9998847 -0.01519244 0 0.9998848 -0.01517921 0 0.9828306 -0.1845108 0 0.982833 -0.1844979 0 0.9377149 -0.3474059 0 0.865318 -0.5012233 0 0.8653124 -0.5012331 0 0.7680756 -0.6403594 0 0.7680758 -0.6403589 0 0.6490652 -0.7607328 0 0.6490586 -0.7607384 0 0.5110729 -0.8595374 0 0.5110789 -0.8595339 0 0.3586446 -0.9334742 0 0.358649 -0.9334725 0 0.1951744 -0.9807686 0 0.1951746 -0.9807686 0 0.02724516 -0.9996289 0 0.02724552 -0.9996289 0 -0.1424852 -0.9897969 0 -0.1424871 -0.9897966 0 -0.3076447 -0.9515014 0 -0.3076408 -0.9515026 0 -0.46375 -0.8859661 0 -0.4637612 -0.8859602 0 -0.6070429 -0.794669 0 -0.607056 -0.7946591 0 -0.7325364 -0.680728 0 -0.7325431 -0.6807206 0 -0.8371688 -0.5469446 0 -0.8371629 -0.5469537 0 -0.9175702 -0.3975739 0 -0.9175655 -0.3975847 0 -0.9714645 -0.2371851 0 -0.9714707 -0.23716 0 -0.9975995 -0.06924808 0 -0.9975995 -0.06924802 0 -0.994983 0.1000439 0 -0.9949845 0.1000307 0 -0.9636837 0.2670466 0 -0.9636872 0.2670341 0 -0.904808 0.4258201 0 -0.9048081 0.4258197 0 -0.8196191 0.572909 0 -0.8196191 0.5729088 0 -0.7111601 0.7030301 0 -0.7111535 0.7030369 0 -0.5822174 0.8130332 0 -0.4362084 0.8998458 0 -0.4362136 0.8998432 0 -0.2780717 0.9605604 0 -0.2780684 0.9605613 0 -0.1116603 0.9937465 0 -0.1116588 0.9937466 0 0.05788987 0.998323 0 0.05789071 0.998323 0 0.2257874 0.9741767 0 0.2257905 0.9741759 0 0.3870773 0.9220473 0 0.387082 0.9220454 0 0.5374276 0.8433099 0 0.6723371 0.7402452 0 0.6723436 0.7402392 0 0.787451 0.6163772 0 0.7874447 0.6163853 0 0.8806293 0.473806 0 2.17373e-6 0 -1 -4.8564e-6 0 -1 -2.17761e-6 0 -1 -4.84574e-6 0 -1 2.17909e-6 0 -1 2.18631e-6 0 -1 -1.0962e-6 0 -1 -1.65003e-6 0 -1 2.3939e-6 0 -1 -1.37884e-7 0 -1 -1.18769e-6 0 -1 1.11172e-6 0 -1 -1.18253e-6 0 -1 -1.17116e-6 0 -1 4.4049e-6 0 -1 -4.3305e-6 0 -1 -2.48479e-6 0 -1 2.51367e-6 0 -1 1.27146e-6 0 -1 3.22258e-7 0 -1 1.03251e-6 0 -1 -5.11139e-7 0 -1 1.51856e-6 0 -1 -2.00173e-6 0 -1 1.9818e-6 0 -1 -5.53759e-6 0 -1 1.95823e-6 0 -1 -3.87513e-6 0 -1 1.16583e-5 0 -1 -4.85267e-6 0 -1 0.6560524 -0.7547155 0 -0.6560524 0.7547155 0 -0.8101205 -0.5862636 0 -0.58731 0.8093263 0.007621347 0.66323 0.7484158 0 0.5234902 0.8520317 0 0.5234895 0.8520322 0 0.3678098 0.9299011 0 0.3678097 0.9299012 0 0.1995334 0.9798911 0 0.02766442 0.9996173 0 0.02766442 0.9996173 0 -0.1464575 0.9892171 0 -0.1464574 0.9892171 0 -0.3159764 0.9487671 0 -0.3159762 0.9487672 0 -0.4762362 0.8793175 0 -0.476236 0.8793175 0 -0.6222994 0.7827794 0 0.8101205 0.5862636 0 0.587288 -0.8093422 0.007621467 -0.6632205 -0.7484241 0 -0.5235027 -0.852024 0 -0.523502 -0.8520244 0 -0.3677949 -0.929907 0 -0.3677948 -0.929907 0 -0.1995334 -0.9798911 0 -0.02768158 -0.9996168 0 -0.02768158 -0.9996169 0 0.1464575 -0.9892171 0 0.1464574 -0.9892171 0 0.3159919 -0.9487619 0 0.3159917 -0.948762 0 0.4762362 -0.8793175 0 0.476236 -0.8793175 0 0.6222892 -0.7827875 0 0.6560533 -0.7547147 0 0.7477907 -0.6639347 0 0.7477906 -0.6639347 0 0.8520984 -0.5233818 0 0.852098 -0.5233823 0 0.9300936 -0.3673228 0 0.9300936 -0.3673226 0 0.9796788 -0.2005729 0 0.9796791 -0.2005717 0 0.9996282 -0.02726811 0 0.9891806 0.1467034 0 0.9891805 0.1467043 0 0.9487076 0.3161548 0 0.9487077 0.3161547 0 0.8791902 0.476471 0 0.8791912 0.4764695 0 0.8101206 0.5862633 0 0.7836043 0.6212486 0.003809869 0.7555636 0.6550753 0 0.6632304 0.7484154 0 -0.6560533 0.7547147 0 -0.7477907 0.6639347 0 -0.7477906 0.6639347 0 -0.8520984 0.5233818 0 -0.852098 0.5233823 0 -0.9300936 0.3673228 0 -0.9300936 0.3673226 0 -0.9796782 0.2005763 0 -0.9796784 0.2005751 0 -0.9996282 0.02726763 0 -0.9996282 0.02726763 0 -0.9891802 -0.1467058 0 -0.9891801 -0.1467069 0 -0.9487094 -0.3161495 0 -0.8791902 -0.476471 0 -0.8791912 -0.4764695 0 -0.8101206 -0.5862633 0 -0.7836043 -0.6212486 0.003813266 -0.7555636 -0.6550753 0 -0.6632207 -0.7484239 0 9.89081e-6 0 1 5.60588e-6 0 1 1.1763e-5 0 1 -5.60991e-6 0 1 -1.17387e-5 0 1 -1.40664e-6 0 1 -1.03412e-6 0 1 -2.82014e-6 0 1 2.82652e-6 0 1 -2.9162e-6 0 1 5.68751e-6 0 1 -1.4516e-6 0 1 2.89593e-6 0 1 -5.75771e-6 0 1 1.14548e-5 0 1 -5.74501e-6 0 1 -1.13947e-5 0 1 1.16149e-5 0 1 -1.12816e-5 0 1 -1.1803e-5 0 1 1.10358e-5 0 1 -6.1065e-6 0 1 -3.07851e-6 0 1 5.37449e-6 0 1 -7.77208e-7 0 1 6.56237e-7 0 1 -2.6059e-6 0 1 5.16956e-6 0 1 -5.08295e-6 0 1 -1.00652e-5 0 1 9.98801e-6 0 1 7.57539e-7 0 -1 -4.93587e-7 0 -1 -1.75121e-7 0 -1 2.85858e-6 0 -1 -1.03611e-5 0 -1 7.59624e-6 0 -1 2.44973e-6 0 -1 -2.82665e-6 0 -1 2.8278e-6 0 -1 -0.9891754 -0.1467375 0 -0.7833867 -0.6215348 0 -0.7833853 -0.6215365 0 -0.367243 -0.9301251 0 -0.3677876 -0.92991 -1.64907e-4 -0.622374 0.7827202 0 -0.929845 0.3679518 0 -0.9298568 0.367922 3.75245e-6 -0.9298756 0.3678743 0 -0.9891756 -0.1467363 0 0.7834017 0.6215158 0 0.3677626 0.9299198 0 0.367762 0.92992 0 -0.1475293 0.9890577 0 -0.1468122 0.9891644 -1.19945e-4 -0.146415 0.9892234 0 -0.6223725 0.7827212 0 -0.3687723 -0.9295199 0 0.1468095 -0.9891648 0 0.1468097 -0.9891648 0 0.6214351 -0.7834657 0 0.621436 -0.783465 0 0.9300677 -0.3673883 0 0.9300683 -0.3673866 0 0.989188 0.1466529 0 0.9891756 0.1467371 1.31201e-5 0.9891673 0.1467922 0 0.7834026 0.6215146 0 6.38309e-6 0 -1 3.19065e-6 0 -1 -1.52421e-7 0 -1 -2.55394e-6 0 -1 -4.0831e-6 0 -1 7.53448e-7 0 -1 2.70944e-6 0 -1 -2.86395e-6 0 -1 -1.46355e-6 0 -1 9.68842e-7 0 -1 -1.28116e-7 0 -1 6.31651e-7 0 -1 -4.93318e-6 0 -1 -7.77876e-7 0 -1 1.77668e-6 0 -1 3.58912e-6 0 -1 2.09415e-6 0 -1 -9.01239e-7 0 -1 8.02324e-7 0 -1 -3.23081e-7 0 -1 -3.21353e-6 0 -1 5.14848e-6 0 -1 -1.42372e-6 0 -1 5.8947e-7 0 -1 -2.9503e-6 0 -1 2.5997e-7 0 -1 1.21962e-6 0 -1 -7.37625e-6 0 -1 3.03988e-6 0 -1 -1.22766e-6 0 -1 1.1928e-6 0 -1 1.53736e-6 0 -1 -1.7451e-6 0 -1 -8.55087e-7 0 -1 3.25679e-6 0 -1 2.14552e-6 0 -1 -1.2031e-6 0 -1 1.08802e-6 0 -1 -1.18471e-6 0 -1 1.41471e-5 0 -1 -1.59563e-6 0 -1 1.11136e-5 0 -1 6.24688e-6 0 -1 -1.52335e-6 0 -1 -4.71357e-7 0 -1 3.88179e-7 0 -1 1.20816e-6 0 -1 -1.39946e-6 0 -1 -1.59585e-6 0 -1 -4.30545e-6 0 -1 4.86025e-6 0 -1 -8.54097e-7 0 -1 4.89555e-7 0 -1 -9.90225e-7 0 -1 4.62832e-6 0 -1 -4.47824e-6 0 -1 -6.47273e-7 0 -1 -3.06565e-7 0 -1 -3.50191e-7 0 -1 -9.19896e-7 0 -1 8.99091e-7 0 -1 1.44556e-6 0 -1 3.04607e-6 0 -1 -5.35717e-7 0 -1 -2.55009e-6 0 -1 7.37035e-6 0 -1 -2.0385e-6 0 -1 -2.9693e-6 0 -1 -4.90904e-6 0 -1 -5.20648e-7 0 -1 -1.3999e-6 0 -1 6.04075e-7 0 -1 -2.03875e-6 0 -1 6.59979e-7 0 -1 3.91751e-6 0 -1 -1.70663e-6 0 -1 3.39309e-7 0 -1 -6.2475e-6 0 -1 -2.71938e-7 0 -1 -8.16524e-7 0 -1 1.71955e-6 0 -1 -1.07626e-6 0 -1 -0.6376894 -0.7702741 0.005490005 -0.8110179 -0.5849249 -0.01062434 -0.5452626 -0.8382652 0 -0.4697846 -0.8808298 -0.05866283 -0.6343842 -0.7729984 0.005502581 0.1620862 -0.9862666 -0.03172379 0.0694189 -0.9975877 0 -0.2056941 -0.9786163 0 -0.1143038 -0.9914025 -0.06368464 -0.2956184 -0.9553062 0 -0.8222131 -0.5691797 0 -0.9676464 -0.2523102 0 -0.9676464 -0.2523102 0 -0.9934519 0.1142519 0 -0.993452 0.1142512 0 -0.8850434 0.4655087 0 -0.8850431 0.4655092 0 -0.656685 0.754165 0 -0.6566852 0.7541649 0 -0.3406584 0.9401872 0 -0.3406577 0.9401875 0 0.02176618 0.9997631 0 0.02176618 0.9997632 0 0.3820031 0.9241611 0 0.3820026 0.9241613 0 0.6899836 0.7238251 0 0.6899843 0.7238244 0 0.9047509 0.4259411 0 0.9047508 0.4259413 0 0.9975303 0.0702393 0 0.9975302 0.07023966 0 0.9555403 -0.2948605 0 0.9555407 -0.2948597 0 0.7845941 -0.6200098 0 0.6007421 -0.799443 0 0.507082 -0.8614624 -0.02739489 0.4422417 -0.896896 0 0.253295 -0.9673891 0 1.60125e-6 0 1 -7.91139e-7 0 1 1.67388e-6 0 1 -6.70354e-6 0 1 1.38596e-5 0 1 -1.56014e-6 0 1 2.85119e-6 0 1 1.1417e-6 0 1 -3.83342e-6 0 1 1.94704e-6 0 1 3.08868e-7 0 1 6.1823e-6 0 1 -2.24433e-6 0 1 -1.07182e-6 0 1 -4.92669e-6 0 1 -1.32956e-6 0 1 2.05479e-7 0 1 6.40533e-5 0 1 2.66485e-6 0 1 -6.06208e-6 0 1 5.03123e-7 0 1 8.42205e-6 0 1 -1.60023e-6 0 1 -3.14043e-6 0 1 -5.38677e-5 0 1 1.56094e-6 0 1 1.89245e-6 0 1 -3.66989e-6 0 1 -1.54166e-6 0 1 2.06116e-6 0 1 -9.71666e-7 0 1 -5.04568e-6 0 1 1.29122e-6 0 1 1.14574e-6 0 1 -3.78962e-7 0 1 -2.37932e-6 0 1 7.57943e-7 0 1 1.49136e-6 0 1 4.39748e-6 0 1 -2.13979e-6 0 1 -1.45579e-6 0 1 2.92499e-6 0 1 -2.4795e-6 0 1 -1.06838e-5 0 1 1.36935e-6 0 1 -7.14204e-6 0 1 -2.53455e-7 0 1 2.4843e-6 0 1 -6.75877e-6 0 1 2.4656e-5 0 1 -3.38021e-6 0 1 -5.26023e-7 0 1 1.59221e-6 0 1 -1.84393e-6 0 1 5.26023e-6 0 1 -1.82818e-6 0 1 -2.74051e-6 0 1 1.4537e-6 0 1 2.71621e-5 0 1 -8.14046e-7 0 1 3.64559e-6 0 1 7.79952e-7 0 1 4.27073e-7 0 1 -1.54927e-6 0 1 -1.02736e-6 0 1 5.66322e-6 0 1 -9.88517e-7 0 1 5.42124e-6 0 1 -1.31893e-6 0 1 -4.22019e-6 0 1 2.1648e-6 0 1 -9.58001e-7 0 1 2.11612e-6 0 1 6.07103e-7 0 1 -3.20982e-6 0 1 1.64117e-6 0 1 5.93261e-6 0 1 4.95843e-7 0 1 -1.19134e-6 0 1 1.57098e-6 0 1 -2.01613e-6 0 1 1.21889e-6 0 1 -1.12633e-6 0 1 -8.11853e-5 0 1 7.12318e-7 0 1 -5.70745e-7 0 1 1.81876e-6 0 1 -1.05828e-6 0 1 -2.68575e-6 0 1 4.19533e-6 0 1 1.00299e-6 0 1 9.32557e-6 0 1 -1.78378e-6 0 1 -2.84863e-7 0 1 4.9298e-6 0 1 -1.86252e-5 0 1 9.54723e-7 0 1 -2.13445e-7 0 1 4.06583e-7 0 1 -1.12046e-6 0 1 9.17984e-7 0 1 2.70229e-6 0 1 -9.8705e-6 0 1 1.75338e-6 0 1 -2.0602e-6 0 1 -1.26744e-6 0 1 3.97501e-6 0 1 -2.34958e-6 0 1 -2.43551e-6 0 1 2.00835e-6 0 1 -2.81634e-6 0 1 -1.47581e-6 0 1 7.55184e-6 0 1 -2.55723e-6 0 1 1.42954e-6 0 1 5.11289e-6 0 1 -2.04284e-6 0 1 -2.14818e-7 0 1 1.87688e-6 0 1 9.87362e-5 0 1 -2.60514e-7 0 1 -1.36528e-6 0 1 6.26906e-7 0 1 -5.70839e-7 0 1 4.0451e-7 0 1 -6.28836e-6 0 1 -4.07325e-6 0 1 6.11098e-6 0 1 -3.73368e-6 0 1 6.538e-6 0 1 -2.65229e-6 0 1 7.23731e-7 0 1 -1.76193e-5 0 1 1.08932e-5 0 1 4.4835e-6 0 1 6.56382e-7 0 1 1.17142e-6 0 1 -4.33035e-7 0 1 -1.05886e-5 0 1 -8.85294e-7 0 1 7.86837e-7 0 1 -1.28813e-5 0 1 -1.17133e-6 0 1 3.18826e-6 0 1 -1.53326e-6 0 1 -1.14934e-6 0 1 1.25813e-6 0 1 -1.11617e-5 0 1 5.48246e-7 0 1 -1.50813e-6 0 1 7.17056e-7 0 1 -3.05128e-7 0 1 1.80095e-6 0 1 -2.61163e-6 0 1 -2.79842e-6 0 1 -6.48374e-6 0 1 1.40734e-6 0 1 -1.06038e-6 0 1 -7.0881e-7 0 1 1.42968e-6 0 1 -7.90779e-7 0 1 -6.17162e-6 0 1 5.88887e-6 0 1 -6.02301e-6 0 1 -5.83158e-6 0 1 6.25438e-6 0 1 -6.33104e-6 0 1 3.20119e-6 0 1 3.23767e-6 0 1 4.21159e-7 0 1 -1.25544e-7 0 1 -3.47299e-6 0 1 1.32539e-6 0 1 7.19549e-6 0 1 -2.58275e-6 0 1 5.03383e-6 0 1 4.97275e-6 0 1 -4.90745e-6 0 1 -1.58613e-5 0 1 4.84093e-6 0 1 0.732899 -0.4881424 0.4738946 -0.6754428 -0.3114966 0.6683914 -0.04619944 0.9132995 0.4046599 -0.1960407 0.8932027 0.4046693 -0.1959937 0.8936032 0.4038065 -0.340615 0.8491129 0.4037188 -0.3405816 0.848853 0.404293 -0.4758004 0.7812367 0.4040833 -0.4758965 0.7818041 0.4028711 -0.5981568 0.6927418 0.4028863 -0.5980164 0.6924268 0.4036355 -0.7360284 0.5394095 0.4090229 -0.727778 0.5434522 0.4183288 -0.7101488 0.5412311 0.4502863 -0.6229554 0.4851524 0.6136398 -0.6246127 0.4853961 0.6117594 -0.7448406 0.5302748 0.4049952 -0.7375271 0.5423264 0.4024125 -0.7344711 0.5478928 0.4004571 -0.7299166 0.5589509 0.3934408 -0.7271359 0.5728961 0.3782373 -0.7280459 0.5934149 0.3432316 -0.7316612 0.607889 0.3084526 -0.6899005 0.6193047 0.374832 -0.6615509 0.631288 0.4047541 -0.8427529 -0.3533232 0.4061162 -0.8374383 -0.3793138 0.3934696 -0.8404983 -0.3633461 0.4019234 -0.842473 -0.3570966 0.4033876 -0.8403819 -0.3568214 0.4079666 -0.8344475 -0.3625628 0.4150247 -0.8059173 -0.3720537 0.4605144 -0.7965401 -0.2603002 0.545681 -0.7815691 -0.3312346 0.5286147 -0.3942657 -0.8264287 0.4019579 -0.5251844 -0.7499834 0.4021273 -0.5247434 -0.7496938 0.4032415 -0.6407434 -0.6532222 0.4034212 -0.6405271 -0.6531208 0.4039285 -0.739418 -0.5386547 0.4038716 -0.7395856 -0.5386994 0.403505 -0.7880434 -0.4640139 0.4045723 -0.8423757 -0.4216557 0.3355737 -0.8539545 -0.4390974 0.2792047 -0.8386864 -0.3991459 0.3705235 -0.259934 -0.9042603 0.3387443 -0.2644172 -0.8759312 0.4035195 -0.3938306 -0.8260242 0.403214 -0.08648848 -0.7818537 0.6174339 -0.0859605 -0.8761581 0.4742973 -0.08194172 -0.8944035 0.4396908 -0.07793444 -0.9015522 0.4255936 -0.06374657 -0.9124539 0.4041835 -0.07950723 -0.9151617 0.395168 -0.09094208 -0.9184042 0.3850496 -0.1068128 -0.9266039 0.3605502 -0.1065164 -0.9263156 0.3613778 -0.1631366 -0.9006489 0.4027633 -0.1934273 -0.8946458 0.4027342 0.6928558 -0.6006051 0.3990292 0.6937729 -0.5867075 0.4176765 0.690162 -0.5737717 0.440979 0.6902383 -0.5735927 0.4410924 0.6902281 -0.5733174 0.4414662 0.7450125 -0.5306347 0.4042071 0.7551097 -0.5161177 0.4042671 0.724383 -0.5832801 0.3674966 0.7039113 -0.5848346 0.4030849 0.7543092 -0.5172809 0.404275 0.7639832 -0.5068202 0.3993284 0.9067769 0.1217914 0.4036369 0.9145027 -0.02915048 0.4035286 0.9144982 -0.02915096 0.4035387 0.8972537 -0.1792821 0.403477 0.8971732 -0.1792257 0.4036813 0.855373 -0.3244488 0.4038196 0.8555363 -0.324594 0.4033566 0.8083478 -0.4280722 0.4041386 0.8294655 -0.4836475 0.2794138 0.8016671 -0.4896361 0.3429087 0.7764619 -0.4985017 0.3854908 0.8663098 0.3107428 0.3910834 0.8918846 0.2947329 0.3430373 0.9175212 0.2826377 0.2797694 0.8844016 0.2334311 0.4041582 0.9068707 0.1217713 0.4034322 0.8139521 0.4207902 0.4005217 0.8241418 0.4123283 0.3882986 0.8239619 0.4124458 0.3885556 0.8446364 0.3505497 0.404604 0.8534097 0.3287087 0.4045277 0.8259093 0.309356 0.4713521 0.8525058 0.3303696 0.4050799 0.8180152 0.4094613 0.4039711 0.7995901 0.3879192 0.4584477 0.8017897 0.4016208 0.4425315 0.8056622 0.4067584 0.4306462 0.8039582 0.4019142 0.4383106 0.8039583 0.4019143 0.4383105 0.8039582 0.4019142 0.4383106 0.1378689 0.901082 0.4111487 0.1324391 0.9082818 0.396843 0.1209961 0.9144702 0.3861399 -0.06069117 0.9439972 0.3243239 0.01573002 0.9150666 0.402996 0.1046082 0.909653 0.4019808 0.09225678 0.9450796 0.3135495 0.1097173 0.9227581 0.3694316 0.1468979 0.9034609 0.4027152 0.1292104 0.8965483 0.4236813 0.117433 0.8812266 0.4578746 0.0926944 0.7778343 0.621596 -0.7428361 0.5331945 0.4048433 -0.7436437 0.5322484 0.4046056 -0.7904108 0.4609389 0.4034676 -0.7904505 0.4609 0.4034346 -0.8555122 0.3245363 0.4034541 -0.8554933 0.3245785 0.4034602 -0.8555036 0.3244677 0.4035276 0.1448863 0.9031404 0.4041603 0.2562141 0.8785407 0.4031383 0.2527732 0.8793575 0.4035297 0.3938739 0.8259508 0.4033223 0.3939911 0.8258604 0.4033929 0.3939012 0.8258965 0.4034069 0.2525846 0.8794756 0.4033902 0.8095281 0.4175245 0.4127197 0.8106118 0.4238656 0.4040379 0.7396431 0.5385299 0.4036257 0.7395862 0.538695 0.4035096 0.6408587 0.6530511 0.4035151 0.6407074 0.6533197 0.4033206 0.5221266 0.751532 0.4032166 0.52468 0.7496086 0.403482 0.5247715 0.7495788 0.4034188 0.5304028 0.7458317 0.4029987 0.7105481 -0.5879747 0.3865324 0.6937217 -0.5962919 0.4039632 0.5979631 -0.6925239 0.4035479 0.5981042 -0.6924679 0.4034349 0.4759501 -0.781472 0.4034515 0.3404077 -0.8491853 0.4037411 0.3406354 -0.8491654 0.403591 0.342344 -0.8483971 0.403761 0.475572 -0.7815701 0.4037073 -0.07220208 -0.9070659 0.4147508 -0.06379151 -0.9124445 0.4041977 0.04678565 -0.9138774 0.4032856 0.04622179 -0.9137413 0.403659 0.1959924 -0.8936596 0.4036827 0.1961326 -0.893646 0.4036446 0.1962643 -0.8935784 0.4037302 0.3413897 -0.8487715 0.4037822 -0.8744071 -0.2694427 0.403501 -0.8744163 -0.2693605 0.4035357 -0.8744509 -0.2692857 0.4035108 -0.8453614 -0.3487764 0.4046225 -0.8463254 -0.3467346 0.4043621 -0.9068342 -0.1218445 0.403492 -0.9068223 -0.1218439 0.4035189 -0.9068396 -0.1218006 0.4034932 -0.9068377 -0.1215264 0.40358 -0.9145135 0.02915012 0.4035039 -0.91452 0.02912163 0.4034913 -0.8972608 0.1792437 0.4034783 -0.8972287 0.1793098 0.4035205 -0.8555437 0.3243641 0.4035258 -3.17452e-6 0 -1 -5.87089e-6 0 -1 6.2729e-6 0 -1 5.9138e-6 0 -1 0.420199 0.8126138 -0.4038463 -0.9139583 -0.04259532 -0.4035665 -0.05387234 -0.8956829 -0.441418 -0.0672419 -0.9016737 -0.4271572 -0.0256837 -0.9119548 -0.4094859 -0.0730977 -0.9022783 -0.4249126 -0.08505851 -0.904913 -0.4170101 -0.09330922 -0.90606 -0.4127332 -0.116176 -0.9069424 -0.404918 -0.1066782 -0.9099625 -0.4007343 -0.09822613 -0.9128685 -0.396261 -0.08734709 -0.91851 -0.3856294 -0.07112342 -0.9328082 -0.3532854 -0.06982636 -0.9349967 -0.3477147 0.07915544 -0.9115781 -0.4034353 0.07903474 -0.9116643 -0.4032642 -0.005518257 -0.9145978 -0.4043272 0.2245326 -0.8870946 -0.4032972 0.2254947 -0.8867409 -0.4035379 0.07788401 -0.9116656 -0.403485 0.364277 -0.839432 -0.4033069 0.3640623 -0.8396483 -0.40305 0.2247581 -0.8871793 -0.402985 0.6718851 -0.6202451 -0.4048042 0.6110413 -0.6808544 -0.4038141 0.6108849 -0.6808772 -0.4040125 0.4937106 -0.7700499 -0.4040706 0.4937834 -0.7700402 -0.4040003 0.4939752 -0.7698877 -0.4040565 0.3630854 -0.8395843 -0.4040635 0.7267066 -0.5858837 -0.3586612 0.7334365 -0.6033585 -0.3130966 0.7294459 -0.5821479 -0.359183 0.7297278 -0.5676837 -0.3810939 0.7322989 -0.5559709 -0.3932364 0.7346652 -0.549453 -0.3979554 0.7344399 -0.5426875 -0.4075395 0.7247345 -0.5517197 -0.4127534 0.7156193 -0.5589185 -0.4189263 0.6986583 -0.5693969 -0.433202 0.7036049 -0.5671336 -0.428135 0.6857933 -0.6006187 -0.4110288 0.6718619 -0.6203184 -0.4047305 0.61401 -0.688556 -0.3858528 0.6662343 -0.6255017 -0.4060538 0.6677617 -0.6238481 -0.4060887 0.2247217 -0.8876723 -0.4019182 0.3641794 -0.840106 -0.4019891 0.3637852 -0.8396798 -0.4032348 0.494067 -0.7702612 -0.4032313 0.4936439 -0.7699419 -0.4043578 0.6109188 -0.6806658 -0.4043172 -0.0102325 -0.914314 -0.404877 0.01264011 -0.9142822 -0.4048807 0.08021241 -0.9181119 -0.3881194 0.08223623 -0.9111176 -0.4038591 0.2242209 -0.8869599 -0.4037661 -0.748902 0.4949728 -0.4406219 -0.7474415 0.5089187 -0.4270049 -0.7757105 0.4795319 -0.4102713 -0.7892192 0.4620266 -0.4045547 -0.7451601 0.5138075 -0.4251335 -0.7412137 0.5263513 -0.4166012 -0.7378938 0.5346387 -0.4119154 -0.729502 0.5519627 -0.4039358 -0.7344144 0.547455 -0.4011589 -0.740862 0.5419108 -0.3968077 -0.7530313 0.5340865 -0.384312 -0.7715932 0.5278546 -0.3549841 -0.7753697 0.527823 -0.3467054 -0.8282825 0.3885484 -0.4037058 -0.82903 0.3870641 -0.403597 -0.8289682 0.3871028 -0.4036872 -0.829232 0.3866915 -0.4035394 -0.8804389 0.2489948 -0.4035207 -0.8804693 0.2489746 -0.403467 -0.9089704 0.1045979 -0.4035246 -0.9287636 0.1449695 -0.3411481 -0.9120547 0.06782728 -0.4044203 -0.8735071 -0.2708253 -0.4045232 -0.8953186 -0.188749 -0.4034582 -0.8952838 -0.1886395 -0.4035868 -0.8952488 -0.1887292 -0.4036225 -0.9139616 -0.04259836 -0.4035587 -0.8373742 -0.3642167 -0.4076161 -0.8442296 -0.3599691 -0.3971129 -0.8516296 -0.3521192 -0.3882513 -0.8701093 -0.3362812 -0.3603123 -0.8908892 -0.3331743 -0.3087254 -0.8662847 -0.3411018 -0.3649663 -0.8399255 -0.3534037 -0.4118629 -0.8425745 -0.3337615 -0.4226955 -0.8423259 -0.3255089 -0.429571 -0.8547055 -0.3076455 -0.4181302 -0.8641836 -0.2912673 -0.410305 -0.9030392 -0.1874699 -0.3864911 -0.8749687 -0.2628979 -0.4065889 -0.8741888 -0.2656641 -0.4064686 -0.8953506 -0.188633 -0.4034413 -0.9140473 -0.04260253 -0.4033642 -0.9139561 -0.04256904 -0.4035742 -0.9120043 0.06782597 -0.4045341 -0.8551986 0.09838885 -0.5088763 -0.9035407 0.1410235 -0.4046316 -0.8802711 0.248979 -0.4038963 -0.787392 0.4653323 -0.4043263 -0.7962825 0.4498803 -0.4044034 -0.8355875 0.3901829 -0.3867182 -0.8299307 0.3843189 -0.4043686 -0.880234 0.2489855 -0.4039733 0.8034498 0.4009076 -0.4401609 0.8145574 0.3928617 -0.4267975 0.8029856 0.432776 -0.4097793 0.8164585 0.3895674 -0.4261841 0.8264588 0.3787352 -0.4165641 0.831462 0.3722749 -0.4124106 0.8435986 0.3526218 -0.4049684 0.8435986 0.3526218 -0.4049685 0.8435986 0.3526218 -0.4049685 0.8413354 0.3625826 -0.4008598 0.8397069 0.3709998 -0.3965495 0.8390164 0.3848062 -0.3846759 0.8428844 0.4041388 -0.3552716 0.8447738 0.407526 -0.3468136 0.7952505 0.4516381 -0.4044749 0.7498022 0.5244543 -0.4034158 0.7498 0.5243898 -0.4035039 0.6558885 0.6379715 -0.403488 0.6559109 0.637952 -0.4034824 0.6556597 0.6382451 -0.4034271 0.5448195 0.7349026 -0.4038439 0.5452234 0.7349061 -0.4032919 0.5451126 0.7349299 -0.4033986 0.2030261 0.8918904 -0.4041188 0.2843407 0.8698831 -0.4030556 0.284299 0.8699343 -0.4029744 0.2826364 0.8704432 -0.4030449 0.4199426 0.8130905 -0.4031529 0.09948569 0.9081861 -0.4065721 0.110018 0.9111537 -0.3971081 0.1220405 0.9140114 -0.386897 0.1439529 0.9215922 -0.3604792 0.1576851 0.9388689 -0.3060404 0.1576852 0.9388689 -0.3060404 0.1576851 0.9388689 -0.3060404 0.1374346 0.9205332 -0.3656916 0.11445 0.9037057 -0.4125739 0.1326401 0.896245 -0.4232631 0.1389015 0.8923461 -0.4294472 0.1594472 0.8940315 -0.4186699 0.1804775 0.8940802 -0.4099372 0.2890958 0.8756968 -0.3867542 0.2153323 0.8884007 -0.4054334 0.2056042 0.8907306 -0.4053712 0.6562358 0.6385916 -0.4019397 0.5455218 0.735582 -0.4016531 0.5454474 0.7353117 -0.4022487 0.4202076 0.8135104 -0.4020279 0.420045 0.8122199 -0.4047976 0.2838994 0.8691919 -0.4048541 0.7973812 0.4485584 -0.4037062 0.7872973 0.4661445 -0.4035748 0.7558866 0.5286111 -0.3862715 0.7478371 0.5266317 -0.4042261 0.6557749 0.6376239 -0.4042215 -0.8386907 -0.3677425 -0.4017007 -0.8346667 -0.3737609 -0.4045173 -0.7894501 -0.4625009 -0.4035613 -0.7895796 -0.4623615 -0.4034675 -0.7051649 -0.5830627 -0.4034606 -0.7050276 -0.5831716 -0.4035431 -0.6022887 -0.6887729 -0.4035348 -0.6023018 -0.6887642 -0.40353 -0.4843202 -0.7762696 -0.4035339 -0.4841546 -0.7763349 -0.403607 -0.353401 -0.8439142 -0.4036296 -0.3531731 -0.8439602 -0.4037327 -0.213047 -0.8897249 -0.4037333 -0.2133876 -0.8897201 -0.403564 -0.1151375 -0.9072468 -0.4045325 -0.1068991 -0.9070141 -0.4073057 0.09784489 0.9099693 -0.402967 0.09350532 0.9096787 -0.40465 -0.005743622 0.9148734 -0.4037003 -0.005552411 0.914923 -0.4035902 -0.1526947 0.9021017 -0.4036049 -0.152307 0.9022603 -0.403397 -0.2951682 0.8661026 -0.403413 -0.2953221 0.8660192 -0.4034795 -0.4302313 0.8075304 -0.4034796 -0.4304254 0.8073567 -0.4036203 -0.5541815 0.7280008 -0.4036059 -0.5541312 0.728058 -0.4035719 -0.6637973 0.6296844 -0.4035726 -0.6638044 0.6296702 -0.403583 -0.7283031 0.5531038 -0.4045377 -0.7341043 0.5423138 -0.4086399 0.7394523 -0.5389782 -0.4033769 0.7409254 -0.5360432 -0.4045829 0.795191 -0.4525234 -0.4036009 0.7952099 -0.4524551 -0.4036403 0.857491 -0.3190665 -0.403616 0.8574827 -0.3191474 -0.4035696 0.897598 -0.1773439 -0.4035677 0.8975991 -0.1773446 -0.4035652 0.9144207 -0.0310682 -0.4035711 0.9144244 -0.03109788 -0.4035602 0.9075723 0.1160014 -0.4035546 0.9075551 0.1160369 -0.4035831 0.8771936 0.26008 -0.403596 0.8772454 0.2599806 -0.4035477 0.8431231 0.3542947 -0.4044979 0.8378695 0.3627803 -0.407879 -0.3490591 -0.1514979 0.9247736 -0.1172023 -0.05074769 0.9918107 -0.1172783 -0.05086702 0.9917956 -0.1380006 -0.05980473 -0.988625 -0.1378154 -0.05969518 -0.9886575 -0.1308088 -0.04695719 -0.990295 -0.3609436 -0.1648781 -0.9178971 -0.3539713 -0.1533867 -0.9225925 -0.5588307 -0.2421577 -0.7931382 -0.5588527 -0.2422494 -0.7930945 -0.7282328 -0.3152955 -0.6084948 -0.728363 -0.3156221 -0.6081694 -0.8464327 -0.3667855 -0.3860315 -0.8464398 -0.3669063 -0.3859008 -0.909416 -0.3943068 -0.1322296 -0.9094315 -0.3941904 -0.1324698 -0.9101463 -0.3944959 0.1265175 -0.9102432 -0.3943794 0.1261832 -0.8487951 -0.3678406 0.3797899 -0.8485444 -0.367994 0.3802013 -0.7278727 -0.3156579 0.6087377 -0.7277329 -0.315701 0.6088824 -0.5580661 -0.2420966 0.7936949 -0.5581525 -0.2420787 0.7936396 -0.348934 -0.1513279 0.9248487 -0.9983397 -0.05693262 0.008760333 -0.9993145 0.03394764 -0.01477319 -0.9983522 -0.05671274 0.008760452 -0.9917755 -0.126795 -0.01744455 -0.98537 -0.170345 0.00533998 -0.9852648 -0.1709521 0.00535655 -0.9586559 -0.2844616 -0.007790625 -0.9595161 -0.2814685 -0.01021951 -0.90079 -0.4338862 -0.01789307 -0.9213591 -0.3886613 0.006321072 -0.9215795 -0.3881388 0.00628066 -0.7456112 -0.6663792 0.001677453 -0.8093994 -0.5872563 -0.001650094 -0.8193073 -0.5732061 -0.01304501 -0.870217 -0.4925959 0.008466184 -0.8707664 -0.4916235 0.008504986 -0.7368066 -0.6761016 0.001680433 -0.7167869 -0.6971163 -0.01566833 -0.6534165 -0.7569363 0.009717881 -0.6562312 -0.7544978 0.009686589 -0.5948524 -0.8036549 -0.01701325 -0.5637555 -0.825932 0.004024386 -0.5731328 -0.8194524 0.004081189 -0.4595169 -0.8881428 -0.006824135 -0.4665722 -0.8843846 -0.0132088 -0.3109226 -0.9502685 -0.01780742 -0.3628751 -0.9318103 0.007175505 -0.3622279 -0.9320617 0.007220566 -0.01715421 -0.9998474 0.003333747 -0.1426004 -0.9897686 -0.004838883 -0.1536203 -0.9880503 -0.01255106 -0.2573351 -0.9662892 0.007997691 -0.2542694 -0.9671002 0.008016765 -0.02943223 -0.9995614 0.003298223 0.00623393 -0.9998381 -0.01688039 0.08582806 -0.9962698 0.008952617 0.08315193 -0.9964968 0.008940696 0.166117 -0.985963 -0.01680099 0.1983215 -0.9801344 0.002266526 0.2058305 -0.9785851 0.002264797 0.3222782 -0.9466383 -0.003595054 0.3080967 -0.9512182 -0.01614034 0.4706709 -0.8821276 -0.01788491 0.4146517 -0.9099406 0.008497238 0.4169089 -0.9089095 0.008405745 0.6976327 -0.7164405 0.004645586 0.6106952 -0.791839 -0.006516337 0.6057265 -0.7955959 -0.01107102 0.5153841 -0.8569341 0.006583333 0.5160458 -0.8565361 0.006545245 0.6968042 -0.7172462 0.004674792 0.7254949 -0.6880121 -0.0172221 0.7738969 -0.6332502 0.008823335 0.7745442 -0.632458 0.008838057 0.8265403 -0.5626734 -0.01516085 0.8408187 -0.5413166 6.38343e-4 0.8360753 -0.5486145 6.33911e-4 0.9060168 -0.4232389 -0.001616418 0.8972176 -0.4411777 -0.01905065 0.9621569 -0.2719241 -0.0176503 0.9416343 -0.3365256 0.00868839 0.9418482 -0.3359258 0.0087049 0.9999827 -3.45513e-4 0.005878031 0.9934007 -0.1143438 -0.008981287 0.9934001 -0.114349 -0.008978188 0.9737407 -0.2275858 0.005825877 0.9739504 -0.2266864 0.005833745 0.9999827 -2.88396e-4 0.005877435 0.9987611 0.04653114 -0.01764249 0.9934659 0.1138082 0.008557677 0.993481 0.1136761 0.008554279 0.9783891 0.2062832 -0.0142129 0.9740482 0.2263387 -9.36047e-4 0.9326914 0.3603543 -0.01522183 0.9418714 0.3359729 7.89235e-4 0.9443311 0.3289961 7.83486e-4 0.8627817 0.5052863 -0.01712989 0.8977278 0.4404564 0.00912255 0.8973236 0.4412792 0.009116351 0.6953577 0.7186266 0.007319092 0.774388 0.6326052 -0.01158183 0.7705973 0.6372857 -0.006835579 0.8397545 0.5429477 0.004487097 0.841732 0.5398766 0.004536569 0.6977316 0.7163221 0.007304251 0.6582061 0.7526273 -0.017811 0.610261 0.7921577 0.008235394 0.5294447 0.8483392 -0.003028452 0.5159721 0.8564522 -0.01620107 0.6120756 0.7907564 0.008232474 0.3859375 0.922396 -0.01542836 0.4141312 0.9102139 0.002468645 0.4315918 0.9020658 0.002433359 0.2323245 0.9724997 -0.01641947 0.3089386 0.9510358 0.009380996 0.3106483 0.9504791 0.009343683 -0.0285682 0.999562 0.00772649 0.0862416 0.9961685 -0.01451486 0.07492482 0.9971759 -0.005144238 0.1892743 0.9819216 0.002295851 0.2000473 0.9797837 0.002282857 -0.02799785 0.9995782 0.007728457 -0.0873984 0.9960063 -0.01825195 -0.1421831 0.9898172 0.006783008 -0.1435246 0.9896237 0.006762206 -0.2448338 0.9694954 -0.01163303 -0.2535386 0.9673112 -0.005223691 -0.3972074 0.9175795 -0.01656132 -0.3633319 0.9316527 0.003622531 -0.3579937 0.933717 0.003645122 -0.5404452 0.841237 -0.01546871 -0.465555 0.8849643 0.009841501 -0.4672239 0.8840847 0.009800195 -0.736141 0.676778 0.00825262 -0.6546914 0.7556951 -0.01744306 -0.6673507 0.744737 -0.003128111 -0.554228 0.8323636 0.001479268 -0.554228 0.8323637 0.001479268 -0.554228 0.8323637 0.001479268 -0.5641368 0.82568 0.001500129 -0.7375015 0.675295 0.008267045 -0.7787681 0.6270686 -0.017475 -0.8084526 0.5885297 0.006128013 -0.8691598 0.4944674 -0.007955551 -0.8707516 0.4916116 -0.01048099 -0.8088816 0.5879393 0.006169617 -0.9370316 0.34881 -0.01742309 -0.921221 0.3890088 0.004918754 -0.9196907 0.3926127 0.004916846 -0.9983571 0.0572983 0 -0.9852669 0.1710242 0 -0.9809021 0.1939454 -0.01471602 -0.9595324 0.2814651 0.008657217 -0.959274 0.2823451 0.008649051 -0.9792894 -0.05576646 0.1946344 -0.9792283 -0.05562788 0.1949809 -0.9664146 -0.1670278 0.1953066 -0.9664184 -0.167075 0.1952474 -0.9664208 -0.1676626 0.1947308 -0.9411889 -0.2759288 0.1950047 -0.9412783 -0.2761089 0.1943168 -0.9040363 -0.3807374 0.1943133 -0.9035274 -0.3815746 0.1950359 -0.9034987 -0.3811268 0.1960421 -0.8540499 -0.4816469 0.1965078 -0.8541424 -0.4822438 0.1946325 -0.8538023 -0.4833067 0.1934846 -0.7940762 -0.5763431 0.1930588 -0.7940536 -0.5761193 0.1938185 -0.7312046 -0.6540821 0.193692 -0.7312046 -0.654082 0.1936921 -0.7312046 -0.6540821 0.1936921 -0.7226102 -0.6628936 0.1959761 -0.7225748 -0.6630454 0.1955932 -0.6408429 -0.7423458 0.1955589 -0.6431214 -0.7413776 0.1917139 -0.6437378 -0.7401418 0.1944013 -0.5530307 -0.8102018 0.1942425 -0.55465 -0.8101553 0.1897681 -0.5622147 -0.8038753 0.1941632 -0.4572096 -0.867873 0.1943094 -0.4575226 -0.8672349 0.1964102 -0.3551768 -0.9139226 0.1964564 -0.3560889 -0.9137415 0.1956458 -0.3559227 -0.9139493 0.194976 -0.2501325 -0.9483419 0.1951448 -0.2495372 -0.949094 0.1922285 -0.2523602 -0.9476001 0.1958786 -0.1389877 -0.9707703 0.1956716 -0.1397545 -0.9700171 0.1988357 -0.01682472 -0.9799219 0.1986709 -0.02951616 -0.9804819 0.1943814 -0.02951616 -0.9804819 0.1943814 -0.02951616 -0.9804819 0.1943814 -0.02888411 -0.9809447 0.1921285 -0.02888405 -0.9809446 0.1921285 -0.02888405 -0.9809446 0.1921285 0.08515495 -0.9776687 0.1921266 0.08418023 -0.9771453 0.1951947 0.08147287 -0.9763734 0.2001427 0.08146882 -0.9763739 0.2001428 0.08147287 -0.9763735 0.2001427 0.1943144 -0.9603069 0.2001318 0.1943144 -0.9603069 0.2001318 0.1943144 -0.9603069 0.2001318 0.1943584 -0.9602706 0.2002629 0.2017644 -0.959182 0.198144 0.302142 -0.9324609 0.1980583 0.3020207 -0.9324355 0.1983621 0.4088232 -0.8908846 0.1979606 0.4088232 -0.8908845 0.1979607 0.4066287 -0.8924919 0.1952214 0.4067056 -0.8925076 0.1949897 0.5069859 -0.8395909 0.1950707 0.5057542 -0.8394594 0.1987982 0.505049 -0.8397822 0.1992272 0.5975194 -0.7767421 0.1991043 0.5990341 -0.7767146 0.1946095 0.6843065 -0.7027559 0.1945737 0.684006 -0.7030575 0.1945404 0.6832461 -0.703286 0.1963763 0.7582242 -0.6217197 0.1963692 0.7594115 -0.6214241 0.1926816 0.7602891 -0.6208106 0.1911932 0.8252114 -0.5312685 0.1917811 0.8251885 -0.5304846 0.1940363 0.8200893 -0.5380789 0.194742 0.8802174 -0.4327447 0.1948062 0.8801391 -0.4327775 0.1950873 0.9238047 -0.3294802 0.1950067 0.9237817 -0.3297188 0.1947127 0.9234736 -0.3300406 0.1956266 0.9551124 -0.2227325 0.1953216 0.9554947 -0.2223906 0.1938363 0.9551716 -0.2232508 0.194439 0.9744593 -0.1120669 0.1946029 0.9743826 -0.1121581 0.1949335 0.9808449 -3.36187e-4 0.1947902 0.9808456 -2.96492e-4 0.1947872 0.9808535 -2.80365e-4 0.1947469 0.9744569 0.1114987 0.1949409 0.9745236 0.1116365 0.1945276 0.9745167 0.1115072 0.1946365 0.9554861 0.2218413 0.1945068 0.9555624 0.2220458 0.1938976 0.9264128 0.3227767 0.1938416 0.9264128 0.3227767 0.1938416 0.9238554 0.329802 0.1942217 0.9237688 0.3295073 0.195131 0.8801195 0.4328182 0.1950849 0.8805376 0.4323621 0.1942077 0.8805559 0.4320329 0.1948562 0.8256027 0.5295174 0.1949148 0.8249368 0.5298402 0.196847 0.8235902 0.5325038 0.1952918 0.7593384 0.6207248 0.1952071 0.7593497 0.6203134 0.1964675 0.6817963 0.7046138 0.196655 0.684283 0.702947 0.1939648 0.6844154 0.7026438 0.1945952 0.6844153 0.7026439 0.1945952 0.6844154 0.7026439 0.1945952 0.5993324 0.7764701 0.1946659 0.5989722 0.7775053 0.1916193 0.600457 0.7757466 0.1940846 0.5059992 0.8404672 0.1938555 0.5061014 0.8400945 0.1951991 0.4232922 0.8846836 0.1953427 0.4077605 0.8909775 0.1997261 0.4063649 0.8931431 0.1927772 0.3048475 0.9327383 0.1925286 0.3040224 0.9326983 0.1940212 0.3032052 0.9333964 0.191932 0.1963223 0.9615452 0.1920638 0.1945773 0.9609122 0.1969458 0.1945773 0.9609122 0.1969458 0.1945773 0.9609122 0.1969457 0.185669 0.9632357 0.1941754 0.0834304 0.9774014 0.1942314 0.08453834 0.9764952 0.198269 0.08454293 0.9764947 0.198269 0.08453834 0.9764952 0.198269 -0.02799934 0.9798009 0.198006 -0.02800381 0.9798008 0.1980061 -0.02800381 0.9798007 0.198006 -0.02606344 0.9801993 0.1962912 -0.02747386 0.9808558 0.1927876 -0.1407667 0.9711304 0.1925891 -0.1393914 0.9704124 0.197154 -0.1407625 0.9705476 0.1955083 -0.2484268 0.9486803 0.1956783 -0.2486768 0.9487618 0.1949643 -0.3511343 0.9158426 0.1947749 -0.3559166 0.9134415 0.1973521 -0.3562479 0.9134811 0.19657 -0.4568665 0.8675619 0.1964928 -0.4586339 0.8678244 0.1911435 -0.4567062 0.8681402 0.1942988 -0.5533803 0.809951 0.194293 -0.5530798 0.8106936 0.1920382 -0.5434244 0.8167266 0.1940296 -0.6425809 0.7411774 0.1942825 -0.6421599 0.7412405 0.195431 -0.72197 0.6637741 0.1953542 -0.7223504 0.6630527 0.1963951 -0.7235968 0.6625707 0.1934108 -0.7937529 0.5765933 0.1936405 -0.7925671 0.5769838 0.1972997 -0.7930554 0.576433 0.1969475 -0.7930553 0.576433 0.1969475 -0.7930548 0.5764337 0.1969475 -0.8534665 0.4827776 0.1962676 -0.8543696 0.48236 0.1933428 -0.9022725 0.3851732 0.1937681 -0.9031933 0.3819774 0.1957936 -0.903684 0.3816026 0.1942547 -0.9411776 0.2764691 0.1942924 -0.9406583 0.2768706 0.1962265 -0.9411832 0.2760748 0.1948257 -0.966412 0.1676115 0.1948187 -0.9662925 0.1677264 0.1953122 -0.9792017 0.05625456 0.1949346 -0.9792394 0.05620211 0.1947602 -0.9792565 -0.05584383 0.1947781 -0.7985242 0.2345778 0.5543757 -0.7981478 0.2346705 0.5548783 -0.7662332 0.3240709 0.5548557 -0.766365 0.3240477 0.5546871 -0.7243043 0.4097254 0.5545345 -0.7252628 0.4097595 0.553255 -0.6741594 0.4897242 0.5528827 -0.6722777 0.4894251 0.555433 -0.6125868 0.5623154 0.5554627 -0.6132121 0.5624758 0.5546097 -0.5451335 0.6288176 0.5544529 -0.5439204 0.6282572 0.5562765 -0.4682725 0.686369 0.5564337 -0.4697718 0.6873047 0.5540099 -0.3879378 0.7366535 0.5539368 -0.3869535 0.7358796 0.5556514 -0.3018693 0.7747282 0.5555817 -0.3031975 0.7758988 0.55322 -0.2110428 0.8059457 0.5530936 -0.2100094 0.8047468 0.5552285 -0.1193116 0.8231631 0.5551283 -0.1181934 0.8214871 0.5578435 -0.02206391 0.8295357 0.5580177 -0.02206391 0.8295357 0.5580177 -0.02206385 0.8295357 0.5580177 -0.02405601 0.8333956 0.5521532 0.0708943 0.8305805 0.5523678 0.07193672 0.8282268 0.5557568 0.1648982 0.8146293 0.5560466 0.1648967 0.8148611 0.5557071 0.2576611 0.7904475 0.5557008 0.2576871 0.7902076 0.5560302 0.3458798 0.7557738 0.5560335 0.3457576 0.7583768 0.5525544 0.4298388 0.7139813 0.5526928 0.429641 0.7109131 0.5567865 0.5075605 0.6575816 0.5567485 0.507612 0.6575389 0.556752 0.5794886 0.5952944 0.5566127 0.5801837 0.5976945 0.5533067 0.6448865 0.5271912 0.5533453 0.6442272 0.525847 0.5553885 0.6997948 0.4494589 0.5552241 0.6994583 0.4489353 0.5560712 0.7461884 0.3664051 0.555833 0.7471097 0.3676481 0.5537707 0.7840248 0.2798855 0.5540481 0.7829328 0.2787991 0.5561363 0.8098161 0.1880286 0.5557367 0.8100174 0.1882069 0.5553828 0.8262836 0.09454619 0.5552626 0.8262932 0.09457117 0.555244 0.831758 -2.51627e-4 0.5551385 0.8317537 -2.39076e-4 0.5551449 0.8263216 -0.09503471 0.5551228 0.8262447 -0.09506118 0.5552324 0.8099322 -0.188878 0.5552792 0.8103413 -0.1887636 0.554721 0.7837762 -0.2797384 0.5544741 0.7830106 -0.2798461 0.5555003 0.7461361 -0.3668206 0.5556289 0.7460131 -0.366809 0.5558018 0.6992371 -0.4495269 0.5558716 0.6997294 -0.4495148 0.5552614 0.643175 -0.5273939 0.5551411 0.6444969 -0.5276594 0.5533529 0.580962 -0.5971622 0.5530648 0.5784991 -0.5962896 0.5565766 0.50656 -0.6584793 0.5565986 0.5089301 -0.6595615 0.5531446 0.430715 -0.7132638 0.5529371 0.4286271 -0.7119604 0.5562295 0.3444988 -0.7560976 0.5564504 0.3447265 -0.7563483 0.5559684 0.2562304 -0.7907346 0.555954 0.2586092 -0.7932183 0.5512949 0.1655133 -0.817727 0.5512965 0.1654225 -0.8175586 0.5515736 0.07237493 -0.8310402 0.5514837 0.07040065 -0.8277861 0.5566093 -0.02499997 -0.8305048 0.5564501 -0.02400839 -0.83246 0.5535649 -0.1180355 -0.8244166 0.5535385 -0.118398 -0.8230235 0.5555307 -0.118398 -0.8230236 0.5555306 -0.2121165 -0.8041672 0.5552672 -0.2117844 -0.8057265 0.5531295 -0.3024738 -0.7761557 0.5532557 -0.3026902 -0.7743815 0.5556185 -0.3874849 -0.7355328 0.5557401 -0.3874372 -0.7336891 0.558205 -0.468835 -0.6848147 0.5578734 -0.4689821 -0.6858788 0.5564408 -0.5444787 -0.6276761 0.5563865 -0.5447868 -0.6289368 0.5546583 -0.6132144 -0.5625388 0.5545433 -0.6129353 -0.5618627 0.5555363 -0.6729063 -0.4884022 0.5555721 -0.6729095 -0.4884085 0.5555629 -0.7242981 -0.4084642 0.5554721 -0.7246143 -0.4089578 0.554696 -0.7664956 -0.3237171 0.5546999 -0.7663555 -0.3235974 0.5549631 -0.7983011 -0.2340423 0.5549231 -0.7985364 -0.2343019 0.5544748 -0.8198672 -0.1417083 0.5547401 -0.8195734 -0.1414669 0.5552356 -0.8303615 -0.04728358 0.5552153 -0.8304103 -0.0473029 0.5551408 -0.8303622 0.04770207 0.5551785 -0.830381 0.04770898 0.5551499 -0.8194624 0.1421266 0.555231 -0.8198812 0.1419983 0.5546453 -0.5335071 0.1568632 0.8311223 -0.5337314 0.1568637 0.8309782 -0.5122553 0.2166026 0.8310703 -0.5118523 0.2165753 0.8313257 -0.4836935 0.2732817 0.8314794 -0.4835683 0.273253 0.8315616 -0.4488615 0.3267745 0.8317102 -0.4505085 0.3272522 0.8306311 -0.4104623 0.3765172 0.8305153 -0.4102442 0.3763821 0.8306841 -0.3644655 0.4209628 0.8306354 -0.3638052 0.4205964 0.8311105 -0.3137491 0.4590316 0.8311748 -0.3144795 0.4595669 0.8306028 -0.2592381 0.4930078 0.8305052 -0.2589802 0.4926844 0.8307777 -0.2026153 0.5185009 0.830725 -0.2014842 0.5172321 0.8317904 -0.1400865 0.5368551 0.831963 -0.1413924 0.5389255 0.830402 -0.07933872 0.5514993 0.8303937 -0.07953655 0.5518322 0.8301537 -0.01608335 0.5573207 0.8301417 -0.01543164 0.5554403 0.8314134 0.04808264 0.5536162 0.8313827 0.04754549 0.5559283 0.8298695 0.110637 0.5467309 0.8299668 0.1110326 0.5438996 0.8317722 0.172115 0.5278008 0.8317469 0.1721166 0.529087 0.830929 0.2307757 0.5061705 0.8309839 0.2307764 0.5058629 0.8311709 0.2875604 0.4758412 0.8311945 0.2877984 0.4767661 0.8305819 0.3402603 0.4407768 0.8306255 0.3402097 0.4406538 0.8307116 0.3877276 0.3994362 0.8307335 0.3874589 0.3988273 0.8311513 0.4308352 0.3516434 0.8311005 0.4313163 0.3524696 0.8305007 0.4687014 0.3008291 0.8305546 0.4693728 0.3015999 0.8298956 0.5002841 0.2461966 0.8301223 0.4990277 0.2449285 0.8312529 0.523965 0.1865721 0.8310545 0.5247066 0.1872277 0.830439 0.5425314 0.1260527 0.8305243 0.5422251 0.1258864 0.8307494 0.5530248 0.06329381 0.8307573 0.5531075 0.06333184 0.8306993 0.556629 -1.60247e-4 0.8307613 0.5565446 -1.65375e-4 0.8308178 0.5527719 -0.06359046 0.8309028 0.5530215 -0.06353831 0.8307408 0.5421825 -0.1262981 0.8307148 0.5417522 -0.1263372 0.8309895 0.523766 -0.1871731 0.8310448 0.5248177 -0.1872032 0.8303744 0.5001808 -0.245918 0.8302673 0.499077 -0.2457735 0.8309739 0.4681057 -0.3007264 0.8309276 0.4672465 -0.3005221 0.8314849 0.4296573 -0.3517811 0.8316517 0.4304553 -0.3520413 0.8311289 0.3872057 -0.3991193 0.8311291 0.3878133 -0.3994199 0.8307014 0.3401522 -0.4408204 0.8306467 0.3402972 -0.4409347 0.8305267 0.2872636 -0.4771746 0.8305324 0.2865341 -0.4765643 0.8311346 0.2306575 -0.5060635 0.8310818 0.2309035 -0.5062522 0.8308985 0.1724718 -0.528979 0.8309241 0.1717364 -0.5280311 0.8316791 0.1100944 -0.5441095 0.8317598 0.1100286 -0.5440816 0.8317867 0.04703956 -0.5530439 0.8318232 0.04735529 -0.5537963 0.8313044 -0.01602357 -0.5556026 0.8312937 -0.01549291 -0.5572713 0.830186 -0.07938909 -0.5516197 0.830309 -0.07946002 -0.5514037 0.8304458 -0.1416544 -0.5388957 0.8303766 -0.1417644 -0.5363115 0.8320294 -0.2020307 -0.5168278 0.8319091 -0.2021042 -0.5187098 0.830719 -0.2598882 -0.4921669 0.8308008 -0.2598882 -0.492167 0.8308008 -0.2598882 -0.492167 0.8308008 -0.2599577 -0.4924359 0.8306196 -0.3142484 -0.4595966 0.8306738 -0.3141003 -0.458827 0.8311551 -0.3640935 -0.4203027 0.8311328 -0.3643091 -0.420962 0.8307044 -0.4103274 -0.3761529 0.8307469 -0.4105181 -0.3763862 0.830547 -0.4505989 -0.3270588 0.8306583 -0.4505653 -0.3270097 0.830696 -0.4848482 -0.2736428 0.8306876 -0.4849958 -0.2737798 0.8305563 -0.5130061 -0.2166091 0.8306053 -0.5133817 -0.216911 0.8302946 -0.5344997 -0.1568353 0.8304895 -0.5344091 -0.1567541 0.8305632 -0.5487184 -0.09471565 0.8306245 -0.5488343 -0.09480988 0.8305372 -0.5558407 -0.03166139 0.8306857 -0.5557188 -0.03159832 0.8307696 -0.555678 0.03192633 0.8307844 -0.5556381 0.03193712 0.8308107 -0.5483425 0.09497243 0.8308434 -0.5481286 0.09500646 0.8309807 -0.1874557 0.05508798 0.9807272 -0.1873091 0.05508577 0.9807553 -0.1798871 0.07611894 0.9807378 -0.1799519 0.07612425 0.9807255 -0.1701539 0.09616351 0.9807142 -0.1702858 0.09618663 0.980689 -0.1583421 0.1150124 0.9806631 -0.1576763 0.1147673 0.980799 -0.143743 0.1318721 0.9807894 -0.1435835 0.1317972 0.9808228 -0.12753 0.1473972 0.9808212 -0.1278501 0.1476376 0.9807434 -0.1103407 0.1612262 0.9807299 -0.1102103 0.1611316 0.98076 -0.09086799 0.1728315 0.9807509 -0.09091919 0.1729142 0.9807316 -0.0709424 0.182084 0.9807205 -0.07117527 0.1823611 0.9806521 -0.04968738 0.1894272 0.9806368 -0.04932743 0.1887703 0.9807816 -0.0278325 0.1931353 0.9807773 -0.02755606 0.1925441 0.9809014 -0.005399882 0.1944087 0.9809058 -0.00560975 0.1950855 0.9807702 0.01663035 0.1943932 0.9807828 0.01675808 0.1937966 0.9808987 0.03892099 0.1906335 0.9808894 0.0388509 0.1911983 0.9807823 0.06036692 0.1855743 0.9807742 0.06038063 0.1863157 0.9806328 0.08126646 0.1781246 0.9806465 0.08123964 0.1778455 0.9806993 0.1010128 0.1673391 0.9807111 0.1010084 0.1673308 0.9807128 0.1194282 0.154683 0.9807192 0.119512 0.1549525 0.9806664 0.1363626 0.1403623 0.9806649 0.1362274 0.140163 0.9807122 0.1513615 0.1236949 0.9807086 0.1511062 0.1233186 0.9807953 0.1640998 0.1054371 0.9807927 0.1637706 0.1050748 0.9808866 0.1747607 0.08577316 0.9808678 0.1753118 0.08629101 0.980724 0.1839748 0.06563693 0.9807371 0.1837522 0.06551766 0.9807868 0.1900472 0.04412245 0.980783 0.1900522 0.04412662 0.9807819 0.1938287 0.02219259 0.9807844 0.193803 0.0221768 0.9807898 0.1951266 -5.80991e-5 0.9807782 0.1950891 -5.92912e-5 0.9807856 0.1939144 -0.022282 0.9807655 0.1937216 -0.02232486 0.9808025 0.1898162 -0.04425191 0.9808219 0.1900082 -0.04423499 0.9807855 0.1838032 -0.06557208 0.9807735 0.1835738 -0.06556606 0.9808169 0.1748834 -0.08610445 0.9808169 0.175239 -0.08616155 0.9807484 0.1642374 -0.105627 0.9807492 0.1640312 -0.105583 0.9807885 0.1510389 -0.1235216 0.9807801 0.151476 -0.1237099 0.9806891 0.1362566 -0.1403332 0.9806838 0.1355663 -0.1399557 0.9808335 0.1190426 -0.1542524 0.9808339 0.118716 -0.1540198 0.9809101 0.1002088 -0.1666401 0.9809125 0.1010251 -0.1674182 0.9806962 0.08114683 -0.1778976 0.9806975 0.0813421 -0.1781469 0.9806361 0.06057339 -0.1862447 0.9806344 0.06015837 -0.1856291 0.9807767 0.03870195 -0.1913035 0.9807677 0.03895443 -0.1917575 0.980669 0.01667046 -0.1949985 0.9806619 0.01643663 -0.1944193 0.9807808 -0.005417287 -0.1950324 0.9807819 -0.005580663 -0.1944343 0.9808997 -0.0277478 -0.1925313 0.9808984 -0.02765357 -0.1931696 0.9807757 -0.04986655 -0.1886529 0.980777 -0.04983073 -0.1893351 0.9806473 -0.07109326 -0.1824175 0.9806476 -0.07103836 -0.1819692 0.9807348 -0.09118688 -0.1727145 0.9807419 -0.09114229 -0.1725845 0.9807689 -0.1102563 -0.1610535 0.9807678 -0.110311 -0.1611791 0.980741 -0.127792 -0.1476489 0.9807493 -0.1276494 -0.1473054 0.9808195 -0.1436594 -0.1317087 0.9808236 -0.1436824 -0.1317815 0.9808104 -0.1578471 -0.1145588 0.980796 -0.1576949 -0.1144241 0.9808361 -0.1697869 -0.09584623 0.9808088 -0.1696169 -0.09570819 0.9808517 -0.1794769 -0.07583397 0.9808351 -0.1794589 -0.07582044 0.9808394 -0.1870259 -0.05485928 0.980822 -0.1870692 -0.05489313 0.9808118 -0.1921782 -0.03319811 0.9807984 -0.1920835 -0.0331695 0.980818 -0.1947403 -0.01107376 0.9807924 -0.1947531 -0.01109266 0.9807896 -0.1947978 0.01119667 0.9807795 -0.1948068 0.01118868 0.9807779 -0.1923573 0.03333753 0.9807586 -0.1923607 0.03332883 0.9807581 -5.28583e-5 0 1 2.58104e-6 0 1 -9.94243e-6 0 1 1.45455e-5 0 1 -0.4309023 0.5636937 0.7046791 -0.3727277 0.5499488 0.7474158 0.5278503 0.434388 0.7298501 0.5199072 0.4803082 0.7063998 0.4182335 0.5737271 0.7042146 0.418145 0.5737316 0.7042634 0.4179409 0.5743482 0.7038819 0.2589908 0.6614634 0.7038394 0.2578936 0.6613574 0.7043417 0.2581906 0.6608973 0.7046648 0.08159732 0.704791 0.7047067 0.08076369 0.7060387 0.7035529 0.08077359 0.7060678 0.7035226 -0.1014133 0.7034513 0.7034712 -0.1005778 0.7026594 0.7043819 -0.1018766 0.7030772 0.7037782 -0.2776549 0.6539678 0.7037286 -0.2767796 0.6535432 0.7044675 -0.2768042 0.653504 0.7044942 -7.31572e-6 0 1 4.97107e-6 0 1 0.9934409 -0.1143471 0 0.9934467 -0.114297 -1.04804e-5 0.9934482 -0.1142835 1.35967e-5 0.3724133 -0.5499839 0.7475467 0.4269345 -0.5576832 0.7118402 -0.5278599 -0.4343968 0.729838 -0.5197734 -0.4809827 0.7060391 -0.5208473 -0.4793295 0.706372 -0.4179379 -0.5739322 0.7042229 -0.4183546 -0.5740211 0.7039029 -0.4180251 -0.5742172 0.7039388 -0.2587318 -0.6616114 0.7037956 -0.2577788 -0.6610576 0.7046652 -0.2581225 -0.6608542 0.7047302 -0.0816043 -0.7047549 0.7047421 -0.08077132 -0.706103 0.7034875 0.09255242 -0.7040736 0.70407 0.1013799 -0.703096 0.703831 0.1014658 -0.7031656 0.7037492 0.276643 -0.654324 0.703796 0.2770913 -0.6541141 0.7038147 0.2770799 -0.6541028 0.7038297 0.3979454 -0.585821 0.7060122 -0.9934409 0.1143471 0 -0.9934467 0.114297 -1.16449e-5 -0.9934482 0.1142835 1.48828e-5 4.20154e-6 0 1 -2.21208e-6 0 1 -1.67106e-6 0 1 2.45283e-6 0 1 2.65445e-7 0 1 -3.15049e-6 0 1 2.11079e-6 0 1 7.18928e-6 0 1 -6.68699e-6 0 1 1.06175e-6 0 1 -1.06181e-6 0 1 -1.20843e-5 0 1 1.79716e-6 0 1 -4.3845e-6 0 1 4.24527e-6 0 1 -4.19324e-6 0 1 0.2328124 -0.9725217 0 -0.4526351 -0.8916959 0 -0.6081941 -0.7937867 -0.001616775 -0.7446756 -0.6673713 0.008592724 -0.7536686 -0.6572147 0.007244884 -0.8270844 -0.5620622 -0.004214525 -0.8683655 -0.495925 0 -0.9694163 -0.2454224 0 -0.9500772 -0.311099 -0.02389305 -0.9973229 -0.04209208 0.05979347 -0.7447049 -0.667394 0 -0.6668677 -0.7424306 -0.06390959 -0.7605458 -0.6489635 -0.02041506 0.409422 -0.9123293 0.005398511 0.211814 -0.9772695 -0.008910417 0.1266449 -0.9910932 -0.04117441 -0.003012239 -0.9999955 0 -0.3482874 -0.9373879 0 -0.2334239 -0.9686399 -0.08514779 -0.4489099 -0.893577 -2.71271e-4 0.4110299 -0.9116057 0.005442321 0.5724844 -0.8194089 -0.02882152 0.5958094 -0.8028922 -0.0193777 0.9616577 -0.2676956 0.05961275 0.8555569 -0.5171857 -0.02326732 0.8884245 -0.4590228 0 0.7273173 -0.6863013 0 0.6778156 -0.7352225 -0.003731489 0.6759119 -0.7369813 0.001354813 0.726499 -0.6871675 0 0.8884246 -0.4590228 0 0.5727235 -0.8197488 0 0.4518057 -0.8918369 0.02232867 0.5860736 -0.8102278 0.006979048 -0.610767 -0.7918089 -0.001617014 -0.4280905 -0.9037333 0.00222367 -0.3482723 -0.93734 0.01000398 -0.2227341 -0.9748793 0 0.1267526 -0.9919345 0 -1.85386e-4 -0.9997752 0.02120435 0.2354074 -0.9718968 -4.16016e-5 0.8884246 -0.4590225 0 0.9999803 0.006295204 0 0.8826379 0.4700537 0 0.882638 0.4700534 0 0.5627694 0.826614 0 0.5627692 0.826614 0 0.2323767 0.9726259 0 0.1142152 0.9934406 -0.005555629 -0.00556302 0.9999846 0 -0.3607119 0.9326773 0 -0.3607122 0.9326772 0 -0.7524468 0.658653 0 -0.7524468 0.6586531 0 -0.9724158 0.2332545 0 -0.9724159 0.233254 0 -0.9694163 -0.2454221 0 -0.9694162 -0.2454224 0 -0.8666097 -0.4989867 0 -0.8265454 -0.5628684 0.001440167 -0.9177383 0.1055732 0.3828979 0.7988442 -0.09189754 -0.5944769 0.9177804 -0.1055766 -0.3827959 0.7887772 -0.07553756 0.6100202 0.4166122 -0.06493073 0.9067626 0.6048013 -0.0666179 0.7935853 0.4125916 -0.04444056 0.9098315 0.3804123 -0.04395687 0.9237717 0.132148 -0.01496249 0.9911171 0.1296024 -0.01491034 0.991454 0.9854031 -0.1087532 0.1309716 0.9013709 -0.107125 0.4195891 0.9176859 -0.105569 0.3830246 0.7988874 -0.09190374 0.5944181 0.6488707 -0.09141266 0.7553878 0.9903531 -0.1139584 -0.07883119 0.9903535 -0.1139535 0.0788325 0.9617109 -0.119094 0.2468379 0.9871068 -0.09137207 -0.1314206 0.9030831 -0.1311172 -0.4089613 0.9617688 -0.1190889 -0.2466145 0.6234508 -0.09095668 -0.7765541 0.7886661 -0.07319813 -0.6104488 0.6176743 -0.06954574 -0.783353 0.6046853 -0.06955593 -0.7934215 0.3824088 -0.04398936 -0.9229456 0.3804662 -0.04395765 -0.9237495 0.1321301 -0.01499849 -0.9911189 -0.7852172 0.1055028 -0.6101666 -0.4205058 0.03139573 -0.9067466 -0.6040585 0.07244199 -0.7936409 -0.4121498 0.05043685 -0.9097191 -0.3805076 0.04356074 -0.9237514 -0.1320286 0.01538193 -0.9911266 -0.1300248 0.01495921 -0.9913979 0.1299879 -0.01495498 -0.9914029 -0.9844017 0.1178991 -0.130588 -0.9021226 0.100323 -0.4196549 -0.9177147 0.1055741 -0.3829541 -0.7988885 0.09190124 -0.5944169 -0.6527042 0.05832839 -0.7553642 -0.9903853 0.1139319 0.07846349 -0.9903854 0.1139304 -0.0784648 -0.9636464 0.1024038 -0.2467775 -0.9821059 0.135227 0.1310795 -0.9092002 0.07733887 0.4091134 -0.9637742 0.1024474 0.2462598 -0.1301836 0.01497751 0.9913768 -0.1323313 0.01543378 0.9910854 -0.3806577 0.04356545 0.9236893 -0.3828474 0.0440365 0.9227614 -0.6046424 0.06955373 0.7934545 -0.6174829 0.07255041 0.7832314 -0.7848344 0.1078472 0.6102492 -0.6278244 0.05299133 0.7765491 -0.7987481 0.09188377 0.5946083 0.6812229 -0.7294098 -0.062424 0.6482889 -0.7613945 0 0.829123 -0.5590664 0 0.8293775 -0.5586885 2.13801e-4 0.7345308 0.6785753 0 0.8295111 -0.5584904 0 0.9494321 -0.3139725 0 0.9494318 -0.3139736 0 0.9989305 -0.04623705 0 0.9989305 -0.04623794 0 0.9743686 0.2249575 0 0.9743685 0.2249581 0 0.8768634 0.4807397 0 0.8775379 0.4795073 -2.88527e-4 0.8776662 0.4792726 0 0.7898213 0.6133371 0 0.715237 0.6984392 -0.02487665 0.70569 0.7084626 -0.009082555 0.5890415 0.8080453 0.009645104 -0.6228969 0.7673026 -0.1524676 -0.5197655 0.854309 0 -0.5383109 0.8427464 0 -0.7457195 0.6662601 0 -0.7455713 0.6664258 -2.29821e-4 -0.7447968 0.6672914 0 -0.8978858 0.4402286 0 -0.8978842 0.4402318 0 -0.9833322 0.181818 0 -0.983332 0.1818193 0 -0.9959206 -0.09023422 0 -0.9959205 -0.09023517 0 -0.934682 -0.3554852 0 -0.9346746 -0.3555047 1.60269e-5 -0.9346652 -0.3555293 0 -0.8304426 -0.5571043 0 -0.803413 -0.5939944 -0.04121214 -0.7478809 -0.6638329 0 -0.1297475 0.9908856 0.03621172 -0.1751483 0.9842255 0.02497076 -0.2547543 0.9668644 0.01653617 -0.1211142 0.9926372 -0.00170201 -0.09234374 0.9957054 -0.006583213 0.3145424 0.9492183 -0.00690937 0.2780919 0.9603422 -0.02019762 -0.05344283 0.9983681 -0.02012455 -0.001924991 0.9986044 -0.05277907 -0.02201724 0.999222 -0.03272151 0.08335781 0.9965197 0 0.2482346 0.9686999 0 0.1594639 0.9797824 -0.1208216 0.2293441 0.9719672 -0.05178064 0.3456068 0.9383786 -0.001323103 0.3494578 0.9369516 -0.001035749 0.5639894 0.8257223 0.009951353 0.4601814 0.8876551 0.01736843 0.3965603 0.9176746 0.02476805 0.3503091 0.9359071 0.03689801 0.3076764 0.9495113 0.06134843 0.363878 0.9314392 -0.003703236 0.2087274 0.9779738 4.99668e-4 0.1134651 0.9918982 0.05712789 0.1551339 0.9844642 0.08224189 0.1132664 0.9901598 0.08218514 0.07831263 0.9962443 0.0369386 -0.1410846 0.9856823 -0.09233438 -0.02994942 0.9922528 0.120571 -0.08441632 0.9945593 0.06103789 0.5883615 0.8085404 0.009647965 0.5008444 0.865465 -0.01119345 0.3645883 0.931164 0.002997279 0.4979332 0.8671583 0.009963035 0.5025698 0.864478 0.01008158 0.1428207 -0.9897479 0.001260995 0.1585358 -0.9873464 -0.003692865 0.3892854 -0.9207618 -0.02558535 0.1567583 -0.9876312 0.003421187 0.3900459 -0.9207888 0.003510057 0.4185844 -0.9081606 -0.005620956 0.5619179 -0.8271898 0.002356827 0.5732814 -0.8193553 0.002353131 0.5606663 -0.8280419 0 0.130276 -0.991477 0.001266062 -0.1136502 -0.9935203 -0.001098752 -0.1145616 -0.9934152 -0.001408576 -0.3638355 -0.9314626 0.001092612 -0.3776516 -0.9259473 0.001095712 -0.364204 -0.9313169 -0.002077937 -0.379198 -0.9253088 -0.003574371 -0.5885475 -0.8084557 0.003394722 -0.5886619 -0.8083722 0.003399014 -0.6134337 -0.7897261 -0.005656719 -0.7358317 -0.6771603 0.002391576 -0.7339642 -0.6791841 0.002394437 -0.5609825 0.8277092 -0.01400303 -0.3899986 0.9207636 0.009774565 -0.2906697 0.9567742 0.009709835 -0.3898894 0.9206216 -0.02103424 -0.2916836 0.9564466 -0.01143634 -0.1434067 0.9896436 0.006337583 -0.2917472 0.9564433 0.009993433 -0.3570542 0.9340317 0.00986272 -0.138294 0.9903912 -3.83932e-4 0.2153658 0.9765334 0 0.5085905 0.8610086 0 0.508589 0.8610095 0 0.8149126 0.579584 0 0.8149134 0.5795828 0 0.9801388 0.1983129 0 0.980139 0.1983119 0 0.9760707 -0.2174536 0 0.9760711 -0.2174521 0 0.8032284 -0.5956712 0 0.8032264 -0.5956739 0 0.4917131 -0.8707574 0 0.4917129 -0.8707575 0 0.09380722 -0.9955904 0 0.0938065 -0.9955905 0 -0.3175382 -0.9482456 0 -0.3175376 -0.9482457 0 -0.6767055 -0.7362538 0 -0.6767029 -0.7362563 0 -0.9174867 -0.3977668 0 -0.9174873 -0.3977653 0 -0.9999518 0.009819209 0 -0.9999518 0.009819209 0 -0.9094318 0.4158532 0 -0.9094306 0.4158558 0 -0.6615322 0.7499169 0 -0.6615313 0.7499176 0 -0.3005347 0.9537709 0 -0.3005362 0.9537704 0 0.01197439 0.9999284 0 0.1141831 0.9929152 -0.0328918 0.09463471 -0.9955121 0 0.09499639 -0.9954777 1.74972e-4 0.4913576 -0.870958 0 0.4923059 -0.8704223 -5.09703e-4 0.4926801 -0.8702104 -6.01632e-4 0.4912796 -0.871002 0 0.8032159 -0.5956881 0 0.8032175 -0.5956859 0 0.9760733 -0.2174416 0 0.9760732 -0.2174424 0 0.9801369 0.1983224 0 0.9801366 0.1983234 0 0.8143886 0.58032 0 0.8145143 0.5801435 -8.08045e-5 0.8146594 0.5799399 0 0.5135372 0.8580673 0 0.508589 0.8610095 3.76845e-4 0.5080201 0.8613454 0 0.2167539 0.9762263 0 0.218883 0.9757511 3.86883e-4 0.1141604 0.9928911 -0.03368431 0.009551346 0.9999544 0 -0.2994271 0.9541193 0 -0.6618593 0.7496282 0 -0.6615417 0.7499084 -1.21175e-4 -0.661265 0.7501524 0 -0.9096356 0.4154074 0 -0.9096354 0.4154077 0 -0.9999519 0.009818792 0 -0.9999518 0.009818971 0 -0.9174911 -0.3977563 0 0.09634 -0.9953486 0 -0.3186165 -0.9478838 0 -0.3186179 -0.9478833 0 -0.6767363 -0.7362255 0 -0.6767037 -0.7362555 1.34546e-5 -0.6766181 -0.7363342 0 -0.9174911 -0.3977565 0 0.5085898 0.8610091 0 0.4908111 -0.871266 3.16438e-4 0.4892866 -0.8721231 0 0.9801342 0.1983354 0 0.9801344 0.1983347 0 0.8151547 0.5792436 0 0.8149129 0.5795835 1.41272e-4 0.8146335 0.5799761 0 0.5085894 0.8610093 0 0.2176769 0.9760209 0 0.1141782 0.9928901 -0.03365731 0.005752921 0.9999828 0.001160979 0.01224613 0.999925 0 -0.3001027 0.953907 0 -0.2994298 0.9541183 -4.2402e-4 -0.293535 0.9559484 0 -0.6618472 0.7496389 0 -0.6622167 0.7493125 1.47985e-4 -0.6625373 0.7490289 0 -0.9094262 0.4158656 0 -0.9094268 0.4158643 0 -0.9999519 0.009807586 0 0.4913684 -0.8709519 0 0.09497994 -0.9954792 0 0.09498006 -0.9954792 0 -0.3174611 -0.9482714 0 -0.3186178 -0.9478833 -1.88419e-4 -0.318927 -0.9477794 0 -0.6755307 -0.7373319 0 -0.6758225 -0.7370645 1.10441e-4 -0.6764369 -0.7365007 -5.82437e-5 -0.6766741 -0.7362827 0 0.09379023 -0.9955921 0 0.4917206 -0.8707531 0 0.4917233 -0.8707515 0 0.8032152 -0.5956891 0 0.803218 -0.5956854 0 0.9801341 0.1983362 0 0.9801346 0.1983339 0 0.8149125 0.5795841 0 0.8149133 0.5795829 0 0.5076997 0.8615341 0 0 0.9999988 -0.001541852 0.01002633 0.9999487 -0.001511931 0.114283 0.9928789 -0.03362727 0.2176422 0.9760286 0 0.5076977 0.8615354 0 0.1104125 0.9938859 0 0.1104125 0.9938859 0 0.1104125 0.9938859 0 -0.2994269 0.9541193 0 -0.2994273 0.9541192 0 -0.6615544 0.7498973 0 -0.6615533 0.7498982 0 -0.9096375 0.4154031 0 -0.9096393 0.415399 0 -0.9999514 0.009866535 0 -0.9174829 -0.3977752 0 -0.9174823 -0.3977767 0 -0.6767036 -0.7362555 0 -0.6767047 -0.7362546 0 -0.3176134 -0.9482203 0 -0.3174599 -0.9482717 0 -0.3174594 -0.9482719 0 0.09379011 -0.9955921 0 0.5085895 0.8610091 0 0.8032161 -0.5956878 -6.72978e-5 0.8032551 -0.5956352 0 0.9760733 -0.217442 0 0.9801343 0.1983352 0 0.9801344 0.1983345 0 0.8149484 0.5795336 0 0.8149185 0.5795755 1.00907e-5 0.8148219 0.5797115 0 0.1141605 0.9928921 -0.03365743 -0.3001024 0.9539071 0 -0.3005188 0.953776 2.42207e-4 -0.3041563 0.9526222 0 -0.6608041 0.7505585 0 -0.6615484 0.7499025 1.61568e-4 -0.661782 0.7496964 0 -0.9094236 0.4158712 0 -0.9094232 0.4158719 0 -0.999952 0.009807467 0 0.7996153 -0.6005127 0 0.4907971 -0.8712739 0 0.4907969 -0.8712741 0 0.09499746 -0.9954776 0 0.09499788 -0.9954776 0 -0.3186142 -0.9478845 -1.615e-4 -0.3189231 -0.9477806 0 -0.6755675 -0.7372983 0 -0.6760529 -0.7368531 1.61586e-4 -0.676408 -0.7365272 0 -0.9157744 -0.4016931 0 -0.9174909 -0.3977568 -2.69206e-5 -0.917509 -0.397715 0 -0.999952 0.009807407 0 0.09497892 -0.9954793 1.61513e-4 0.4923376 -0.8704044 0 0.4917134 -0.8707572 -2.28783e-4 0.4912525 -0.8710173 0 0.7990783 -0.601227 0 0.8032159 -0.5956881 -4.03787e-5 0.8032613 -0.5956267 0 0.9760729 -0.217444 0 0.9801363 0.1983249 0 0.9801368 0.1983225 0 0.8144171 0.5802801 0 0.814515 0.5801426 -8.41716e-5 0.513665 0.8579909 0 0.5085897 0.861009 3.49928e-4 0.5080048 0.8613543 0 0.2167527 0.9762266 0 0.1141605 0.9928911 -0.03368431 0.009551346 0.9999545 0 -0.6607384 0.7506164 0 -0.6615408 0.7499093 1.61567e-4 -0.6617963 0.7496838 0 -0.9096352 0.4154081 0 -0.9999517 0.009831011 0 0.09625601 -0.9953567 0 -0.3186014 -0.9478889 0 -0.3186011 -0.9478889 0 -0.6767051 -0.7362542 0 -0.6767033 -0.736256 0 -0.9153618 -0.4026325 0 -0.9174867 -0.3977668 -4.03807e-5 -0.9999517 0.009831011 0 -0.9174353 -0.3978852 0 -0.7291953 0.6843057 0 -0.7291938 0.6843072 0 -0.9337533 0.3579175 0 -0.9337557 0.3579111 1.16265e-5 -0.9339356 0.3574415 0 -0.9997685 -0.02151924 0 -0.9997686 -0.02151066 -6.3553e-6 -0.9997699 -0.02144896 0 -0.9174353 -0.397885 0 -0.698978 -0.7151432 0 -0.6990796 -0.7150439 6.97641e-5 -0.6992652 -0.7148624 0 -0.3770394 -0.9261972 0 0.001036942 -0.9999995 0 0.001036942 -0.9999995 0 0.9997687 0.0215106 0 0.7291938 -0.6843072 0 0.7291953 -0.6843057 0 0.9337533 -0.3579175 0 0.9337556 -0.3579113 1.27165e-5 0.9339356 -0.3574415 0 0.9997687 0.02151072 0 0.9172115 0.3984009 0 0.9172421 0.3983302 1.67225e-5 0.9174686 0.3978083 -1.00422e-4 0.9175394 0.3976449 0 0.6992484 0.7148789 0 0.6992502 0.714877 0 0.6983775 0.7157297 0 0.6983758 0.7157314 0 0.3770519 0.9261922 0 0.3770531 0.9261916 0 -0.001036942 0.9999995 0 -0.001036942 0.9999995 0 3.67197e-6 0 1 0.1568452 -0.9876233 0 -0.2284706 -0.9735508 0 -0.2284703 -0.973551 0 0.5176172 -0.8556124 3.59883e-4 0.520313 -0.8539757 0 0.5192019 -0.8546516 0 0.5191956 -0.8546556 0 0.5181257 -0.8553045 0 0.8034524 -0.5953691 0 0.8034535 -0.5953677 0 0.968904 -0.2474369 0 0.9687181 -0.2481641 -6.98079e-5 0.9686924 -0.2482642 0 0.9911224 0.1329526 0 0.9906415 0.1364898 -3.19652e-5 0.990636 0.1365303 0 0.8657396 0.5004948 0 0.8657388 0.5004961 0 -0.4109522 -0.9116569 0 -0.4109224 -0.9116703 4.26915e-4 -0.4108858 -0.9116868 4.08822e-4 -0.410354 -0.9119264 0 0.6660385 -0.2405527 0.7060647 0.6661525 -0.2404468 0.7059931 0.6662202 -0.2402989 0.7059796 0.6660611 -0.2404934 0.7060634 0.6951669 -0.1350596 0.7060467 0.6951553 -0.1350384 0.7060621 0.7033084 0.08283084 0.7060428 0.703319 0.08291244 0.7060226 0.7032911 0.08294147 0.7060469 0.7033046 0.08300757 0.7060258 0.7077009 -0.02630865 0.7060223 0.7076766 -0.02636277 0.7060446 0.707683 -0.02638369 0.7060373 0.6951635 -0.1350216 0.7060573 -0.1918405 0.9814261 0 -0.1936765 0.9810655 -3.16654e-4 -0.1942509 0.9809519 0 -0.1936222 0.9810762 -2.82202e-4 -1.68784e-7 0 1 -1.52486e-6 0 1 4.36651e-6 0 1 -1.08397e-6 0 1 -6.28087e-7 0 1 1.62425e-5 0 1 -7.58157e-6 0 1 0.2800775 0.65033 0.7061356 0.2799198 0.6505274 0.7060163 0.2797893 0.6505517 0.7060456 0.3766697 0.5996894 0.7060402 0.3764913 0.5997329 0.7060983 0.3763275 0.5998768 0.7060634 0.3762155 0.5999267 0.7060806 0.4641785 0.53478 0.70608 0.4646729 0.5343942 0.7060467 0.4646106 0.5346447 0.7058982 0.464758 0.5344496 0.7059488 0.541402 0.456687 0.7059186 0.5412104 0.4567569 0.7060202 0.5413138 0.4565864 0.7060512 0.5405009 0.4577503 0.7059203 -0.9467126 0.3220798 0 -0.9464094 0.3229696 1.70479e-4 -0.9463132 0.3232515 0 -0.9463836 0.3230451 8.81946e-5 -0.8664085 0.499336 0 0.9572317 0.2893228 0 0.9572318 0.2893221 0 0.7766126 0.6299785 0 0.7777113 0.6286218 0 0.7777125 0.6286202 0 0.4809792 0.8767321 0 0.4809803 0.8767315 0 0.114251 0.993452 0 0.1142514 0.993452 0 -0.2690503 0.9631262 0 -0.2690504 0.9631261 0 -0.6143776 0.7890121 0 -0.6143797 0.7890105 0 -0.6135444 0.7896603 0 -0.6135432 0.7896612 0 -0.8664088 0.4993354 0 0.9950169 0.0997073 0 0.9950166 0.09970951 4.12323e-5 0.9950237 0.09963917 8.94105e-5 0.9950125 0.09975069 0 -0.124929 0.6969437 0.7061603 -0.1246353 0.6971781 0.7059808 -0.1252452 0.6971441 0.7059063 -0.2307156 0.6696917 0.7058919 -0.2304152 0.6696851 0.7059963 -0.2307886 0.6694539 0.7060936 -0.2314853 0.669295 0.7060162 -0.3305669 0.6262938 0.7060322 -0.3308932 0.6261694 0.7059898 -0.3310042 0.62603 0.7060615 -0.422438 0.5685601 0.7058935 -0.4234876 0.5677274 0.7059347 -0.4235739 0.5675247 0.7060459 -0.3311387 0.6259783 0.7060441 1.52486e-6 0 1 -2.29082e-6 0 1 -0.8657432 -0.5004885 0 0.2284703 0.973551 0 0.2284706 0.9735508 0 -0.1568303 0.9876255 0 -0.5183425 0.8551731 0 -0.5183459 0.8551711 0 -0.8033832 0.5954625 0 -0.8037204 0.5950073 -3.56302e-4 -0.8039567 0.5946878 -4.41147e-4 -0.8029667 0.5960239 0 -0.9687169 0.2481682 0 -0.9687173 0.2481669 0 -0.9911225 -0.1329522 0 -0.9906415 -0.1364898 3.19652e-5 -0.990636 -0.1365303 0 0.4109591 0.9116539 0 0.4109284 0.9116675 4.26913e-4 0.4108327 0.9117108 4.08833e-4 0.410354 0.9119264 0 -0.6660316 0.2405483 0.7060726 -0.6661392 0.240442 0.7060073 -0.6662437 0.2403138 0.7059524 -0.666077 0.2404953 0.7060478 -0.6951534 0.135057 0.7060605 -0.6951571 0.1350381 0.7060604 -0.6951585 0.1350225 0.706062 -0.7076888 0.02638393 0.7060315 -0.7076793 0.02636319 0.7060419 -0.7076918 0.02630794 0.7060313 -0.703298 -0.08300679 0.7060325 -0.7033048 -0.08294421 0.706033 -0.7033197 -0.08291262 0.7060219 -0.7033084 -0.08282941 0.7060429 -1.57558e-6 0 1 1.49971e-6 0 1 9.7045e-6 0 1 -2.80934e-6 0 1 -5.91968e-7 0 1 1.02168e-6 0 1 6.43973e-7 0 1 0.5038213 0.8635839 -0.01967352 0.5316283 0.8468618 0.0140134 0.5312255 0.8471149 0.01400029 0.6389455 0.7690874 -0.01591223 0.6561364 0.754584 0.009389996 0.6561678 0.7545568 0.009380161 0.7567573 0.6536169 -0.01017349 0.7642093 0.644958 0.003662645 0.7631033 0.6462661 0.003687024 0.8541839 0.5199558 -0.004011929 0.8557927 0.5173189 0 0.9281157 0.372292 0 0.928116 0.3722912 0 0.9696938 0.2443233 0 0.9763894 0.2144409 -0.0260539 0.992864 0.1169316 0.02341246 0.9984397 0.05072778 0.02334743 0.9909288 0.1168644 -0.06635469 0.9990158 -0.03713703 0.02425497 0.9931564 -0.114257 0.02420473 0.9961263 -0.03713768 -0.07970774 0.9813662 -0.1906138 0.02422475 0.9813566 -0.1906641 0.02421951 0.9607428 -0.2760778 -0.02747017 0.9403085 -0.3395159 0.02343136 0.9403439 -0.3394176 0.02343255 0.9022135 -0.430509 -0.02594166 0.8889759 -0.4579539 0 0.8193324 -0.5733188 0 0.7158042 -0.6983011 0 0.7136363 -0.7005048 -0.004022538 0.596261 -0.8027822 0.003684878 0.5981263 -0.8013935 0.003667712 0.5888363 -0.8081868 -0.0102989 0.4675392 -0.8839227 0.009364366 0.4671996 -0.8841026 0.009340345 0.4477201 -0.8940436 -0.01526266 0.3267987 -0.9449856 0.0143156 0.3253195 -0.945496 0.01430183 0.2943993 -0.9554855 -0.01940381 0.1767886 -0.9840749 0.01850825 0.1764101 -0.9841428 0.01850223 0.1328296 -0.9908635 -0.02336561 0.0748099 -0.9971979 0 -0.03179883 -0.9994943 0 -0.1960154 -0.9806009 0 -0.1960158 -0.9806008 0 -0.2992548 -0.9541732 0 -0.3544909 -0.9347648 -0.02346998 -0.3954716 -0.9182917 0.0185154 -0.3950185 -0.9184865 0.01851665 -0.5038213 -0.8635833 -0.01969587 -0.5316284 -0.846862 0.01400482 -0.5312254 -0.8471146 0.0140227 -0.6389499 -0.7690837 -0.01591217 -0.6561355 -0.7545845 0.009403824 -0.6562042 -0.7545248 0.009398162 -0.7567571 -0.6536167 -0.0101884 -0.7642062 -0.6449617 0.003677785 -0.7631034 -0.6462661 0.003674268 -0.8541819 -0.519959 -0.004019379 -0.8557927 -0.5173189 0 -0.9281157 -0.372292 0 -0.928116 -0.3722912 0 -0.9696938 -0.2443233 0 -0.9763894 -0.2144409 -0.02605301 -0.9928643 -0.1169295 0.02341204 -0.9984397 -0.05072778 0.02334743 -0.9909288 -0.1168652 -0.06635344 -0.9990159 0.03713643 0.02425456 -0.9990118 0.03724712 0.02425503 -0.9930661 0.1141951 -0.02791476 -0.9813631 0.1906162 0.02433407 -0.9813538 0.1906635 0.02433943 -0.960712 0.2761937 -0.02738106 -0.9403094 0.3395132 0.02343446 -0.9403442 0.3394176 0.02342247 -0.9022131 0.4305097 -0.02594172 -0.8889741 0.4579576 0 -0.8193342 0.5733162 0 -0.8193348 0.5733153 0 -0.7158014 0.6983041 0 -0.7136336 0.7005077 -0.004017889 -0.5963758 0.8026971 0.003661394 -0.5981223 0.8013965 0.003667712 -0.5888364 0.808187 -0.01028025 -0.4675884 0.8838968 0.009358942 -0.4671943 0.8841053 0.009340345 -0.44772 0.8940435 -0.0152738 -0.3268336 0.9449737 0.01430386 -0.3253118 0.9454984 0.01432126 -0.2944049 0.9554834 -0.01942241 -0.1767887 0.984075 0.01850092 -0.1764094 0.9841426 0.01852345 -0.1328235 0.9908635 -0.02340292 -0.0748099 0.9971979 0 0.03179883 0.9994943 0 0.1960154 0.9806009 0 0.1960158 0.9806008 0 0.2992355 0.9541793 0 0.3544909 0.9347648 -0.02346998 0.3954792 0.9182887 0.01849961 0.3950188 0.9184872 0.01848447 -0.5409495 -0.4569944 0.7060665 -0.5405638 -0.45777 0.7058594 -0.5413448 -0.4562264 0.7062601 -0.5412855 -0.4568254 0.7059183 -0.4648274 -0.5344702 0.7058875 -0.4645951 -0.534634 0.7059164 -0.4646823 -0.5344051 0.7060323 -0.4642155 -0.534776 0.7060585 -0.3763145 -0.5998725 0.7060739 -0.3762351 -0.5999584 0.7060433 -0.376613 -0.5996 0.7061463 -0.280075 -0.6503389 0.7061284 -0.2799219 -0.6505199 0.7060225 -0.2797944 -0.6505637 0.7060326 -0.3765203 -0.5997788 0.7060438 -0.5839914 0.8117599 0 -0.5840076 0.8117482 7.75972e-5 -0.5841944 0.8116138 0 -0.5841364 0.8116557 0 0.8664085 -0.499336 0 -0.9572317 -0.2893228 0 -0.9572318 -0.2893221 0 -0.7766037 -0.6299895 0 -0.7766053 -0.6299877 0 -0.7777669 -0.6285529 0 -0.4809681 -0.8767383 0 -0.4809668 -0.8767388 0 -0.114251 -0.993452 0 -0.1142514 -0.993452 0 0.2690503 -0.9631262 0 0.2690504 -0.9631261 0 0.6143348 -0.7890455 0 0.6143368 -0.789044 0 0.6135444 -0.7896603 0 0.6135432 -0.7896612 0 0.8664088 -0.4993354 0 -0.3691779 -0.9293587 0 0.1472682 -0.9890967 0 0.1472683 -0.9890966 0 0.622493 -0.7826254 0 0.6224952 -0.7826237 0 0.9299748 -0.3676235 0 0.9299752 -0.3676223 0 0.9891442 0.1469483 0 0.9891443 0.1469478 0 0.7838715 0.6209231 0 0.7838702 0.6209248 0 0.3671283 0.9301704 0 -0.1473056 0.9890911 0 -0.1473056 0.989091 0 -0.6210119 0.7838012 0 -0.6210117 0.7838014 0 -0.9299768 0.3676182 0 -0.9299773 0.3676171 0 -0.9891963 -0.1465979 0 -0.9891964 -0.1465971 0 -0.782961 -0.6220709 0 -0.7829614 -0.6220704 0 -0.3691778 -0.9293588 0 -0.1447123 0.9894738 0 -0.14837 0.988932 0 -0.1483705 0.9889319 0 -0.6210127 0.7838005 0 -0.6210111 0.7838019 0 -0.9891974 -0.1465901 0 -0.9891968 -0.1465933 0 -0.7829473 -0.6220883 0 -0.7829464 -0.6220893 0 -0.3691324 -0.9293769 0 -0.3691332 -0.9293766 0 -0.3693961 -0.9292721 0 -0.3693949 -0.9292726 0 0.1473037 -0.9890913 0 0.6224887 -0.7826288 0 0.6224924 -0.7826258 0 0.9299762 -0.3676196 0 0.9299768 -0.3676185 0 0.9891447 0.1469454 0 0.9891452 0.1469416 0 0.7838682 0.6209273 0 0.7838652 0.620931 0 0.3670971 0.9301827 0 -0.1447116 0.9894739 0 0.3692085 0.9293466 0 -0.1473038 0.9890913 0 -0.1473039 0.9890914 0 -0.622493 0.7826254 0 -0.6224952 0.7826237 0 -0.9299747 0.3676237 0 -0.9299752 0.3676225 0 -0.9891435 -0.1469535 0 -0.9891434 -0.1469539 0 -0.7838845 -0.6209067 0 -0.7838858 -0.6209051 0 -0.3670976 -0.9301825 0 0.1473056 -0.9890911 0 0.1473056 -0.989091 0 0.6210119 -0.7838012 0 0.6210117 -0.7838014 0 0.9299723 -0.3676298 0 0.989197 0.1465925 0 0.9891971 0.1465917 0 0.7829465 0.622089 0 0.782947 0.6220885 0 0.3692084 0.9293467 0 -0.9299762 0.3676196 6.42172e-5 -0.9296305 0.368493 0 -0.9891447 -0.1469454 0 -0.9891452 -0.1469416 0 -0.7838682 -0.6209273 0 -0.7838652 -0.620931 0 -0.3671278 -0.9301706 0 0.1447116 -0.9894739 0 0.1447123 -0.9894738 0 0.1484201 -0.9889245 0 0.1484207 -0.9889243 0 0.6210127 -0.7838005 0 0.6210111 -0.7838019 0 0.9299768 -0.3676182 0 0.9299773 -0.3676171 0 0.9892992 0.1459013 0 0.9891965 0.1465954 -5.73911e-5 0.9891614 0.1468325 0 0.7829617 0.6220701 0 0.7829607 0.6220712 0 0.3690876 0.9293947 0 0.3690894 0.9293939 0 0.3693961 0.9292721 0 0.3693949 0.9292726 0 -0.1472681 0.9890966 0 -0.6224887 0.7826288 0 -0.6224924 0.7826258 0 -0.9300914 0.3673282 0 -3.35435e-5 0 -1 -2.23491e-6 0 -1 -5.03221e-6 0 -1 2.03543e-7 0 -1 8.78364e-6 0 -1 2.98929e-7 0 -1 -5.84331e-6 0 -1 3.54088e-6 0 -1 -5.88429e-6 0 -1 3.5012e-6 0 -1 1.75016e-6 0 -1 2.9237e-6 0 -1 1.01239e-6 0 -1 -1.44253e-5 0 -1 -1.942e-6 0 -1 1.62043e-6 0 -1 7.02484e-6 0 -1 2.2063e-6 0 -1 -4.22754e-6 0 -1 -4.71389e-6 0 -1 4.74792e-6 0 -1 -2.2839e-6 0 -1 5.34264e-6 0 -1 -1.55775e-6 0 -1 6.72853e-6 0 -1 -2.40468e-6 0 -1 -1.38724e-5 0 -1 6.59677e-6 0 -1 2.44141e-6 0 -1 -3.84462e-6 0 -1 5.10376e-6 0 -1 -6.34639e-6 0 -1 2.26183e-5 0 -1 -1.39896e-6 0 -1 3.24136e-6 0 -1 -1.43332e-6 0 -1 -6.88781e-6 0 -1 8.79941e-6 0 -1 -1.77271e-5 0 -1 2.89144e-6 0 -1 -2.69713e-5 0 -1 -5.9208e-6 0 -1 7.67212e-6 0 -1 -7.32156e-6 0 -1 -5.52685e-5 0 -1 -2.34303e-6 0 -1 -1.98029e-6 0 -1 3.54922e-6 0 -1 -6.75584e-6 0 -1 7.80196e-6 0 -1 1.05226e-5 0 -1 1.51258e-5 0 -1 -1.27095e-5 0 -1 1.56318e-5 0 -1 -2.6812e-6 0 -1 2.93083e-6 0 -1 5.71742e-6 0 -1 -2.45194e-6 0 -1 5.23125e-6 0 -1 2.65078e-6 0 -1 2.65215e-6 0 -1 -3.19497e-6 0 -1 1.36169e-5 0 -1 5.89275e-6 0 -1 -8.80195e-7 0 -1 6.7352e-7 0 -1 -1.21415e-5 0 -1 -3.61679e-6 0 -1 3.53923e-6 0 -1 5.81278e-6 0 -1 2.8664e-5 0 -1 -1.08333e-5 0 -1 -3.1387e-7 0 -1 -7.84814e-7 0 -1 -1.97822e-6 0 -1 3.55194e-6 0 -1 6.45128e-6 0 -1 -3.6904e-7 0 -1 -2.65083e-6 0 -1 1.32553e-6 0 -1 -6.2837e-6 0 -1 -8.05172e-6 0 -1 1.47728e-5 0 -1 1.0834e-5 0 -1 8.07269e-6 0 -1 -9.70859e-6 0 -1 9.11876e-6 0 -1 4.90292e-6 0 -1 -1.75858e-6 0 -1 -1.51647e-6 0 -1 -1.36173e-5 0 -1 1.42304e-5 0 -1 4.68727e-6 0 -1 -6.96786e-6 0 -1 -5.89623e-5 0 -1 9.42344e-7 0 -1 2.36915e-6 0 -1 1.01492e-4 0 -1 1.01554e-4 0 -1 1.016e-4 0 -1 -4.27637e-7 0 -1 1.9756e-6 0 -1 4.68516e-6 0 -1 -2.40004e-6 0 -1 2.77236e-6 0 -1 -4.02876e-5 0 -1 -3.64618e-5 0 -1 3.24305e-6 0 -1 0 0 -1 9.36835e-7 0 -1 2.98258e-5 0 -1 3.03722e-6 0 -1 -4.15987e-6 0 -1 2.40052e-6 0 -1 8.27048e-7 0 -1 -2.39436e-6 0 -1 1.60102e-6 0 -1 3.78095e-6 0 -1 -5.25597e-6 0 -1 2.43974e-5 0 -1 -2.28804e-6 0 -1 -2.28745e-6 0 -1 -3.84809e-6 0 -1 1.77693e-4 0 -1 1.77853e-4 0 -1 1.77789e-4 0 -1 -9.30129e-6 0 -1 1.49679e-6 0 -1 -2.75908e-6 0 -1 2.63115e-6 0 -1 -7.05577e-7 0 -1 -2.99742e-5 0 -1 -1.17327e-5 0 -1 4.16056e-6 0 -1 -2.1815e-6 0 -1 -4.04053e-6 0 -1 1.43008e-6 0 -1 6.42264e-7 0 -1 7.80214e-6 0 -1 -1.20908e-6 0 -1 -1.52618e-6 0 -1 9.34286e-7 0 -1 4.11265e-6 0 -1 -1.25318e-6 0 -1 1.21044e-6 0 -1 -2.9002e-6 0 -1 -2.81215e-6 0 -1 3.77134e-6 0 -1 -3.73871e-6 0 -1 3.4211e-6 0 -1 5.50491e-6 0 -1 -7.5798e-7 0 -1 4.11807e-6 0 -1 -1.71396e-6 0 -1 -1.01165e-5 0 -1 1.01953e-5 0 -1 -3.03956e-5 0 -1 -5.14785e-6 0 -1 0 0 -1 4.70945e-7 0 -1 2.332e-5 0 -1 -6.32399e-6 0 -1 1.21997e-5 0 -1 3.38128e-6 0 -1 -4.37598e-5 0 -1 5.09341e-6 0 -1 -2.54412e-6 0 -1 6.76782e-6 0 -1 -2.65506e-6 0 -1 4.06987e-6 0 -1 -1.2578e-5 0 -1 -2.75737e-6 0 -1 2.12527e-6 0 -1 9.58424e-6 0 -1 -3.71096e-6 0 -1 1.29587e-5 0 -1 5.49233e-6 0 -1 5.93328e-7 0 -1 -8.66431e-6 0 -1 7.09784e-6 0 -1 8.51591e-7 0 -1 -7.01951e-6 0 -1 1.03955e-6 0 -1 -2.81453e-6 0 -1 2.75743e-6 0 -1 -9.58765e-7 0 -1 -3.65129e-6 0 -1 -6.96076e-6 0 -1 -2.30436e-6 0 -1 2.81474e-6 0 -1 -1.21669e-5 0 -1 -1.0799e-5 0 -1 -8.42681e-7 0 -1 2.84498e-6 0 -1 3.67301e-6 0 -1 3.49006e-6 0 -1 -1.70379e-6 0 -1 1.09361e-6 0 -1 1.68192e-5 0 -1 5.10173e-6 0 -1 -6.34276e-6 0 -1 4.16965e-6 0 -1 -1.36132e-5 0 -1 1.58378e-5 0 -1 -1.20993e-6 0 -1 -3.52073e-6 0 -1 -1.67029e-5 0 -1 6.46688e-6 0 -1 -2.59032e-6 0 -1 -4.20156e-6 0 -1 7.05358e-6 0 -1 2.75646e-6 0 -1 0.1484159 -0.9889251 0 0.148415 -0.9889252 0 0.929978 -0.3676156 0 0.9891964 0.1465971 0 0.7829349 0.6221038 0 0.3691341 0.9293763 0 0.3691324 0.9293769 0 -0.1473037 0.9890913 0 -0.1473032 0.9890914 0 -0.6224904 0.7826275 0 -0.9299762 0.3676196 0 -0.9299768 0.3676185 0 -0.9891445 -0.146947 0 -0.9891443 -0.1469475 0 -0.7838665 -0.6209294 0 -2.56312e-5 0 1 6.44197e-6 0 1 2.73907e-6 0 1 4.11171e-6 0 1 9.4611e-7 0 1 1.46107e-6 0 1 4.32182e-6 0 1 6.79941e-6 0 1 -8.18254e-6 0 1 9.70393e-6 0 1 -8.34943e-7 0 1 5.89067e-6 0 1 1.81642e-6 0 1 -3.21676e-6 0 1 -5.06298e-6 0 1 -9.70699e-6 0 1 -3.38937e-5 0 1 -1.03714e-6 0 1 -2.68693e-6 0 1 7.12181e-6 0 1 -5.45066e-6 0 1 -8.27508e-7 0 1 -1.98498e-6 0 1 -1.97117e-6 0 1 7.71755e-6 0 1 -1.15651e-5 0 1 -4.59779e-6 0 1 -4.16583e-6 0 1 -1.52517e-6 0 1 9.16758e-6 0 1 4.49107e-6 0 1 -3.30643e-5 0 1 -1.04541e-5 0 1 1.44429e-6 0 1 1.73582e-6 0 1 2.8595e-6 0 1 2.12889e-6 0 1 -7.19751e-6 0 1 0 0 1 4.3997e-6 0 1 -2.92405e-6 0 1 -7.5589e-7 0 1 -6.95062e-6 0 1 7.32102e-6 0 1 -2.02952e-5 0 1 -1.42981e-6 0 1 1.1672e-5 0 1 -1.83972e-5 0 1 7.96381e-6 0 1 9.84686e-6 0 1 -2.89144e-6 0 1 -8.7868e-6 0 1 -3.37792e-6 0 1 -1.87389e-6 0 1 5.27454e-6 0 1 -2.16202e-5 0 1 -1.05226e-5 0 1 7.80202e-6 0 1 1.00898e-6 0 1 1.33982e-6 0 1 -1.94589e-6 0 1 -4.02194e-6 0 1 1.8318e-6 0 1 4.6813e-6 0 1 -1.55322e-6 0 1 4.01606e-6 0 1 -4.45545e-6 0 1 -2.65078e-6 0 1 -3.71884e-6 0 1 2.89426e-6 0 1 3.58187e-6 0 1 -4.48962e-6 0 1 8.98053e-6 0 1 -4.06552e-7 0 1 -1.92883e-6 0 1 2.00096e-6 0 1 1.02111e-5 0 1 -5.41044e-6 0 1 -2.92761e-6 0 1 -7.29352e-6 0 1 7.4958e-6 0 1 2.89288e-6 0 1 -2.27128e-5 0 1 1.88009e-5 0 1 -1.44249e-6 0 1 -2.44069e-5 0 1 2.28728e-6 0 1 4.05134e-6 0 1 1.21987e-5 0 1 4.28449e-6 0 1 -9.07853e-6 0 1 2.00199e-6 0 1 3.85797e-6 0 1 -1.62612e-6 0 1 4.48758e-6 0 1 3.05521e-6 0 1 7.21193e-7 0 1 -7.69787e-6 0 1 -3.03398e-6 0 1 -3.79202e-6 0 1 8.07181e-6 0 1 -9.29645e-6 0 1 2.03239e-6 0 1 1.05162e-5 0 1 -2.16313e-5 0 1 3.4211e-6 0 1 -3.73871e-6 0 1 1.05517e-6 0 1 -1.27305e-6 0 1 2.07216e-6 0 1 -1.82258e-6 0 1 2.49598e-6 0 1 -2.21456e-6 0 1 3.62274e-6 0 1 2.70227e-6 0 1 -3.3771e-6 0 1 2.56335e-5 0 1 3.728e-6 0 1 -1.04901e-5 0 1 1.42453e-5 0 1 -4.38227e-6 0 1 -9.53383e-7 0 1 -2.46665e-6 0 1 4.46812e-6 0 1 7.42721e-6 0 1 1.79634e-6 0 1 -1.15719e-6 0 1 4.21998e-6 0 1 -8.13948e-6 0 1 2.36855e-5 0 1 -8.74585e-5 0 1 1.01763e-5 0 1 3.02967e-6 0 1 7.61823e-6 0 1 -5.09362e-6 0 1 4.37522e-5 0 1 -1.01442e-5 0 1 2.65601e-6 0 1 -3.26951e-6 0 1 -1.58819e-6 0 1 1.10259e-6 0 1 -1.7618e-5 0 1 3.59092e-6 0 1 2.52382e-6 0 1 -7.64503e-6 0 1 9.60209e-6 0 1 -9.35769e-6 0 1 4.38335e-6 0 1 -2.17983e-6 0 1 4.04536e-6 0 1 -2.39427e-6 0 1 3.24305e-6 0 1 -4.86457e-6 0 1 3.24423e-6 0 1 -1.24495e-6 0 1 2.46678e-6 0 1 -4.46812e-6 0 1 7.58495e-7 0 1 2.77735e-6 0 1 -8.611e-6 0 1 4.06954e-6 0 1 -1.65418e-6 0 1 -4.0408e-6 0 1 8.07077e-6 0 1 -1.47388e-5 0 1 3.44885e-6 0 1 -3.04077e-6 0 1 -2.63999e-5 0 1 -1.46037e-5 0 1 5.75612e-6 0 1 -2.10211e-6 0 1 4.79791e-6 0 1 -7.36247e-6 0 1 6.59339e-6 0 1 -7.73629e-6 0 1 6.22169e-6 0 1 -4.18284e-6 0 1 -5.71037e-6 0 1 1.72876e-6 0 1 1.67347e-5 0 1 -6.21693e-6 0 1 -7.73742e-6 0 1 1.97999e-5 0 1 9.10084e-6 0 1 -6.3336e-6 0 1 -7.36768e-6 0 1 -5.96481e-5 0 1 3.48948e-6 0 1 5.72303e-6 0 1 7.25788e-6 0 1 -1.27801e-6 0 1 -2.62649e-6 0 1 1.56998e-6 0 1 -7.07908e-6 0 1 -6.7627e-6 0 1 4.205e-6 0 1 -7.04106e-6 0 1 -4.20136e-6 0 1 5.49913e-6 0 1 1.01334e-5 0 1 -1.12914e-5 0 1 5.72254e-6 0 1 5.96516e-5 0 1 0.4223859 -0.5686554 0.7058479 0.4225643 -0.5684278 0.7059245 0.4240019 -0.5670807 0.7061458 0.4235839 -0.5675318 0.7060343 0.4235268 -0.5675512 0.706053 0.3310787 -0.6259484 0.7060989 0.3310067 -0.6260214 0.7060679 0.3309005 -0.6261713 0.7059848 0.330577 -0.6262996 0.7060225 0.2314653 -0.6692893 0.7060281 0.2307759 -0.6694541 0.7060975 0.2304223 -0.6696859 0.7059933 0.2307217 -0.6696836 0.7058976 0.1252486 -0.6971518 0.7058981 0.1246294 -0.6971732 0.7059866 0.1249297 -0.6969473 0.7061566 0.7528559 0.6581855 3.96939e-5 0.7528995 0.6581357 0 0.7529764 0.6580477 -5.99888e-5 0.7531378 0.6578629 -8.94061e-5 0.7529574 0.6580693 0 0.9976102 -0.06909322 0 -0.9282345 0.3719959 0 -0.9284688 -0.3714103 0 -0.7769551 -0.6295561 0 -0.2776545 -0.960681 0 0.8046543 0.5937438 0 -0.127726 0.9918095 0 -0.1083008 0.9941182 0 -0.01782017 0.9998413 0 0.1139461 0.993487 0 0.1139461 0.993487 0 0.3489509 0.937141 0 0.2634832 0.9646641 0 0.2454718 0.969376 -0.007334113 0.3506906 0.9364722 0.005996763 0.9104542 0.4127733 -0.02629542 0.9289527 0.3701984 0 0.8480042 0.5299896 0 0.9585067 0.2850705 0 0.9804049 0.1966152 0.01219719 0.9708806 0.2395635 -5.05693e-4 0.9585214 0.2850205 0 0.94403 0.3298599 0 0.9440298 0.3298604 0 0.8902828 -0.4546467 -0.02632886 0.8684877 -0.4957109 0 0.943135 -0.33241 0 0.9091978 -0.4133848 0.04972505 0.9439682 -0.3300365 0 0.8232545 -0.5676726 0 0.5754262 -0.8178538 0 0.6136518 -0.7895768 0 0.1715118 -0.9851821 0 0.1999031 -0.9794577 -0.02648204 0.08081018 -0.9958592 0.04164642 0.07530009 -0.997161 0 -0.201169 -0.9795562 -8.33235e-4 -0.2026254 -0.9792563 0 -0.02672523 -0.9996429 0 -0.02479314 -0.999692 -0.001087486 0.07530003 -0.997161 0 0.1110571 -0.9938141 0 0.111057 -0.9938141 0 -0.3340895 -0.9425414 0 -0.2776501 -0.9606823 0 -0.3340899 -0.9425413 0 -0.3062891 -0.9518995 0.008615016 -0.4176356 -0.9085161 -0.0133816 -0.390904 -0.9204315 0 -0.7356705 -0.6773396 0 -0.8913753 -0.4532651 -9.66703e-4 -0.8921478 -0.4517437 0 -0.7979947 -0.6026645 0 -0.9451257 -0.3267071 0 -0.9942328 -0.107243 0 -0.9284894 -0.3713589 0 -0.9451259 -0.3267067 0 -0.9583241 -0.2853983 -0.01275843 -0.9706872 -0.2403466 0 -0.980904 -0.1944931 0 -0.9939751 -0.1095989 0.001347124 -0.9942333 -0.1072399 3.77962e-5 -0.8907467 0.4538601 0.02411478 -0.9101943 0.4141804 -9.28861e-4 -0.8445422 0.5354893 0 -0.7055036 0.7086795 0.006179332 -0.7144168 0.6997205 0 -0.7930944 0.6090989 0 -0.8205513 0.5714314 -0.01272112 -0.8445422 0.5354891 0 -0.8713802 0.4906085 0 -0.871366 0.4906337 0 0.1715111 -0.9851822 0 0.3269896 -0.945028 0 0.3280078 -0.944675 9.96181e-5 0.5286519 -0.8488388 0 0.5286526 -0.8488383 0 0.5754261 -0.8178539 0 0.6137014 -0.7895381 -4.84822e-4 0.6403752 -0.7679752 0.01157611 0.6827483 -0.7306537 0 0.7649564 -0.6440822 0 0.766137 -0.6426766 -0.001020014 0.8232359 -0.5676994 0 0.8463292 -0.5326602 0 0.8463307 -0.5326579 0 0.3282086 -0.9446053 0 0.4910761 -0.8711166 0 0.4504255 -0.8927974 -0.005462944 0.491818 -0.8706147 -0.01205384 0.4812147 -0.8764719 -0.01514542 0.9439418 -0.3301121 3.35439e-5 0.943992 -0.3299685 0 0.9788293 -0.2046789 0 0.9872539 -0.1586936 -0.01209509 0.9884132 0.1517875 0 0.9884129 0.1517898 0 0.9998003 0.01998728 0 0.9997631 0.02176415 -5.91368e-5 0.9997981 0.02007681 -8.9283e-4 0.9976116 -0.06907343 0 0.9932686 -0.1158351 0 0.9932686 -0.1158345 0 0.7101684 0.7040319 0 0.6072241 0.7945302 -7.33952e-4 0.6063767 0.7951774 -5.87391e-4 0.8545181 0.5193739 0.007063269 0.8046495 0.5937502 0 0.7702123 0.6377876 0 0.7397336 0.6727924 -0.01202237 0.7101672 0.7040331 0 0.6636444 0.7480483 0 0.6636329 0.7480584 0 0.3769876 0.9262184 0 0.6075739 0.7942633 0 0.4566295 0.8896571 0 0.4577038 0.8891048 -2.17554e-4 0.4559961 0.8899813 -8.96066e-4 0.3769849 0.9262194 0 0.3304784 0.9438137 0 0.3304777 0.9438139 0 -0.2422727 0.9702078 -9.38644e-4 -0.2439188 0.9697956 -3.62596e-4 -0.03705376 0.9992997 -0.005237996 -0.1295701 0.9915524 0.005970835 -0.1083009 0.9941182 0 -0.1511992 0.9885033 0 -0.1512004 0.9885031 0 -0.4999677 0.8660441 0 -0.6478763 0.7617456 0 -0.6478737 0.7617478 0 -0.5674031 0.8234402 0 -0.6048351 0.7959592 -0.02496856 -0.2420051 0.9702751 0 -0.4112249 0.911534 0 -0.4096642 0.9122363 -6.70908e-4 -0.4119427 0.9112093 -0.001007676 -0.49997 0.8660428 0 -0.5314377 0.8470975 0 -0.5314377 0.8470974 0 -0.9878306 0.1555343 0 -0.9994204 0.02305763 -0.02504587 -0.9975737 0.06961995 0 -0.9942506 -0.1070783 0 -0.9282328 0.372 0 -0.9694188 0.2454126 0 -0.9686788 0.2483174 -9.97448e-5 -0.9691109 0.2466235 -9.63255e-4 -0.9878354 0.1555033 0 -0.9936314 0.11268 0 -0.9936314 0.1126804 0 -0.6820453 -0.7312451 -0.009740293 -0.6762151 -0.7366054 -0.01206815 -0.6414291 -0.7671622 -0.005554974 -0.8297565 -0.5572758 0.03078722 -0.77701 -0.6294881 -6.40854e-4 -0.7356451 -0.6773672 0 -0.7076033 -0.70661 0 -0.7076022 -0.7066112 0 -0.6766862 -0.7362715 0 -0.5342198 -0.8453457 0 -0.5339711 -0.8455028 1.28082e-4 -0.5327015 -0.8463032 0 -0.3908948 -0.9204354 0 -0.8455103 0.5339592 0 -0.8455099 0.5339598 0 -0.8452841 0.5343169 6.60241e-4 -0.1960158 -0.9806008 0 -0.03179883 -0.9994943 0 0.1328657 -0.9911341 0 0.1328659 -0.9911341 0 0.2944544 -0.9556655 0 0.2944547 -0.9556654 0 0.4477713 -0.8941482 0 0.4477716 -0.894148 0 0.5888671 -0.80823 0 0.5888671 -0.80823 0 0.7136416 -0.7005111 0 0.7136417 -0.7005109 0 0.8193332 -0.5733178 0 0.8193324 -0.5733188 0 0.902517 -0.4306544 0 0.9025173 -0.4306539 0 0.9611054 -0.2761824 0 0.9611054 -0.2761822 0 0.9934475 -0.1142901 0 0.9934474 -0.1142907 0 0.9987118 0.05074226 0 0.9987119 0.05074059 0 0.9767212 0.2145127 0 0.9767211 0.2145134 0 0.9281162 0.3722909 0 0.928116 0.3722913 0 0.8541899 0.5199613 0 0.8541902 0.5199607 0 0.7567961 0.6536511 0 0.7567963 0.6536509 0 0.6390262 0.7691851 0 0.6390266 0.7691846 0 0.5039181 0.8637515 0 0.5039186 0.8637512 0 0.3545883 0.9350225 0 0.3545888 0.9350224 0 0.1960156 0.9806008 0 0.1960158 0.9806008 0 0.03179883 0.9994943 0 -0.1328594 0.991135 0 -0.1328595 0.991135 0 -0.2944604 0.9556638 0 -0.2944606 0.9556636 0 -0.4477713 0.8941482 0 -0.4477716 0.894148 0 -0.5888671 0.80823 0 -0.5888671 0.80823 0 -0.7136382 0.7005145 0 -0.7136386 0.7005141 0 -0.8193352 0.5733149 0 -0.8193347 0.5733156 0 -0.902517 0.4306544 0 -0.9025173 0.4306539 0 -0.9610721 0.2762978 0 -0.9610722 0.2762976 0 -0.9934532 0.1142407 0 -0.993453 0.1142414 0 -0.9987118 -0.05074226 0 -0.9987119 -0.05074059 0 -0.9767212 -0.2145127 0 -0.9767211 -0.2145134 0 -0.9281162 -0.3722909 0 -0.928116 -0.3722913 0 -0.8541882 -0.5199642 0 -0.8541885 -0.5199636 0 -0.7567961 -0.6536511 0 -0.7567963 -0.6536509 0 -0.6390298 -0.769182 0 -0.6390306 -0.7691813 0 -0.5039181 -0.8637515 0 -0.5039186 -0.8637512 0 -0.3545883 -0.9350225 0 -0.3545888 -0.9350224 0 -0.1960156 -0.9806008 0 0.02947801 0.9995655 0 0.1983037 0.9801406 0 0.1983037 0.9801406 0 0.3609002 0.9326045 0 0.3609 0.9326045 0 0.5132395 0.8582454 0 0.5132397 0.8582454 0 0.6511256 0.75897 0 0.6511259 0.7589699 0 0.7699708 0.6380792 0 0.7699714 0.6380785 0 0.8666357 0.4989416 0 0.8666355 0.4989418 0 0.9385095 0.3452534 0 0.9385097 0.3452532 0 0.9833762 0.18158 0 0.9833762 0.1815807 0 0.9999179 0.01281696 0 0.9999179 0.0128178 0 0.9877014 -0.1563524 0 0.9877014 -0.1563523 0 0.9470585 -0.3210612 0 0.9470585 -0.321061 0 0.8792428 -0.476374 0 0.8792432 -0.4763731 0 0.7860624 -0.6181471 0 0.7860628 -0.6181466 0 0.6700997 -0.7422711 0 0.6700993 -0.7422715 0 0.5351141 -0.8447799 0 0.5351148 -0.8447795 0 0.3849729 -0.9229279 0 0.3849731 -0.9229278 0 0.2233231 -0.9747445 0 0.2233232 -0.9747444 0 0.05493664 -0.9984899 0 0.05493664 -0.9984899 0 -0.1143433 -0.9934413 0 -0.1143434 -0.9934413 0 -0.2805048 -0.9598527 0 -0.2805049 -0.9598526 0 -0.438628 -0.8986687 0 -0.4386283 -0.8986685 0 -0.5842409 -0.8115803 0 -0.5842414 -0.81158 0 -0.7129358 -0.7012293 0 -0.7129366 -0.7012284 0 -0.8213033 -0.570492 0 -0.9058578 -0.4235821 0 -0.9058584 -0.4235808 0 -0.9644445 -0.2642856 0 -0.9644448 -0.2642847 0 -0.99523 -0.09755694 0 -0.9952299 -0.09755766 0 -0.9974045 0.07200253 0 -0.9974045 0.07200253 0 -0.970869 0.2396115 0 -0.970869 0.2396113 0 -0.9164437 0.4001636 0 -0.9164439 0.4001633 0 -0.8356475 0.5492663 0 -0.8356474 0.5492665 0 -0.7307415 0.6826544 0 -0.6050953 0.7961531 0 -0.6050949 0.7961534 0 -0.461443 0.8871699 0 -0.461443 0.8871699 0 -0.3050608 0.9523329 0 -0.305061 0.9523329 0 -0.1398004 0.9901797 0 -0.1398005 0.9901797 0 -3.03445e-7 0 -1 1.21359e-6 0 -1 -4.81649e-6 0 -1 -4.39955e-6 0 -1 4.78667e-6 0 -1 -4.414e-6 0 -1 4.77222e-6 0 -1 4.7293e-6 0 -1 -2.23254e-6 0 -1 1.12783e-6 0 -1 4.27692e-7 0 -1 1.15029e-6 0 -1 -5.71925e-7 0 -1 -8.52366e-7 0 -1 -1.12796e-6 0 -1 -2.23886e-6 0 -1 4.78103e-6 0 -1 4.25427e-6 0 -1 1.97885e-6 0 -1 -1.95808e-6 0 -1 -0.4408369 -0.8747351 0.2012497 -0.4386987 -0.8773317 0.1945062 -0.4386986 -0.8773317 0.1945063 -0.4386987 -0.8773317 0.1945063 -0.3386641 -0.9205061 0.1948724 -0.3389475 -0.9200664 0.1964495 -0.3359634 -0.9216038 0.194358 -0.2330098 -0.9528856 0.194205 -0.2330448 -0.9528473 0.1943508 -0.119839 -0.9735037 0.1947541 -0.1199498 -0.9735294 0.1945571 -0.1212766 -0.9725612 0.1985363 -0.0104162 -0.9800121 0.198665 -0.008096575 -0.9816995 0.1902647 -0.009604215 -0.9813231 0.1921272 0.1026492 -0.9760146 0.1919866 0.1018651 -0.9756035 0.1944768 0.1988253 -0.9604902 0.1947488 0.1988254 -0.9604902 0.1947488 0.1988254 -0.9604902 0.1947488 0.2115913 -0.957302 0.1969825 0.2130494 -0.9578748 0.1925772 0.3214872 -0.9271445 0.1924815 0.3217626 -0.9269674 0.1928737 0.3207294 -0.926948 0.1946796 0.424308 -0.8843038 0.1948577 0.4240856 -0.8846387 0.1938193 0.4167792 -0.8873184 0.197386 0.5210846 -0.8303508 0.1974549 0.5231118 -0.8304153 0.1917409 0.6130897 -0.7662711 0.1922233 0.6132398 -0.7660545 0.1926075 0.6141721 -0.7659016 0.1902306 0.6976542 -0.6906677 0.1904121 0.6959233 -0.6910334 0.1953552 0.6964329 -0.6906442 0.1949151 0.7710677 -0.6061248 0.1951088 0.771704 -0.6059426 0.193149 0.8288334 -0.5249705 0.1934974 0.8348034 -0.5137156 0.1979889 0.834953 -0.5136484 0.1975324 0.887346 -0.4167687 0.1972843 0.8873165 -0.4168043 0.1973412 0.8894255 -0.4146007 0.1924285 0.9301912 -0.3125097 0.1925668 0.9302892 -0.3129835 0.1913202 0.9286637 -0.3170111 0.1925815 0.9599549 -0.203479 0.1925695 0.9597426 -0.2037288 0.1933619 0.9765871 -0.09343731 0.1937714 0.9766062 -0.09385758 0.1934716 0.9769471 -0.09328591 0.1920213 0.9811872 0.01914668 0.1921069 0.9792043 0.01615488 0.2022325 0.9798662 0.02025353 0.198626 0.9716502 0.1286171 0.1983777 0.9730651 0.1313794 0.1894302 0.953224 0.2352833 0.1897521 0.9510653 0.2412046 0.1931204 0.9509283 0.2408414 0.1942441 0.9179115 0.3460137 0.194199 0.9179043 0.3456135 0.1949437 0.9178782 0.3456658 0.194974 0.8715383 0.4500068 0.1947181 0.8718755 0.4497846 0.1937191 0.864351 0.4646933 0.1922438 0.8643509 0.4646933 0.1922438 0.864351 0.4646933 0.1922438 0.815493 0.5459758 0.1920459 0.8154956 0.5460141 0.191926 0.7499251 0.6330603 0.1919561 0.7476509 0.6346609 0.1955091 0.7474961 0.6351497 0.1945112 0.6706469 0.7157915 0.1946154 0.6705522 0.716177 0.1935209 0.6682673 0.718996 0.1909551 0.5839805 0.7890065 0.1908813 0.5847322 0.7865663 0.1984987 0.4880484 0.8499361 0.1985383 0.4911758 0.8487265 0.1959837 0.4908703 0.8492041 0.1946759 0.3893267 0.9003618 0.1943536 0.389644 0.8998453 0.1961022 0.3909513 0.8987743 0.1983988 0.2864221 0.9373889 0.1981526 0.2849289 0.9393377 0.1909459 0.2055438 0.9598188 0.1910486 0.1773394 0.9649381 0.1935081 0.1773781 0.9648777 0.1937727 0.06340706 0.9790756 0.1933662 0.06435531 0.9792615 0.1921076 0.06723678 0.9779038 0.197948 -0.0469098 0.9790154 0.1983135 -0.04519188 0.9801857 0.1928573 -0.04506391 0.980167 0.1929821 -0.1581988 0.9683927 0.192844 -0.1569877 0.9678046 0.1967467 -0.2693592 0.9427171 0.1967993 -0.2671843 0.9437456 0.1948255 -0.2666153 0.9436381 0.1961207 -0.373452 0.9066776 0.1961365 -0.3729735 0.9065653 0.197561 -0.3730307 0.9065628 0.1974642 -0.4728522 0.8587887 0.1972128 -0.4753203 0.8590512 0.1900044 -0.5601264 0.806251 0.1903099 -0.5601265 0.8062509 0.19031 -0.5601264 0.806251 0.19031 -0.569603 0.79881 0.1935333 -0.5687198 0.7988872 0.1957987 -0.6552825 0.7296207 0.1955979 -0.6551237 0.7298192 0.1953892 -0.6579024 0.728734 0.19003 -0.7352758 0.6505954 0.1899875 -0.7353345 0.6501723 0.191205 -0.7264561 0.658786 0.1956084 -0.8042932 0.5610714 0.1957331 -0.8044377 0.5610543 0.1951876 -0.8633953 0.4652203 0.1952406 -0.8632929 0.4655215 0.194975 -0.8624257 0.466128 0.1973492 -0.9099606 0.364694 0.1974084 -0.9119886 0.3633774 0.1903514 -0.9087735 0.3682807 0.1962145 -0.9458759 0.2586147 0.1960539 -0.9455863 0.2588362 0.197156 -0.969192 0.1481037 0.1968052 -0.9691302 0.1493541 0.1961639 -0.9699184 0.1484403 0.1929348 -0.9804813 0.03825259 0.192856 -0.9802424 0.03856515 0.1940047 -0.9806576 0.03735494 0.1921336 -0.9786134 -0.07451653 0.1917375 -0.9784726 -0.07474881 0.1923646 -0.9787518 -0.06737047 0.193665 -0.9632662 -0.1860427 0.1936655 -0.9627779 -0.1849884 0.1970738 -0.935785 -0.2926003 0.1967012 -0.9353742 -0.2933586 0.1975242 -0.9358173 -0.2965803 0.1904894 -0.8964284 -0.4003704 0.1900518 -0.8956077 -0.3963158 0.2020418 -0.8949859 -0.3986948 0.2001069 -0.8449199 -0.4961508 0.199862 -0.8450863 -0.4983991 0.1934615 -0.7836292 -0.5903079 0.1935511 -0.7816801 -0.592307 0.1953168 -0.7818536 -0.590573 0.1998209 -0.7100211 -0.675309 0.1995691 -0.7093182 -0.6800317 0.1855391 -0.7123206 -0.6743372 0.1945993 -0.6282925 -0.7533158 0.1943296 -0.6280896 -0.7540683 0.1920534 -0.5375615 -0.8211001 0.1918917 -0.53864 -0.8183078 0.2005978 -0.4415324 -0.8745719 0.2004331 -0.6035138 -0.5740044 0.5534348 -0.6032521 -0.573241 0.5545104 -0.6632668 -0.5026077 0.5544933 -0.6624565 -0.50089 0.5570104 -0.7163432 -0.4206794 0.5566699 -0.7177522 -0.4228601 0.5531917 -0.7604157 -0.3396099 0.5535642 -0.7595853 -0.3385787 0.5553329 -0.7936596 -0.2488446 0.5551404 -0.7939649 -0.2491769 0.5545545 -0.8169635 -0.1578004 0.5546798 -0.8163425 -0.1572103 0.5557608 -0.8290542 -0.06336349 0.5555667 -0.8284048 -0.06289923 0.5565871 -0.8302809 0.03237378 0.5564042 -0.8320821 0.03155428 0.5537542 -0.8230626 0.1268478 0.5536041 -0.8213925 0.1274256 0.5559471 -0.8018277 0.219213 0.555894 -0.8026541 0.2190012 0.5547837 -0.7721604 0.3094924 0.5549619 -0.7733666 0.3093466 0.5533615 -0.7330048 0.3952741 0.5535905 -0.7305683 0.3951708 0.5568754 -0.6810875 0.4751706 0.5570752 -0.6822165 0.4753204 0.5555639 -0.6228187 0.5506294 0.5557916 -0.6223385 0.5505415 0.5564162 -0.5551013 0.6184359 0.5562371 -0.5578874 0.6195328 0.5522143 -0.4840376 0.6788159 0.5521925 -0.4809134 0.6772161 0.556867 -0.4005434 0.7274384 0.5571341 -0.401518 0.7281072 0.5555568 -0.3167375 0.7690043 0.5552566 -0.3160606 0.7684189 0.5564514 -0.2263757 0.7996231 0.5561987 -0.2266058 0.7998817 0.555733 -0.1339814 0.8202022 0.5561631 -0.132985 0.8188241 0.5584282 -0.03820127 0.8286428 0.5584726 -0.04058504 0.8328928 0.5519443 0.05467462 0.8319773 0.5521093 0.05553144 0.8299884 0.5550095 0.150343 0.8180364 0.5551699 0.1500046 0.8190714 0.5537337 0.2434164 0.7966017 0.5533301 0.243402 0.7963165 0.5537468 0.3304913 0.7643005 0.553733 0.3306465 0.7615246 0.5574526 0.4159079 0.7186207 0.5573195 0.4160326 0.7209321 0.5542327 0.4950393 0.6688548 0.5545895 0.4945942 0.6664584 0.5578619 0.5674554 0.6056596 0.557827 0.5677055 0.6066953 0.5564454 0.6334493 0.5377088 0.5564272 0.6342114 0.5395149 0.5538047 0.691892 0.4632062 0.5538281 0.6923618 0.46406 0.5525246 0.7408168 0.3822262 0.5523529 0.7401861 0.3813265 0.5538183 0.7791029 0.2936536 0.553865 0.7799699 0.2945963 0.5521414 0.8082004 0.2049874 0.55208 0.804603 0.2018533 0.5584526 0.8222332 0.1088334 0.5586482 0.8255128 0.1111461 0.553331 0.8329263 0.01616805 0.5531477 0.8306067 0.01501321 0.5566571 0.8267324 -0.07947129 0.556954 0.8271464 -0.07924932 0.5563709 0.8129436 -0.1723049 0.5562678 0.812541 -0.1724489 0.5568111 0.7872576 -0.2648544 0.5568463 0.7871651 -0.2648649 0.5569719 0.7518857 -0.3531196 0.5567536 0.7542189 -0.3530673 0.5536221 0.709206 -0.4364503 0.5536587 0.7077244 -0.4363056 0.5556651 0.6535762 -0.5137527 0.5557844 0.6528053 -0.5135425 0.5568836 0.5901592 -0.5843181 0.557032 0.5903618 -0.5843518 0.5567817 0.5189936 -0.6484017 0.5569747 0.5200037 -0.6488382 0.5555225 0.4419304 -0.7041632 0.5557444 0.4419668 -0.7041549 0.5557259 0.3593811 -0.7496644 0.5557415 0.360114 -0.7502576 0.5544651 0.2728829 -0.7862322 0.5544131 0.2709233 -0.7843772 0.5579902 0.1790825 -0.8102458 0.5580604 0.1815883 -0.8134064 0.5526263 0.08716607 -0.8288706 0.552608 0.08548545 -0.8262376 0.5567977 -0.00882852 -0.8305561 0.5568651 -0.007507324 -0.8333334 0.5527198 -0.101884 -0.8268657 0.5530939 -0.103264 -0.8231322 0.5583816 -0.1970359 -0.8057444 0.5585274 -0.1964542 -0.8082783 0.5550604 -0.2872269 -0.7807158 0.5549627 -0.2869932 -0.7828198 0.5521125 -0.37528 -0.7446752 0.5519274 -0.3752905 -0.743044 0.5541145 -0.4559764 -0.6964907 0.5540634 -0.4559566 -0.695967 0.5547374 -0.5329955 -0.6390329 0.5545746 -0.5332204 -0.6398981 0.5533593 -0.4026389 -0.382614 0.8315579 -0.4030772 -0.3834612 0.8309552 -0.4438118 -0.3356249 0.8308953 -0.4438761 -0.3357289 0.830819 -0.4794813 -0.282494 0.8308398 -0.479589 -0.282579 0.8307487 -0.5086248 -0.2267189 0.8306018 -0.5070278 -0.2252163 0.8319859 -0.5292988 -0.1661096 0.8320159 -0.5302752 -0.1668034 0.8312551 -0.5458855 -0.1051636 0.8312338 -0.5455942 -0.1050199 0.8314433 -0.5539185 -0.04206657 0.8315075 -0.5543339 -0.04227566 0.8312201 -0.5553522 0.0210914 0.8313478 -0.5537803 0.02153396 0.8323844 -0.5478397 0.08497923 0.8322561 -0.5499033 0.08462375 0.8309304 -0.5367749 0.1464199 0.8309236 -0.5373422 0.1464928 0.8305441 -0.5171826 0.2068225 0.8305099 -0.5153355 0.2068154 0.8316591 -0.4885029 0.2642212 0.8315962 -0.491203 0.2647373 0.8298397 -0.4577725 0.3189143 0.8299024 -0.4568122 0.3187031 0.8305126 -0.4172036 0.3690727 0.8304979 -0.4158971 0.3685022 0.8314059 -0.3716962 0.4127858 0.8315346 -0.3715484 0.4126781 0.8316541 -0.3213773 0.4525762 0.8318001 -0.3224982 0.4533458 0.8309468 -0.268656 0.4871898 0.8309453 -0.2690057 0.4874715 0.830667 -0.2118096 0.5149146 0.8306621 -0.2113288 0.5144044 0.8311006 -0.1515471 0.5348945 0.8312168 -0.1514759 0.5347709 0.8313092 -0.08909958 0.5485473 0.8313586 -0.08971858 0.5497668 0.830486 -0.02709621 0.5561461 0.8306428 -0.02673417 0.5552178 0.8312752 0.03711152 0.5546867 0.8312314 0.03712493 0.5547566 0.8311842 0.1001524 0.5468732 0.8312035 0.1004987 0.5445899 0.8326596 0.1618703 0.5295432 0.8326957 0.1617674 0.5327183 0.8306881 0.2218466 0.5108946 0.8305245 0.221796 0.5106747 0.8306733 0.2783617 0.4823421 0.8305786 0.2781187 0.4810305 0.8314203 0.331216 0.4463186 0.8313218 0.3320848 0.44898 0.82954 0.3814715 0.4076483 0.8296399 0.3811418 0.4069669 0.8301259 0.4246111 0.3612052 0.8302026 0.4228025 0.3581563 0.8324435 0.4603456 0.3085851 0.8323805 0.4614729 0.3100808 0.8311997 0.4942024 0.2546114 0.8312264 0.4935617 0.2539672 0.8318039 0.5193299 0.1961144 0.8317667 0.5199519 0.1966569 0.8312498 0.5392702 0.1353111 0.8311911 0.5406072 0.1362112 0.830175 0.5527068 0.07437932 0.8300499 0.5527533 0.07439327 0.8300177 0.5576869 0.01004153 0.8299907 0.558533 0.01033592 0.8294179 0.5560407 -0.05326926 0.8294463 0.5546946 -0.05362433 0.8303243 0.5450147 -0.1156539 0.8304116 0.5451641 -0.1156277 0.8303171 0.5282483 -0.1777523 0.8302758 0.5291059 -0.1777113 0.8297383 0.5055007 -0.2366909 0.8297268 0.503959 -0.2364952 0.8307198 0.4737436 -0.2920458 0.8308287 0.4753087 -0.2924477 0.8297928 0.4385973 -0.3450428 0.829806 0.4375237 -0.3446384 0.8305404 0.3958365 -0.3918151 0.8305386 0.3960708 -0.391964 0.8303567 0.3484894 -0.4348646 0.83033 0.3476966 -0.4343612 0.8309257 0.2957896 -0.4712296 0.8309339 0.2981347 -0.4731277 0.829015 0.2419923 -0.5041419 0.829024 0.2404218 -0.5025115 0.8304695 0.1818567 -0.5264728 0.8305147 0.181554 -0.5261251 0.8308013 0.1212308 -0.5429981 0.830937 0.1218038 -0.544023 0.8301824 0.05733871 -0.5541864 0.8304154 0.05792599 -0.5554484 0.829531 -0.005028069 -0.5582979 0.8296254 -0.006170809 -0.5550077 0.8318223 -0.06907808 -0.5506319 0.831885 -0.06827062 -0.5544462 0.8294147 -0.1319491 -0.5429239 0.8293511 -0.1321359 -0.5409182 0.8306309 -0.1916361 -0.5227062 0.8306949 -0.191658 -0.5224466 0.830853 -0.2508078 -0.4965909 0.8309592 -0.2509371 -0.4977408 0.8302317 -0.3054447 -0.4662156 0.8302689 -0.3051165 -0.4649004 0.8311268 -0.3557941 -0.4269655 0.8313309 -0.3556909 -0.4266309 0.8315469 -0.1409563 -0.1340972 0.9808921 -0.1415752 -0.1352103 0.9806501 -0.1561973 -0.1181453 0.9806345 -0.1558789 -0.1177704 0.9807304 -0.1683638 -0.09919422 0.9807212 -0.1682537 -0.09907078 0.9807527 -0.1784596 -0.07927805 0.9807484 -0.1785421 -0.07934957 0.9807275 -0.1864081 -0.05863147 0.9807214 -0.1866825 -0.05886262 0.9806554 -0.1922209 -0.03699475 0.9806541 -0.191309 -0.03654551 0.9808493 -0.1941835 -0.01479595 0.9808537 -0.194607 -0.01493966 0.9807676 -0.1950631 0.007585525 0.9807614 -0.1954031 0.007481038 0.9806945 -0.1932275 0.02973896 0.9807033 -0.1938501 0.02962285 0.9805838 -0.1893414 0.05159705 0.9805548 -0.1881687 0.05163109 0.9807787 -0.1810556 0.0726428 0.9807864 -0.1817855 0.07271641 0.9806459 -0.1722806 0.09284657 0.9806625 -0.1710633 0.09259623 0.9808992 -0.1596209 0.1113401 0.9808795 -0.1591564 0.1111959 0.9809713 -0.1453468 0.128793 0.9809622 -0.1465471 0.1293557 0.9807096 -0.1308497 0.1453488 0.9806896 -0.1305977 0.1451843 0.9807475 -0.1132397 0.1591871 0.9807325 -0.1132259 0.1591534 0.9807397 -0.09440439 0.1711336 0.9807146 -0.09426015 0.1709395 0.9807623 -0.07417416 0.1805642 0.9807624 -0.07462167 0.1811136 0.9806271 -0.05339014 0.1884845 0.9806238 -0.0530731 0.1879642 0.980741 -0.03148639 0.1929029 0.9807125 -0.03145146 0.1928426 0.9807256 -0.009395897 0.1951634 0.9807258 -0.009341299 0.1949899 0.9807608 0.01302516 0.1947063 0.9807751 0.01306599 0.1945246 0.9808107 0.03539562 0.1917551 0.9808044 0.03527379 0.1928415 0.9805957 0.05695742 0.1875849 0.9805957 0.05695635 0.187373 0.9806362 0.07800483 0.1795837 0.9806452 0.07799947 0.1796019 0.9806423 0.09798055 0.1694711 0.9806526 0.09781557 0.1687592 0.9807918 0.115994 0.1568136 0.980793 0.1158856 0.1564834 0.9808586 0.1331402 0.1421414 0.9808514 0.1330355 0.1419997 0.9808862 0.1485119 0.1257908 0.9808776 0.1489837 0.1265197 0.9807124 0.1622251 0.1089842 0.9807168 0.1617721 0.1084763 0.980848 0.1732403 0.08912491 0.9808388 0.1733803 0.08931779 0.9807965 0.1824346 0.06899923 0.980794 0.1824734 0.0690416 0.9807838 0.1892113 0.0476647 0.9807789 0.1895136 0.04784804 0.9807116 0.1936951 0.02606141 0.9807156 0.1930191 0.02576935 0.9808567 0.1946189 0.003597199 0.9808724 0.194982 0.003736734 0.9807997 0.1942656 -0.01877409 0.9807693 0.1945659 -0.0187177 0.9807109 0.1912927 -0.04056245 0.9806946 0.1901951 -0.04065245 0.9809044 0.1843519 -0.06193172 0.9809072 0.1850696 -0.06195408 0.9807707 0.1767021 -0.08291304 0.980766 0.1766254 -0.08290487 0.9807806 0.1663069 -0.1023086 0.9807522 0.1653833 -0.1020718 0.9809331 0.1527146 -0.1202778 0.9809239 0.1533492 -0.1205445 0.9807921 0.1387304 -0.1372499 0.9807734 0.137962 -0.1368715 0.9809347 0.1215245 -0.1518031 0.9809116 0.1216607 -0.1519084 0.9808785 0.1037878 -0.1646612 0.9808745 0.1041579 -0.1650042 0.9807777 0.08420419 -0.1759985 0.9807825 0.08393687 -0.1756971 0.9808593 0.06352257 -0.1840363 0.9808648 0.06388962 -0.1845923 0.9807364 0.04267835 -0.1906135 0.980737 0.04195111 -0.189327 0.9810177 0.02011716 -0.1928867 0.9810149 0.02049893 -0.1937951 0.9808279 -0.002171337 -0.1949895 0.980803 -0.00187534 -0.1960012 0.9806019 -0.02396005 -0.1945582 0.9805984 -0.02421379 -0.1929862 0.9809027 -0.04615908 -0.1889461 0.980902 -0.04607141 -0.1902926 0.9806458 -0.06744641 -0.1838532 0.980637 -0.06735312 -0.1823211 0.9809294 -0.08752632 -0.1736194 0.9809157 -0.08761739 -0.1741415 0.980815 -0.1070062 -0.1630237 0.9808022 -0.1070405 -0.1632038 0.9807685 -0.1249842 -0.1499162 0.9807671 -0.124717 -0.1493128 0.9808932 -0.4506379 -0.8926668 0.008448541 -0.5296117 -0.8481059 -0.01509642 -0.4471712 -0.8944087 0.00843507 -0.3861678 -0.9222804 -0.01652914 -0.3456923 -0.938329 0.005977094 -0.3425528 -0.9394796 0.00597459 -0.232217 -0.972638 -0.007125914 -0.237555 -0.9713075 -0.01138383 -0.07496368 -0.9970213 -0.01814085 -0.1237471 -0.9922979 0.005632579 -0.1221842 -0.9924914 0.00564754 0.2027269 -0.9792348 0.001074612 0.1038545 -0.9945901 -0.002177476 0.08737415 -0.9960887 -0.01316404 -0.009787797 -0.9999127 0.0088768 -0.008247554 -0.9999266 0.008882701 0.21712 -0.9761443 0.001095175 0.2448385 -0.9694319 -0.01599693 0.3276302 -0.9447622 0.00911498 0.3270205 -0.9449732 0.009120821 0.3970333 -0.917656 -0.01649266 0.432573 -0.9015852 0.004982471 0.4252327 -0.9050705 0.004977285 0.5404878 -0.8413323 -0.005731821 0.5329378 -0.8460559 -0.01291835 0.6672125 -0.7446581 -0.0176568 0.6256104 -0.7801035 0.007100462 0.6247313 -0.7808075 0.007121205 0.8449644 -0.5348169 0.002467811 0.8449645 -0.5348168 0.002467811 0.8449645 -0.5348168 0.002467811 0.7865059 -0.6175692 -0.004096627 0.7790962 -0.6267835 -0.01231694 0.7098573 -0.7043018 0.007851302 0.7098573 -0.7043018 0.00784707 0.7098574 -0.7043018 0.007851243 0.7095299 -0.7046316 0.007853865 0.8517429 -0.5239542 0.002475023 0.8690371 -0.4944584 -0.01689779 0.9051187 -0.425075 0.008464634 0.9063404 -0.422464 0.008450984 0.9371241 -0.3486222 -0.01615726 0.9479193 -0.3185011 0.002459049 0.9462245 -0.3235015 0.00246483 0.9462245 -0.3235015 0.00246483 0.9462245 -0.3235015 0.00246483 0.9808056 -0.194948 -0.003989815 0.978116 -0.2075281 -0.01487267 0.999289 -0.03368639 -0.01694089 0.9954341 -0.09503293 0.00893867 0.9954019 -0.09536832 0.008943438 0.9708374 0.2396955 0.004579067 0.9909955 0.1337645 -0.005934 0.9917895 0.1274399 -0.0106123 0.9997657 0.02059358 0.00667721 0.9998408 0.01654928 0.006673455 0.9693934 0.2454701 0.004570186 0.9587612 0.2837256 -0.01664394 0.9357585 0.3525244 0.009083747 0.9357615 0.3525163 0.009087979 0.9007221 0.4341233 -0.01539057 0.8885871 0.4587057 0.001495897 0.8808197 0.4734495 0.001516938 0.8808201 0.4734487 0.001516938 0.8808206 0.4734479 0.001513302 0.8193513 0.5732919 -3.73605e-4 0.8308503 0.5561949 -0.01830786 0.7169304 0.6969298 -0.01731216 0.7620425 0.6474687 0.008685052 0.7639917 0.6451678 0.008691489 0.4980335 0.8671404 0.005501151 0.5965977 0.8024824 -0.009660363 0.5949701 0.8037067 -0.008136987 0.6808344 0.7324104 0.006288051 0.6834422 0.7299777 0.006276249 0.5004224 0.8657639 0.00553137 0.4590547 0.8882234 -0.01811218 0.3973997 0.9176067 0.008460044 0.3988147 0.9169924 0.008467972 0.3109555 0.9503161 -0.01435649 0.2902441 0.9569527 -2.43977e-4 0.1536397 0.9880001 -0.01583385 0.1807918 0.9835208 0.001110792 0.2096701 0.9777716 0.001076102 -0.04594522 0.9989342 0.004432976 -0.04785931 0.9988443 0.004424273 -0.006247997 0.9998222 -0.01779258 0.06859439 0.997605 0.008897244 0.06461793 0.9978705 0.008899033 -0.1601185 0.9870749 -0.006713986 -0.1660071 0.9860628 -0.01103919 -0.2747469 0.961491 0.007030129 -0.2718811 0.9623052 0.007033586 -0.3221663 0.9465171 -0.01772695 -0.3804735 0.924753 0.008474528 -0.4710257 0.8821138 -0.003191769 -0.4841049 0.8748692 -0.01569789 -0.3804619 0.9247577 0.008479475 -0.6057113 0.7955195 -0.01620477 -0.579985 0.8146235 0.002436935 -0.5705464 0.8212617 0.002467274 -0.740425 0.6721317 0.003149151 -0.748955 0.6626135 0.003122508 -0.7254762 0.6880515 -0.01641893 -0.6701145 0.7422072 0.008667767 -0.6680948 0.7440257 0.008671104 -0.8202198 0.5720255 -0.005122601 -0.8263829 0.5629649 -0.01272583 -0.8801555 0.474627 0.007451415 -0.8797388 0.4753989 0.007461488 -0.9057362 0.4234626 -0.01792705 -0.9289081 0.3702144 0.008448064 -0.9268059 0.3754458 0.008441925 -0.9621977 0.2721289 -0.01102256 -0.9645161 0.2639761 -0.005055248 -0.9933738 0.1137434 -0.01646298 -0.9884814 0.1512793 0.004387021 -0.9885296 0.150964 0.004384577 -0.9988081 -0.04622799 -0.01566475 -0.9992294 0.03823262 0.008884608 -0.999192 0.03919696 0.008882164 -0.9543344 -0.298631 0.008090853 -0.9818897 -0.1886323 -0.01762545 -0.9785107 -0.2061833 -0.002301871 -0.997639 -0.06864136 0.002213418 -0.997639 -0.0686413 0.00221306 -0.997639 -0.06864136 0.002213418 -0.9971103 -0.07593548 0.002213776 -0.9532337 -0.3021264 0.008083939 -0.9325002 -0.3607666 -0.01705533 -0.9144402 -0.4046767 0.005994975 -0.9134758 -0.4068494 0.005980789 -0.8626929 -0.505627 -0.01012343 -0.8613173 -0.5080029 -0.008096516 -0.7706741 -0.6369755 -0.01798939 -0.7979146 -0.6027526 0.00466454 -0.7988694 -0.6014866 0.004664182 -0.5498061 -0.8352923 0 -0.6400285 -0.7683512 0 -0.657966 -0.7528985 -0.01498889 -0.7262046 -0.6874142 0.009414196 -0.7217425 -0.6920974 0.009439647 7.45717e-7 0 -1 -2.99818e-6 0 -1 3.14086e-6 0 -1 -1.56071e-6 0 -1 3.11146e-6 0 -1 3.0881e-6 0 -1 1.26165e-5 0 -1 -1.17933e-5 0 -1 -1.29146e-5 0 -1 -1.37627e-5 0 -1 -4.09567e-6 0 -1 -1.26749e-5 0 -1 3.72734e-6 0 -1 -3.26823e-6 0 -1 1.49179e-6 0 -1 -3.1396e-6 0 -1 2.53817e-6 0 -1 -1.54634e-6 0 -1 -3.07685e-6 0 -1 1.23238e-5 0 -1 -6.10232e-6 0 -1 1.24187e-5 0 -1 -6.048e-6 0 -1 -1.14386e-5 0 -1 1.09977e-5 0 -1 -1.41957e-5 0 -1 1.08234e-5 0 -1 0.5281634 0.8491429 0 0.6589208 0.7522124 0 0.6589457 0.7521905 0 0.7702876 0.6376968 0 0.7702383 0.6377563 0 0.8631151 0.5050073 0 0.8630713 0.5050821 0 0.9327257 0.3605868 0 0.9326915 0.3606754 0 0.9783757 0.2068359 0 0.9783654 0.2068845 0 0.9989603 0.04559075 0 0.9934921 -0.1139016 0 0.9935034 -0.1138028 0 0.962398 -0.2716436 0 0.9623714 -0.2717376 0 0.9057186 -0.4238796 0 0.9056988 -0.423922 0 0.8272542 -0.5618279 0 0.8272065 -0.5618982 0 0.7244605 -0.6893163 0 0.7245092 -0.6892653 0 0.6052879 -0.7960067 0 0.6052859 -0.7960082 0 0.4702667 -0.8825244 0 0.4702863 -0.8825139 0 0.3230368 -0.9463865 0 0.3230675 -0.946376 0 0.1677414 -0.9858311 0 0.1677489 -0.9858298 0 0.006216645 -0.9999807 0 0.006216347 -0.9999807 0 -0.1553238 -0.9878637 0 -0.1553152 -0.987865 0 -0.310626 -0.9505322 0 -0.3106416 -0.9505272 0 -0.457964 -0.8889707 0 -0.4579411 -0.8889826 0 -0.5970295 -0.8022193 0 -0.5970055 -0.8022373 0 -0.7163618 -0.6977291 0 -0.7163351 -0.6977564 0 -0.8194531 -0.5731464 0 -0.8194049 -0.5732152 0 -0.9013711 -0.4330476 0 -0.9013503 -0.4330909 0 -0.9581546 -0.2862514 0 -0.9581819 -0.2861599 0 -0.9919955 -0.126273 0 -0.9919893 -0.1263225 0 -0.9993829 0.03512787 0 -0.9993829 0.03512799 0 -0.9812096 0.1929452 0 -0.9812 0.1929942 0 -0.937615 0.3476753 0 -0.9375983 0.3477204 0 -0.8691398 0.4945666 0 -0.8691174 0.4946058 0 -0.7786479 0.6274611 0 -0.7786467 0.6274628 0 -0.6666597 0.7453623 0 -0.6666811 0.7453432 0 -0.5407613 0.8411762 0 -0.5407602 0.8411769 0 -0.3976623 0.917532 0 -0.3976792 0.9175245 0 -0.2444682 0.9696573 0 -0.2444801 0.9696543 0 -0.08700245 0.9962082 0 -0.08699768 0.9962086 0 0.07463967 0.9972106 0 0.0746355 0.9972109 0 0.231827 0.9727571 0 0.2318142 0.9727601 0 0.3873839 0.9219185 0 0.3874005 0.9219115 0 0.528142 0.8491562 0 0.9891544 0.1468801 0 0.7839226 0.6208587 0 0.7828034 0.6222689 4.75569e-4 0.6213082 -0.7835663 0 0.9314116 -0.3639677 0 0.9299649 -0.3676481 -6.21939e-4 0.9291568 -0.3696858 0 0.9891718 0.146763 0 0.1468294 -0.9891617 -4.77923e-4 0.1414293 -0.9899485 0 0.621279 -0.7835894 0 -0.7835918 -0.6212763 0 -0.3691134 -0.9293844 0 -0.3676691 -0.9299568 2.39788e-4 -0.3668397 -0.9302842 0 0.1482545 -0.9889492 0 -0.989163 -0.1468214 2.66144e-4 -0.9887316 -0.149699 0 -0.7835626 -0.6213131 0 -0.9299445 0.3677 0 -0.9889062 -0.1485422 0 -0.9889062 -0.1485422 0 -0.9889062 -0.1485423 0 -0.98942 -0.1450796 -3.23153e-4 -0.6213079 0.7835665 1.53685e-4 -0.6220827 0.7829516 0 -0.929965 0.3676481 0 0.780637 0.6249847 -3.47943e-7 0.7806371 0.6249848 0 0.7806371 0.6249848 0 0.368172 0.9297577 0 -0.1487011 0.9888823 0 -0.1468182 0.9891636 -1.79924e-4 -0.1463347 0.9892352 0 -0.6208816 0.7839044 0 -0.4937725 0.77003 -0.4040329 -0.6555237 -0.6375339 -0.4047707 -0.4201171 -0.8128431 -0.4034696 0.748938 -0.4949903 -0.4405414 0.7475335 -0.5087245 -0.4270753 0.7750931 -0.4801464 -0.4107192 0.745379 -0.5132703 -0.4253985 0.7413858 -0.5259217 -0.4168375 0.7383741 -0.5333649 -0.4127054 0.7335283 -0.5481974 -0.4017662 0.7334882 -0.5484129 -0.4015449 0.740665 -0.5421987 -0.3967821 0.7523174 -0.534732 -0.3848122 0.7724627 -0.5279384 -0.3529624 0.7750895 -0.5278997 -0.3472152 0.8290169 -0.3869643 -0.4037197 0.8290559 -0.3871661 -0.4034465 0.7899724 -0.460777 -0.40451 0.8802187 -0.2489694 -0.4040167 0.8801616 -0.2492748 -0.4039525 0.8277708 -0.3895002 -0.403838 0.9089146 -0.1045939 -0.4036514 0.9088873 -0.1044898 -0.4037399 0.8804209 -0.2487862 -0.4036884 0.8952183 0.188407 -0.4038401 0.9138518 0.04279267 -0.4037868 0.9137374 0.04259312 -0.4040666 0.9136906 0.04300028 -0.4041293 0.9086013 -0.1053532 -0.4041591 0.8364696 0.3675318 -0.406496 0.8440625 0.3601588 -0.3972961 0.8514714 0.3522778 -0.3884543 0.8701588 0.3364972 -0.359991 0.8898921 0.3336201 -0.3111106 0.8661944 0.3412368 -0.3650546 0.8398615 0.3532807 -0.4120991 0.8425589 0.3329572 -0.4233603 0.842341 0.3256948 -0.4294005 0.8535279 0.3096101 -0.4190844 0.8649928 0.2898525 -0.4096011 0.871324 0.2760189 -0.4057194 0.8739014 0.269886 -0.4042993 0.8954038 0.1887978 -0.4032462 0.9029105 0.1875174 -0.3867685 0.8738899 0.2654116 -0.4072753 0.8743669 0.2638029 -0.4072965 0.9085313 -0.1046392 -0.4045017 0.9136381 0.04225754 -0.4043262 0.9147009 0.04271501 -0.4018679 0.8960227 0.1885765 -0.4019732 0.7868503 -0.466948 -0.4035172 0.8012662 -0.4417244 -0.4035494 0.8350036 -0.3900033 -0.3881577 0.8293589 -0.3841317 -0.4057175 0.8795772 -0.2488829 -0.4054642 -0.8044708 -0.3999072 -0.4392049 -0.8145139 -0.3926102 -0.4271117 -0.8028033 -0.4331197 -0.4097734 -0.8177636 -0.3882691 -0.4248645 -0.8260388 -0.3792627 -0.416917 -0.8303257 -0.3737465 -0.4133677 -0.8434324 -0.3530836 -0.4049124 -0.8411338 -0.3633232 -0.4006125 -0.8394439 -0.3723247 -0.395864 -0.8388617 -0.3844606 -0.3853586 -0.8429896 -0.4048668 -0.3541913 -0.8442869 -0.40721 -0.3483673 -0.7498495 -0.5244456 -0.4033395 -0.7497963 -0.5244076 -0.4034876 -0.7948733 -0.452335 -0.4044374 -0.5150347 -0.7558431 -0.4042778 -0.5525888 -0.7449609 -0.3737365 -0.5737092 -0.7124873 -0.4040046 -0.655991 -0.6381028 -0.4031139 -0.6559816 -0.6381502 -0.4030541 -0.7498474 -0.524673 -0.4030475 -0.7498486 -0.5246645 -0.4030563 -0.2017018 -0.8919552 -0.4046387 -0.2842512 -0.8696423 -0.403638 -0.2842316 -0.8696669 -0.4035986 -0.2845587 -0.8696152 -0.4034796 -0.4201189 -0.812842 -0.40347 -0.1019066 -0.9076579 -0.4071512 -0.1101279 -0.9111297 -0.3971328 -0.1212574 -0.9137713 -0.3877097 -0.1437929 -0.92164 -0.3604214 -0.1567152 -0.9378738 -0.3095691 -0.1378589 -0.920845 -0.3647459 -0.1145838 -0.9038969 -0.4121174 -0.1319311 -0.8967368 -0.4224424 -0.1392474 -0.8922219 -0.4295932 -0.160954 -0.8940166 -0.4181246 -0.179892 -0.8940295 -0.410305 -0.289324 -0.8759712 -0.3859615 -0.2081369 -0.8896604 -0.4064278 -0.2064948 -0.8900983 -0.4063068 -0.2843901 -0.8697861 -0.4032302 -0.4202058 -0.8129768 -0.4031076 -0.4201828 -0.8129439 -0.4031981 -0.5452063 -0.7350391 -0.403073 -0.452688 -0.6648163 -0.5942162 -0.5733858 -0.7119277 -0.4054477 -0.7971175 -0.4480531 -0.4047868 -0.7882312 -0.4634988 -0.404797 -0.6558589 -0.6382973 -0.4030209 0.05654984 0.8969066 -0.4385894 0.06725013 0.9016948 -0.4271113 0.02560389 0.9119408 -0.4095222 0.06932348 0.9013103 -0.4275912 0.08433276 0.9047376 -0.4175381 0.09643554 0.9063562 -0.4113621 0.1170801 0.9067411 -0.4051085 0.1086376 0.9093475 -0.4016032 0.09949266 0.9125931 -0.3965793 0.08608835 0.9194588 -0.3836462 0.07161247 0.9321785 -0.3548449 0.06983232 0.935157 -0.3472821 0.005485355 0.9146079 -0.4043048 -0.07917368 0.9116541 -0.4032599 -0.07897216 0.9115446 -0.4035468 -0.2246631 0.8869311 -0.4035835 -0.2244503 0.8871554 -0.403209 -0.2262077 0.8868436 -0.4029126 -0.3642349 0.8390793 -0.4040781 -0.3635794 0.8401622 -0.4024146 -0.3640219 0.8397928 -0.4027857 -0.6720894 0.6199242 -0.4049566 -0.6110878 0.6807662 -0.4038925 -0.6109011 0.6807796 -0.4041523 -0.6118566 0.6798727 -0.4042335 -0.4935784 0.7700317 -0.4042667 -0.7362101 0.5410847 -0.4064752 -0.7340623 0.5508453 -0.3971423 -0.7309377 0.5611967 -0.3883147 -0.7261825 0.585117 -0.360967 -0.7336651 0.6039784 -0.3113613 -0.7286061 0.5804088 -0.3636741 -0.7262123 0.5504689 -0.4118251 -0.7099611 0.5630367 -0.4230189 -0.7029243 0.5667937 -0.4297004 -0.6936516 0.5863364 -0.4183983 -0.6836575 0.6037409 -0.4100115 -0.6138288 0.6885059 -0.3862304 -0.6683236 0.6223665 -0.4074353 -0.6683236 0.6223665 -0.4074353 -0.6683236 0.6223666 -0.4074353 -0.6661221 0.624737 -0.4074128 -0.2247793 0.8875961 -0.4020543 -0.3640491 0.8400554 -0.4022129 -0.3638692 0.839863 -0.4027771 -0.494264 0.7704274 -0.4026722 -0.4933365 0.7697231 -0.4051487 -0.6106324 0.6803492 -0.4052814 0.009877622 0.9143295 -0.4048508 -0.01266336 0.914304 -0.4048307 -0.08019357 0.9180848 -0.3881872 -0.08190518 0.9121944 -0.4014885 -0.2248124 0.8876505 -0.4019154 -0.09946751 -0.9101111 -0.4022488 -0.09378015 -0.9097218 -0.4044893 0.005751848 -0.9149417 -0.403545 0.152438 -0.9021662 -0.4035579 0.1524315 -0.9021685 -0.403555 0.2951489 -0.8660402 -0.4035612 0.2951642 -0.866028 -0.403576 0.4302854 -0.8074445 -0.4035941 0.4301859 -0.8075299 -0.4035292 0.554342 -0.7279181 -0.4035348 0.5544038 -0.7278513 -0.4035703 0.6638193 -0.6296631 -0.4035695 0.7279365 -0.5536876 -0.404399 0.7336074 -0.5431713 -0.4083935 -0.7388426 0.5402956 -0.4027311 -0.7408075 0.5363067 -0.4044495 -0.7951182 0.4527568 -0.4034831 -0.7952665 0.4522639 -0.4037432 -0.8574904 0.318942 -0.4037153 -0.8574188 0.3194584 -0.4034591 -0.8976539 0.1773035 -0.4034612 -0.8976509 0.1773133 -0.4034636 -0.9144631 0.03118187 -0.4034665 -0.9075524 -0.1161586 -0.403554 -0.9075325 -0.1162267 -0.4035794 -0.8772542 -0.2598552 -0.4036092 -0.8771752 -0.2599919 -0.4036928 -0.8432407 -0.3538424 -0.404649 -0.8375944 -0.3630167 -0.4082337 0.8392302 0.3668477 -0.4013916 0.8346929 0.3737128 -0.4045078 0.7895538 0.4623342 -0.4035491 0.7895491 0.4623279 -0.4035655 0.7050387 0.5831623 -0.4035372 0.7049583 0.5832263 -0.4035851 0.6024104 0.6886407 -0.4035787 0.6024758 0.6886069 -0.4035387 0.4841872 0.7763526 -0.4035337 0.4839911 0.7764156 -0.4036479 0.3534047 0.8439059 -0.4036435 0.3532245 0.8439397 -0.4037305 0.2130885 0.8897153 -0.4037325 0.1154004 0.9072086 -0.4045436 0.1038681 0.9068536 -0.4084461 -2.98736e-6 0 1 1.7487e-6 0 1 1.74909e-6 0 1 7.59616e-7 0 1 5.68059e-6 0 1 -6.25665e-6 0 1 5.81625e-6 0 1 -5.8572e-6 0 1 -5.97429e-6 0 1 -1.53367e-6 0 1 -1.26804e-6 0 1 -7.14939e-7 0 1 -2.76781e-6 0 1 -6.64275e-6 0 1 5.47969e-6 0 1 6.84182e-6 0 1 -5.35424e-6 0 1 5.23396e-6 0 1 5.16733e-6 0 1 -4.97334e-6 0 1 -4.90408e-6 0 1 -7.92393e-6 0 1 0.7870784 0.3904126 0.4775832 -0.06730961 -0.7422078 0.6667811 -0.8145347 0.4168434 0.4034538 -0.8719808 0.276915 0.4036926 -0.8714028 0.2764696 0.4052428 -0.905059 0.1294022 0.4051213 -0.9051938 0.1295021 0.4047883 -0.914185 -0.021223 0.4047414 -0.9147281 -0.02103203 0.4035224 -0.8985623 -0.1715466 0.4039279 -0.8985542 -0.1715598 0.4039402 -0.8395158 -0.3655064 0.4020178 -0.8319249 -0.3532825 0.4278931 -0.7924641 -0.3220878 0.5179383 -0.7784996 -0.3435013 0.525305 -0.6948826 -0.2813687 0.6617929 -0.8373973 -0.3693581 0.4029151 -0.8352552 -0.36102 0.4147452 -0.8349987 -0.3705819 0.4067509 -0.8348393 -0.3712543 0.4064648 -0.8490728 -0.3523261 0.3936266 -0.8649355 -0.3392927 0.3698203 -0.8910422 -0.3294267 0.312285 -0.8819519 -0.2979763 0.3652002 -0.8772873 -0.2573462 0.4051418 -0.1128204 -0.9066035 0.4066224 -0.1184585 -0.9065584 0.4051166 -0.090981 -0.9147714 0.3935933 -0.1062988 -0.9094642 0.4019646 -0.1119757 -0.9082302 0.4032115 -0.1097535 -0.9062983 0.4081391 -0.1049941 -0.9050251 0.4121965 -0.08138179 -0.8841806 0.4600021 -0.1701229 -0.8227384 0.5423651 -0.1036492 -0.8446541 0.5251824 0.5181586 -0.7543134 0.4031414 0.3870785 -0.8292805 0.4030686 0.3870304 -0.8285636 0.4045861 0.2450536 -0.8810114 0.4046821 0.2449645 -0.881968 0.4026475 0.09679317 -0.9102668 0.4025489 0.09698706 -0.9095281 0.4041685 0.007342159 -0.9141641 0.405278 -0.05614292 -0.9398636 0.336904 -0.04624104 -0.9597935 0.2768721 -0.0735026 -0.9264149 0.3692599 0.6531739 -0.6771593 0.3388497 0.6261245 -0.6667653 0.4042182 0.5180628 -0.7539686 0.4039089 0.6326329 -0.4649344 0.6193639 0.7159386 -0.5123407 0.4742773 0.7336412 -0.5179913 0.4398359 0.7433784 -0.5180787 0.4230638 0.7590989 -0.5091733 0.4056003 0.753059 -0.5256447 0.395727 0.749921 -0.5382184 0.384629 0.7490785 -0.55565 0.3607417 0.7490417 -0.5555194 0.3610191 0.6948934 -0.5940812 0.4052046 0.6788671 -0.6123302 0.4052053 0.8664122 0.2998918 0.3992428 0.8540713 0.3080308 0.4191411 0.8416964 0.3112031 0.4412481 0.8424364 0.3103979 0.4404022 0.8422677 0.3105862 0.4405922 0.8323386 0.381429 0.4021498 0.8323386 0.3814289 0.4021499 0.8323386 0.381429 0.4021498 0.8254269 0.3960931 0.4022199 0.8254269 0.3960931 0.4022199 0.8254269 0.3960931 0.4022198 0.867339 0.3363726 0.3668467 0.858128 0.3172776 0.4036723 0.8248382 0.3946645 0.4048233 0.8213357 0.4059497 0.4007652 0.3479006 0.8460106 0.404019 0.4821868 0.7772428 0.4042147 0.4824396 0.7774236 0.4035649 0.603908 0.6873762 0.4034963 0.6042613 0.6875677 0.40264 0.709249 0.5787513 0.4025084 0.7084154 0.5784789 0.4043634 0.7743971 0.4857823 0.4053699 0.8333095 0.4763026 0.2805907 0.8248388 0.4497663 0.3425658 0.8200852 0.4248018 0.3834106 0.1639668 0.9055894 0.3911815 0.1906005 0.9197367 0.3431559 0.2139666 0.9358977 0.2798463 0.2400412 0.8825106 0.4044201 0.3480667 0.8461818 0.4035171 0.04205417 0.9151916 0.400819 0.05500358 0.9199582 0.3881385 0.0546925 0.9197919 0.3885766 0.1192163 0.9066464 0.4046972 0.1419628 0.9033671 0.4046907 0.1447624 0.8679565 0.4750742 0.1447623 0.8679565 0.4750742 0.1447623 0.8679565 0.4750742 0.1394818 0.9038598 0.4044533 0.05434834 0.9135029 0.403186 0.06403785 0.8860813 0.4590852 0.05317783 0.8949047 0.4430776 0.0503233 0.9016122 0.429608 0.05389195 0.897514 0.4376807 -0.7109452 0.5707859 0.4108046 -0.7200983 0.5689371 0.3972014 -0.7309215 0.5623149 0.3867245 -0.8474087 0.4195536 0.3253817 -0.7837879 0.4713756 0.4043287 -0.7350775 0.5451717 0.4030495 -0.7736083 0.5524666 0.3103399 -0.7436838 0.5566757 0.370198 -0.7083458 0.5804125 0.4017059 -0.7113925 0.5601089 0.4244984 -0.7040786 0.5423166 0.4584389 -0.628682 0.4708305 0.6189328 -0.833321 -0.3763357 0.4049043 -0.8324797 -0.3785742 0.4045482 -0.7943526 -0.454168 0.4034047 -0.7943816 -0.4540501 0.4034805 -0.7084762 -0.5790565 0.4034293 -0.7086696 -0.578761 0.4035137 -0.7087983 -0.5786609 0.4034311 -0.7095974 0.5770205 0.4043748 -0.636735 0.6570549 0.4035437 -0.6353351 0.6585415 0.4033268 -0.5181857 0.7541073 0.4034919 -0.5181144 0.7541331 0.4035355 -0.5181944 0.7540725 0.4035457 -0.6349798 0.6587283 0.4035813 0.043675 0.9095299 0.4133375 0.03828257 0.9139872 0.4039331 -0.09675669 0.9098696 0.4034546 -0.09673357 0.9098636 0.4034735 -0.2451596 0.8815447 0.4034548 -0.245141 0.881547 0.403461 -0.3878747 0.8287241 0.4034473 -0.3869166 0.8291423 0.4035079 -0.3869271 0.8291282 0.403527 -0.3854789 0.8297979 0.403536 -0.3854789 0.829798 0.403536 -0.3854791 0.829798 0.4035361 0.864468 0.3219972 0.3860217 0.8632295 0.3026378 0.4040363 0.8987062 0.1715863 0.4035906 0.8987264 0.171738 0.4034811 0.9147405 0.0212301 0.4034837 0.9057888 -0.1296897 0.4033946 0.9056887 -0.1299163 0.4035465 0.9059222 -0.1274008 0.4038245 0.9146437 0.02089393 0.4037209 0.7490251 -0.516453 0.4150153 0.7580037 -0.5117831 0.4043619 0.8147301 -0.4164618 0.4034532 0.8144135 -0.4167768 0.4037671 0.8717811 -0.2774015 0.4037896 0.8721328 -0.2765442 0.4036184 0.8720983 -0.2769459 0.4034175 0.9057751 -0.1295522 0.4034698 -0.1211978 -0.9064131 0.4046311 -0.2036908 -0.8920249 0.4034869 -0.2040535 -0.8919897 0.4033815 -0.2041238 -0.8919674 0.4033952 -0.3479677 -0.846265 0.4034282 -0.3477776 -0.8463302 0.4034551 -0.3482788 -0.8459756 0.4037662 -0.347439 -0.8464256 0.4035469 -0.4825639 -0.777349 0.4035599 -0.482352 -0.7775911 0.4033468 -0.604035 -0.6873398 0.4033681 -0.6041017 -0.6872224 0.4034681 -0.7087413 -0.5787248 0.4034397 6.29168e-7 0 1 -1.18993e-6 0 1 8.42466e-7 0 1 8.55286e-6 0 1 -4.9324e-7 0 1 -1.28074e-5 0 1 -1.52681e-5 0 1 8.87123e-6 0 1 -8.74818e-7 0 1 1.67477e-6 0 1 7.73893e-6 0 1 -1.68693e-6 0 1 -6.25532e-7 0 1 2.42319e-6 0 1 -2.60841e-6 0 1 9.2923e-6 0 1 -1.94809e-6 0 1 1.85062e-6 0 1 -2.87717e-5 0 1 1.21524e-5 0 1 -1.92625e-6 0 1 4.10074e-6 0 1 1.82671e-6 0 1 -1.56706e-6 0 1 -1.79366e-5 0 1 -6.02141e-6 0 1 7.68176e-6 0 1 -2.40545e-6 0 1 3.99954e-6 0 1 -1.14837e-5 0 1 1.91512e-5 0 1 -5.73163e-7 0 1 2.51705e-6 0 1 4.84767e-7 0 1 -1.51618e-6 0 1 3.30149e-6 0 1 5.74026e-6 0 1 -2.58506e-6 0 1 -2.4391e-6 0 1 2.2909e-6 0 1 -2.83046e-6 0 1 8.796e-7 0 1 5.43667e-6 0 1 2.92299e-6 0 1 -3.30177e-6 0 1 5.34348e-6 0 1 -3.57274e-6 0 1 1.59714e-5 0 1 -2.97803e-6 0 1 -2.24233e-5 0 1 3.3824e-6 0 1 -1.0692e-5 0 1 -5.96331e-6 0 1 8.41978e-6 0 1 -1.60472e-5 0 1 4.05489e-6 0 1 -1.30019e-6 0 1 2.05477e-6 0 1 -2.90989e-6 0 1 1.3793e-7 0 1 1.28048e-6 0 1 -1.45317e-6 0 1 -5.81504e-6 0 1 5.36583e-6 0 1 6.62189e-7 0 1 -3.02936e-6 0 1 4.20808e-6 0 1 2.90833e-5 0 1 6.55686e-6 0 1 -3.89761e-7 0 1 -4.27715e-7 0 1 -2.26224e-6 0 1 -1.54745e-6 0 1 3.0874e-6 0 1 -9.58159e-7 0 1 1.57387e-6 0 1 1.96861e-6 0 1 -3.83795e-6 0 1 1.97868e-6 0 1 4.75747e-6 0 1 1.33564e-6 0 1 -2.42408e-6 0 1 5.28792e-7 0 1 -3.96341e-6 0 1 2.23534e-6 0 1 -1.60697e-6 0 1 1.23655e-6 0 1 1.48543e-6 0 1 4.76172e-6 0 1 -4.1828e-6 0 1 -1.61708e-5 0 1 4.88072e-6 0 1 2.88937e-6 0 1 -2.23382e-6 0 1 -2.23246e-6 0 1 -2.28165e-6 0 1 7.2758e-6 0 1 -1.99946e-6 0 1 1.05856e-6 0 1 2.24745e-6 0 1 3.84852e-7 0 1 6.70148e-7 0 1 1.78298e-6 0 1 8.44423e-7 0 1 1.07814e-5 0 1 -4.08831e-5 0 1 1.68697e-6 0 1 5.24141e-5 0 1 -4.671e-7 0 1 3.25457e-6 0 1 3.53048e-6 0 1 -1.19124e-6 0 1 -5.24433e-7 0 1 2.53581e-6 0 1 -4.73148e-7 0 1 -2.09706e-6 0 1 1.98438e-6 0 1 1.36067e-6 0 1 -6.57969e-7 0 1 1.02921e-6 0 1 5.78315e-6 0 1 -1.47062e-5 0 1 1.60472e-5 0 1 4.19287e-6 0 1 -1.78451e-6 0 1 3.0775e-6 0 1 -2.72771e-6 0 1 7.03227e-7 0 1 3.68971e-7 0 1 1.39573e-6 0 1 1.42911e-6 0 1 -1.43102e-6 0 1 3.54117e-6 0 1 4.91932e-5 0 1 -1.36501e-6 0 1 7.10126e-7 0 1 -8.93387e-7 0 1 -3.24069e-6 0 1 1.23425e-6 0 1 1.74808e-6 0 1 -2.85545e-6 0 1 -3.05728e-6 0 1 -3.08856e-6 0 1 1.50553e-5 0 1 3.02825e-6 0 1 -1.52166e-6 0 1 -3.78352e-6 0 1 2.20181e-6 0 1 8.22253e-6 0 1 -1.31264e-6 0 1 -1.17234e-6 0 1 4.37315e-6 0 1 -1.76658e-6 0 1 -1.46182e-5 0 1 -4.72521e-6 0 1 -5.38793e-5 0 1 6.84744e-5 0 1 -2.3403e-6 0 1 4.08017e-6 0 1 -1.4474e-6 0 1 1.28087e-5 0 1 -1.23552e-6 0 1 -2.2535e-6 0 1 2.19296e-6 0 1 -2.07848e-6 0 1 1.7944e-7 0 1 0 0 1 -1.80304e-5 0 1 -1.92986e-7 0 1 0.9293707 0.369148 0 0.8873787 0.4565098 -0.06448245 0.9472429 0.3203645 -0.009879767 0.4377422 0.8985356 -0.03187179 0.519131 0.8546947 0 0.7330006 0.6802281 0 0.6663107 0.7429814 -0.06331419 0.7932635 0.6088786 0 0.08371829 0.9960641 -0.02911221 0.1883319 0.9821056 0 0.352755 0.9357158 0 0.9767361 0.2144451 0 0.9767361 0.2144451 0 0.9767361 0.2144451 0 0.9999623 0.008698046 0 0.9999618 0.008740305 0 0.9357842 -0.3525734 0 0.9357839 -0.3525743 0 0.7446981 -0.6674016 0 0.4537332 -0.8911377 0 0.4537327 -0.8911378 0 0.1001483 -0.9949726 0 0.1001527 -0.9949722 0 -0.2654995 -0.9641111 0 -0.2655103 -0.9641081 0 -0.5954636 -0.8033823 0 -0.8458734 -0.533384 0 -0.8458352 -0.5334444 0 -0.9812471 -0.1927543 0 -0.9812472 -0.1927539 0 -0.9845381 0.1751711 0 -0.9845452 0.1751306 0 -0.8546704 0.519171 0 -0.8546888 0.5191407 0 -0.6097194 0.7926174 0 -0.609699 0.7926331 0 -0.2818663 0.9594537 0 -0.2818549 0.959457 0 -0.07386034 0.9972686 0 0.03020042 0.9994999 -0.009384274 2.09887e-6 0 -1 -2.79178e-6 0 -1 2.1749e-6 0 -1 -1.66815e-6 0 -1 1.43561e-6 0 -1 -1.2579e-6 0 -1 -9.90788e-7 0 -1 -2.14371e-6 0 -1 4.60551e-7 0 -1 -2.42203e-7 0 -1 -9.3278e-7 0 -1 9.41648e-7 0 -1 1.01661e-6 0 -1 -1.15914e-6 0 -1 -4.91343e-6 0 -1 -6.31964e-7 0 -1 -1.27649e-6 0 -1 8.3206e-7 0 -1 3.58678e-7 0 -1 7.11532e-7 0 -1 0 0 -1 7.58495e-7 0 -1 9.80848e-7 0 -1 -1.11929e-6 0 -1 8.53854e-7 0 -1 4.26497e-6 0 -1 -5.60101e-7 0 -1 1.00336e-6 0 -1 -4.74982e-7 0 -1 6.99622e-7 0 -1 1.30202e-5 0 -1 2.14575e-6 0 -1 -1.20316e-6 0 -1 2.65312e-6 0 -1 2.48282e-6 0 -1 -1.83959e-6 0 -1 -2.30481e-6 0 -1 5.18167e-6 0 -1 -7.97827e-7 0 -1 -2.63989e-6 0 -1 1.61209e-6 0 -1 -8.13471e-6 0 -1 -7.03837e-7 0 -1 -2.95603e-7 0 -1 -1.19629e-6 0 -1 -5.52927e-7 0 -1 -7.04753e-7 0 -1 9.10501e-7 0 -1 4.94979e-7 0 -1 -2.30793e-6 0 -1 -5.85003e-7 0 -1 1.25971e-6 0 -1 3.04702e-6 0 -1 -7.84683e-7 0 -1 -2.14276e-6 0 -1 2.42321e-7 0 -1 5.70089e-7 0 -1 4.79511e-7 0 -1 2.97874e-6 0 -1 -6.62467e-6 0 -1 4.89869e-6 0 -1 1.18455e-5 0 -1 -4.07558e-6 0 -1 -1.84325e-6 0 -1 -5.18156e-6 0 -1 9.41159e-6 0 -1 -7.97925e-7 0 -1 1.38905e-6 0 -1 3.19338e-6 0 -1 -1.39912e-6 0 -1 2.41565e-6 0 -1 -3.47161e-6 0 -1 7.00257e-7 0 -1 -3.9879e-7 0 -1 1.04572e-6 0 -1 -2.9615e-6 0 -1 4.35206e-6 0 -1 7.03853e-7 0 -1 3.76977e-6 0 -1 -2.07309e-6 0 -1 4.61892e-6 0 -1 4.34752e-6 0 -1 -8.17009e-7 0 -1 0.4689089 0.8832466 0 0.7087646 0.7054451 0 0.7087889 0.7054207 0 0.8855391 0.464565 0 0.8855389 0.4645654 0 0.9829806 0.1837098 0 0.9829894 0.1836627 0 0.9934647 -0.1141403 0 0.9934702 -0.1140921 0 0.915766 -0.4017122 0 0.915775 -0.4016917 0 0.7564141 -0.6540931 0 0.7564021 -0.654107 0 0.5300793 -0.8479481 0 0.5300678 -0.8479554 0 0.2565153 -0.9665402 0 -0.03943091 -0.9992223 0 -0.03943085 -0.9992223 0 -0.3330397 -0.9429128 0 -0.3330244 -0.9429183 0 -0.5954371 -0.8034021 0 -0.5954251 -0.8034108 0 -0.8058974 -0.5920552 0 -0.8058972 -0.5920556 0 -0.9447613 -0.3277593 0 -0.9993781 -0.03526413 0 -0.999379 -0.03523975 0 -0.9653857 0.2608266 0 -0.9653733 0.2608723 0 -0.8453521 0.5342097 0 -0.6505265 0.7594836 0 -0.650502 0.7595046 0 -0.3975554 0.9175782 0 -0.397564 0.9175745 0 -0.1098828 0.9939447 0 -0.1098802 0.993945 0 0.1886931 0.9820362 0 0.1886884 0.9820371 0 0.4688889 0.8832572 0 0.9819645 0.1890661 0 -0.9819813 -0.1889785 0 0.1036088 -0.9946181 0 -0.9946004 -0.1035094 0.007487773 -0.3158813 0.9487987 0 -0.4765142 0.8791669 0 -0.4764913 0.8791792 0 -0.6218947 0.783101 0 -0.6218814 0.7831115 0 -0.7479694 0.6637333 0 -0.7479829 0.6637181 0 -0.852068 0.5234311 0 -0.8520441 0.5234701 0 -0.9303823 0.366591 0 -0.9303638 0.3666378 0 -0.9796387 0.200769 0 -0.9996177 0.02764976 0 -0.9892244 -0.1464071 0 -0.1036185 0.9946171 0 0.9945889 0.103619 0.00748378 0.3158812 -0.9487988 0 0.476503 -0.8791729 0 0.4765139 -0.879167 0 0.6218762 -0.7831155 0 0.6218893 -0.7831052 0 0.7479694 -0.6637333 0 0.7479963 -0.663703 0 0.8520561 -0.5234506 0 0.8520441 -0.5234701 0 0.9299882 -0.3675895 0 0.9299789 -0.367613 0 0.9796443 -0.2007414 0 0.9796337 -0.2007931 0 0.9996476 -0.02654993 0 0.9996483 -0.02652305 0 0.9819695 0.1890392 0 0.9487998 0.3158783 0 0.8791622 0.4765228 0 0.8791766 0.4764962 0 0.783669 0.6211786 0 0.7836859 0.6211574 0 0.6631342 0.7485006 0 0.6631512 0.7484855 0 0.5234448 0.8520596 0 0.5234603 0.8520502 0 0.3676213 0.9299756 0 0.3676097 0.9299802 0 0.1996651 0.9798643 0 0.02767038 0.9996172 0 0.02766847 0.9996172 0 -0.1036067 0.9946184 0 -0.1464205 0.9892153 0.00374794 -0.1890265 0.981972 0 -0.3158817 0.9487986 0 -0.9819689 -0.1890424 0 -0.9484396 -0.3169578 0 -0.9484604 -0.3168962 0 -0.8791785 -0.4764925 0 -0.8791643 -0.476519 0 -0.7836658 -0.6211827 0 -0.783666 -0.6211826 0 -0.6631512 -0.7484855 0 -0.6631342 -0.7485006 0 -0.5239762 -0.851733 0 -0.5239919 -0.8517234 0 -0.3676022 -0.9299831 0 -0.3676138 -0.9299786 0 -0.1994361 -0.9799109 0 -0.1994363 -0.9799108 0 -0.02770924 -0.999616 0 -0.02770924 -0.999616 0 0.1036137 -0.9946177 0 0.1464205 -0.9892153 0.00374794 0.1890265 -0.981972 0 0.3158814 -0.9487987 0 -1.15597e-5 0 1 1.45641e-5 0 1 -1.59953e-6 0 1 -0.7038593 -0.09159499 0.7044093 -0.6624724 -0.04758268 0.7475736 -0.1122786 0.6742641 0.7299051 -0.1566964 0.6905717 0.7060857 -0.2869948 0.6497252 0.7039114 -0.2878661 0.6487672 0.7044389 -0.2873967 0.6486755 0.704715 -0.4433787 0.5538967 0.7047085 -0.4431893 0.554296 0.7045134 -0.4437959 0.5542516 0.7041665 -0.5703083 0.4229786 0.7041574 -0.5698977 0.4229834 0.7044869 -0.5708213 0.4225742 0.7039845 -0.659686 0.2635169 0.7038276 -0.6586126 0.2638318 0.7047144 -0.6594999 0.2630417 0.7041797 -0.7047801 0.08726817 0.7040379 -0.7048383 0.08720874 0.7039869 -0.7046527 0.087511 0.7041352 -7.26871e-6 0 1 9.1507e-7 0 1 4.9778e-6 0 1 0.5956715 0.8032281 0 0.5956904 0.8032141 0 0.5956907 0.803214 -4.65764e-6 0.6624099 0.04746431 0.7476366 0.6961423 0.09057348 0.7121674 0.1122742 -0.674283 0.7298883 0.1561413 -0.6903798 0.7063963 0.1570254 -0.6903911 0.7061893 0.2878225 -0.6491094 0.7041414 0.2879039 -0.6488345 0.7043616 0.2847176 -0.6501398 0.7044532 0.4434322 -0.5538513 0.7047104 0.4434135 -0.5545791 0.7041494 0.4435971 -0.5541496 0.7043719 0.570304 -0.4229933 0.7041521 0.5698817 -0.4229876 0.7044972 0.6618011 -0.2573439 0.7041261 0.6593049 -0.2633646 0.7042416 0.6586478 -0.2635532 0.7047856 0.7043744 -0.08592838 0.7046084 0.7042444 -0.08718508 0.704584 0.7046805 -0.08688163 0.7041854 0.7060002 0.05120897 0.7063578 -0.5956715 -0.8032281 0 -0.5956904 -0.8032141 5.8794e-6 -0.5956907 -0.803214 0 6.73782e-6 0 1 -4.24841e-6 0 1 5.02796e-6 0 1 3.35895e-6 0 1 2.10135e-6 0 1 -5.37182e-7 0 1 2.55885e-6 0 1 -1.91817e-6 0 1 2.12321e-6 0 1 2.08955e-6 0 1 -2.12357e-6 0 1 1.09811e-6 0 1 -1.68599e-6 0 1 7.55378e-7 0 1 1.09591e-6 0 1 2.12433e-6 0 1 0.9601774 -0.2793909 0 0.5463309 -0.8375695 0 0.3802783 -0.9248711 -0.001392126 0.2062788 -0.9784557 0.0085783 0.1924431 -0.9812818 0.007187545 0.07179409 -0.9974121 -0.003849804 -0.2715863 -0.9624142 0 -0.2044067 -0.9785876 -0.02416932 -0.4697978 -0.8805591 0.06249564 -0.4697978 -0.8805591 0.06249564 -0.4697978 -0.8805592 0.0624957 0.2062798 -0.978493 0 0.3118918 -0.9479012 -0.06486141 0.1798194 -0.9834983 -0.01990526 0.9945442 -0.104161 0.005696475 0.9945442 -0.104161 0.005696535 0.9945442 -0.104161 0.005696535 0.9534019 -0.301593 -0.008162975 0.9219257 -0.3851286 -0.04158145 0.8642901 -0.5029937 0 0.6363468 -0.7714031 0 0.7205027 -0.6882731 -0.0845927 0.548644 -0.8360561 -1.93659e-4 0.9949414 -0.1002955 0.005701601 0.9958454 0.08640015 -0.02875596 0.9933916 0.1130459 -0.01984369 0.7275238 0.6839934 0.05350029 0.7275238 0.6839934 0.05350035 0.7275237 0.6839935 0.05350041 0.8715766 0.48983 -0.02051436 0.8413553 0.5404826 0 0.958391 0.2854588 0 0.9749189 0.2225333 -0.00349003 0.975601 0.2195477 0.001302778 0.9583495 0.2855982 0 0.8413714 0.5404576 0 0.9962591 0.08641755 0 0.9983139 -0.05362743 0.02221769 0.9949218 0.1003956 0.007166624 0.3871054 -0.9220345 -0.001398026 0.5694676 -0.8220105 0.002370417 0.6363174 -0.7713639 0.009896695 0.7307354 -0.6826609 0 0.9227117 -0.3854909 0 0.8655316 -0.5003976 0.02139163 0.9596675 -0.2811375 3.12583e-5 0.8413634 0.5404701 0 0.494476 0.8691913 0 0.4944939 0.8691812 0 0.03485208 0.9993926 0 -0.4343597 0.9007396 0 -0.43436 0.9007394 0 -0.7248065 0.6889526 0 -0.8031576 0.59574 -0.005629956 -0.8694542 0.4940139 0 -0.988178 0.1533112 0 -0.988178 0.1533111 0 -0.946866 -0.3216283 0 -0.9468534 -0.3216656 0 -0.6880536 -0.72566 0 -0.6880537 -0.7256598 0 -0.2715855 -0.9624143 0 -0.2715965 -0.9624112 0 0.07518994 -0.9971682 0.001436114 -0.5501356 -0.7419181 0.3832864 0.4792411 0.6463376 -0.5937809 0.5508927 0.7429279 -0.3802309 0.4591292 0.6438367 0.6121068 0.2635454 0.3265771 0.9076845 0.3606852 0.4913807 0.7927491 0.2451996 0.3357611 0.9094734 0.2281737 0.3072298 0.9238759 0.07889825 0.1067389 0.9911518 0.07781475 0.1049625 0.9914271 0.5868936 0.7988804 0.1317049 0.5437318 0.7273513 0.4187076 0.550781 0.7427867 0.3806684 0.4791744 0.6462398 0.5939412 0.4034411 0.5160238 0.7556156 0.5939183 0.8009409 -0.07586008 0.5939158 0.8009449 0.07583773 0.5839595 0.7730773 0.2476747 0.5727882 0.8089367 -0.132421 0.5653295 0.7171716 -0.4075139 0.5839112 0.7729842 -0.2480789 0.3896905 0.4931272 -0.7777962 0.4571108 0.6454623 -0.6119054 0.370068 0.5019303 -0.7817389 0.3629071 0.4893845 -0.79297 0.2295927 0.3096347 -0.9227207 0.2282177 0.3073343 -0.9238303 0.07893055 0.1067227 -0.991151 -0.4840745 -0.6275008 -0.609848 -0.2358037 -0.3466047 -0.9078887 -0.3649569 -0.487069 -0.7934547 -0.2497846 -0.3316923 -0.9097186 -0.2283902 -0.3081569 -0.9235136 -0.07949465 -0.1067928 -0.9910984 -0.07770502 -0.1048361 -0.9914491 0.07802361 0.1052488 -0.9913803 -0.5942106 -0.7935684 -0.1310074 -0.5378597 -0.7310779 -0.4197999 -0.5501032 -0.7418869 -0.3833933 -0.4788215 -0.6457735 -0.5947324 -0.3771842 -0.5365144 -0.754907 -0.5937114 -0.8006371 0.08054316 -0.5936995 -0.8006436 -0.08056509 -0.5707252 -0.7834807 -0.2458271 -0.6080315 -0.7829349 0.1315708 -0.5219242 -0.7489158 0.4083139 -0.5705998 -0.7833838 0.2464264 -0.07791721 -0.1050789 0.9914068 -0.0794689 -0.1068381 0.9910956 -0.2281596 -0.3080459 0.9236076 -0.2300577 -0.3101286 0.922439 -0.362161 -0.4882413 0.7940151 -0.3701 -0.4966459 0.7850916 -0.4866901 -0.6265904 0.6087012 -0.3597343 -0.517275 0.7765424 -0.4789895 -0.6459707 0.5943828 0.9974443 0.07144969 0 0.9721735 0.2256461 -0.06295096 0.9835413 0.1806836 0 0.8987178 0.4385276 0 0.8987869 0.438386 -7.47989e-5 -0.2212823 0.9752098 0 0.8988238 0.4383104 0 0.7463645 0.6655374 0 0.7463515 0.665552 0 0.5395383 0.8419612 0 0.5395286 0.8419674 0 0.2923293 0.9563177 0 0.2923222 0.95632 0 0.02335816 0.9997273 0 0.02350538 0.9997238 -4.27561e-5 0.02353376 0.9997231 0 -0.1356964 0.9907506 0 -0.2466018 0.9687957 -0.02494877 -0.2603561 0.9654728 -0.008787274 -0.4040356 0.9146902 0.009849905 -0.9756623 -0.1565644 -0.1535279 -0.999741 -0.02276074 0 -0.9973267 -0.07172214 -0.01397871 -0.9989957 -0.04480904 0 -0.9498108 -0.3128249 0 -0.9497804 -0.3129172 1.14241e-4 -0.9496182 -0.3134095 0 -0.8303535 -0.557237 0 -0.8303403 -0.5572568 0 -0.6490963 -0.7607063 0 -0.6491023 -0.7607012 0 -0.4202607 -0.9074034 0 -0.4202749 -0.9073969 0 -0.1584753 -0.9873631 0 -0.1592846 -0.9872325 -7.37012e-4 -0.1608641 -0.9869766 0 0.0676279 -0.9977107 0 0.1129997 -0.9927434 -0.04112941 0.2011117 -0.9795684 0 -0.9225283 0.3841584 0.03693056 -0.9407455 0.3382036 0.02482533 -0.9637539 0.2662582 0.01688319 -0.9874234 0.1577811 0.01001238 -0.9249252 0.3801491 -4.30621e-4 -0.9206783 0.3903204 -0.001261472 -0.9076079 0.4197653 -0.006712794 -0.6629403 0.748646 -0.006278157 -0.6936649 0.7199925 -0.02097219 -0.8910502 0.4534715 -0.01983171 -0.8650281 0.4989359 -0.05281448 -0.8761307 0.4810178 -0.03189325 -0.822407 0.5688997 0 -0.7147803 0.6993491 0 -0.7682887 0.6287997 -0.1197637 -0.7271838 0.6844925 -0.0517075 -0.6431781 0.7657147 -0.001814723 -0.6315839 0.7753073 -6.8273e-4 -0.4356462 0.9000633 0.009922564 -0.5344491 0.8450316 0.01690554 -0.5344491 0.8450316 0.01690548 -0.5344491 0.8450316 0.01690548 -0.5998079 0.7997465 0.02521991 -0.6358557 0.7709438 0.03651684 -0.6685139 0.7412176 0.06070911 -0.6250435 0.7805799 -0.003959178 -0.7425258 0.6698175 3.03845e-4 -0.8016932 0.5950832 0.0562511 -0.7745638 0.6272575 0.08123397 -0.8010659 0.5930223 0.08135133 -0.8232188 0.5665031 0.0372163 -0.9243124 0.3702879 -0.09237748 -0.8748419 0.4694704 0.1193708 -0.9033861 0.4244173 0.06134766 -0.405059 0.9142376 0.009845316 -0.500063 0.8659138 -0.01141911 -0.6249012 0.780699 0.002757966 -0.4985514 0.8668029 0.009960651 -0.4952015 0.8687201 0.01005005 -0.4952015 0.8687201 0.01005005 -0.4952015 0.8687201 0.01005005 0.9962931 0.0859946 0.002262771 0.9973664 0.07249283 0.002262115 0.9957599 -0.09181416 -0.005697965 0.9924832 -0.1223377 0.00328505 0.992666 -0.1208453 0.003284692 0.9341903 -0.3567551 -0.003773689 0.9284157 -0.3715361 -0.002304673 0.9341036 -0.3570006 0.001112222 0.9320175 -0.3624117 0.001113951 0.8029729 -0.596014 -0.001452088 0.803343 -0.5955153 -0.001253366 0.6245865 -0.7809547 0.001248538 0.6245865 -0.7809547 0.001249372 0.6245866 -0.7809547 0.001248538 0.6125074 -0.7904641 0.001248955 0.6249889 -0.7806307 -0.002229869 0.6127803 -0.7902448 -0.003664851 0.4012518 -0.9159612 0.003477275 0.4053466 -0.9141565 0.003478169 0.3768306 -0.9262655 -0.005577087 0.2218301 -0.9750827 0.002303838 0.220565 -0.9753696 0.002304971 -0.9751756 0.2212007 0.01014703 -0.973759 0.2273617 0.01000928 -0.9288421 0.3704641 0.002971231 -0.9739711 0.2263961 -0.01118612 -0.9923846 0.1227852 0.009828448 -0.9923141 0.1233537 0.009828984 -0.7362698 0.6766882 0 -0.0948593 0.9954907 0 0.3185375 0.9479104 0 0.318539 0.9479098 0 0.67612 0.7367916 0 0.676095 0.7368145 0 0.917366 0.3980448 0 0.9173862 0.3979983 0 0.9999415 -0.01081645 0 0.9999416 -0.01081639 0 0.9097514 -0.4151535 0 0.6618813 -0.7496088 0 0.6619079 -0.7495852 0 -0.8144702 -0.5802056 0 -0.8144447 -0.5802412 0 -0.9760391 0.2175957 0 -0.9760505 0.2175444 0 -0.8604593 0.5095191 0 -0.8022421 0.5960601 -0.03347051 0.909938 -0.4147445 2.69105e-4 0.9097335 -0.4151928 0 0.9999356 -0.01135236 0 0.9999513 -0.009867608 4.11632e-4 0.9999656 -0.008301794 1.08764e-4 0.999961 -0.008834362 0 0.917856 0.3969137 0 0.9178364 0.396959 0 0.317669 0.9482017 0 0.3176675 0.9482023 0 -0.09438133 0.9955362 0 -0.09378993 0.995592 -2.01897e-4 -0.09309858 0.995657 0 -0.4937546 0.8696014 0 -0.4918275 0.8706927 -1.21146e-4 -0.4916861 0.8707726 0 -0.7350611 0.678001 0 -0.8027277 0.5960111 -0.01998221 -0.7365044 0.6732283 -0.06576406 -0.8606486 0.5091993 0 -0.9799949 -0.199023 0 -0.9801058 -0.1984761 -2.10336e-4 -0.9802407 -0.1978085 0 -0.5072163 -0.8618188 0 -0.5072386 -0.8618057 0 0.9107882 -0.4128739 0 0.661229 -0.7501842 0 0.6612023 -0.7502077 0 0.3009096 -0.9536527 0 0.299579 -0.9540714 -6.5316e-4 0.2960004 -0.9551879 0 -0.4909633 0.8711803 0 0.9999536 -0.009632647 -1.13776e-4 0.999961 -0.008834064 0 0.9174044 0.3979566 0 0.9173847 0.3980018 0 0.3183829 0.9479622 0 0.3183977 0.9479573 0 -0.09497964 0.9954792 1.95144e-4 -0.09565699 0.9954144 0 -0.4909415 0.8711926 0 -0.7363314 0.6766212 0 -0.8030251 0.5949839 -0.03383582 -0.8625879 0.5059072 5.30407e-4 -0.8625879 0.5059071 5.30488e-4 -0.8625879 0.5059071 5.30438e-4 -0.8611232 0.5083963 0 -0.9759078 0.2181837 0 -0.9760384 0.2175981 3.76326e-4 -0.9772832 0.2119376 0 -0.9799731 -0.1991299 0 -0.980106 -0.1984748 -2.10334e-4 -0.815026 -0.5794245 0 -0.815027 -0.5794229 0 -0.114257 -0.9934513 0 0.9999515 -0.009851574 0 0.9093034 -0.4161339 0 0.6633275 -0.7483292 0 0.6618167 -0.7496656 -2.69393e-4 0.6614087 -0.7500258 0 0.3016878 -0.9534069 0 0.300436 -0.953802 3.30773e-4 0.2993414 -0.9541461 1.338e-4 0.3000472 -0.9539244 0 -0.1142513 -0.9934519 0 -0.09498602 0.9954787 0 0.9173945 0.3979791 0 0.9999535 -0.009644269 0 0.9999541 -0.009590327 0 0.9094908 -0.4157242 0 0.909501 -0.4157019 0 -0.8480098 0.5299797 -0.001058459 -0.8480097 0.52998 -0.001058459 -0.8480097 0.5299798 -0.001058459 -0.8612092 0.5082496 -0.001050889 -0.8023419 0.5959248 -0.03348362 -0.736358 0.6765922 0 -0.8065651 0.5911453 0 -0.814076 -0.5807584 0 -0.8140506 -0.5807941 0 -0.1142631 -0.9934506 0 0.2995783 -0.9540718 0 0.6614713 -0.7499705 0 0.6614421 -0.7499963 0 0.6609971 -0.7503885 0 0.6610232 -0.7503654 0 -0.4918594 0.8706746 0 0.9173945 0.3979791 3.70119e-4 0.9176219 0.3974545 0 0.3173123 0.9483212 0 0.3173027 0.9483243 0 -0.09496122 0.995481 0 -0.09377586 0.9955932 -5.7201e-4 -0.09004944 0.9959373 0 -0.4918698 0.8706689 0 -0.8030219 0.594989 -0.03382265 -0.8623917 0.5062415 5.14865e-4 -0.9759019 0.2182099 0 -0.9760446 0.2175703 3.74222e-4 -0.9807525 -0.195255 0 -0.9801213 -0.1983989 5.16594e-4 -0.9798988 -0.1994954 0 0.8947347 0.4465982 0 0.8947349 0.4465977 0 0.8947348 0.4465979 0 0.9999539 -0.009605765 0 0.9092915 -0.41616 0 0.6618215 -0.7496615 -2.76126e-4 0.6614316 -0.7500056 0 0.3008463 -0.9536727 0 0.3003233 -0.9538375 1.47919e-4 0.2999274 -0.9539621 0 -0.1101112 -0.9939193 0 -0.1101112 -0.9939193 0 -0.1101112 -0.9939193 0 -0.1142509 -0.993452 -2.69257e-5 0.9094908 -0.4157242 -2.9587e-4 0.9097464 -0.4151645 0 0.9999349 -0.01141637 0 0.9999535 -0.009640753 4.73056e-4 0.9999656 -0.008296489 0 0.9379463 0.3467805 0 0.937946 0.3467816 -1.35646e-7 0.9379456 0.3467826 0 0.9178168 0.3970044 -3.56825e-4 0.9176235 0.3974508 0 0.6761741 0.7367419 0 0.3184337 0.9479452 0 -0.09480202 0.9954962 0 -0.09473747 0.9955024 -2.69164e-5 -0.09453207 0.9955219 0 -0.4884908 0.8725692 0 -0.4910618 0.8711248 1.88293e-4 -0.491369 0.8709517 0 -0.7375345 0.6753095 0 -0.8033041 0.595252 -0.01943117 -0.7359779 0.6737781 -0.06602728 -0.8606444 0.5092067 0 -0.9798187 -0.1998886 0 -0.980111 -0.19845 -2.38942e-4 -0.9802169 -0.1979267 0 -0.814636 -0.5799726 0 0.908638 -0.4175849 0 0.661834 -0.7496505 0 0.6618224 -0.7496607 0 -0.1141284 -0.993466 -1.34474e-5 -0.1141653 -0.9934619 0 0.7290957 -0.6844118 0 0.7290725 -0.6844366 0 0.9339566 -0.3573867 0 0.9339647 -0.3573654 0 0.9997912 0.02044123 0 0.9997935 0.02032709 0 0.9997798 0.02098405 0 0.9997824 0.0208652 4.10373e-6 0.9997829 0.02083778 0 0.9174135 0.3979352 0 0.6941558 0.7198249 0 0.6987656 0.7153506 -5.81113e-4 0.6993719 0.714758 0 0.3420277 0.9396899 0 0.377295 0.9260932 3.2577e-4 0.3777345 0.9259141 0 -0.001036703 0.9999995 0 -0.001036763 0.9999995 0 -1.5788e-6 0 1 2.87845e-6 0 1 1.12424e-6 0 1 0.4809607 0.8767421 0 0.95714 0.2896258 0 0.7768417 0.6296961 0 0.7770099 0.6294885 -1.80142e-4 0.7892585 0.6140611 0 0.7892587 0.6140611 0 0.7892585 0.6140611 0 0.1182377 0.9929854 0 0.113404 0.9935489 -4.67615e-4 0.1135738 0.9935294 -5.08555e-4 0.1146146 0.9934101 0 -0.2700705 0.9628406 0 -0.2700629 0.9628427 0 -0.265269 0.9641745 0 -0.2652406 0.9641823 0 -0.613874 0.7894041 0 -0.6138646 0.7894114 0 -0.8662651 0.4995846 0 0.541134 0.4566975 0.7061172 0.5410913 0.4568903 0.7060253 0.5414326 0.4562781 0.7061593 0.5413056 0.4566273 0.706031 0.4644621 0.5346543 0.7059886 0.4646512 0.5345821 0.7059187 0.2798469 0.6504728 0.7060955 0.279837 0.6504954 0.7060787 0.2801609 0.6504099 0.7060289 0.2801463 0.6504188 0.7060265 0.3764942 0.5998568 0.7059915 0.3764828 0.5998525 0.7060013 0.3764494 0.5998716 0.7060028 0.4647586 0.5343955 0.7059894 -0.9463676 0.323092 0 -0.9463842 0.3230433 6.08826e-6 -0.9463092 0.3232631 0 -0.9464817 0.3227576 1.49947e-4 -1.84114e-6 0 1 1.28642e-6 0 1 -5.79068e-7 0 1 -8.68645e-7 0 1 -1.21535e-6 0 1 -3.14401e-6 0 1 1.44574e-6 0 1 -0.423488 0.5676957 0.70596 -0.4234683 0.5677172 0.7059545 -0.4236531 0.5675332 0.7059916 -0.3306687 0.6262843 0.7059931 -0.3308867 0.6260464 0.706102 -0.3313279 0.6259073 0.7060183 -0.3314395 0.6258389 0.7060267 -0.2299489 0.6698653 0.7059773 -0.2304789 0.669598 0.7060582 -0.2308448 0.6696645 0.7058755 -0.2312829 0.6694627 0.7059236 -0.1245942 0.6972724 0.7058948 -0.1249197 0.6970145 0.706092 -0.1248675 0.6970153 0.7061005 -0.1274092 0.6965479 0.7061077 -0.7533317 -0.6576408 0 -0.7528465 -0.6581961 -1.33958e-4 -0.7526605 -0.658409 0 -0.7528076 -0.6582408 -9.70232e-5 -0.8658244 -0.5003481 0 0.2285751 0.9735264 0 0.2285847 0.973524 0 -0.1574639 0.9875248 0 -0.157463 0.987525 0 -0.1545615 0.9879832 0 -0.1545295 0.9879882 0 -0.5184733 0.8550938 0 -0.5184342 0.8551176 0 -0.8032418 0.5956531 0 -0.8032186 0.5956845 0 -0.9689123 0.2474051 0 -0.9907273 -0.1358659 0 -0.9907273 -0.1358659 0 -0.9907273 -0.1358659 0 -0.9907642 -0.1355964 0 -0.9906837 -0.1361832 0 -0.9906837 -0.1361837 0 0.4108287 0.9117125 3.49211e-4 0.4103339 0.9119354 1.02075e-4 0.410268 0.9119651 0 -0.6659888 0.240266 0.706209 -0.6660438 0.2407506 0.7059922 -0.6664922 0.2399073 0.705856 -0.6955371 0.1344408 0.7058002 -0.6950601 0.1352329 0.7061187 -0.6950676 0.1355594 0.7060487 -0.6951416 0.1353799 0.7060104 -0.7076399 0.02668321 0.7060693 -0.7077467 0.02627247 0.7059777 -0.7077167 0.02618825 0.7060108 -0.7033681 -0.0838266 0.7058658 -0.7034389 -0.08283853 0.7059119 -0.7032366 -0.08310681 0.7060819 -0.7076044 0.02734047 0.7060797 0.1917497 -0.9814439 0 0.193608 -0.9810789 -3.28731e-4 0.1941569 -0.9809706 0 0.1936694 -0.9810668 -2.38162e-4 0.001036703 -0.9999995 0 -0.7290841 0.6844242 0 -0.9336001 0.3583165 0 -0.9336158 0.358276 0 -0.9997624 -0.02180111 0 -0.9997614 -0.02184748 0 -0.9172819 -0.3982385 0 -0.9170818 -0.398699 -3.34749e-4 -0.9182823 -0.3959263 1.77228e-4 -0.9180817 -0.3963915 0 -0.371412 -0.9284682 0 -0.3714123 -0.9284681 0 -0.3714117 -0.9284683 0 -0.3773207 -0.9260827 -5.81769e-5 -0.3773476 -0.9260717 0 0.001036703 -0.9999995 0 -0.5839021 0.8118241 0 -0.5839287 0.8118049 2.71636e-4 -0.5838674 0.811849 3.57418e-4 -0.5842191 0.8115961 0 -0.5412449 -0.4566587 0.7060572 -0.5411931 -0.4568706 0.7059599 -0.5412155 -0.4568613 0.7059488 -0.5412419 -0.4567814 0.7059801 -0.4648453 -0.534324 0.7059864 -0.4645999 -0.5344234 0.7060727 -0.4644476 -0.5347049 0.7059598 -0.3767406 -0.5997132 0.7059822 -0.3766279 -0.5997565 0.7060053 -0.3766047 -0.5997585 0.7060161 -0.2798451 -0.6505667 0.7060098 -0.2798696 -0.6505604 0.7060057 -0.2799199 -0.6505448 0.7060002 -0.2798431 -0.6505909 0.7059882 2.98918e-6 0 1 1.14687e-6 0 1 -1.57549e-6 0 1 1.0817e-6 0 1 -3.67923e-6 0 1 2.62551e-6 0 1 -0.1141885 -0.9934591 0 -0.9570984 -0.2897632 0 -0.7767716 -0.6297826 0 -0.7769992 -0.6295016 2.73251e-4 -0.7957462 -0.6056302 0 -0.795746 -0.6056306 0 -0.7957459 -0.6056308 0 -0.4811985 -0.8766117 0 -0.4812056 -0.8766079 0 -0.4812581 -0.8765791 0 0.2697584 -0.9629281 0 0.2695748 -0.9629795 8.13995e-5 0.2692358 -0.9630743 0 0.6137341 -0.7895128 0 0.6137549 -0.7894967 0 -0.9950323 -0.09955281 0 -0.9950375 -0.09949958 -4.9175e-4 -0.9949483 -0.1003842 -9.96686e-4 -0.9950814 -0.09906047 0 0.2312201 -0.6692671 0.7061294 0.230582 -0.6695887 0.7060332 0.2307026 -0.6695986 0.7059844 0.2309938 -0.6694805 0.7060013 0.1247709 -0.6971098 0.7060242 0.1248213 -0.6970767 0.7060479 0.1247023 -0.6970627 0.7060828 0.1242603 -0.6971614 0.7060633 0.3307946 -0.6260759 0.706119 0.3309861 -0.6260873 0.7060192 0.3311972 -0.6259845 0.7060112 0.4235786 -0.5675002 0.7060629 0.4234216 -0.5675488 0.7061181 0.4234838 -0.5674882 0.7061294 0.3309324 -0.6260112 0.7061117 -0.4960908 0.868046 -0.01975238 -0.4672358 0.8840146 0.01446187 -0.467979 0.8836214 0.01445692 -0.346591 0.9378889 -0.01546001 -0.3254471 0.9455088 0.009859085 -0.3265302 0.9451354 0.009855866 -0.1872989 0.9822534 -0.009873211 -0.1764118 0.98431 0.003570497 -0.1799079 0.983677 0.003580927 -0.02308857 0.9997248 -0.004161238 -0.01988899 0.9998022 0 0.1416042 0.9899234 0 0.1416063 0.9899231 0 0.2729892 0.9620172 0 0.3022339 0.9528769 -0.02608358 0.3950964 0.9183398 0.02347284 0.4554238 0.8899675 0.02339035 0.3947472 0.9164277 -0.06584113 0.5314492 0.8467411 0.0243135 0.5953598 0.8030934 0.02423965 0.5298459 0.8443183 -0.07993644 0.6560472 0.7543182 0.02462095 0.6555919 0.7547142 0.02461504 0.719576 0.6938768 -0.02730607 0.7641416 0.6446239 0.02340197 0.7638397 0.6449812 0.02341353 0.8239095 0.5661193 -0.02611935 0.8411798 0.5407557 0 0.9062922 0.4226519 0 0.9625093 0.2712489 0 0.9633344 0.2682737 -0.004025936 0.994294 0.1065942 0.004158258 0.9930839 0.1173334 0.004160046 0.9943746 0.1054077 -0.01041185 0.9992097 -0.03861749 0.009429514 0.999268 -0.03707653 0.009428977 0.9981211 -0.05926609 -0.01555633 0.9814915 -0.1909711 0.0142979 0.9815943 -0.1904415 0.01430392 0.9746132 -0.2229775 -0.0202564 0.9401595 -0.3402571 0.01803737 0.9405035 -0.339305 0.01804113 0.9246697 -0.3800438 -0.02351051 0.9010636 -0.4336869 0 0.8497308 -0.527217 0 0.8497318 -0.5272154 0 0.751302 -0.6599587 0 0.675828 -0.7370594 0 0.6320915 -0.7745496 -0.02309918 0.598033 -0.8012691 0.018013 0.5979662 -0.8013189 0.01801711 0.4961879 -0.8679835 -0.0200566 0.467316 -0.8839761 0.01420915 0.467372 -0.8839469 0.01419365 0.3466196 -0.9378769 -0.01555669 0.3255863 -0.9454637 0.009598255 0.3260852 -0.9452916 0.009607732 0.1874697 -0.982218 -0.01014894 0.1762552 -0.9843376 0.003692865 0.1755826 -0.9844579 0.003682017 0.02326053 -0.9997219 -0.003915131 0.0202586 -0.9997948 0 -0.1415847 -0.9899262 0 -0.1415851 -0.9899261 0 -0.2734304 -0.9618919 0 -0.3025545 -0.9527783 -0.02596944 -0.3950264 -0.9183725 0.02337253 -0.4552244 -0.8900708 0.02334129 -0.3943217 -0.9165852 -0.06619721 -0.5315876 -0.8466544 0.024311 -0.5954969 -0.8029918 0.02424407 -0.5302563 -0.8440927 -0.07959824 -0.6555716 -0.754743 0.02427029 -0.6561652 -0.7542268 0.02427262 -0.7196617 -0.69379 -0.02724826 -0.764006 -0.6447923 0.0231927 -0.7638961 -0.6449224 0.02318978 -0.8239526 -0.5660431 -0.02640724 -0.8414096 -0.5403979 0 -0.9061264 -0.4230071 0 -0.9626262 -0.2708339 0 -0.9634459 -0.2678734 -0.004006743 -0.992946 -0.1185143 0.003560185 -0.992946 -0.1185143 0.003560185 -0.992946 -0.1185143 0.003560185 -0.9930842 -0.1173505 0.003576874 -0.9943286 -0.1058353 -0.01047211 -0.9992097 0.03861749 0.009428918 -0.999268 0.03707629 0.009429454 -0.9981211 0.0592662 -0.01555705 -0.9814739 0.1910611 0.01430773 -0.981489 0.1909838 0.0143097 -0.9746278 0.2229659 -0.01967334 -0.9407558 0.3386047 0.01804178 -0.9405035 0.3393051 0.01803582 -0.9246645 0.3800566 -0.02351033 -0.9010636 0.4336869 0 -0.849513 0.5275678 0 -0.8495135 0.5275669 0 -0.7513596 0.659893 0 -0.7513604 0.6598921 0 -0.6763941 0.73654 0 -0.6323614 0.7743244 -0.02325493 -0.5978032 0.8014306 0.01845556 -0.5981085 0.8012025 0.01845866 2.2748e-6 0 1 2.24885e-6 0 1 2.94542e-6 0 1 -1.54322e-6 0 1 -9.45461e-6 0 1 0.8657149 0.5005376 0 -0.2283372 -0.9735822 0 -0.2283468 -0.9735798 0 0.157473 -0.9875234 0 0.1574785 -0.9875224 0 0.1545112 -0.987991 0 0.1545119 -0.9879909 0 0.5184694 -0.8550962 0 0.5184591 -0.8551024 0 0.8037268 -0.5949985 0 0.8037168 -0.5950121 0 0.9686607 -0.2483879 0 0.9686551 -0.2484098 0 0.9907783 0.1354937 0 0.9906839 0.1361822 0 -0.4108359 -0.9117093 3.39517e-4 -0.4121188 -0.9111295 0.0011276 -0.4106785 -0.9117802 0 -0.9291725 0.3696467 0 -0.9295042 0.3688116 0 -0.9295042 0.3688116 0 -0.9295042 0.3688116 0 -0.9292262 0.3695115 0 -0.9891183 -0.1471226 0 -0.9891183 -0.1471231 0 -0.7822367 -0.6229814 0 -0.3693242 -0.9293007 0 -0.3692857 -0.9293161 0 0.1475165 -0.9890597 0 0.1474999 -0.9890621 0 0.6213026 -0.7835709 0 0.6213763 -0.7835124 0 0.622698 -0.7824623 0 0.6226963 -0.7824636 0 0.930161 -0.3671518 0 0.9301245 -0.3672443 0 -0.1471532 0.9891138 0 -0.6214556 0.7834494 0 -0.9295049 0.3688097 0 -0.7843797 -0.6202811 3.03927e-5 -0.7846934 -0.6198841 0 0.1471611 -0.9891126 0 0.6214293 -0.7834703 0 0.929558 -0.3686758 0 0.9294955 -0.3688336 0 0.9294955 -0.3688337 0 0.9294955 -0.3688336 0 0.9303683 -0.3666266 0 0.9303947 -0.3665596 0 0.9894615 0.1447964 0 0.9894615 0.1447969 0 0.7822631 0.6229484 0 0.3763539 0.926476 0 0.3693056 0.9293079 -6.21448e-4 0.3669738 0.9302314 0 -0.6229757 0.7822414 0 -0.6230134 0.7822112 0 -0.6228722 0.7823237 0 -0.6227834 0.7823944 0 -0.9301034 0.367298 0 -0.9301403 0.3672044 0 -0.989058 -0.1475272 0 -0.7843093 -0.6203701 0 8.38476e-6 0 -1 2.98173e-6 0 -1 4.07071e-7 0 -1 -2.64156e-6 0 -1 3.25534e-6 0 -1 -2.52169e-6 0 -1 3.4976e-6 0 -1 -1.74231e-6 0 -1 7.06638e-6 0 -1 4.03326e-6 0 -1 1.77209e-6 0 -1 2.3418e-5 0 -1 1.77255e-6 0 -1 2.51788e-6 0 -1 -3.50133e-6 0 -1 -1.17069e-6 0 -1 -1.98252e-6 0 -1 5.59472e-6 0 -1 2.60749e-6 0 -1 1.40837e-5 0 -1 -1.38504e-5 0 -1 -3.10707e-6 0 -1 1.18367e-6 0 -1 -8.82768e-6 0 -1 -3.38387e-5 0 -1 4.71716e-6 0 -1 2.28302e-6 0 -1 -7.66918e-6 0 -1 7.11551e-6 0 -1 -4.40129e-6 0 -1 -8.52591e-7 0 -1 3.8959e-5 0 -1 -7.68793e-6 0 -1 1.46563e-5 0 -1 9.60681e-7 0 -1 3.24179e-6 0 -1 2.09778e-6 0 -1 -2.61594e-6 0 -1 -5.16017e-6 0 -1 1.09904e-6 0 -1 5.91695e-6 0 -1 -1.37246e-6 0 -1 3.94677e-6 0 -1 -1.92089e-6 0 -1 -9.60892e-6 0 -1 3.6615e-6 0 -1 -3.38501e-5 0 -1 -1.97772e-6 0 -1 3.55023e-6 0 -1 -1.38397e-5 0 -1 7.04781e-6 0 -1 2.65273e-6 0 -1 1.05126e-5 0 -1 -1.0816e-5 0 -1 3.74302e-6 0 -1 -2.77966e-6 0 -1 1.00973e-5 0 -1 2.9248e-6 0 -1 1.70219e-6 0 -1 9.77234e-7 0 -1 -9.00074e-6 0 -1 5.01599e-6 0 -1 2.06687e-6 0 -1 1.56874e-6 0 -1 1.97726e-6 0 -1 6.38056e-6 0 -1 -2.59255e-5 0 -1 -1.02142e-5 0 -1 -9.35979e-5 0 -1 2.11262e-6 0 -1 1.66128e-6 0 -1 -1.43488e-5 0 -1 -1.09288e-5 0 -1 -1.30768e-6 0 -1 -1.28003e-5 0 -1 -1.39736e-6 0 -1 2.14708e-6 0 -1 2.89613e-6 0 -1 2.0695e-6 0 -1 -1.70119e-6 0 -1 4.03656e-6 0 -1 -2.59196e-6 0 -1 1.82714e-5 0 -1 1.43135e-5 0 -1 5.42005e-6 0 -1 -4.88316e-6 0 -1 2.58218e-6 0 -1 -2.59771e-5 0 -1 -2.56172e-5 0 -1 -2.55781e-5 0 -1 -8.80133e-7 0 -1 7.45414e-7 0 -1 6.7781e-6 0 -1 -9.29005e-6 0 -1 2.23483e-5 0 -1 -3.76727e-6 0 -1 -2.5456e-6 0 -1 -1.04891e-5 0 -1 3.99568e-6 0 -1 5.44307e-5 0 -1 2.43266e-6 0 -1 -1.82282e-5 0 -1 1.6211e-6 0 -1 -5.55519e-6 0 -1 -2.02684e-5 0 -1 -1.67414e-5 0 -1 3.21663e-6 0 -1 -3.55353e-6 0 -1 6.07362e-6 0 -1 -8.17127e-6 0 -1 2.02118e-5 0 -1 -1.62665e-5 0 -1 8.53976e-6 0 -1 -9.57263e-6 0 -1 -1.66549e-5 0 -1 -1.77547e-6 0 -1 -4.14952e-6 0 -1 4.57473e-6 0 -1 8.09402e-6 0 -1 -1.92594e-6 0 -1 2.98796e-6 0 -1 0 0 -1 3.09928e-6 0 -1 -8.57427e-6 0 -1 8.32898e-6 0 -1 2.62812e-6 0 -1 2.5699e-6 0 -1 2.82127e-6 0 -1 -4.3643e-6 0 -1 4.03916e-6 0 -1 2.9263e-6 0 -1 -2.90027e-6 0 -1 2.81218e-6 0 -1 -6.00658e-6 0 -1 -4.10236e-6 0 -1 2.50702e-6 0 -1 3.74348e-6 0 -1 -2.33551e-6 0 -1 7.3221e-6 0 -1 6.0715e-6 0 -1 -6.06884e-6 0 -1 -2.42795e-6 0 -1 2.75877e-5 0 -1 -4.11896e-6 0 -1 -3.14933e-6 0 -1 2.69234e-6 0 -1 -2.54395e-4 0 -1 1.29504e-6 0 -1 -2.33758e-6 0 -1 -3.50592e-6 0 -1 2.61572e-6 0 -1 2.55196e-6 0 -1 8.15799e-7 0 -1 1.69524e-6 0 -1 -3.18663e-6 0 -1 3.81045e-6 0 -1 -1.49636e-6 0 -1 6.58144e-7 0 -1 2.54996e-6 0 -1 -1.0963e-5 0 -1 2.65791e-6 0 -1 -2.03427e-6 0 -1 4.08017e-6 0 -1 -7.41752e-6 0 -1 1.43173e-5 0 -1 -1.4252e-6 0 -1 -3.76325e-6 0 -1 -4.74305e-6 0 -1 -3.40731e-6 0 -1 3.16153e-5 0 -1 -8.07494e-6 0 -1 5.03724e-6 0 -1 -8.92019e-5 0 -1 -1.46741e-6 0 -1 3.68674e-6 0 -1 -5.76244e-7 0 -1 1.40951e-6 0 -1 1.50531e-6 0 -1 6.39525e-6 0 -1 -1.10422e-5 0 -1 -1.70307e-6 0 -1 -1.68913e-5 0 -1 -2.58545e-5 0 -1 1.04866e-6 0 -1 6.32895e-6 0 -1 5.12957e-7 0 -1 -2.11335e-6 0 -1 4.17112e-6 0 -1 1.76566e-6 0 -1 1.10411e-5 0 -1 -2.39856e-6 0 -1 -1.50578e-6 0 -1 1.83845e-6 0 -1 0.9283958 -0.3715932 0 0.9308297 -0.3654531 0 0.9308304 -0.3654515 0 0.989403 0.1451957 0 0.9894108 0.1451427 0 0.7832227 0.6217414 0 -0.1475007 0.989062 0 -0.6213026 0.7835709 0 -0.6213387 0.7835422 0 -0.6178674 0.7862823 0 -0.9891105 -0.1471754 0 -0.9891104 -0.147176 0 -0.7834764 -0.6214217 0 -0.3692871 -0.9293155 0 0.9285207 -0.3712806 0 -1.28548e-5 0 1 1.28789e-5 0 1 4.3473e-6 0 1 -5.04793e-6 0 1 2.51453e-6 0 1 -8.20506e-6 0 1 2.54034e-6 0 1 1.60917e-6 0 1 -1.06448e-6 0 1 -2.11499e-6 0 1 4.31771e-6 0 1 -2.35283e-5 0 1 1.8117e-6 0 1 -2.14524e-6 0 1 -4.84496e-6 0 1 4.08483e-6 0 1 7.24218e-5 0 1 -2.3322e-4 0 1 -2.33238e-4 0 1 -2.33248e-4 0 1 -2.51246e-6 0 1 9.33756e-7 0 1 2.23268e-6 0 1 -9.76425e-6 0 1 4.14662e-6 0 1 -6.71689e-7 0 1 -1.16861e-6 0 1 3.56766e-6 0 1 -2.33579e-5 0 1 1.75513e-5 0 1 -2.88877e-6 0 1 -2.95685e-6 0 1 -1.986e-6 0 1 3.98928e-6 0 1 -7.58684e-6 0 1 4.21102e-6 0 1 2.28653e-6 0 1 1.98924e-6 0 1 -1.12247e-6 0 1 -8.5253e-6 0 1 7.19321e-5 0 1 2.8884e-6 0 1 -3.02335e-6 0 1 -6.93462e-6 0 1 2.85708e-6 0 1 -2.07302e-6 0 1 3.59821e-6 0 1 9.98339e-7 0 1 -6.04833e-6 0 1 1.44414e-6 0 1 -3.67943e-6 0 1 1.06472e-6 0 1 -4.43451e-6 0 1 3.69071e-6 0 1 -3.94465e-6 0 1 1.96744e-6 0 1 -5.78583e-6 0 1 -8.80468e-6 0 1 1.74911e-5 0 1 7.96178e-6 0 1 1.95117e-6 0 1 4.45297e-6 0 1 -1.14379e-5 0 1 1.00696e-6 0 1 -4.38002e-6 0 1 1.95392e-6 0 1 -2.27475e-6 0 1 -5.02719e-7 0 1 -1.98719e-6 0 1 2.87449e-6 0 1 -1.83246e-6 0 1 2.63428e-6 0 1 9.39585e-6 0 1 1.17947e-5 0 1 -2.70988e-6 0 1 1.18014e-5 0 1 6.83673e-6 0 1 2.65244e-6 0 1 3.89281e-6 0 1 -3.85736e-6 0 1 4.00118e-6 0 1 -1.11388e-5 0 1 4.98972e-6 0 1 -8.3036e-6 0 1 -1.08209e-5 0 1 2.84933e-6 0 1 3.58747e-6 0 1 -5.61808e-6 0 1 1.43047e-6 0 1 -1.07938e-5 0 1 5.89164e-6 0 1 -1.55245e-6 0 1 -7.71778e-7 0 1 2.62269e-6 0 1 -2.66224e-6 0 1 2.57284e-6 0 1 2.25888e-6 0 1 -2.93376e-5 0 1 2.2777e-5 0 1 -1.93397e-6 0 1 -2.89744e-6 0 1 -8.12572e-6 0 1 4.57959e-6 0 1 -1.4482e-6 0 1 1.13746e-6 0 1 -9.6499e-7 0 1 -1.62616e-6 0 1 -7.63881e-7 0 1 7.33267e-6 0 1 -5.57625e-6 0 1 8.00461e-7 0 1 -1.92444e-6 0 1 -2.97697e-6 0 1 8.70716e-6 0 1 -2.79345e-6 0 1 3.81185e-6 0 1 -2.36771e-6 0 1 5.91455e-6 0 1 1.08103e-5 0 1 -5.27643e-6 0 1 -9.05823e-7 0 1 1.49203e-6 0 1 -1.66112e-6 0 1 -1.97724e-6 0 1 4.99211e-6 0 1 -1.21536e-6 0 1 -3.59162e-6 0 1 -1.69033e-6 0 1 -1.40946e-5 0 1 1.28034e-5 0 1 1.06571e-5 0 1 2.296e-6 0 1 -2.67333e-6 0 1 -1.31479e-6 0 1 4.73898e-6 0 1 -4.39389e-6 0 1 1.0308e-5 0 1 8.81686e-6 0 1 -6.58077e-6 0 1 1.29239e-6 0 1 2.22013e-6 0 1 3.01765e-6 0 1 -2.17645e-6 0 1 1.78294e-6 0 1 -4.21898e-6 0 1 2.091e-5 0 1 -2.04238e-5 0 1 8.34927e-6 0 1 -2.61473e-6 0 1 1.62721e-5 0 1 -1.01976e-5 0 1 2.1058e-5 0 1 -8.21972e-6 0 1 -3.17628e-6 0 1 2.20471e-6 0 1 2.94846e-5 0 1 -9.77571e-7 0 1 -2.92788e-6 0 1 1.18792e-4 0 1 2.40101e-6 0 1 -4.95754e-6 0 1 1.0963e-5 0 1 -1.16217e-5 0 1 8.07441e-6 0 1 -1.76382e-6 0 1 2.97647e-6 0 1 -1.82282e-5 0 1 -4.97812e-6 0 1 6.58189e-6 0 1 1.48845e-5 0 1 -5.55932e-6 0 1 4.3154e-6 0 1 6.00477e-6 0 1 -2.84508e-6 0 1 4.78771e-6 0 1 -4.0391e-6 0 1 2.37001e-6 0 1 4.04565e-6 0 1 -1.57868e-5 0 1 3.05429e-6 0 1 2.35999e-5 0 1 -2.92039e-5 0 1 1.21999e-5 0 1 -1.32121e-5 0 1 9.08628e-6 0 1 6.58293e-6 0 1 -3.87501e-6 0 1 6.19894e-6 0 1 6.61481e-6 0 1 1.13289e-5 0 1 6.95575e-6 0 1 -1.04447e-5 0 1 2.49451e-5 0 1 -5.31553e-6 0 1 -6.60397e-6 0 1 4.55349e-6 0 1 -1.39538e-5 0 1 -4.84332e-6 0 1 4.4994e-6 0 1 -8.82793e-6 0 1 -1.37414e-6 0 1 -2.25621e-6 0 1 -2.93427e-6 0 1 2.85477e-5 0 1 -2.36141e-6 0 1 -3.37724e-6 0 1 1.71989e-6 0 1 3.52985e-6 0 1 6.9772e-6 0 1 2.98151e-5 0 1 0.7044528 0.07547032 0.705727 0.7044528 0.07547038 0.705727 0.7044528 0.07547038 0.705727 0.7035295 0.0821191 0.7059056 0.7032763 0.08311295 0.7060416 0.7032848 0.08309894 0.7060348 0.7032347 0.08298671 0.7060979 0.7076338 -0.0273416 0.7060502 0.7077133 -0.02620428 0.7060137 0.70775 -0.02627265 0.7059743 0.7076579 -0.02668374 0.7060512 0.6951608 -0.1353095 0.7060049 0.6952795 -0.1348446 0.7059769 0.6952725 -0.1348848 0.7059761 0.6951549 -0.1350767 0.7060553 0.6658902 -0.241086 0.7060227 0.6660476 -0.2407516 0.7059882 0.6659888 -0.240266 0.706209 -0.1935825 0.9810839 -3.04181e-4 -0.1942163 0.9809588 0 -0.1956074 0.9806821 7.64846e-4 -0.1917105 0.9814516 -2.42706e-4 -0.1922349 0.981349 0 0.5563641 0.8309386 0 -0.786249 -0.6179098 0 -0.1520037 -0.98838 0 0.6947409 -0.7192601 0 0.9389346 -0.344096 0 -0.112044 0.9937033 0 -0.9225713 0.3858267 0 -0.9148666 0.4037563 0 -0.8754743 0.4832648 0 -0.8031311 0.5958023 0 -0.8031383 0.5957926 0 -0.6369829 0.770878 0 -0.7038658 0.710333 0 -0.7171128 0.6969178 -0.007416903 -0.6355534 0.7720338 0.00599569 0.09770578 0.9948651 -0.02640312 0.1440283 0.9895736 0 -0.03502875 0.9993863 0 0.2296348 0.9732769 0 0.3199189 0.9473668 0.01216953 0.2778896 0.9606129 -5.39718e-4 0.2295307 0.9733015 0 0.1866596 0.9824247 0 0.186658 0.982425 0 0.8387038 0.5439576 -0.02619814 0.8632421 0.5047903 0 0.7595788 0.6504154 0 0.8171345 0.573891 0.05422449 0.8171347 0.5738909 0.05422317 0.8171346 0.573891 0.05422449 0.7578575 0.6524202 0 0.9136396 0.4065252 0 0.9950199 0.09967768 0 0.9950198 0.09967797 0 0.9950199 0.09967732 0 0.9905509 0.1371456 0 0.9037393 -0.426139 0.04075479 0.9481546 -0.3167266 -0.02621608 0.8890846 -0.4577431 0 0.7476719 -0.6640679 -8.33603e-4 0.7466987 -0.6651625 0 0.852533 -0.5226734 0 0.8532541 -0.5214949 -7.83645e-4 0.8892729 -0.4573771 0 0.8892729 -0.4573771 0 0.889273 -0.4573771 0 0.9165164 -0.3999972 0 0.9165146 -0.4000012 0 0.6489029 -0.7608713 0 0.6946949 -0.7193046 0 0.648896 -0.7608773 0 0.6707453 -0.7416386 0.008549332 0.57817 -0.8158085 -0.01326972 0.6015964 -0.7988002 0 0.2007001 -0.9796528 0 0.06728327 -0.9972506 0.03105509 0.1229619 -0.9924115 0 -0.05483531 -0.9984954 0 -0.05296742 -0.9985958 -0.001062572 -0.1899429 -0.9817951 0 -0.404656 -0.9144691 0 -0.1520755 -0.9883689 0 -0.1899413 -0.9817956 0 -0.2320731 -0.9726155 -0.01269572 -0.2770665 -0.9608508 0 -0.3112179 -0.9503386 0 -0.4020141 -0.9156323 0.001519143 -0.4046297 -0.9144807 -4.82633e-5 -0.8385484 -0.5442902 0.02418273 -0.8138336 -0.5810973 -9.40163e-4 -0.8856295 -0.4643925 0 -0.966514 -0.2565424 0.006052553 -0.9632781 -0.2685059 0 -0.9241878 -0.3819383 0 -0.9050474 -0.4251152 -0.01289588 -0.8856504 -0.4643526 0 -0.8619194 -0.5070455 0 -0.8619193 -0.5070455 0 -0.8619194 -0.5070455 0 -0.8621706 -0.506618 0 0.9389299 -0.3441085 0 0.9821178 -0.1882676 0 0.9821078 -0.1883198 -8.89442e-7 0.9994543 0.03303581 0 0.9994547 0.03302109 0 0.9950345 0.09953147 0 0.9950345 0.09953147 0 0.9950345 0.09953147 0 0.9905462 0.1371791 -3.92732e-4 0.9852825 0.1705485 0.01147371 0.9742656 0.2254033 0 0.9402076 0.3406022 0 0.9397479 0.3418676 -7.36945e-4 0.9138382 0.4060788 0 0.8840945 0.4673081 0 0.8841131 0.4672732 0 0.9821089 -0.1883141 0 0.999962 -0.008722007 0 0.99839 -0.05644023 -0.005661487 0.9998761 -0.009967446 -0.01218801 0.9993718 -0.03072834 -0.01765793 0.7577375 0.6525595 -7.04317e-5 0.7578998 0.6523711 0 0.6665527 0.745458 0 0.631113 0.7755975 -0.01204556 0.362609 0.9319414 0 0.3626039 0.9319434 0 0.4845488 0.8747642 0 0.4810627 0.8766863 -1.34183e-4 0.4823842 0.8759593 -8.83985e-4 0.5566915 0.8307193 0 0.5971113 0.8021584 0 0.5971276 0.8021464 0 -0.2550853 0.9669186 0 -0.3840474 0.923313 -9.21909e-4 -0.3855443 0.9226891 -6.96172e-4 -0.02257198 0.9997203 0.007069408 -0.1120516 0.9937024 0 -0.1671948 0.9859239 0 -0.2129898 0.9769797 -0.01208359 -0.2550829 0.9669193 0 -0.2991247 0.9542141 0 -0.2986793 0.9543536 0 -0.2986793 0.9543536 0 -0.2986793 0.9543536 0 -0.6061819 0.7953261 0 -0.3838864 0.9233803 0 -0.5424223 0.8401061 0 -0.5413572 0.8407928 -2.30302e-4 -0.5427516 0.8398929 -7.97475e-4 -0.6061831 0.7953253 0 -0.6519559 0.758257 0 -0.6519717 0.7582433 0 -0.9611953 0.2758675 -8.33288e-4 -0.9617088 0.2740733 -1.91296e-4 -0.8843038 0.4668845 -0.005088567 -0.9232649 0.3841177 0.005969703 -0.9148634 0.4037635 0 -0.9353852 0.3536307 0 -0.9352238 0.3540571 0 -0.9352239 0.3540571 0 -0.9352238 0.3540571 0 -0.9997014 0.02443861 0 -0.9833695 -0.1816161 0 -0.983364 -0.1816465 0 -0.9967881 -0.08008456 0 -0.9916245 -0.126672 -0.02520215 -0.9614173 0.2750943 0 -0.9950702 0.09917408 0 -0.9948771 0.1010891 -7.48956e-4 -0.9948983 0.1008803 -7.80155e-4 -0.9996845 0.02512073 0 -0.9996845 0.02512073 0 -0.9996845 0.02512073 0 -0.9993262 -0.03670579 0 -0.9993261 -0.0367065 0 -0.6278033 -0.7783721 0 -0.6278033 -0.7783721 0 -0.6278033 -0.7783721 0 -0.5195635 -0.8540601 -0.02520585 -0.5592067 -0.8290283 0 -0.4044345 -0.9145671 0 -0.7862628 -0.6178922 0 -0.6993355 -0.7147936 0 -0.6992872 -0.714841 3.62643e-6 -0.6978948 -0.7161998 -9.55884e-4 -0.6277565 -0.7784098 0 -0.5946894 -0.8039556 0 -0.5947099 -0.8039405 0 0.2982174 -0.9544292 -0.01146292 0.2996727 -0.9539676 -0.01192224 0.3437194 -0.9390569 -0.005398035 0.1551302 -0.9878941 0 0.156531 -0.9876731 -4.56133e-4 0.2008153 -0.9796291 0 0.2586955 -0.965959 0 0.2586885 -0.9659609 0 0.3006253 -0.9537423 0 0.4651578 -0.8852278 0 0.465242 -0.8851836 3.82403e-5 0.4655991 -0.8849958 0 0.6017096 -0.7987149 0 0.2561852 -0.9666277 -3.72795e-4 0.2564429 -0.9665594 0 0.2564321 -0.9665623 0 0.7513039 -0.6599565 0 0.8497299 -0.5272184 0 0.8497358 -0.5272089 0 0.92492 -0.3801621 0 0.9249246 -0.3801507 0 0.9748162 -0.2230102 0 0.9748134 -0.2230222 0 0.9982422 -0.05926728 0 0.9982437 -0.05924153 0 0.994429 0.1054084 0 0.9633457 0.2682636 0 0.9633424 0.2682753 0 0.9062947 0.4226465 0 0.9062948 0.4226464 0 0.8241883 0.566316 0 0.8241944 0.566307 0 0.7198334 0.694147 0 0.7198402 0.6941399 0 0.5955264 0.8033358 0 0.5955328 0.803331 0 0.455559 0.8902056 0 0.4555594 0.8902055 0 0.3023346 0.953202 0 0.302342 0.9531995 0 0.1416062 0.9899231 0 0.1416044 0.9899234 0 -0.02308899 0.9997335 0 -0.1873114 0.9823006 0 -0.346632 0.9380013 0 -0.3466361 0.9379997 0 -0.4961857 0.8682165 0 -0.496186 0.8682163 0 -0.6325201 0.774544 0 -0.6325333 0.7745333 0 -0.7513616 0.6598908 0 -0.751362 0.6598904 0 -0.8495086 0.5275748 0 -0.8495146 0.5275653 0 -0.92492 0.3801621 0 -0.9249246 0.3801507 0 -0.9748134 0.2230225 0 -0.9748162 0.22301 0 -0.9982422 0.05926728 0 -0.9982429 0.0592544 0 -0.9943829 -0.1058427 0 -0.9634555 -0.2678688 0 -0.9634555 -0.2678685 0 -0.9061263 -0.4230073 0 -0.9061264 -0.4230072 0 -0.8242429 -0.5662364 0 -0.8242311 -0.5662536 0 -0.7199342 -0.6940424 0 -0.719928 -0.6940488 0 -0.5956645 -0.8032335 0 -0.5956712 -0.8032284 0 -0.4553481 -0.8903136 0 -0.4553536 -0.8903108 0 -0.3026537 -0.9531006 0 -0.3026577 -0.9530994 0 -0.141586 -0.9899259 0 -0.1415841 -0.9899263 0 0.02326095 -0.9997295 0 0.1874781 -0.9822688 0 0.1874805 -0.9822683 0 0.3466577 -0.9379917 0 0.3466619 -0.9379903 0 0.4962859 -0.8681591 0 0.4962862 -0.8681589 0 0.6322587 -0.7747575 0 0.6322589 -0.7747572 0 0.7513037 -0.6599566 0 -0.8507159 0.5256258 0 -0.7499266 0.661521 0 -0.7499203 0.6615283 0 -0.6271427 0.7789044 0 -0.4865433 0.8736565 0 -0.4865378 0.8736596 0 -0.3319018 0.943314 0 -0.167689 0.98584 0 -0.1676891 0.98584 0 0.001294434 0.9999992 0 0.001294434 0.9999992 0 0.1703245 0.9853881 0 0.1703225 0.9853885 0 0.3344064 0.942429 0 0.3344066 0.9424289 0 0.4888802 0.872351 0 0.4888806 0.8723507 0 0.629266 0.77719 0 0.6292601 0.7771949 0 0.7515476 0.659679 0 0.7515478 0.6596788 0 0.8522852 0.5230775 0 0.8522854 0.5230771 0 0.928355 0.3716948 0 0.9778273 0.2094131 0 0.97783 0.2094005 0 0.9991554 0.04109394 0 0.9991554 0.04109394 0 0.9917473 -0.1282079 0 0.9917457 -0.1282209 0 0.9557134 -0.2942994 0 0.9557096 -0.2943112 0 0.8924514 -0.4511437 0 0.8924567 -0.4511331 0 0.8031005 -0.5958436 0 0.8030942 -0.5958522 0 0.6910686 -0.7227892 0 0.6910752 -0.7227829 0 0.5587186 -0.8293573 0 0.5587128 -0.8293613 0 0.4109361 -0.9116643 0 0.4109412 -0.9116619 0 0.2505128 -0.9681134 0 0.250513 -0.9681133 0 0.08352279 -0.9965059 0 0.08352392 -0.9965058 0 -0.08622199 -0.996276 0 -0.08622086 -0.9962761 0 -0.2532408 -0.9674032 0 -0.253241 -0.9674032 0 -0.413133 -0.9106707 0 -0.4131233 -0.9106752 0 -0.5610814 -0.8277606 0 -0.5610756 -0.8277646 0 -0.6926733 -0.7212514 0 -0.6926672 -0.7212574 0 -0.8050066 -0.593266 0 -0.805013 -0.5932574 0 -0.8934412 -0.4491803 0 -0.8934412 -0.4491801 0 -0.956505 -0.2917159 0 -0.9565014 -0.2917279 0 -0.9920914 -0.1255182 0 -0.9920897 -0.125531 0 -0.9990413 0.04377835 0 -0.9990419 0.04376512 0 -0.9772393 0.2121403 0 -0.9772366 0.2121527 0 -0.9274513 0.3739442 0 -0.927456 0.3739325 0 -0.8507277 0.5256068 0 2.84095e-6 0 -1 5.43677e-7 0 -1 -5.43488e-7 0 -1 -2.72118e-7 0 -1 1.20913e-6 0 -1 -1.09199e-6 0 -1 4.52829e-7 0 -1 -2.19838e-6 0 -1 4.68551e-6 0 -1 -4.66156e-6 0 -1 -4.56483e-6 0 -1 4.53959e-6 0 -1 2.3274e-6 0 -1 1.1836e-6 0 -1 5.96944e-7 0 -1 -9.47757e-7 0 -1 2.45932e-6 0 -1 -1.6098e-6 0 -1 2.12737e-6 0 -1 -2.10672e-6 0 -1 5.08606e-6 0 -1 5.14806e-6 0 -1 4.04698e-6 0 -1 -4.00503e-6 0 -1 3.91733e-6 0 -1 -3.82772e-6 0 -1 -5.82751e-6 0 -1 0.3227248 -0.946493 0 0.4702916 -0.8825111 0 0.470302 -0.8825055 0 0.6053848 -0.795933 0 0.7251026 -0.6886409 0 0.725117 -0.6886258 0 0.8270325 -0.5621543 0 0.8270173 -0.5621767 0 0.9062449 -0.4227532 0 0.9062589 -0.4227232 0 0.9620386 -0.2729136 0 0.9620306 -0.2729418 0 0.9935481 -0.1134117 0 0.993548 -0.1134127 0 0.9989432 0.04596346 0 0.9784459 0.2065036 0 0.9784525 0.2064723 0 0.9326102 0.3608856 0 0.8630357 0.5051429 0 0.8630522 0.505115 0 0.770883 0.6369768 0 0.7708797 0.6369808 0 0.6583147 0.752743 0 0.6583008 0.7527551 0 0.5285453 0.8489051 0 0.5285306 0.8489143 0 0.3862439 0.9223967 0 0.2336376 0.9723238 0 0.2336227 0.9723273 0 0.0743193 0.9972346 0 0.07432222 0.9972343 0 -0.08651274 0.9962508 0 -0.0865156 0.9962505 0 -0.2457084 0.9693438 0 -0.2457162 0.9693418 0 -0.397351 0.9176667 0 -0.3973237 0.9176787 0 -0.5402836 0.841483 0 -0.5402687 0.8414926 0 -0.6675404 0.7445737 0 -0.6675566 0.7445591 0 -0.7786224 0.6274929 0 -0.869071 0.4946873 0 -0.8690691 0.4946909 0 -0.937322 0.3484647 0 -0.9373327 0.3484359 0 -0.980887 0.1945783 0 -0.9808999 0.1945137 0 -0.9994297 0.03377121 0 -0.9994297 0.03377151 0 -0.9919024 -0.1270031 0 -0.9918984 -0.1270343 0 -0.9589312 -0.2836388 0 -0.9589402 -0.2836087 0 -0.9005591 -0.4347335 0 -0.9005335 -0.4347866 0 -0.8198075 -0.5726394 0 -0.8197894 -0.5726652 0 -0.7165131 -0.6975737 0 -0.5954503 -0.8033923 0 -0.5954686 -0.8033787 0 -0.4590541 -0.8884084 0 -0.4590573 -0.8884068 0 -0.3109461 -0.9504276 0 -0.3109576 -0.9504238 0 -0.1538765 -0.9880901 0 -0.1538725 -0.9880908 0 0.005396604 -0.9999855 0 0.005396246 -0.9999855 0 0.1674646 -0.9858781 0 0.16747 -0.9858772 0 0.3227029 -0.9465003 0 0.622247 -0.7828209 0 0.9297562 -0.368176 0 0.9297559 -0.3681766 0 0.9892159 0.1464647 0 0.989172 0.1467614 9.74611e-5 -0.3682023 -0.9297457 0 0.1461086 -0.9892686 0 0.1468295 -0.9891619 1.94918e-4 0.1481399 -0.9889665 0 0.6222476 -0.7828205 0 -0.9891543 -0.1468804 0 -0.9891718 -0.1467627 0 -0.7808545 -0.6247131 0 -0.7827991 -0.6222744 -4.86807e-4 -0.7839158 -0.6208672 0 -0.3681825 -0.9297536 0 0.9890433 0.1476261 0 0.7835874 0.6212817 0 0.7835581 0.6213185 0 0.3676695 0.9299566 0 0.3676481 0.929965 0 -0.1468294 0.9891619 0 -0.1468381 0.9891606 0 -0.621279 0.7835894 -1.49929e-4 -0.6209269 0.7838685 0 4.97436e-7 0 -1 7.05975e-7 0 -1 -1.6375e-6 0 -1 8.44914e-7 0 -1 0.04364764 0.3785318 0.9245585 0.0146203 0.1267888 0.991822 0.01458919 0.1268531 0.9918143 0.01721966 0.1496177 -0.9885939 0.01722675 0.1489707 -0.9886916 0.02019619 0.1440844 -0.9893593 0.04272162 0.3961923 -0.9171731 0.04477411 0.3919776 -0.9188846 0.06920796 0.6058391 -0.7925713 0.06945574 0.6054512 -0.792846 0.09074044 0.7868953 -0.6103785 0.09058088 0.7870596 -0.6101905 0.1055222 0.9169498 -0.3847963 0.1051784 0.9172189 -0.3842487 0.1126875 0.9845964 -0.1336842 0.1134033 0.9843553 -0.1348494 0.113493 0.9851573 0.1287809 0.1134929 0.9851506 0.1288316 0.1059372 0.9195464 0.3784334 0.1061209 0.9196636 0.3780971 0.09091538 0.7879134 0.6090377 0.08991575 0.7869367 0.6104473 0.06882393 0.6032515 0.794576 0.06994456 0.6048296 0.7932773 0.04374718 0.3782813 0.9246564 -6.61629e-6 0 -1 5.81605e-6 0 -1 6.40697e-6 0 -1 -0.8291197 0.3870237 -0.4034517 0.2246863 -0.8876475 -0.4019926 0.493765 -0.7700312 -0.4040398 0.803424 0.4011341 -0.4400015 0.8145152 0.3930616 -0.4266939 0.803315 0.4319308 -0.4100257 0.8166064 0.3895686 -0.4258995 0.8256225 0.379731 -0.4173153 0.8256226 0.3797309 -0.4173153 0.8336126 0.3694125 -0.4106392 0.8439179 0.3511696 -0.4055647 0.8439179 0.3511695 -0.4055647 0.8439179 0.3511696 -0.4055647 0.8409408 0.3646455 -0.3998151 0.8397341 0.3708342 -0.3966466 0.8390233 0.3854071 -0.3840591 0.8427852 0.403923 -0.3557516 0.8447282 0.4074329 -0.3470342 0.7499414 0.5244829 -0.4031199 0.7497569 0.5245632 -0.4033586 0.7949007 0.4522741 -0.4044514 0.6559252 0.6380946 -0.4032338 0.6549823 0.6388826 -0.4035184 0.7537377 0.5187967 -0.4033975 0.5449239 0.7348874 -0.4037308 0.5450271 0.7348572 -0.4036464 0.6559967 0.6377556 -0.4036534 0.2842472 0.8697121 -0.4034904 0.420125 0.8128424 -0.4034628 0.4201211 0.8128522 -0.4034472 0.4200824 0.8128364 -0.4035195 0.5446627 0.7352246 -0.4034693 0.10275 0.9074487 -0.4074055 0.1102315 0.911109 -0.3971518 0.1213671 0.9137583 -0.3877061 0.1438657 0.9216958 -0.3602491 0.1564967 0.9375884 -0.3105427 0.1378204 0.9207465 -0.3650088 0.1146597 0.9038785 -0.412137 0.1318579 0.8967904 -0.4223512 0.1392483 0.8922213 -0.4295942 0.1604807 0.8940009 -0.41834 0.1803022 0.8939788 -0.4102356 0.2016705 0.8920305 -0.4044881 0.2017083 0.8919312 -0.4046882 0.2843105 0.8696261 -0.4036313 0.2893259 0.8759665 -0.3859707 0.2077451 0.889703 -0.4065349 0.207745 0.889703 -0.4065349 0.207745 0.889703 -0.4065349 0.2074323 0.8898194 -0.4064397 0.6560847 0.638103 -0.402961 0.5449974 0.7351663 -0.4031233 0.5447887 0.7344781 -0.404657 0.41995 0.8124873 -0.4043595 0.4199739 0.8125281 -0.4042524 0.2841601 0.8694982 -0.4040123 0.7965309 0.4490975 -0.4047841 0.7882364 0.4635164 -0.4047664 0.7556595 0.5286747 -0.3866286 0.7483282 0.5268691 -0.4030062 0.6560782 0.6380884 -0.4029948 -0.05380743 -0.8957519 -0.4412861 -0.06725037 -0.901709 -0.4270812 -0.02602756 -0.9118651 -0.4096643 -0.005485832 -0.9146066 -0.4043078 -0.07343155 -0.9023866 -0.4246248 -0.0858106 -0.9051475 -0.4163467 -0.09307324 -0.9061311 -0.4126305 -0.1234521 -0.9047098 -0.4077497 -0.1031602 -0.9111387 -0.398979 -0.09958344 -0.9124105 -0.3969764 -0.08603924 -0.9193977 -0.3838036 -0.07207727 -0.9317331 -0.355919 -0.06985676 -0.9354881 -0.3463845 0.3974197 -0.8234756 -0.4049022 0.3687399 -0.8510416 -0.3738436 0.3303202 -0.8531025 -0.4038621 0.2247967 -0.8871464 -0.4030356 0.2245398 -0.8870439 -0.4034045 0.07972645 -0.9115031 -0.4034921 0.07911676 -0.9114598 -0.4037101 0.07893747 -0.9115754 -0.4034837 0.07470571 -0.9120687 -0.4031744 0.6722983 -0.6200404 -0.4044316 0.6111388 -0.6810038 -0.4034146 0.6107537 -0.6810806 -0.4038678 0.6115202 -0.6801726 -0.4042381 0.4935832 -0.7700267 -0.4042705 0.7361338 -0.5410094 -0.4067136 0.7337822 -0.5508748 -0.3976188 0.7308707 -0.5605193 -0.3894178 0.7262574 -0.5856078 -0.3600192 0.7336289 -0.6041995 -0.3110172 0.7284777 -0.5804544 -0.3638583 0.7261103 -0.5504106 -0.4120826 0.7092383 -0.5634609 -0.4236662 0.7032737 -0.5666345 -0.4293386 0.695815 -0.5825583 -0.4200802 0.6821777 -0.6061965 -0.4088513 0.6138363 -0.6885143 -0.3862035 0.6634205 -0.6288884 -0.405429 0.6680768 -0.6238663 -0.4055419 0.6106348 -0.6803418 -0.4052904 0.4935138 -0.7695918 -0.4051824 0.4939365 -0.769927 -0.4040285 0.3639363 -0.8393729 -0.403737 0.3497052 -0.7261517 -0.5919544 0.3299684 -0.8536447 -0.4030033 -0.008725583 -0.914339 -0.404856 0.01251637 -0.914242 -0.4049754 0.08020359 -0.9181991 -0.3879147 0.08191347 -0.9122863 -0.401278 0.2248778 -0.8879088 -0.4013079 -0.7488166 0.496323 -0.4392462 -0.7475249 0.5087028 -0.4271159 -0.7753718 0.479699 -0.410716 -0.7753719 0.479699 -0.4107159 -0.7753718 0.479699 -0.4107159 -0.7899602 0.4607698 -0.404542 -0.7456864 0.5123587 -0.4259583 -0.741029 0.52718 -0.4158813 -0.7376844 0.535317 -0.4114091 -0.7376844 0.5353171 -0.4114091 -0.7376844 0.535317 -0.4114091 -0.7285656 0.552966 -0.4042535 -0.7360649 0.5461807 -0.3998691 -0.7407218 0.5420921 -0.3968217 -0.7526782 0.5343884 -0.3845838 -0.7718962 0.5278791 -0.354288 -0.7750295 0.5278497 -0.3474251 -0.8804811 0.2490563 -0.4033907 -0.8803586 0.2486181 -0.4039281 -0.8288091 0.3872002 -0.4039203 -0.908894 0.1044023 -0.4037475 -0.9088966 0.1044104 -0.4037393 -0.8799962 0.2503899 -0.4036233 -0.909001 0.1046038 -0.4034541 -0.9140262 -0.04260659 -0.4034115 -0.9138759 -0.0423724 -0.4037767 -0.8940646 -0.1941982 -0.403653 -0.8954187 -0.1884235 -0.4033881 -0.8954591 -0.1885613 -0.4032341 -0.8698516 -0.3363908 -0.3608318 -0.8902094 -0.3331848 -0.310669 -0.8676692 -0.3410674 -0.361695 -0.8579332 -0.346998 -0.3788711 -0.8470038 -0.356983 -0.393888 -0.8431886 -0.3615368 -0.3978998 -0.8369017 -0.3658769 -0.4070993 -0.8400286 -0.3524588 -0.4124621 -0.8419262 -0.3394728 -0.4194264 -0.8424505 -0.3217906 -0.4321204 -0.842835 -0.3258973 -0.428276 -0.863954 -0.2920892 -0.4102041 -0.8735282 -0.2710772 -0.4043088 -0.9030406 -0.1871232 -0.3866557 -0.8736506 -0.2659989 -0.4074056 -0.8736506 -0.2659991 -0.4074056 -0.8736506 -0.2659988 -0.4074056 -0.8731768 -0.267556 -0.4074019 -0.8806467 0.2488017 -0.4031863 -0.909201 0.1044746 -0.4030368 -0.9085148 0.1046373 -0.4045391 -0.9136069 -0.04267817 -0.4043526 -0.9135957 -0.04266339 -0.4043796 -0.894962 -0.1883533 -0.4044332 -0.7869884 0.4648612 -0.4056517 -0.795748 0.4496758 -0.4056809 -0.8350101 0.3900064 -0.3881407 -0.8293378 0.384122 -0.4057698 -0.8795701 0.2488809 -0.4054811 0.7364088 -0.5451089 -0.4006973 0.7408906 -0.5360522 -0.4046346 0.7952249 -0.4524128 -0.4036586 0.7952617 -0.4522764 -0.4037389 0.8574929 -0.3189429 -0.4037097 0.857423 -0.3194448 -0.403461 0.897653 -0.1773168 -0.4034575 0.8976547 -0.1772989 -0.4034615 0.9144634 -0.03120887 -0.4034633 0.9144263 -0.03100574 -0.4035631 0.9075961 0.115773 -0.4035667 0.9075971 0.1157633 -0.4035672 0.8771488 0.2602286 -0.4035978 0.877258 0.2600316 -0.4034876 0.843183 0.3542073 -0.40445 0.8350514 0.3673042 -0.4096058 -0.8366363 -0.3707457 -0.4032213 -0.8347519 -0.3735877 -0.4045017 -0.7893859 -0.4626269 -0.4035424 -0.7896144 -0.4623814 -0.4033765 -0.7052969 -0.5829576 -0.4033819 -0.7049572 -0.5832254 -0.4035883 -0.6022058 -0.6888249 -0.4035698 -0.6022449 -0.6887993 -0.4035552 -0.4843724 -0.7762314 -0.4035448 -0.4841997 -0.7762938 -0.4036317 -0.3534052 -0.843907 -0.4036407 -0.3532194 -0.8439428 -0.4037285 -0.2130911 -0.8897125 -0.4037374 -0.2133999 -0.8897112 -0.4035773 -0.1148879 -0.9072723 -0.4045462 -0.1054529 -0.9070851 -0.4075248 0.09999513 0.9101392 -0.4020543 0.0937196 0.9097188 -0.4045103 -0.005749225 0.9149438 -0.4035402 -0.005788266 0.9149346 -0.4035608 -0.1524398 0.9021636 -0.4035627 -0.1524294 0.9021714 -0.4035495 -0.2951523 0.8660368 -0.4035658 -0.2951686 0.8660255 -0.4035782 -0.4302807 0.8074491 -0.4035896 -0.4301851 0.8075286 -0.4035324 -0.5543365 0.7279244 -0.4035308 -0.5544099 0.7278442 -0.4035748 -0.6638137 0.6296713 -0.4035661 -0.6636829 0.6298895 -0.4034407 -0.7280848 0.5534899 -0.4044026 -0.7365833 0.5375845 -0.4104242 -6.4699e-6 0 1 -5.65841e-6 0 1 -2.83579e-6 0 1 2.84796e-6 0 1 2.86074e-6 0 1 3.12531e-6 0 1 -1.45298e-6 0 1 -3.10528e-6 0 1 1.82744e-6 0 1 8.08216e-7 0 1 2.94513e-6 0 1 -6.19709e-6 0 1 6.4754e-6 0 1 6.64894e-6 0 1 -6.736e-6 0 1 5.42146e-6 0 1 -5.29425e-6 0 1 2.32709e-7 0 1 -6.13732e-7 0 1 0.0562188 0.8837884 0.4644972 0.6086542 -0.4287384 0.6676254 -0.7682507 -0.4972581 0.4031441 -0.6759755 -0.6168686 0.4031507 -0.6760834 -0.616904 0.4029155 -0.5652377 -0.7197672 0.4030405 -0.5651156 -0.7197048 0.4033228 -0.4389376 -0.8028916 0.4033598 -0.4392663 -0.8031966 0.4023934 -0.3009451 -0.8644316 0.4027285 -0.3007057 -0.8641401 0.403532 -0.1047245 -0.9097942 0.4016309 -0.1105613 -0.8958633 0.430355 -0.1175915 -0.8475633 0.5175026 -0.0907287 -0.8459546 0.5254799 -0.102899 -0.7420261 0.6624267 -0.09516513 -0.9098581 0.403859 -0.09516507 -0.909858 0.4038589 -0.09516513 -0.9098581 0.403859 -0.1041588 -0.9043619 0.4138605 -0.09815734 -0.9076372 0.4081175 -0.09314024 -0.9091724 0.4058701 -0.1194507 -0.911328 0.3939706 -0.138606 -0.918486 0.3703671 -0.1604097 -0.9363538 0.3122667 -0.1829812 -0.9129337 0.3647877 -0.2156857 -0.8886522 0.4046939 0.7258289 -0.5563842 0.4044861 0.7273101 -0.5539264 0.4051982 0.7273101 -0.5539265 0.4051982 0.7273101 -0.5539264 0.4051982 0.7476921 -0.5350841 0.3932448 0.7348101 -0.5462915 0.4020196 0.7290194 -0.5526711 0.4038386 0.7297121 -0.5484645 0.4082977 0.7315053 -0.5415347 0.4142948 0.7255234 -0.5122762 0.459553 0.6303831 -0.5575025 0.5401927 0.6802162 -0.5128067 0.5237703 0.9118503 0.07160657 0.4042298 0.9113012 -0.07948434 0.4039955 0.9113892 -0.07951027 0.4037919 0.8859555 -0.2284345 0.4036095 0.8853121 -0.2279826 0.4052733 0.8356212 -0.3707325 0.4053326 0.8364971 -0.3715947 0.4027285 0.7960431 -0.4507064 0.4039546 0.7865533 -0.5184784 0.3354316 0.8070541 -0.519774 0.2801762 0.7651336 -0.5264683 0.3706773 0.9133939 0.2270678 0.3378638 0.8908092 0.2087594 0.4035821 0.9122485 0.07151627 0.4033464 0.8207577 0.3855707 0.4215356 0.6441734 0.2825047 0.7107966 0.7923259 0.3568176 0.4948748 0.8155328 0.375904 0.4400029 0.8264204 0.3956136 0.4006485 0.8320231 0.3888475 0.3956453 0.8380708 0.3828674 0.3886517 0.849424 0.3742955 0.3719971 0.8625264 0.3679889 0.3473218 0.8532799 0.3699223 0.3675201 0.8630723 0.3015561 0.4051791 0.8695024 0.2824351 0.4052111 0.1729645 0.900178 0.3997035 0.1600956 0.893795 0.4189273 0.1516922 0.8852031 0.4397785 0.1528586 0.8855137 0.4387481 0.151222 0.8845057 0.4413408 0.08820921 0.9101647 0.4047462 0.06732493 0.9120715 0.4044663 0.1430733 0.918763 0.3679738 0.1545512 0.9019024 0.4033434 0.06948047 0.9119313 0.4044179 0.05688965 0.9147849 0.3999153 -0.559094 0.7249026 0.4024057 -0.4323303 0.8069757 0.4023444 -0.4322855 0.806694 0.4029569 -0.2931473 0.8668439 0.4032942 -0.2931491 0.8665304 0.4039662 -0.1467751 0.9029449 0.4039155 -0.1466795 0.9033973 0.4029373 -0.03331077 0.9143574 0.4035356 0.003930687 0.9600179 0.2799112 0.02210211 0.9400371 0.3403554 0.04422736 0.9210591 0.3869033 -0.7025434 0.594165 0.391664 -0.7012936 0.6271692 0.3388895 -0.7033361 0.6531047 0.2806648 -0.6439821 0.6489764 0.4051133 -0.5588561 0.7241116 0.4041563 -0.7711801 0.4952889 0.3999629 -0.77118 0.4952889 0.3999629 -0.7711802 0.4952889 0.3999629 -0.7692396 0.506623 0.389363 -0.7691901 0.5074892 0.3883316 -0.7250366 0.5573192 0.40462 -0.7112204 0.57486 0.4046005 -0.6775024 0.5584021 0.4787252 -0.713256 0.5725426 0.4043031 -0.7638795 0.5040715 0.4029889 -0.7356778 0.4988127 0.4582186 -0.7494951 0.4935387 0.4412217 -0.7546848 0.4941784 0.4315538 -0.7440539 0.4962593 0.4473371 -0.8483546 -0.3316307 0.4126932 -0.8526061 -0.341302 0.3956965 -0.8523194 -0.3516739 0.3871396 -0.7868759 -0.5241878 0.3256589 -0.7999985 -0.4426232 0.4050767 -0.8392802 -0.3638445 0.4040124 -0.8648622 -0.3935706 0.3116343 -0.8539248 -0.3663114 0.369633 -0.855805 -0.3241487 0.4031447 -0.8420524 -0.3356206 0.4222638 -0.8206161 -0.3385133 0.4604324 -0.7206096 -0.3087952 0.6207798 -0.08722418 -0.9104757 0.40426 -0.08895105 -0.9101445 0.4046292 -0.003951489 -0.9149819 0.4034757 -0.003956377 -0.91498 0.40348 0.1468489 -0.90314 0.4034523 0.1466948 -0.9031544 0.4034761 0.1467604 -0.9031294 0.4035082 -0.8547097 -0.3254836 0.4043909 -0.8881435 -0.2200632 0.4034516 -0.8879346 -0.2207309 0.4035469 -0.9121869 -0.0717653 0.4034415 -0.9121664 -0.07164674 0.4035088 -0.9121736 -0.07156962 0.4035061 -0.8879366 -0.2208434 0.4034811 -0.7671509 0.4920501 0.4115413 -0.7723543 0.4900816 0.4040903 -0.8362708 0.3711206 0.4036347 -0.836298 0.3710948 0.4036017 -0.8859655 0.2284207 0.4035954 -0.8861073 0.2281953 0.4034113 -0.9117186 0.07786822 0.4033682 -0.9115162 0.07952022 0.4035032 -0.9115158 0.07954084 0.4035 -0.9110438 0.08636498 0.403163 0.4386898 0.8029043 0.4036039 0.4388402 0.8027391 0.4037688 0.3011267 0.8638764 0.4037824 0.3007004 0.8641967 0.4034146 0.1694503 0.8990016 0.4038351 0.1534009 0.9096894 0.3859187 0.5671056 0.7180196 0.4035333 0.5647979 0.7196887 0.4037964 0.5650823 0.7195717 0.4036071 0.8221366 0.3947392 0.4102103 0.8217778 0.401498 0.4043274 0.7680575 0.4973571 0.4033902 0.7681315 0.4970992 0.4035671 0.6764139 0.6160867 0.4036105 0.6759015 0.6167615 0.4034383 0.6755975 0.616967 0.4036333 0.5664343 0.7183798 0.4038349 0.7258307 -0.5562939 0.4046071 0.6703982 -0.622738 0.40344 0.6705051 -0.6225746 0.4035145 0.6704102 -0.6226511 0.403554 0.5589099 -0.7244047 0.4035561 0.5588203 -0.7244912 0.4035249 0.5589064 -0.7244544 0.4034718 0.5587798 -0.7245281 0.4035147 0.4319857 -0.8065772 0.4035116 0.4319842 -0.8065846 0.4034985 0.2933627 -0.866675 0.4035006 0.2933436 -0.8666754 0.4035136 0.1467567 -0.9031254 0.4035184 -6.29094e-7 0 1 -2.52707e-6 0 1 3.16342e-6 0 1 3.84618e-6 0 1 -8.69384e-6 0 1 -6.15764e-6 0 1 2.14854e-6 0 1 -7.62242e-6 0 1 3.45913e-6 0 1 3.12086e-6 0 1 -1.25121e-6 0 1 1.90024e-6 0 1 -3.03045e-7 0 1 -3.40608e-6 0 1 9.08073e-6 0 1 -1.21265e-5 0 1 2.20264e-6 0 1 1.73025e-6 0 1 1.61417e-5 0 1 6.14885e-6 0 1 -1.13082e-6 0 1 -3.39916e-6 0 1 1.37058e-6 0 1 -4.18639e-6 0 1 4.79393e-6 0 1 -9.0524e-6 0 1 -5.74854e-6 0 1 -9.35104e-6 0 1 4.30219e-6 0 1 3.89384e-6 0 1 8.37058e-7 0 1 -3.9467e-6 0 1 7.56398e-6 0 1 9.46439e-7 0 1 9.59619e-6 0 1 1.61547e-6 0 1 -1.09151e-6 0 1 -1.14497e-6 0 1 1.51626e-6 0 1 -2.82789e-6 0 1 1.07021e-6 0 1 1.70666e-6 0 1 1.21333e-6 0 1 -1.46023e-6 0 1 1.91953e-5 0 1 -2.66786e-6 0 1 -1.30012e-6 0 1 2.97941e-6 0 1 -1.62519e-5 0 1 -1.19464e-6 0 1 3.25682e-6 0 1 1.35631e-6 0 1 -3.37728e-6 0 1 -1.06067e-5 0 1 -8.43865e-7 0 1 2.60173e-6 0 1 -2.38914e-6 0 1 -4.61418e-7 0 1 -2.10155e-6 0 1 1.82765e-6 0 1 -4.3631e-6 0 1 1.28183e-6 0 1 -1.45339e-6 0 1 -3.56789e-5 0 1 -7.38724e-7 0 1 4.41287e-6 0 1 -1.69145e-5 0 1 2.89519e-5 0 1 3.89837e-7 0 1 1.70726e-6 0 1 -4.52474e-6 0 1 1.54842e-6 0 1 4.89033e-6 0 1 -7.54262e-6 0 1 4.79089e-7 0 1 0 0 1 -2.96376e-6 0 1 1.57322e-6 0 1 2.9568e-6 0 1 -1.43766e-6 0 1 -1.31834e-6 0 1 -2.10766e-6 0 1 1.08402e-6 0 1 2.98562e-6 0 1 -7.92477e-7 0 1 2.67202e-6 0 1 3.2089e-6 0 1 -8.20608e-7 0 1 -2.96951e-6 0 1 -3.57058e-6 0 1 -1.5977e-5 0 1 2.8925e-6 0 1 -2.97607e-6 0 1 2.23456e-6 0 1 -1.0863e-5 0 1 -1.26604e-6 0 1 -7.52124e-7 0 1 -1.14012e-6 0 1 2.00075e-6 0 1 -3.3368e-6 0 1 2.09419e-6 0 1 -2.24694e-6 0 1 -6.18108e-6 0 1 -7.6476e-6 0 1 2.33554e-7 0 1 1.31333e-6 0 1 -3.25835e-6 0 1 -1.11883e-6 0 1 -3.6956e-6 0 1 3.07186e-6 0 1 -2.46073e-5 0 1 4.18718e-6 0 1 5.88945e-7 0 1 -9.06546e-7 0 1 3.04601e-6 0 1 1.98972e-6 0 1 -8.80827e-7 0 1 -6.98293e-7 0 1 3.77632e-6 0 1 -9.59335e-7 0 1 1.0724e-6 0 1 2.4572e-6 0 1 -2.14011e-6 0 1 5.63579e-6 0 1 -1.70631e-7 0 1 -1.25422e-6 0 1 -7.09876e-7 0 1 -6.79172e-6 0 1 3.24117e-6 0 1 -1.74708e-6 0 1 -3.26861e-5 0 1 1.30143e-6 0 1 2.88357e-6 0 1 -9.44922e-7 0 1 -2.70259e-6 0 1 -1.164e-6 0 1 -2.1883e-6 0 1 8.82606e-7 0 1 1.4699e-5 0 1 -8.85771e-7 0 1 2.7571e-6 0 1 9.86291e-6 0 1 -6.87947e-5 0 1 2.34063e-6 0 1 1.64149e-7 0 1 1.44788e-6 0 1 -1.28153e-5 0 1 -4.50847e-6 0 1 1.62779e-6 0 1 -2.05373e-6 0 1 -2.63595e-6 0 1 0.9877002 -0.1562409 0.006096661 0.9118955 -0.4102791 -0.01085233 0.9985767 -0.05333614 0 0.9977886 0.03238517 -0.05804544 0.9864191 -0.164135 0.006093025 0.7734257 0.6330892 -0.03179228 0.8297331 0.5581603 0 0.9499638 0.3123603 0 0.9155262 0.3972535 -0.06325834 0.9746812 0.2235993 0 0.9036832 -0.4282018 0 0.7022026 -0.7119773 0 0.3982428 -0.91728 0 0.03918635 -0.999232 0 -0.3243802 -0.9459268 0 -0.3243932 -0.9459224 0 -0.6434993 -0.7654467 0 -0.6434778 -0.7654649 0 -0.8772627 -0.4800106 0 -0.8772802 -0.4799786 0 -0.9912952 -0.1316589 0 -0.991295 -0.1316593 0 -0.9719642 0.2351291 0 -0.9719738 0.2350893 0 -0.8211588 0.5706998 0 -0.8211783 0.570672 0 -0.5592231 0.8290173 0 -0.5592035 0.8290305 0 -0.223024 0.9748131 0 -0.2230335 0.9748108 0 0.1447719 0.9894651 0 0.144778 0.9894642 0 0.3938997 0.9191535 0 0.4930235 0.8695986 -0.02695053 0.5550915 0.8317894 0 0.7114321 0.7027549 0 -1.84249e-6 0 -1 1.0715e-6 0 -1 1.79121e-6 0 -1 1.44583e-6 0 -1 4.85362e-7 0 -1 -1.37283e-7 0 -1 -7.97458e-7 0 -1 1.26418e-6 0 -1 -1.43255e-6 0 -1 6.37056e-7 0 -1 -1.04331e-6 0 -1 -6.14036e-7 0 -1 -1.41886e-6 0 -1 -3.69613e-7 0 -1 1.69837e-4 0 -1 2.30742e-6 0 -1 -2.87684e-6 0 -1 1.18673e-6 0 -1 6.10015e-7 0 -1 -1.84203e-6 0 -1 -2.43736e-5 0 -1 -1.70702e-6 0 -1 2.04576e-7 0 -1 1.81039e-6 0 -1 -3.4196e-6 0 -1 1.08796e-5 0 -1 -3.06696e-6 0 -1 5.35727e-6 0 -1 -9.02879e-7 0 -1 -1.35645e-6 0 -1 2.25313e-7 0 -1 4.01341e-7 0 -1 -4.35237e-6 0 -1 8.13961e-6 0 -1 1.08836e-6 0 -1 -2.62186e-6 0 -1 7.0411e-7 0 -1 1.90414e-7 0 -1 -1.88364e-6 0 -1 4.61078e-7 0 -1 -4.45021e-6 0 -1 -7.08456e-6 0 -1 3.71383e-6 0 -1 -7.97713e-7 0 -1 1.20869e-6 0 -1 -1.39895e-6 0 -1 1.58477e-6 0 -1 2.7135e-6 0 -1 -1.12048e-6 0 -1 -4.55259e-6 0 -1 2.44912e-7 0 -1 2.82504e-6 0 -1 9.83168e-6 0 -1 -2.18985e-7 0 -1 -4.15138e-6 0 -1 3.83606e-6 0 -1 -3.32654e-6 0 -1 7.22924e-7 0 -1 4.84564e-7 0 -1 1.84246e-6 0 -1 -2.14303e-6 0 -1 2.23838e-6 0 -1 -2.35396e-6 0 -1 4.60378e-7 0 -1 1.31114e-6 0 -1 1.08847e-6 0 -1 -6.95381e-7 0 -1 -1.01665e-6 0 -1 -6.99872e-7 0 -1 2.41844e-6 0 -1 1.52333e-6 0 -1 -1.55256e-6 0 -1 5.56087e-7 0 -1 -3.62834e-6 0 -1 -1.95876e-6 0 -1 4.80038e-7 0 -1 3.39285e-7 0 -1 -5.79208e-7 0 -1 -1.74537e-6 0 -1 -1.39956e-6 0 -1 1.59638e-6 0 -1 4.35229e-6 0 -1 -4.86601e-6 0 -1 3.22886e-6 0 -1 -0.5300678 0.8479554 0 -0.2567272 0.9664839 0 0.03939729 0.9992237 0 0.03939723 0.9992237 0 0.3330397 0.9429128 0 0.333032 0.9429155 0 0.5954371 0.8034021 0 0.5954368 0.8034023 0 0.8058974 0.5920552 0 0.8058855 0.5920714 0 0.9447613 0.3277593 0 0.9447538 0.327781 0 0.999379 0.03523975 0 0.999379 0.03523975 0 0.9651703 -0.2616226 0 0.9651641 -0.2616455 0 0.8457378 -0.5335988 0 0.8457267 -0.5336163 0 0.6505145 -0.7594939 0 0.6505261 -0.7594839 0 0.3975554 -0.9175782 0 0.397564 -0.9175745 0 0.1098828 -0.9939447 0 0.1098802 -0.993945 0 -0.1886931 -0.9820362 0 -0.1886884 -0.9820371 0 -0.4688889 -0.8832572 0 -0.4688887 -0.8832573 0 -0.7087891 -0.7054205 0 -0.7087889 -0.7054207 0 -0.8851876 -0.4652345 0 -0.8851873 -0.4652348 0 -0.9829893 -0.1836625 0 -0.982985 -0.1836863 0 -0.9933702 0.1149597 0 -0.9933758 0.1149115 0 -0.915766 0.4017122 0 -0.915775 0.4016917 0 -0.7564021 0.654107 0 -0.5300793 0.8479481 0 0.5486769 -0.8359866 0.008957982 0.4709948 -0.8820179 -0.01443296 0.5470984 -0.8370205 0.008942484 0.6050948 -0.7959605 -0.01752972 0.6410049 -0.7675113 0.006266534 0.6353431 -0.7722046 0.006262481 0.7262182 -0.6874201 -0.007800996 0.7235725 -0.6901651 -0.01072776 0.826308 -0.5629138 -0.01852697 0.7974792 -0.603321 0.005541801 0.7961105 -0.6051257 0.005567014 0.7961105 -0.6051257 0.005567073 0.7961105 -0.6051257 0.005567073 0.9615021 -0.2747871 0.002438127 0.9615021 -0.274787 0.002438008 0.9615021 -0.274787 0.002437949 0.9129013 -0.408175 -0.002097427 0.9058012 -0.4234918 -0.01337552 0.8630598 -0.5050472 0.007432937 0.8607991 -0.508891 0.007426142 0.9537592 -0.3005622 0.002445161 0.9621637 -0.2720386 -0.01536548 0.9815607 -0.1909418 0.008942186 0.9817712 -0.1898564 0.008942484 0.9933668 -0.1137019 -0.01715731 0.9970496 -0.07668888 0.003319442 0.9976752 -0.06806695 0.003320515 0.9989184 0.04611217 -0.005978524 0.999222 0.037099 -0.0133841 0.9783438 0.2061883 -0.01816719 0.9886991 0.1497076 0.007861733 0.9878672 0.1551023 0.007854282 0.8874989 0.4608032 0.002474725 0.9283449 0.3716996 -0.003902077 0.932568 0.3607934 -0.01204431 0.9648876 0.262539 0.008077383 0.9643222 0.2646084 0.008073568 0.8798503 0.4752446 0.002468943 0.8631623 0.5046529 -0.01662248 0.8196389 0.572801 0.009549558 0.8207236 0.5712457 0.009557783 0.770065 0.6377614 -0.01613372 0.7496253 0.6618586 0.002278506 0.7511462 0.660132 0.002288281 0.6586754 0.7524168 -0.003960907 0.6690675 0.7430347 -0.01575034 0.5290255 0.8484198 -0.01777291 0.5799911 0.8145834 0.008013665 0.5811592 0.8137506 0.00800848 0.2746606 0.9615305 0.004556894 0.3804759 0.9247694 -0.006308436 0.3861841 0.9223583 -0.01082873 0.4880116 0.8728054 0.007445573 0.4828008 0.8756985 0.007462024 0.2722487 0.962216 0.004586577 0.2322055 0.972509 -0.0175212 0.1623757 0.9866979 0.007849752 0.1617658 0.9867981 0.007829904 0.07496625 0.9970552 -0.01616168 0.0469551 0.9988964 0.001124382 -0.0873692 0.9960712 -0.01444983 -0.06686866 0.9977613 -0.001109659 0.06624877 0.9978026 0.001106381 -0.2448419 0.9694023 -0.0176534 -0.1801557 0.9836053 0.008044898 -0.1792859 0.983764 0.008065462 -0.4979123 0.8672033 0.006471395 -0.3979453 0.917374 -0.008042871 -0.3970575 0.917752 -0.008761644 -0.2904877 0.9568602 0.005957901 -0.2901953 0.9569488 0.005981326 -0.5004178 0.8657598 0.006497979 -0.5404197 0.8412224 -0.01707226 -0.5949521 0.8037146 0.008653938 -0.6679594 0.7441973 -8.5956e-4 -0.6827774 0.73039 -0.01859402 -0.5963636 0.8026673 0.008696377 -0.7784513 0.6275153 -0.01543068 -0.761828 0.6477791 7.16829e-4 -0.7398964 0.6727205 7.46287e-4 -0.7398961 0.6727209 7.46439e-4 -0.7398968 0.6727201 7.46308e-4 -0.8873921 0.4609888 0.004971265 -0.8893516 0.4571972 0.004980802 -0.8690243 0.4944512 -0.01774042 -0.8296276 0.5582456 0.008938431 -0.830805 0.556492 0.008933603 -0.9352133 0.3540288 -0.006314814 -0.9372081 0.348613 -0.01049637 -0.9689103 0.2473208 0.006732285 -0.9692629 0.2459351 0.006741762 -0.9808946 0.1936726 -0.01835 -0.9911995 0.1321431 0.007861614 -0.9912455 0.131798 0.007859051 -0.999349 0.0336883 -0.01291298 -0.9998077 0.01935315 -0.003164529 -0.9918727 -0.1261169 -0.01682627 -0.9956163 -0.09350329 0.002312898 -0.9957459 -0.09211319 0.002312481 -0.9584111 -0.2848746 -0.01716572 -0.9784958 -0.2060634 0.009156107 -0.977804 -0.2093216 0.009159266 -0.8533958 -0.5212023 0.007999062 -0.9053287 -0.4245025 -0.01332795 -0.9013038 -0.4331536 -0.005454778 -0.9468992 -0.3215212 0.002452075 -0.9480829 -0.3180139 0.002459645 -0.8517793 -0.5238398 0.007996141 -0.819238 -0.5731759 -0.01784986 -0.7853481 -0.6190031 0.007983863 -0.786997 -0.6169056 0.007965803 -0.7163296 -0.6976751 -0.01101714 -0.7106211 -0.7035564 -0.005119204 -0.5948963 -0.8036087 -0.01765114 -0.6261586 -0.7796856 0.003984272 -0.6281553 -0.7780779 0.003974258 -0.4595998 -0.8879856 -0.01580131 -0.5306865 -0.8475305 0.007993817 -0.5326246 -0.8463136 0.008030891 -0.2205547 -0.9753412 0.008082926 -0.3272513 -0.9447835 -0.01705396 -0.3109754 -0.9504153 -0.002280533 -0.4189333 -0.9080158 0.001464605 -0.4338153 -0.9010007 0.001468777 -0.21719 -0.976096 0.008068919 -0.1536339 -0.9879626 -0.01807492 -0.1051746 -0.9944379 0.005631268 -0.09951382 -0.9950203 0.00563097 0.006240904 -0.9999325 -0.009809553 0.0088014 -0.9999301 -0.007902681 0.1662032 -0.9859381 -0.01739674 0.1243005 -0.9922342 0.004539132 0.1179459 -0.9930097 0.004528105 0.450743 -0.8926538 0 0.3435647 -0.939129 0 0.3221839 -0.9465695 -0.01428031 0.2354586 -0.9718413 0.00915426 0.2361904 -0.9716637 0.009160697 -4.35176e-6 0 1 1.60839e-6 0 1 1.08707e-6 0 1 6.45106e-6 0 1 6.13196e-6 0 1 -4.31734e-6 0 1 -6.13301e-6 0 1 8.64846e-6 0 1 -3.02693e-6 0 1 -3.03302e-6 0 1 2.2996e-6 0 1 -3.05146e-6 0 1 8.76609e-6 0 1 -1.03055e-5 0 1 6.13663e-6 0 1 -1.21242e-5 0 1 -6.01323e-6 0 1 -6.13738e-6 0 1 2.15733e-6 0 1 -3.04938e-6 0 1 3.4488e-6 0 1 6.124e-6 0 1 -2.14836e-6 0 1 -6.11471e-6 0 1 6.10359e-6 0 1 -5.38162e-7 0 1 -6.06105e-6 0 1 5.8972e-6 0 1 -3.03236e-6 0 1 4.5544e-6 0 1 -3.73072e-6 0 1 -4.28758e-6 0 1 -6.13346e-6 0 1 6.10352e-6 0 1 5.89762e-6 0 1 6.12235e-6 0 1 -8.68674e-6 0 1 2.98493e-6 0 1 0.5386754 -0.8202193 0.1925337 0.5363633 -0.820685 0.1969532 0.6269977 -0.7537592 0.1967763 0.6293645 -0.753592 0.1897359 0.6231814 -0.7575463 0.1943419 0.7098906 -0.6768757 0.1946657 0.709737 -0.6769134 0.1950942 0.780997 -0.5933543 0.19487 0.7822672 -0.591017 0.196868 0.7816702 -0.5912753 0.1984577 0.8438977 -0.4983958 0.1985908 0.8434851 -0.4985125 0.2000453 0.8465686 -0.4954603 0.1945267 0.8959414 -0.3993697 0.1944039 0.8948246 -0.4000169 0.1981801 0.9424578 -0.269545 0.1977846 0.9355555 -0.2956125 0.1932597 0.9362369 -0.2950438 0.1908133 0.9635135 -0.187429 0.1910814 0.9633377 -0.1860979 0.1932563 0.9632471 -0.1862338 0.1935771 0.9781935 -0.07518953 0.1936084 0.9778959 -0.07466238 0.1953078 0.9790968 -0.06725186 0.1919547 0.98061 0.03814721 0.1922206 0.9793797 0.03632408 0.1987358 0.9683261 0.1520844 0.198028 0.9699276 0.1477422 0.1934238 0.9696112 0.1468181 0.1957002 0.9458793 0.2590488 0.1954641 0.9460688 0.2595568 0.1938669 0.9462221 0.2573465 0.1960526 0.9462221 0.2573465 0.1960526 0.9462221 0.2573464 0.1960526 0.9107859 0.3632652 0.1962334 0.9111405 0.3648036 0.191681 0.8710243 0.4521287 0.192085 0.862822 0.4653089 0.1975499 0.862926 0.4661224 0.1951636 0.8043638 0.5611351 0.1952599 0.8043542 0.5621063 0.1924868 0.8048839 0.5601922 0.1958229 0.735125 0.6490292 0.1958377 0.7356698 0.6489133 0.1941689 0.7366977 0.6475647 0.1947732 0.6561332 0.729207 0.1942842 0.656227 0.7287524 0.1956683 0.5699182 0.7980148 0.1958718 0.5692083 0.7982978 0.1967806 0.5688792 0.7989347 0.1951408 0.4743742 0.8583697 0.195373 0.4738456 0.8594475 0.1918868 0.4783284 0.8557687 0.1971341 0.3733549 0.906442 0.197406 0.3730906 0.9068152 0.1961879 0.2693079 0.9428732 0.1961208 0.2674797 0.9431516 0.197281 0.2670131 0.9436812 0.1953713 0.1578485 0.9678282 0.1959397 0.1590538 0.9666429 0.200757 0.1585247 0.9668738 0.2000627 0.04601472 0.9788436 0.1993691 0.04696881 0.9794462 0.1961605 0.06512689 0.9780907 0.1977301 -0.06415933 0.9780115 0.1984371 -0.06560122 0.9789152 0.1934462 -0.1758798 0.9651753 0.1936566 -0.1756565 0.9652817 0.193329 -0.1768392 0.9655526 0.1908829 -0.2868538 0.9387529 0.1909398 -0.2844312 0.9379663 0.1982879 -0.2847275 0.937914 0.1981102 -0.38902 0.8996288 0.1983219 -0.390354 0.8999128 0.1943728 -0.4886083 0.8505107 0.1946626 -0.4898915 0.8494853 0.1959112 -0.4909747 0.849488 0.1931686 -0.58366 0.7885869 0.1935765 -0.5837502 0.7885813 0.1933274 -0.5853744 0.7878972 0.1911936 -0.5853744 0.7878971 0.1911936 -0.5853743 0.7878971 0.1911936 -0.6711291 0.7163475 0.1908717 -0.6698857 0.7165099 0.194594 -0.7256646 0.6598877 0.1948308 -0.7256652 0.6598871 0.194831 -0.7256643 0.659888 0.1948309 -0.7464721 0.6354016 0.1975961 -0.7470342 0.6352317 0.1960117 -0.8148009 0.5457853 0.1954939 -0.814442 0.5469915 0.1936092 -0.8136224 0.5475768 0.1953931 -0.8723056 0.4484054 0.1949757 -0.872331 0.4482454 0.19523 -0.8698011 0.4521169 0.1975767 -0.8698011 0.4521168 0.1975767 -0.9165655 0.3479222 0.1971242 -0.9174448 0.3472515 0.1941948 -0.950457 0.2426596 0.1942878 -0.9505642 0.2411187 0.1956771 -0.95056 0.2411313 0.1956816 -0.9719856 0.1303913 0.195556 -0.9726577 0.1296774 0.1926671 -0.9727482 0.129585 0.192272 -0.981117 0.01902234 0.1924777 -0.9811874 0.01904588 0.1921162 -0.9771925 -0.09072262 0.1920009 -0.9767319 -0.09382438 0.1928521 -0.9755222 -0.09165483 0.1998899 -0.9582505 -0.2050093 0.1993169 -0.9592825 -0.2033321 0.1960437 -0.9590868 -0.2019072 0.1984588 -0.929259 -0.3116883 0.1983138 -0.9299269 -0.3111278 0.1960501 -0.9288228 -0.3153061 0.194603 -0.8887655 -0.4148095 0.1950103 -0.88908 -0.4168877 0.1890544 -0.8380714 -0.5117575 0.1890522 -0.8350242 -0.5149867 0.1937091 -0.8351637 -0.5135915 0.1967878 -0.7708112 -0.6058082 0.1970959 -0.7706292 -0.6074787 0.1926145 -0.7719501 -0.6050281 0.1950236 -0.697858 -0.6891956 0.1949449 -0.6976245 -0.6907312 0.1902906 -0.6165015 -0.7640137 0.1902868 -0.6132757 -0.7661663 0.1920472 -0.6139266 -0.7643908 0.1969798 -0.5224275 -0.8296238 0.1969619 -0.5223476 -0.8299536 0.1957804 -0.5207381 -0.8317611 0.1923681 -0.425756 -0.8842409 0.1919631 -0.4246615 -0.884087 0.1950715 -0.4108387 -0.8911595 0.1924741 -0.3212217 -0.9272127 0.1925968 -0.3211737 -0.927233 0.1925786 -0.2164371 -0.9571172 0.1925662 -0.2136385 -0.957041 0.1960389 -0.2130494 -0.9574968 0.1944475 -0.1026012 -0.975547 0.1943739 -0.1031259 -0.9750585 0.1965349 -0.09766131 -0.976513 0.192054 0.00868231 -0.9812936 0.1923214 0.008637249 -0.9812729 0.1924287 0.1157904 -0.974432 0.1925483 0.121627 -0.9729754 0.1962796 0.121895 -0.9730876 0.1955563 0.2308806 -0.9530993 0.1956937 0.2317578 -0.9534163 0.1930952 0.231002 -0.9533738 0.1942076 0.3371807 -0.9211608 0.1943503 0.3369983 -0.9211115 0.1948994 0.4414008 -0.8759056 0.19482 0.4423652 -0.8760259 0.192072 0.538596 -0.8203797 0.1920718 0.1958407 -0.80835 0.5551728 0.1967216 -0.8094643 0.5532343 0.1032964 -0.826413 0.5535084 0.1017005 -0.8240913 0.5572527 0.007347345 -0.8302863 0.5572889 0.00749576 -0.8305361 0.5569146 -0.08685147 -0.8257933 0.5572453 -0.08678424 -0.8258772 0.5571314 -0.1809396 -0.8105416 0.5570307 -0.1811422 -0.8098961 0.5579032 -0.2716441 -0.7841193 0.5580023 -0.2712563 -0.7868126 0.5543882 -0.3603503 -0.7502362 0.5543405 -0.3603134 -0.7506933 0.5537453 -0.443867 -0.7048265 0.553355 -0.4436531 -0.7030341 0.5558013 -0.5195785 -0.6490758 0.5556429 -0.518932 -0.6460067 0.5598081 -0.5895114 -0.5822309 0.5598959 -0.590984 -0.5864402 0.5539187 -0.6544492 -0.5144551 0.554105 -0.6537384 -0.512788 0.5564841 -0.7068653 -0.4359123 0.5570656 -0.7067213 -0.4357002 0.557414 -0.7522037 -0.3511493 0.5575695 -0.7525691 -0.3515878 0.5567996 -0.7876059 -0.2635401 0.5569773 -0.7899245 -0.2657934 0.5526059 -0.8154202 -0.1728298 0.552467 -0.8157131 -0.1730799 0.5519562 -0.8300663 -0.07978773 0.5519276 -0.8268228 -0.07775443 0.5570622 -0.8305709 0.01624608 0.5566759 -0.8329294 0.01497083 0.5531768 -0.825496 0.110809 0.5534237 -0.8249185 0.1109763 0.5542507 -0.8069368 0.2046459 0.5540515 -0.8075629 0.2045482 0.5531747 -0.7785136 0.2954854 0.5537192 -0.7784613 0.2954568 0.5538081 -0.7406051 0.3805859 0.5537675 -0.7386947 0.3806422 0.5562748 -0.6899373 0.4633691 0.5561255 -0.6916739 0.463613 0.55376 -0.6341022 0.5396931 0.5537562 -0.6345837 0.5398496 0.5530517 -0.5694503 0.6078302 0.5534156 -0.5684511 0.607408 0.5549045 -0.4947987 0.668571 0.555146 -0.4946011 0.6684788 0.5554331 -0.4152708 0.7200891 0.5558974 -0.4143576 0.7195401 0.557288 -0.3295411 0.762038 0.5574056 -0.3316068 0.7638269 0.5537198 -0.2433687 0.7964042 0.5536354 -0.2412504 0.7942277 0.5576743 -0.1485678 0.8164012 0.5580474 -0.1498401 0.8181024 0.5552085 -0.05445742 0.83004 0.5550387 -0.05567342 0.832147 0.5517537 0.03993672 0.8327882 0.5521495 0.04052495 0.8314316 0.5541474 0.1339855 0.8215625 0.5541509 0.1336269 0.8228087 0.5523856 0.2274035 0.8018587 0.552549 0.2279595 0.7993806 0.5559003 0.2279594 0.7993807 0.5559003 0.2279595 0.7993807 0.5559003 0.316433 0.7682488 0.5564747 0.3163709 0.7691733 0.5552314 0.4022034 0.7277927 0.555473 0.4022366 0.7294525 0.5532674 0.4835815 0.6782175 0.5533263 0.4834835 0.6771296 0.5547426 0.5562737 0.6183164 0.5551976 0.556056 0.6174756 0.5563502 0.6231164 0.5496582 0.5564187 0.6241234 0.5521019 0.5528594 0.6833278 0.4767066 0.5530045 0.6827584 0.475698 0.5545741 0.7323092 0.3948878 0.5547854 0.7320261 0.394498 0.555436 0.7721883 0.3079742 0.5557672 0.7733554 0.3093674 0.5533655 0.8032101 0.2199571 0.5535995 0.8019084 0.2188819 0.555908 0.8217834 0.1251635 0.5558832 0.8227757 0.125863 0.5542553 0.8319792 0.03238201 0.5538611 0.8303104 0.0314871 0.5564112 0.82837 -0.06326681 0.5565972 0.8291009 -0.06291323 0.5555481 0.8162395 -0.1576606 0.5557845 0.817075 -0.1574354 0.5546194 0.7935044 -0.250711 0.5545222 0.7939875 -0.2506575 0.5538547 0.7606759 -0.3391119 0.553512 0.7592993 -0.3391266 0.5553898 0.7159671 -0.4228367 0.555518 0.7168453 -0.4228887 0.5543447 0.6640828 -0.5017358 0.5543061 0.6639433 -0.5017284 0.5544798 0.6022961 -0.5743313 0.5544214 0.6030504 -0.5745441 0.55338 0.5326522 -0.6403828 0.5533457 0.5342095 -0.6409923 0.5511344 0.4580388 -0.6974508 0.5511469 0.4562813 -0.6963784 0.5539536 0.3746446 -0.7434145 0.5540546 0.3723469 -0.7416739 0.5579227 0.2852978 -0.7794537 0.557725 0.2868251 -0.7808584 0.55497 0.1315122 -0.5411124 0.8306034 0.1305258 -0.5395929 0.8317466 0.06802213 -0.5511785 0.8316101 0.06936448 -0.5538747 0.8297057 0.005035161 -0.5580697 0.8297787 0.005165219 -0.5583976 0.8295574 -0.05836516 -0.555447 0.8295012 -0.05876451 -0.553622 0.8306922 -0.1215258 -0.5433793 0.8306446 -0.1212172 -0.5459417 0.829008 -0.1822996 -0.5287911 0.8289432 -0.1822848 -0.5252721 0.8311808 -0.2405192 -0.5010839 0.8313035 -0.2404319 -0.5003722 0.8317574 -0.2963342 -0.4695192 0.8317078 -0.2972053 -0.4732714 0.8292667 -0.3499389 -0.435659 0.8293033 -0.3500843 -0.4360155 0.8290545 -0.3969371 -0.3939389 0.8290073 -0.3948972 -0.3897681 0.8319478 -0.4364995 -0.3424019 0.8320031 -0.4383532 -0.345318 0.8298205 -0.4750317 -0.292869 0.8298027 -0.4739683 -0.2915798 0.8308642 -0.5043853 -0.2356446 0.8307029 -0.5054977 -0.2367395 0.8297147 -0.5290153 -0.1780104 0.829732 -0.5258862 -0.1756398 0.8322227 -0.5422804 -0.1150692 0.8322808 -0.542198 -0.1150078 0.8323429 -0.5519729 -0.05187165 0.8322472 -0.5562918 -0.05388367 0.8292383 -0.5584393 0.01009732 0.8294839 -0.55465 0.01127892 0.8320073 -0.5498394 0.07399344 0.8319866 -0.5497776 0.07394969 0.8320313 -0.5376385 0.136214 0.8321001 -0.5398687 0.1359279 0.8307018 -0.5207543 0.1976696 0.8305069 -0.5216395 0.1977241 0.8299383 -0.4958015 0.2554243 0.8300238 -0.4938918 0.255172 0.831239 -0.4618086 0.3095659 0.8312051 -0.4641891 0.3101382 0.8296642 -0.4251999 0.3617483 0.8296646 -0.4244261 0.3614319 0.8301985 -0.3810447 0.4071921 0.8300601 -0.3776641 0.4053652 0.8324956 -0.3296707 0.4455621 0.8323411 -0.3330569 0.4478331 0.8297702 -0.2785569 0.4836918 0.8297279 -0.279556 0.4846014 0.8288607 -0.2228268 0.5131822 0.82885 -0.2210204 0.5112375 0.8305337 -0.1617881 0.5326666 0.8307173 -0.1617467 0.5325717 0.830786 -0.100304 0.5476366 0.8306825 -0.09989237 0.5468453 0.8312532 -0.03711062 0.5547158 0.8312119 -0.03703975 0.5545186 0.8313466 0.02707076 0.5554081 0.8311372 0.02683287 0.5561862 0.8306245 0.08928316 0.5497747 0.8305277 0.08962041 0.5479868 0.8316723 0.1522243 0.533836 0.8317734 0.151991 0.5376296 0.8293692 0.2125622 0.5168544 0.829264 0.2124252 0.5145576 0.8307263 0.268868 0.4875322 0.8306758 0.2687878 0.4871199 0.8309438 0.3233543 0.4528559 0.8308812 0.3236293 0.4539261 0.8301899 0.3730615 0.4143208 0.8301588 0.3722267 0.4122828 0.8315469 0.4162178 0.3681822 0.8313873 0.4169189 0.36947 0.8304641 0.4569886 0.3183681 0.830544 0.4560188 0.317071 0.8315725 0.488816 0.2634363 0.8316611 0.4908085 0.2655208 0.8298228 0.5181449 0.2073001 0.8297907 0.5163593 0.2056815 0.8313051 0.5364894 0.1464261 0.8311069 0.5367421 0.146569 0.8309185 0.5500072 0.08414489 0.8309103 0.5507962 0.08456492 0.8303448 0.5567711 0.02114534 0.8303968 0.5554967 0.02060431 0.8312634 0.5541604 -0.04208171 0.8313456 0.553855 -0.04212379 0.8315469 0.545538 -0.1051387 0.831465 0.5459002 -0.1050356 0.8312404 0.5301263 -0.1673707 0.831236 0.5318769 -0.1673072 0.8301297 0.509052 -0.2273931 0.8301557 0.5096486 -0.22743 0.8297794 0.4807825 -0.2836216 0.8297029 0.4789158 -0.2832312 0.8309151 0.444028 -0.335484 0.8308367 0.4438607 -0.3355076 0.8309167 0.4028424 -0.3838574 0.830886 0.4018493 -0.383327 0.8316115 0.3556045 -0.4267255 0.8315352 0.3538542 -0.4256224 0.8328461 0.3033954 -0.4631036 0.8327583 0.3044446 -0.4638334 0.8319689 0.248906 -0.4958429 0.831977 0.2510327 -0.4978872 0.8301151 0.1921712 -0.5232101 0.8302539 0.1917648 -0.5227081 0.8306639 0.04595559 -0.1900164 0.9807049 0.04620367 -0.1904216 0.9806146 0.02433729 -0.1943834 0.9806237 0.02381461 -0.19319 0.9808724 0.001802027 -0.1947646 0.9808483 0.001866161 -0.1949917 0.9808032 -0.02058988 -0.1939483 0.9807956 -0.02056419 -0.1940692 0.9807723 -0.04228961 -0.1904708 0.9807816 -0.04235947 -0.1894784 0.9809707 -0.06366306 -0.1834572 0.9809641 -0.06367176 -0.183963 0.9808688 -0.08435273 -0.1755313 0.9808535 -0.08441692 -0.175918 0.9807786 -0.1037673 -0.1652231 0.9807822 -0.103628 -0.1647543 0.9808758 -0.1218754 -0.151786 0.9808709 -0.1217356 -0.1515457 0.9809253 -0.1383851 -0.1365526 0.9809195 -0.1391622 -0.1380511 0.9805997 -0.1540214 -0.1213241 0.9805906 -0.1529492 -0.119834 0.9809417 -0.165541 -0.1018482 0.9809298 -0.1657086 -0.1020277 0.9808828 -0.1762744 -0.08254098 0.9808743 -0.1766486 -0.08291578 0.9807754 -0.1851481 -0.06182783 0.9807637 -0.1858369 -0.06231254 0.9806029 -0.1917362 -0.04068279 0.980603 -0.1912328 -0.0404281 0.9807119 -0.1945886 -0.01883882 0.9807041 -0.1941439 -0.01867711 0.9807953 -0.1950671 0.003987312 0.9807818 -0.1957791 0.003748536 0.9806409 -0.1940829 0.02612149 0.9806373 -0.1936796 0.02616775 0.9807158 -0.1895434 0.04774296 0.980711 -0.18919 0.04775518 0.9807786 -0.1824526 0.06914526 0.9807803 -0.1823462 0.06912606 0.9808015 -0.1733545 0.08955067 0.9807798 -0.1729939 0.08948653 0.9808493 -0.1619564 0.1082155 0.9808464 -0.1609206 0.1078905 0.9810526 -0.1475309 0.125616 0.9810481 -0.1483232 0.1259777 0.9808822 -0.1326775 0.1423948 0.9808774 -0.1335662 0.1429243 0.9806797 -0.1167791 0.1570183 0.9806671 -0.1162683 0.1566424 0.9807878 -0.09749561 0.1689593 0.9807892 -0.09722566 0.1687132 0.9808584 -0.07728046 0.1787259 0.9808592 -0.07797175 0.1795604 0.9806522 -0.05688226 0.1873776 0.9806396 -0.05633115 0.1864909 0.9808405 -0.03500819 0.1916705 0.9808348 -0.0350731 0.1917331 0.9808202 -0.01299113 0.1945646 0.9808037 -0.01308321 0.1947699 0.9807617 0.009402155 0.1949359 0.980771 0.009338319 0.195161 0.9807268 0.03153955 0.1928269 0.9807258 0.0316621 0.1918225 0.9809189 0.05291092 0.1871711 0.9809014 0.05289947 0.1873996 0.9808584 0.07432496 0.1800031 0.9808542 0.07436627 0.1805048 0.9807588 0.09432989 0.1709486 0.980754 0.09412181 0.1700337 0.9809331 0.1128162 0.1582101 0.9809395 0.1128247 0.158242 0.9809334 0.1302585 0.144307 0.9809221 0.1307826 0.1454037 0.9806904 0.1462796 0.1296195 0.9807146 0.1455632 0.1284983 0.9809687 0.1594453 0.1108515 0.9809635 0.160403 0.1120444 0.9806717 0.1720502 0.09308999 0.9806799 0.1713235 0.09235823 0.9808763 0.1808365 0.07204359 0.980871 0.1815561 0.07263362 0.9806945 0.1886065 0.05149137 0.980702 0.1878579 0.0510798 0.9808671 0.1924911 0.0295692 0.9808531 0.1933711 0.02997875 0.9806677 0.19546 0.007236421 0.9806851 0.1950085 0.007097065 0.9807759 0.1946116 -0.01479566 0.9807689 0.194096 -0.01490384 0.9808694 0.1911577 -0.03677517 0.9808701 0.1907218 -0.03681159 0.9809538 0.1853036 -0.05828404 0.9809514 0.1860429 -0.05828791 0.9808112 0.1779707 -0.07941722 0.9808259 0.178304 -0.07946449 0.9807615 0.1680719 -0.09938997 0.9807515 0.16754 -0.09925568 0.9808561 0.155288 -0.1173952 0.980869 0.1554777 -0.1174504 0.9808324 0.1410331 -0.1345264 0.9808223 0.1415203 -0.134777 0.9807177 0.1248977 -0.150252 0.9807268 0.1246972 -0.1501013 0.9807754 0.1070862 -0.1631728 0.9807687 0.1072407 -0.1633095 0.9807291 0.08798778 -0.1745239 0.9807139 0.08805799 -0.174625 0.9806895 0.06737124 -0.1836186 0.9806863 0.0672537 -0.1834608 0.9807237 0.3265824 0.9451687 0 -0.3272798 -0.9449276 0 0.9133071 -0.4072716 0 -0.407221 -0.9132993 0.007448971 -0.979639 0.2007673 0 -0.9892243 -0.1464082 0 -0.9892243 -0.1464084 0 -0.9484466 -0.3169373 0 -0.9484627 -0.3168891 0 -0.8791719 -0.4765048 0 -0.8791605 -0.4765259 0 -0.7836734 -0.6211731 0 -0.7836732 -0.6211736 0 -0.5239619 -0.8517417 0 -0.5239735 -0.8517346 0 -0.3676111 -0.9299797 0 -0.913345 0.4071867 0 0.4080446 0.9129304 0.007608592 0.9796333 -0.2007947 0 0.9892244 0.146407 0 0.9892168 0.1464596 0 0.9488002 0.315877 0 0.9488 0.3158774 0 0.8791626 0.476522 0 0.8791738 0.4765012 0 0.7836702 0.6211772 0 0.7836829 0.6211611 0 0.5234591 0.8520508 0 0.5234708 0.8520437 0 0.3676126 0.9299791 0 0.3265394 0.9451836 0 0.1996569 0.979866 0 0.199657 0.9798659 0 0.02767896 0.9996169 0 0.02767705 0.9996169 0 -0.1464257 0.9892217 0 -0.3158829 0.9487982 0 -0.3158934 0.9487947 0 -0.4764954 0.879177 0 -0.621888 0.7831063 0 -0.6218715 0.7831193 0 -0.7479889 0.6637114 0 -0.747972 0.6637304 0 -0.8520669 0.523433 0 -0.8520518 0.5234577 0 -0.9133037 0.4072791 0 -0.9303753 0.3665887 0.003826737 -0.9456402 0.3252147 0 -0.9796338 0.2007929 0 -0.3272777 -0.9449282 0 -0.1994444 -0.9799093 0 -0.02770066 -0.9996163 0 0.1464306 -0.989221 0 0.315865 -0.9488041 0 0.3158752 -0.9488008 0 0.4765098 -0.8791692 0 0.6218766 -0.7831153 0 0.6218934 -0.7831019 0 0.7479718 -0.6637305 0 0.7480059 -0.6636921 0 0.8520517 -0.5234578 0 0.8520365 -0.5234825 0 0.9133518 -0.4071716 0 0.9299724 -0.3676105 0.003733634 0.9449469 -0.327224 0 0.979644 -0.2007432 0 -0.9542589 -0.2989816 0 -0.9999537 0.009632647 0 -0.9999542 0.009578824 0 -0.909283 0.4161784 0 -0.9092932 0.4161562 0 -0.6618301 0.7496539 0 -0.6618034 0.7496775 0 -0.3003324 0.9538346 0 0.1142544 0.9934516 0 0.1142509 0.993452 0 0.5086542 0.860971 0 0.5086554 0.8609703 0 0.8150398 0.579405 0 0.8150133 0.5794424 0 0.9801166 0.1984228 0 0.9801217 0.1983976 0 0.97605 -0.2175466 0 0.8034337 -0.5953944 0 0.8034582 -0.5953612 0 0.4904337 -0.8714786 0 0.490435 -0.8714779 0 0.09497725 -0.9954794 0 0.0949794 -0.9954792 0 -0.3187553 -0.9478372 0 -0.3187487 -0.9478394 0 -0.6763851 -0.7365482 0 -0.6763717 -0.7365606 0 -0.8702838 -0.4925507 0 -0.9168766 -0.3977276 -0.03391402 0.8142404 0.5805279 0 0.8146238 0.5799897 -3.3505e-4 0.5091737 0.8606638 0 0.5098844 0.8602429 3.82614e-4 0.507238 0.861806 -2.51226e-4 0.5077547 0.8615018 0 0.1142601 0.9934509 0 -0.2992399 0.954178 0 -0.2992415 0.9541774 0 -0.6618435 0.7496421 0 -0.66179 0.7496892 0 -0.9096271 0.4154258 0 -0.9094908 0.4157242 -8.4054e-5 -0.9093776 0.4159716 0 -0.999929 0.01192313 0 -0.999929 0.01192313 0 -0.999929 0.01192313 0 -0.9999541 0.009590387 1.39537e-4 -0.9999556 0.009422779 0 -0.9546447 -0.2977476 0 -0.9537099 -0.300728 -5.41867e-4 -0.9168567 -0.3977728 -0.03392338 -0.8703297 -0.4924696 0 -0.6770402 -0.7359461 0 -0.6770133 -0.7359707 0 -0.3178005 -0.9481576 0 -0.3183814 -0.9479628 -1.8828e-4 -0.3189499 -0.9477717 0 0.09498351 -0.9954789 0 0.09498816 -0.9954785 0 0.4918518 -0.870679 0 0.8034558 -0.5953644 0 0.8160391 0.5779968 0 0.9801162 0.1984248 0 0.976188 -0.2169266 0 0.976039 -0.2175957 -3.00217e-4 0.975674 -0.2192267 0 0.8034546 -0.595366 0 -0.9999542 0.009578883 0 0.5086715 0.8609607 3.76906e-4 0.5104635 0.8598995 0 0.1142575 0.9934512 0 -0.3003248 0.953837 0 -0.3003233 0.9538375 0 -0.6617957 0.7496842 0 -0.6618473 0.7496387 0 -0.9095864 0.415515 0 -0.9093016 0.4161377 -2.49079e-4 -0.9089294 0.41695 0 -0.9999536 0.009632647 0 -0.9542894 -0.2988841 0 -0.9168764 -0.3977275 -0.03391736 -0.8713531 -0.4906561 -7.18608e-4 -0.8695247 -0.4938895 0 -0.676976 -0.7360051 0 -0.677041 -0.7359454 -2.60809e-5 -0.6773356 -0.7356742 0 -0.3177657 -0.9481694 0 -0.3173108 -0.9483217 1.47999e-4 -0.3168876 -0.9484631 0 0.09378099 -0.9955929 0 0.4918352 -0.8706884 0 0.4918825 -0.8706616 0 0.5079499 0.8613867 0 0.8150293 0.5794197 0 0.9801257 0.1983772 0 0.9801162 0.1984248 1.68271e-5 0.9801001 0.1985039 0 0.9763043 -0.2164025 0 0.9761879 -0.2169265 1.74763e-4 0.975844 -0.2184684 -1.3829e-4 0.9756312 -0.2194174 0 -0.9999414 0.01082551 0 -0.9099583 0.4147 0 -0.909938 0.4147445 0 -0.6612328 0.7501808 0 -0.661208 0.7502028 0 -0.2995706 0.9540742 0 -0.2995861 0.9540694 0 0.1142662 0.9934502 0 0.5081296 0.8612806 0 0.5081061 0.8612945 0 0.8146234 0.5799905 0 -0.8702538 -0.492601 -0.001650154 -0.8714492 -0.490483 -0.001652836 -0.9167593 -0.3980523 -0.03326952 -0.9535623 -0.3011957 0 -0.9999415 0.01082557 0 -0.9225898 -0.3857825 0 -0.6761626 -0.7367525 0 -0.6761608 -0.7367542 0 -0.3184256 -0.9479479 0 0.09474021 -0.9955021 0 0.09473466 -0.9955026 0 0.4916031 -0.8708194 0 0.49158 -0.8708324 0 0.8028633 -0.5961631 0 0.802888 -0.5961301 0 0.976045 -0.2175693 0 0.9804799 0.1966193 0 0.9805011 0.1965135 0 0.9797644 0.2001546 0 0.9797437 0.2002558 0 0.9760563 -0.217518 0 0.1142597 0.9934509 5.38514e-5 0.1143072 0.9934455 0 -0.2992323 0.9541804 0 -0.662482 0.7490779 0 -0.6625087 0.7490543 0 -0.9091117 0.4165523 0 -0.9092934 0.4161559 2.08684e-4 -0.909823 0.4149966 0 -0.9168574 -0.3977703 -0.03393447 -0.8689189 -0.4949538 8.37376e-4 -0.8711538 -0.4910103 0 -0.676189 -0.7367283 0 -0.6767103 -0.7362493 -4.00633e-4 -0.681169 -0.7321262 0 -0.31788 -0.948131 0 -0.3181808 -0.9480301 -5.38011e-5 -0.3182549 -0.9480053 0 0.09486186 -0.9954905 0 0.09486395 -0.9954903 0 0.4915686 -0.870839 0 0.110257 0.9939031 0 0.5086479 0.8609747 0 0.8150421 0.5794019 0 0.9801135 0.1984382 0 0.9763312 -0.2162809 0 0.976039 -0.2175957 3.46469e-4 0.9758442 -0.2184678 0 0.8132244 -0.5819503 1.64541e-7 0.8132258 -0.5819485 1.65327e-6 0.8132231 -0.5819522 0 0.8032711 -0.5956137 -1.21218e-4 0.8031706 -0.5957491 0 0.8144586 0.5802218 2.62209e-4 0.8147728 0.5797804 0 0.5077607 0.8614982 0 0.5077683 0.8614937 6.73442e-6 0.5077343 0.8615137 0 0.1142627 0.9934507 5.38529e-5 0.1143041 0.9934459 0 -0.2995937 0.9540669 0 -0.2995798 0.9540712 0 -0.6612157 0.7501959 0 -0.9100005 0.4146073 0 -0.9095009 0.4157015 -5.68211e-4 -0.9079159 0.4191524 0 -0.9999534 0.009644269 -6.29496e-4 -0.9999427 0.01071304 0 -0.9530984 -0.3026608 0 -0.9542644 -0.2989632 7.31964e-4 -0.9168884 -0.3977596 -0.03321164 -0.8713156 -0.4907231 0 -0.6764369 -0.7365007 0 -0.6764235 -0.736513 0 -0.3162773 -0.9486668 0 -0.3176512 -0.9482077 -2.28971e-4 -0.318129 -0.9480475 0 0.09378725 -0.9955924 0 0.09378767 -0.9955922 0 0.4918634 -0.8706725 0 0.8133465 0.5817797 0 0.9803512 0.1972605 0 0.9803459 0.1972864 0 0.9762957 -0.2164416 0 0.9763013 -0.216416 0 0.758772 -0.6513565 0 0.7587718 -0.6513565 0 0.758772 -0.6513563 0 0.8028878 -0.59613 4.84352e-4 0.8033444 -0.5955148 0 0.9571047 0.2897427 0 0.9571049 0.2897418 0 0.7769992 0.6295016 0 0.4793738 0.8776108 0 0.4794203 0.8775855 0 0.4813325 0.8765382 0 0.4816901 0.8763417 2.92406e-5 0.4817097 0.8763309 0 0.1141881 0.9934592 0 0.1141937 0.9934586 0 -0.2691895 0.9630873 0 -0.2695682 0.9629814 3.48847e-5 -0.2696201 0.9629668 0 -0.6300334 0.7765681 0 -0.6137436 0.7895054 1.86056e-4 -0.6135342 0.7896682 0 -0.8662973 0.499529 0 -0.8663173 0.4994941 0 0.9949863 0.1000112 0 0.9949895 0.09997987 -6.66953e-6 0.9953663 0.09613108 0.002166748 0.9950863 0.09901219 0 -0.1248129 0.6970589 0.706067 -0.1247349 0.6970523 0.7060874 -0.1247783 0.6970561 0.706076 -0.1248356 0.6970545 0.7060674 -0.2307071 0.6695041 0.7060727 -0.2306323 0.6695478 0.7060557 -0.4233248 0.5677059 0.7060496 -0.4235637 0.5676174 0.7059777 -0.4235196 0.5676617 0.7059684 -0.4233557 0.5677422 0.706002 -0.3312203 0.6259636 0.7060189 -0.3309766 0.6260187 0.7060844 -0.3310073 0.6259657 0.706117 -0.2305172 0.6695623 0.7060794 -4.40259e-6 0 1 1.47255e-6 0 1 -0.5184385 0.8551151 0 -0.1567261 0.9876422 0 -0.1568132 0.9876284 7.97377e-5 -0.1641422 0.9864367 0 -0.5184797 0.85509 0 -0.8019411 0.5974033 0 -0.8035448 0.5952443 -2.74836e-4 -0.8034104 0.5954256 -3.14495e-4 -0.8030748 0.5958783 0 -0.9687506 0.248037 0 -0.9687365 0.2480919 0 -0.9695397 0.2449348 0 -0.9695117 0.2450454 0 -0.9695117 0.2450453 0 -0.9695117 0.2450453 0 -0.9907017 -0.136052 0 -0.9907079 -0.1360064 0 -0.8657242 -0.5005214 0 -0.8657451 -0.5004853 0 0.4101917 0.9119994 0 0.4104342 0.9118902 6.38078e-5 0.4103347 0.911935 9.00647e-5 0.4108287 0.9117125 3.39511e-4 -0.6656134 0.2411739 0.7062535 -0.6680209 0.2368906 0.7054297 -0.6660755 0.240601 0.7060132 -0.6663177 0.2404261 0.7058443 -0.6950424 0.1366216 0.7058687 -0.6953219 0.134733 0.7059565 -0.6950427 0.1350853 0.706164 -0.6949075 0.1370356 0.7059213 -0.7077106 0.02621173 0.706016 -0.7078342 0.02595764 0.7059015 -0.7077558 0.02627539 0.7059684 -0.7034572 -0.0828973 0.7058866 -0.7034403 -0.08285307 0.7059088 -0.7031659 -0.08387464 0.7060616 -0.7076251 0.0264787 0.7060918 0.866245 -0.4996196 0 -0.9571395 -0.2896274 0 -0.9571336 -0.2896472 0 -0.7770106 -0.6294875 0 -0.480952 -0.8767469 0 -0.4809706 -0.8767368 0 -0.1146307 -0.9934082 0 -0.1147574 -0.9933935 -7.02494e-5 -0.1133748 -0.9935523 -2.83891e-4 -0.1103922 -0.9938881 0 0.2690935 -0.9631141 0 0.6644619 -0.7473222 0 0.6138645 -0.7894113 -6.16219e-4 0.6132284 -0.7899057 0 -1.01316e-6 0 1 1.57128e-6 0 1 -0.9338836 0.3575772 0 -0.933903 0.3575263 0 -0.9325966 0.3609205 0 -0.9325971 0.3609194 0 -0.9174305 -0.3978961 0 -0.6987541 -0.715362 0 -0.3762951 -0.9264999 0 -0.3761469 -0.9265601 0 -0.3775898 -0.9259731 0 -0.3776106 -0.9259645 0 -0.584022 0.8117378 0 -0.5840454 0.811721 2.03706e-4 -0.5410286 -0.4568459 0.7061019 -0.5413709 -0.4566957 0.7059367 -0.5411082 -0.4570841 0.7058867 -0.4646059 -0.5347536 0.7058186 -0.4648533 -0.5342896 0.7060072 -0.4646754 -0.5344106 0.7060327 -0.4643983 -0.5346641 0.706023 -0.3765118 -0.5998071 0.7060243 -0.3765458 -0.5998038 0.706009 -0.3764406 -0.5997965 0.7060713 -0.2789431 -0.6507988 0.7061528 -0.2799169 -0.6504242 0.7061125 -0.2800904 -0.6504552 0.7060151 -0.3758662 -0.6002332 0.7060062 0.9477314 -0.3190694 0 0.9463914 -0.3230214 7.42774e-4 0.9459269 -0.3243802 0 0.946336 -0.3231841 5.88674e-4 1.52512e-6 0 1 -5.52146e-7 0 1 -1.28816e-6 0 1 1.13646e-4 0 1 0.1247408 -0.696965 0.7061725 0.1250726 -0.6970425 0.7060374 0.1240776 -0.6970251 0.70623 0.1250275 -0.6972241 0.7058659 0.2305921 -0.6697874 0.7058414 0.2308421 -0.6695898 0.7059472 0.4238853 -0.5673822 0.7059736 0.4232221 -0.567667 0.7061425 0.4234175 -0.5674538 0.7061968 0.4236862 -0.5673598 0.7061111 0.3310464 -0.6259407 0.7061209 0.3309135 -0.6259613 0.7061649 0.3306769 -0.6262149 0.7060509 0.2306036 -0.6695984 0.706017 3.14911e-6 0 1 -1.44259e-6 0 1 3.68274e-6 0 1 -2.42554e-6 0 1 -2.24804e-6 0 1 -0.9997869 0.00435549 -0.02018457 -0.9992012 0.03739327 0.01410096 -0.9992294 0.03663176 0.01410108 -0.9855686 0.1685336 -0.01584565 -0.9815837 0.1907925 0.009578943 -0.9811967 0.1927729 0.009577155 -0.9443252 0.3288668 -0.009831964 -0.9406334 0.3394041 0.003721117 -0.9426483 0.3337669 0.003724575 -0.8775426 0.4794807 -0.00416404 -0.7863946 0.6177245 0 -0.7864019 0.6177152 0 -0.6962805 0.7177698 0 -0.6737996 0.7384563 -0.02600765 -0.5975958 0.8014552 0.02343118 -0.5432583 0.8392404 0.02336686 -0.5966681 0.7997595 -0.06612217 -0.4675652 0.8836258 0.02425259 -0.397679 0.9172056 0.02419507 -0.4659547 0.8812074 -0.07974827 -0.3254345 0.9452494 0.02441626 -0.3257022 0.9451568 0.02442598 -0.2411753 0.9700945 -0.02740919 -0.1762295 0.9840732 0.02330642 -0.1761087 0.9840949 0.0233075 -0.07828086 0.9965918 -0.02602088 -0.04780161 0.9988569 0 0.08690017 0.996217 0 0.08690172 0.996217 0 0.2467694 0.9690743 0 0.2496409 0.9683308 -0.00386846 0.3908207 0.92046 0.003555476 0.3953354 0.9185301 0.003545105 0.4056679 0.9139644 -0.01014208 0.5304077 0.8476921 0.009273946 0.5320079 0.8466887 0.009269833 0.5503749 0.8347762 -0.01537114 0.6553725 0.7551696 0.01434814 0.655826 0.754776 0.01433765 0.6803725 0.7325938 -0.01998919 0.764932 0.6438491 0.01837021 0.7640369 0.6449107 0.01838332 0.7916787 0.610483 -0.02356624 0.8264099 0.5630691 0 0.9472337 0.3205437 0 0.9758023 0.2186551 0 0.9867881 0.160259 -0.02379822 0.9929755 0.1169838 0.01773422 0.9930183 0.1166201 0.01773488 0.9997916 -0.003908038 -0.02003985 0.9991927 -0.03739291 0.0146963 0.9992209 -0.03663074 0.01469755 0.9855017 -0.1689699 -0.01535445 0.9815838 -0.1907924 0.009570419 0.9819927 -0.1886771 0.009569168 0.944329 -0.3288384 -0.01039499 0.9404801 -0.3398283 0.00372374 0.9425098 -0.334158 0.003721177 0.8775364 -0.4794923 -0.004167735 0.7863626 -0.6177653 0 0.6963258 -0.7177259 0 0.6739199 -0.7383502 -0.02590698 0.5983103 -0.8009296 0.02316766 0.5431538 -0.8393142 0.02314609 0.5966837 -0.7997052 -0.06663548 0.4673835 -0.8837306 0.0239368 0.4668289 -0.8840239 0.02393162 0.3975996 -0.9171344 -0.02791345 0.3255166 -0.9452222 0.02437168 0.3254364 -0.9452499 0.02436834 0.2412183 -0.9700874 -0.02728229 0.1764574 -0.9840323 0.02330994 0.1765676 -0.9840127 0.02330553 0.07836753 -0.9965799 -0.02621436 0.04766279 -0.9988635 0 -0.08711922 -0.9961979 0 -0.08711946 -0.9961979 0 -0.2464686 -0.9691509 0 -0.2495986 -0.9683404 -0.004197597 -0.3938795 -0.9191558 0.003389656 -0.3954967 -0.9184611 0.003401994 -0.4055925 -0.9139993 -0.009997844 -0.5307264 -0.8474904 0.009471237 -0.5316587 -0.8469057 0.009477853 -0.5504149 -0.8347445 -0.01565533 -0.6556398 -0.7549412 0.01415586 -0.6563079 -0.7543604 0.01415646 -0.6803585 -0.7326208 -0.0194717 -0.7637465 -0.6452549 0.01837831 -0.7639173 -0.6450525 0.01837736 -0.7916584 -0.6105033 -0.02372175 -0.8265764 -0.5628246 0 -0.8814341 -0.4723071 0 -0.9472342 -0.3205425 0 -0.9761229 -0.2172191 0 -0.9868015 -0.1602614 -0.02321892 -0.9929627 -0.1170036 0.01831096 -0.99279 -0.1184604 0.01831126 -3.67196e-6 0 1 7.51649e-7 0 1 -3.15812e-6 0 1 2.69849e-6 0 1 -5.99743e-6 0 1 -1.57277e-6 0 1 -0.4367709 0.8995728 0 0.8000673 -0.5999104 0 0.8000673 -0.5999104 0 0.8000671 -0.5999105 0 0.4268684 0.9043138 0 -0.9164748 0.4000927 0 -0.7956801 -0.6057172 0 -0.8071125 -0.5903979 0 -0.8568775 -0.5155202 0 -0.9173384 -0.3981084 0 -0.9173333 -0.3981204 0 -0.9860147 -0.1666591 0 -0.9672554 -0.2538051 0 -0.9622056 -0.2722203 -0.00751698 -0.9862915 -0.1649103 0.005809128 -0.8122545 0.5827235 -0.02599996 -0.7849417 0.6195696 0 -0.8830922 0.4691997 0 -0.7317607 0.6815617 0 -0.6604162 0.7507985 0.01233899 -0.6934278 0.7205259 -5.85926e-4 -0.7318562 0.6814591 0 -0.7578967 0.6523747 0 -0.7578867 0.6523863 0 -0.05243182 0.9982661 -0.02675509 -0.005241632 0.9999864 0 -0.1835407 0.9830121 0 -0.08589154 0.9947532 0.05557703 -0.1862757 0.9824976 0 0.07671827 0.9970528 0 0.3449145 0.9385634 0.01152092 0.2915866 0.9565444 0 0.1754182 0.984494 0 0.1735951 0.9848166 -0.001027822 0.07672715 0.9970521 0 0.03853815 0.9992572 0 0.03853791 0.9992572 0 0.7675473 0.6409924 0 0.7481213 0.6630316 -0.02652746 0.8214324 0.5688249 0.04107499 0.8320052 0.554768 0 0.8320052 0.5547679 0 0.8320052 0.554768 0 0.948974 0.3153529 -0.001014709 0.9495382 0.3136516 0 0.8788571 0.4770851 0 0.8780403 0.4785858 -9.52372e-4 0.831967 0.5548253 0 0.8051599 0.5930578 0 0.8051427 0.5930814 0 0.9925448 0.1218813 0 0.9833369 0.181793 0 0.9955773 0.09300798 -0.01324367 0.9775192 0.2106682 0.008669435 0.9833337 0.1818102 0 0.974456 0.2245784 0 0.9744561 0.2245784 0 0.9744561 0.2245785 0 0.9743403 0.2250804 0 0.9743402 0.2250806 0 0.9743402 0.2250807 1.92974e-7 0.9536103 -0.301044 0 0.9536102 -0.3010442 0 0.9536103 -0.3010441 0 0.8971322 -0.4406739 0.03099262 0.9207437 -0.3901682 0 0.8375822 -0.5463114 0 0.838278 -0.5452426 -7.20543e-4 0.7552593 -0.655426 0 0.5900633 -0.807357 0 0.8001106 -0.5998526 0 0.8001106 -0.5998526 0 0.8001105 -0.5998526 0 0.7552372 -0.6554515 0 0.7261461 -0.6874227 -0.01272886 0.6933653 -0.7205862 0 0.6576554 -0.7533189 0 0.5918666 -0.8060349 0.001327216 0.5900377 -0.8073757 7.72091e-5 0.1417255 -0.989906 0 0.09647107 -0.9953354 -9.93944e-4 0.05244201 -0.9983351 0.02402257 -0.0413841 -0.9991434 0 -0.2610792 -0.9652981 0.006111741 -0.2489863 -0.968507 0 -0.1308305 -0.9914048 0 -0.08447694 -0.9963443 -0.01271939 -0.04138505 -0.9991434 0 0.005029737 -0.9999874 0 0.005026102 -0.9999874 0 0.7675409 0.6410001 0 0.6531738 0.7572082 0 0.653994 0.7564997 -9.96012e-5 0.4709144 0.8821789 0 0.4709289 0.8821713 0 0.4268972 0.9043002 0 0.3770356 0.9261987 -5.50488e-4 0.3755391 0.9268066 0 0.6541721 0.7563458 0 0.5084441 0.861095 0 0.5475929 0.8367272 -0.005466341 0.5082965 0.8610993 -0.01195269 0.5055527 0.8627212 -0.01134771 -0.18608 0.9825347 1.10688e-4 -0.1865628 0.982443 0 -0.3120599 0.9500625 0 -0.3561064 0.9343671 -0.01209545 -0.6252095 0.7804571 0 -0.6251949 0.7804688 0 -0.5167969 0.8561081 0 -0.5187695 0.8549143 -7.97468e-5 -0.5173354 0.8557823 -9.11705e-4 -0.4369773 0.8994726 0 -0.3962459 0.9181445 0 -0.3962469 0.9181441 0 -0.9649153 0.2625614 0 -0.9915173 0.1299715 -9.88691e-4 -0.9918615 0.127321 -6.20141e-4 -0.8771724 0.4801242 0.007039368 -0.9164728 0.400097 0 -0.9373447 0.3484035 0 -0.9525443 0.304159 -0.01211589 -0.964908 0.2625886 0 -0.9743741 0.2249336 0 -0.9744656 0.2245367 0 -0.9918645 -0.1272988 0 -0.9916573 0.1289025 0 -0.9987463 -0.05005788 0 -0.9988193 -0.04857951 -2.69748e-4 -0.9987458 -0.0500645 -7.81758e-4 -0.9918613 -0.1273232 0 -0.9918613 -0.1273232 0 -0.9918613 -0.1273232 0 -0.9826743 -0.1853412 0 -0.9826772 -0.1853253 0 -0.719185 -0.6948181 -9.12185e-4 -0.7180535 -0.6959878 -3.40029e-4 -0.8468252 -0.5318455 -0.005235254 -0.7945708 -0.6071437 0.005838215 -0.8071013 -0.5904131 0 -0.7782955 -0.6278983 0 -0.7783572 -0.6278217 0 -0.5127652 -0.8585289 0 -0.3350974 -0.9421835 0 -0.3351116 -0.9421785 0 -0.4293057 -0.9031593 0 -0.3867578 -0.9218429 -0.02498275 -0.7193859 -0.6946107 0 -0.5834015 -0.812184 0 -0.5847846 -0.8111884 -6.62445e-4 -0.5836259 -0.8120223 -8.61112e-4 -0.512523 -0.8586735 0 -0.4678038 -0.8838323 0 -0.467796 -0.8838366 0 0.3562138 -0.9344045 0 0.4797848 -0.8770287 -0.02504885 0.4385267 -0.8987182 0 0.5897895 -0.8075571 0 0.1417348 -0.9899047 0 0.2711217 -0.9625452 0 0.2693349 -0.9630467 -6.16426e-5 0.2709884 -0.9625822 -9.14036e-4 0.355897 -0.9345253 0 0.3993096 -0.9168161 0 0.3993112 -0.9168155 0 0.9767883 -0.2138149 -0.0129593 0.9767885 -0.2138136 -0.01296514 0.9767885 -0.2138137 -0.0129652 0.976051 -0.2172094 -0.01202356 0.9850419 -0.1722247 -0.005589306 0.9328523 -0.3602592 0 0.9328523 -0.3602592 0 0.9328523 -0.3602592 0 0.9335821 -0.3583632 -6.21347e-4 0.9536408 -0.3009476 0 0.9536408 -0.3009476 0 0.9536408 -0.3009476 0 0.9658868 -0.2589646 0 0.9659085 -0.2588839 0 0.9758234 -0.2185607 0 0.9992019 -0.03994435 0 0.9992173 -0.03956025 1.67345e-4 0.9992893 -0.03769683 0 0.9925467 0.1218654 0 -0.4108359 -0.9117093 3.49217e-4 -0.4120975 -0.9111392 0.00107634 0.7032344 0.08285403 0.7061138 0.7032113 0.08281177 0.7061417 0.703277 0.08264744 0.7060955 0.7076223 -0.02627032 0.7061025 0.7076956 -0.02648133 0.7060211 0.7077459 -0.02624243 0.7059796 0.7077398 -0.02595359 0.7059963 0.6949032 -0.1370295 0.7059267 0.6950485 -0.1350724 0.7061609 0.6953209 -0.1347324 0.7059575 0.6954769 -0.1336475 0.7060102 0.6660224 -0.2406436 0.7060488 0.6660198 -0.2406636 0.7060444 0.6658856 -0.2408621 0.7061033 0.667448 -0.2367101 0.7060322 -0.1917113 0.9814514 0 -0.1936033 0.9810799 -3.40898e-4 -0.194236 0.9809549 0 -0.1935823 0.9810841 -2.73322e-4 0.9338951 -0.3575474 0 0.9339045 -0.3575226 0 0.9341794 -0.3568037 0 0.9341798 -0.3568026 0 0.9997842 0.02077895 0 0.9997846 0.02075558 0 0.6987511 0.7153649 0 0.6987496 0.7153664 0 0.3762866 0.9265033 0 0.3762881 0.9265027 0 0.3775817 0.9259763 0 0.3775922 0.925972 0 0.5838943 -0.8118297 0 0.5839287 -0.8118049 2.81338e-4 0.5842075 -0.8116043 0 0.2766183 0.6520492 0.7059138 0.2801448 0.6503291 0.7061097 0.2798334 0.6504226 0.706147 0.2799523 0.6504435 0.7060808 0.2798208 0.6505764 0.7060104 0.3756352 0.600381 0.7060036 0.3766643 0.5996356 0.7060887 0.3767675 0.5996249 0.7060427 0.3760862 0.6001903 0.7059255 0.4642109 0.5348876 0.705977 0.4646447 0.5344298 0.7060384 0.4644618 0.5345348 0.7060792 0.4645299 0.534388 0.7061455 0.5417348 0.4559826 0.7061185 0.5412711 0.4567204 0.7059972 0.5411549 0.4567828 0.7060461 -0.9464816 0.3227578 4.52048e-5 -0.9464142 0.3229554 0 -0.9460409 0.3240468 -7.0458e-4 -0.9461568 0.323708 -7.15249e-4 -0.9461568 0.323708 -7.15205e-4 -0.9461568 0.3237081 -7.15238e-4 -0.9465929 0.3224312 0 -0.7844053 -0.6202487 0 0.9301426 -0.3671987 0 0.3693056 0.929308 0 0.3693227 0.9293012 0 -0.6229067 0.7822962 0 -0.6229614 0.7822527 0 0.146442 -0.9892193 -6.75143e-6 0.1465 -0.9892107 0 0.622764 -0.7824099 0 0.6228146 -0.7823695 0 0.7824228 0.6227477 0 0.7825111 0.6226369 0 0.7835211 0.6213652 0 0.7835579 0.6213189 0 0.3672179 0.930135 0 0.3672548 0.9301204 0 -0.1475181 0.9890594 0 -0.1475339 0.9890571 0 -0.6153516 0.7882528 0 -0.6202448 0.7844083 -5.13285e-4 -0.6219832 0.7830306 0 -0.9894503 -0.1448729 0 -0.9894613 -0.144798 0 -0.9882975 -0.1525387 0 -0.9882706 -0.1527135 0 -0.7838168 -0.6209923 0 -0.7838445 -0.6209574 0 -0.3676228 -0.9299751 0 -0.3676598 -0.9299604 0 0.1464549 -0.9892174 0 6.38537e-6 0 -1 4.4018e-5 0 -1 4.42948e-6 0 -1 -3.60191e-6 0 -1 3.54524e-6 0 -1 -6.5241e-7 0 -1 4.03382e-6 0 -1 -3.54519e-6 0 -1 3.20453e-5 0 -1 -2.18723e-7 0 -1 6.52404e-7 0 -1 -4.11292e-6 0 -1 6.44596e-6 0 -1 3.24393e-6 0 -1 1.35487e-6 0 -1 3.54668e-6 0 -1 -1.40697e-5 0 -1 2.35889e-6 0 -1 1.58294e-6 0 -1 3.46443e-6 0 -1 -3.56092e-6 0 -1 -4.80543e-6 0 -1 -1.47796e-6 0 -1 -1.722e-6 0 -1 -7.35121e-6 0 -1 2.41057e-6 0 -1 7.67201e-6 0 -1 -1.80337e-6 0 -1 8.82208e-6 0 -1 -3.54841e-6 0 -1 1.35077e-6 0 -1 6.92406e-6 0 -1 -7.02721e-6 0 -1 -5.26316e-6 0 -1 1.07949e-5 0 -1 3.41803e-6 0 -1 -9.01437e-6 0 -1 -1.17025e-5 0 -1 2.33693e-6 0 -1 2.68109e-6 0 -1 -2.20798e-6 0 -1 1.46524e-6 0 -1 -1.70251e-6 0 -1 -7.14596e-7 0 -1 2.50642e-6 0 -1 1.31845e-6 0 -1 -1.23269e-6 0 -1 -1.65696e-6 0 -1 1.14124e-6 0 -1 -3.25309e-5 0 -1 3.54231e-6 0 -1 8.55945e-6 0 -1 -8.0683e-6 0 -1 -2.58761e-6 0 -1 -3.54022e-6 0 -1 1.84186e-6 0 -1 2.92694e-6 0 -1 -2.93572e-6 0 -1 3.54977e-6 0 -1 7.17237e-6 0 -1 -7.39033e-6 0 -1 -4.30037e-6 0 -1 -2.64884e-6 0 -1 2.74608e-6 0 -1 -3.27239e-7 0 -1 5.42017e-6 0 -1 2.58904e-6 0 -1 -4.13767e-6 0 -1 1.35199e-6 0 -1 -3.03706e-6 0 -1 -3.39572e-6 0 -1 -7.11035e-6 0 -1 -4.67412e-6 0 -1 1.29493e-6 0 -1 -1.48941e-6 0 -1 1.62667e-4 0 -1 1.62645e-4 0 -1 1.6275e-4 0 -1 -3.76631e-6 0 -1 -5.01288e-6 0 -1 2.62181e-6 0 -1 -9.97877e-6 0 -1 5.449e-5 0 -1 -3.76857e-5 0 -1 4.67582e-6 0 -1 4.80871e-6 0 -1 6.81595e-6 0 -1 9.69744e-5 0 -1 1.11074e-5 0 -1 -5.39174e-6 0 -1 -5.05766e-6 0 -1 7.4618e-6 0 -1 1.21336e-5 0 -1 7.59315e-7 0 -1 -4.74003e-6 0 -1 -3.25892e-5 0 -1 -1.19922e-6 0 -1 3.31038e-6 0 -1 -7.83199e-6 0 -1 2.21666e-6 0 -1 -9.45609e-7 0 -1 -2.63047e-6 0 -1 -2.2844e-6 0 -1 3.05691e-6 0 -1 -1.43367e-6 0 -1 0 0 -1 2.95351e-6 0 -1 8.0966e-7 0 -1 2.86293e-6 0 -1 1.02775e-5 0 -1 -1.19689e-5 0 -1 2.75749e-5 0 -1 -3.94471e-6 0 -1 2.07759e-6 0 -1 -5.05712e-6 0 -1 3.10574e-6 0 -1 -3.7461e-6 0 -1 -5.93542e-6 0 -1 -5.39072e-6 0 -1 -3.90031e-6 0 -1 6.10926e-6 0 -1 -9.7947e-6 0 -1 1.64374e-5 0 -1 -6.26994e-6 0 -1 -1.0881e-6 0 -1 3.76642e-6 0 -1 -3.75402e-7 0 -1 2.33594e-6 0 -1 2.23023e-5 0 -1 1.24789e-5 0 -1 3.74431e-6 0 -1 5.501e-5 0 -1 -5.15324e-7 0 -1 -6.39812e-6 0 -1 -1.495e-5 0 -1 -1.21473e-5 0 -1 1.51302e-5 0 -1 -8.4717e-5 0 -1 6.28097e-6 0 -1 -9.26718e-6 0 -1 2.06515e-5 0 -1 -4.02891e-6 0 -1 -1.91241e-6 0 -1 2.63269e-6 0 -1 1.42418e-5 0 -1 -6.04171e-6 0 -1 1.26134e-6 0 -1 -1.26284e-5 0 -1 1.04892e-5 0 -1 -1.02045e-5 0 -1 1.05245e-5 0 -1 -1.27346e-6 0 -1 4.22846e-6 0 -1 -1.1619e-6 0 -1 -3.26879e-6 0 -1 -5.07709e-6 0 -1 1.32795e-6 0 -1 -6.85035e-6 0 -1 -2.52725e-5 0 -1 -1.37467e-6 0 -1 1.06288e-6 0 -1 -3.59244e-6 0 -1 -5.68861e-6 0 -1 1.81686e-6 0 -1 3.76483e-6 0 -1 4.75475e-6 0 -1 -1.7324e-5 0 -1 9.46199e-6 0 -1 -1.7438e-6 0 -1 1.14183e-5 0 -1 1.05606e-6 0 -1 -4.15538e-6 0 -1 -2.82072e-6 0 -1 2.52505e-5 0 -1 3.83686e-6 0 -1 -1.82695e-6 0 -1 -6.95517e-6 0 -1 1.1422e-5 0 -1 2.02387e-6 0 -1 -2.30475e-6 0 -1 2.81773e-6 0 -1 1.21999e-5 0 -1 -1.0085e-5 0 -1 1.42189e-6 0 -1 -1.48792e-5 0 -1 6.5879e-7 0 -1 5.50394e-6 0 -1 5.46857e-7 0 -1 3.56593e-6 0 -1 9.71223e-6 0 -1 4.85032e-6 0 -1 1.76282e-6 0 -1 4.05218e-6 0 -1 -6.47078e-7 0 -1 -6.34655e-6 0 -1 1.61934e-6 0 -1 6.79707e-6 0 -1 -2.11007e-6 0 -1 0 0 -1 -6.42079e-6 0 -1 0.7862599 0.6178961 0 0.7818383 0.6234813 0 0.7819135 0.623387 0 -0.6202974 0.7843669 0 -0.9301615 0.3671507 0 -0.9889699 -0.1481169 0 -0.98897 -0.1481162 0 -0.9894606 -0.1448024 0 -0.9894785 -0.1446806 0 -0.9894784 -0.1446807 0 -0.9894785 -0.1446807 0 -0.7835027 -0.6213884 0 0.622933 -0.7822752 0 0.6229351 -0.7822736 0 0.9292725 -0.3693949 0 0.9293472 -0.369207 0 0.7862588 0.6178975 0 -6.46095e-6 0 1 -1.44857e-6 0 1 6.44828e-6 0 1 2.49103e-5 0 1 3.07958e-5 0 1 6.56237e-6 0 1 1.46062e-6 0 1 -1.25746e-6 0 1 -2.16117e-6 0 1 4.08871e-6 0 1 4.85286e-6 0 1 -2.19037e-6 0 1 1.01523e-5 0 1 -2.37556e-6 0 1 -9.28251e-6 0 1 1.45404e-5 0 1 1.70184e-6 0 1 1.96387e-4 0 1 1.96384e-4 0 1 1.96398e-4 0 1 3.73619e-6 0 1 -7.50942e-6 0 1 1.0116e-5 0 1 4.14504e-6 0 1 -1.42625e-5 0 1 5.22724e-6 0 1 -1.16398e-5 0 1 1.75119e-5 0 1 7.22794e-7 0 1 -1.76044e-5 0 1 9.92725e-7 0 1 1.98761e-6 0 1 -1.99569e-6 0 1 2.52461e-5 0 1 -1.82929e-5 0 1 -4.49002e-6 0 1 -2.58117e-5 0 1 -5.65185e-5 0 1 -2.88961e-6 0 1 3.01943e-6 0 1 6.94715e-6 0 1 -1.03619e-6 0 1 2.61654e-6 0 1 -2.01602e-6 0 1 1.99538e-6 0 1 -8.27349e-7 0 1 8.98944e-7 0 1 6.9403e-6 0 1 -5.77246e-6 0 1 -4.90725e-6 0 1 5.87034e-6 0 1 -2.2972e-6 0 1 -2.9541e-6 0 1 2.46521e-6 0 1 2.20848e-6 0 1 2.89218e-6 0 1 -8.78457e-6 0 1 -2.22717e-6 0 1 3.74122e-6 0 1 8.54502e-7 0 1 -1.07945e-5 0 1 5.26316e-6 0 1 9.75496e-7 0 1 -5.73289e-6 0 1 -8.06335e-6 0 1 1.07149e-5 0 1 -1.94511e-6 0 1 -3.41434e-6 0 1 2.97924e-6 0 1 -5.496e-6 0 1 6.58803e-7 0 1 9.37699e-6 0 1 4.84696e-5 0 1 2.71156e-6 0 1 2.22606e-6 0 1 7.32502e-7 0 1 -4.75118e-6 0 1 2.39856e-6 0 1 -2.10102e-5 0 1 2.65043e-6 0 1 -6.09756e-6 0 1 -5.39479e-6 0 1 1.14153e-5 0 1 6.3192e-6 0 1 -7.16112e-6 0 1 -4.49208e-6 0 1 1.4017e-7 0 1 -1.94643e-6 0 1 1.9293e-6 0 1 -1.47358e-5 0 1 2.49581e-6 0 1 -8.43341e-6 0 1 2.10997e-5 0 1 -1.0782e-5 0 1 6.04164e-6 0 1 5.7258e-6 0 1 -4.7478e-6 0 1 5.68233e-6 0 1 -3.36836e-6 0 1 -5.35488e-7 0 1 -1.56475e-6 0 1 -9.73035e-7 0 1 6.83882e-6 0 1 8.0177e-6 0 1 -3.36441e-6 0 1 -1.28662e-6 0 1 -1.44684e-6 0 1 -3.6808e-6 0 1 2.58104e-6 0 1 -7.33654e-6 0 1 5.67666e-6 0 1 3.86481e-6 0 1 -1.44877e-6 0 1 -1.99972e-6 0 1 -2.79336e-6 0 1 1.52778e-6 0 1 4.05834e-6 0 1 1.02847e-5 0 1 -2.10084e-5 0 1 1.01974e-5 0 1 -2.09674e-5 0 1 -7.88917e-6 0 1 -1.68832e-6 0 1 9.65661e-6 0 1 -1.43887e-5 0 1 -8.41567e-6 0 1 9.84667e-6 0 1 -9.71949e-6 0 1 2.07342e-6 0 1 -4.99426e-6 0 1 3.95498e-6 0 1 -2.21351e-6 0 1 -1.35913e-6 0 1 2.01369e-6 0 1 3.90028e-6 0 1 5.28765e-6 0 1 1.31898e-6 0 1 1.71045e-6 0 1 7.43915e-6 0 1 1.06608e-5 0 1 -9.21331e-6 0 1 -7.49677e-6 0 1 -1.19014e-5 0 1 8.75887e-6 0 1 1.03008e-5 0 1 4.40925e-6 0 1 -6.58441e-6 0 1 -5.9566e-6 0 1 -2.22139e-6 0 1 6.04122e-6 0 1 -1.79779e-6 0 1 2.54563e-6 0 1 4.21563e-6 0 1 -3.42774e-7 0 1 -2.65449e-6 0 1 1.0181e-5 0 1 -6.52886e-6 0 1 -5.26981e-6 0 1 5.09996e-6 0 1 -3.26439e-6 0 1 4.06981e-6 0 1 5.07367e-6 0 1 -7.64269e-6 0 1 3.81127e-6 0 1 -1.58806e-6 0 1 1.3781e-6 0 1 1.10292e-6 0 1 5.16657e-6 0 1 7.80354e-6 0 1 -4.03758e-6 0 1 2.92737e-6 0 1 -2.35707e-4 0 1 -1.02695e-5 0 1 9.90795e-6 0 1 -1.91877e-5 0 1 4.38462e-6 0 1 -9.11278e-6 0 1 3.24408e-6 0 1 -5.56558e-6 0 1 8.61905e-6 0 1 -2.40435e-6 0 1 8.53621e-6 0 1 -9.5896e-6 0 1 -2.01785e-6 0 1 6.0607e-6 0 1 -4.34106e-6 0 1 6.11305e-6 0 1 -1.4331e-5 0 1 -2.95648e-6 0 1 1.37787e-5 0 1 1.22097e-5 0 1 -3.66161e-6 0 1 2.33566e-6 0 1 -3.30443e-6 0 1 -3.86698e-6 0 1 5.32422e-7 0 1 2.14428e-6 0 1 -4.1862e-6 0 1 -3.00192e-6 0 1 -4.90215e-6 0 1 1.70707e-5 0 1 -3.79524e-6 0 1 -4.18554e-6 0 1 -3.89787e-7 0 1 7.31524e-6 0 1 -1.06336e-5 0 1 1.26256e-5 0 1 -2.33828e-6 0 1 6.61341e-6 0 1 4.54678e-6 0 1 -3.66118e-6 0 1 5.75374e-6 0 1 -6.98129e-6 0 1 -1.21799e-5 0 1 9.33184e-6 0 1 1.93843e-5 0 1 -1.86905e-6 0 1 2.74925e-6 0 1 -1.2117e-6 0 1 -1.35018e-5 0 1 4.51011e-6 0 1 -6.30093e-6 0 1 -3.5246e-6 0 1 8.74073e-6 0 1 -2.86238e-6 0 1 2.86166e-6 0 1 -1.74279e-6 0 1 -6.22411e-7 0 1 1.81264e-6 0 1 -2.74036e-6 0 1 1.63002e-6 0 1 1.29044e-6 0 1 -3.65764e-6 0 1 4.83886e-7 0 1 -0.27239 -0.6556493 0.7042214 -0.2897905 -0.5978499 0.7473935 -0.6399089 0.2397951 0.7300788 -0.6761868 0.209564 0.7062963 -0.7060887 0.07567656 0.7040681 -0.7060468 0.07553011 0.7041259 -0.70591 0.0756762 0.7042473 -0.701756 -0.1081961 0.7041535 -0.7022267 -0.107497 0.7037912 -0.701737 -0.1064489 0.7044388 -0.6510007 -0.2829787 0.7043588 -0.6513805 -0.2826656 0.7041333 -0.6512223 -0.2814725 0.7047573 -0.5575395 -0.4385306 0.7048693 -0.5576655 -0.4392238 0.7043379 -0.5575983 -0.4395652 0.7041779 -0.4279098 -0.5666543 0.7041279 -0.4279374 -0.5658447 0.7047619 -0.4271942 -0.567124 0.7041843 0.2891872 0.5985701 0.7470507 0.2690848 0.6483244 0.7122281 0.6399118 -0.239797 0.7300756 0.6757412 -0.2099546 0.7066067 0.674921 -0.2116171 0.7068945 0.7054649 -0.07520812 0.7047433 0.7057104 -0.07549291 0.7044669 0.7060282 -0.0734384 0.7043656 0.701862 0.1070936 0.7042164 0.7021981 0.1068859 0.7039129 0.7014812 0.1108897 0.7040082 0.7014813 0.1108898 0.7040082 0.7014813 0.1108896 0.7040082 0.6517379 0.2828018 0.7037478 0.6514955 0.2823941 0.7041358 0.5546141 0.4436905 0.7039474 0.5546141 0.4436905 0.7039474 0.5546142 0.4436904 0.7039474 0.5581405 0.439032 0.704081 0.5581223 0.4389783 0.704129 0.4270634 0.5673388 0.7040905 0.4279978 0.5667678 0.703983 0.4279471 0.5671462 0.7037092 0.3108836 0.6363438 0.7059872 0.3977567 -0.917491 -5.88e-5 0.3977004 -0.9175153 4.65779e-5 2.45306e-6 0 1 1.10625e-6 0 1 8.38184e-7 0 1 8.42477e-7 0 1 -1.23665e-6 0 1 -1.67374e-6 0 1 3.18424e-6 0 1 1.0499e-6 0 1 1.05536e-6 0 1 -8.59623e-6 0 1 -3.34377e-6 0 1 -2.1256e-6 0 1 -0.3974864 0.9176082 0 -0.3977589 0.91749 -5.88003e-5 -0.3977009 0.9175152 5.12357e-5 -0.9942551 0.1065872 0.009799838 0.4350636 0.9003998 0 0.2919632 0.9544444 -0.06159001 0.3355464 0.9420238 0 0.06738507 0.997727 0 0.06900751 0.9976159 -7.47774e-4 -0.9551889 0.2959972 0 0.06983083 0.9975588 0 -0.2034612 0.9790831 0 -0.2034569 0.979084 0 -0.4592297 0.8883177 0 -0.4592209 0.8883222 0 -0.682076 0.7312814 0 -0.6820837 0.7312741 0 -0.8538063 0.5205909 0 -0.8538438 0.5205295 4.27347e-5 -0.8538514 0.5205171 0 -0.9263104 0.3767617 0 -0.9624904 0.2701836 -0.02476412 -0.9664105 0.2568496 -0.008900344 -0.9942518 0.1066185 0.009799242 -0.3539686 -0.9229655 -0.1511327 -0.4798222 -0.8773658 0 -0.4606749 -0.8875691 0 -0.2038171 -0.9790091 0 -0.2041581 -0.9789378 -4.27465e-4 -0.2060308 -0.9785456 0 0.06754344 -0.9977164 0 0.06754022 -0.9977167 0 0.3342465 -0.9424858 0 0.3342417 -0.9424875 0 0.5758807 -0.8175339 0 0.5758789 -0.8175351 0 0.7749934 -0.6319694 0 0.775386 -0.6314875 5.66309e-4 0.776194 -0.6304942 0 0.8974968 -0.441021 0 0.9160318 -0.3989619 -0.04141485 0.9488846 -0.3156234 0 -0.793296 -0.6077356 0.03659284 -0.7640939 -0.6446151 0.02513825 -0.7103382 -0.7036587 0.01685541 -0.7970035 -0.6039741 -8.65041e-4 -0.8183482 -0.5746797 -0.007029533 -0.970548 -0.2400277 -0.02057719 -0.9798484 -0.1996474 -0.006175875 -0.9845336 -0.1751855 -0.001938402 -0.8369904 -0.5469002 -0.01863551 -0.8640199 -0.5007247 -0.05238908 -0.8545623 -0.5183278 -0.0325517 -0.9047006 -0.426048 0 -0.9630387 -0.2693631 0 -0.9282696 -0.3517612 -0.1207458 -0.9563939 -0.2874468 -0.05181813 -0.9992557 -0.0346347 0.01698738 -0.9992557 -0.0346347 0.01698738 -0.9992558 -0.0346347 0.01698738 -0.9925174 -0.1193333 0.02586263 -0.9862625 -0.1611829 0.03614479 -0.9758683 -0.2090604 0.06304585 -0.9886841 -0.1499695 -0.003600955 -0.9514104 -0.3079251 7.0584e-4 -0.9155995 -0.3979499 0.05756288 -0.9300853 -0.3578821 0.08283603 -0.9147669 -0.3953724 0.08295959 -0.9020817 -0.4300822 0.03574824 -0.7820808 -0.615979 -0.09444344 -0.8443863 -0.521955 0.1207261 -0.8190914 -0.5703603 0.06147068 -0.9876284 -0.1568118 -5.13916e-4 -0.9970353 0.07628059 0.01010519 -0.9999476 0 0.01024776 -0.988309 -0.1523221 0.00658673 -0.9999368 0 -0.01124995 -0.9999355 8.46425e-4 -0.01132905 0.42193 0.9066256 0.002237141 0.4389228 0.898522 0.002235352 0.5775492 0.816337 -0.005565464 0.6023277 0.7982417 0.003400444 0.6012945 0.7990202 0.003398478 0.7764256 0.630198 -0.003740549 0.7859978 0.618225 -0.002319097 0.7758492 0.6309173 0.001246809 0.7807187 0.6248814 0.001247763 0.7807186 0.6248816 0.001247823 0.7807188 0.6248815 0.001247823 0.917517 0.3976945 -0.001309394 0.9173416 0.3980993 -0.001163363 0.9877359 0.156129 0.001271486 0.987736 0.1561282 0.001271665 0.9877358 0.1561297 0.001271605 0.9909031 0.1345715 0.001270413 0.9885525 0.1508592 -0.00233674 0.9907082 0.135954 -0.003726184 0.9945768 -0.103954 0.003286361 0.9943602 -0.1060045 0.003286957 0.9905976 -0.1366871 -0.005746364 0.954195 -0.2991765 0.002292692 0.9549835 -0.2966504 0.002294421 -0.4361395 -0.89977 -0.01401382 -0.6016423 -0.7987074 0.009651422 -0.6827387 -0.7305998 0.009590029 -0.6030738 -0.7974162 -0.02072632 -0.6850135 -0.7284501 -0.01081836 -0.7853133 -0.6190645 0.006495773 -0.6816141 -0.7316408 0.01020914 -0.629188 -0.7771878 0.01008296 -0.7980997 -0.6025248 -0.001015901 0.3673772 -0.8477381 0.3825888 -0.3198784 0.7376551 -0.5945947 -0.3673671 0.8471618 -0.3838729 -0.3285615 0.7203431 0.6108626 -0.1517955 0.3928647 0.9069815 -0.2450471 0.5577813 0.7929893 -0.1675797 0.3789666 0.9101107 -0.1522566 0.3514852 0.9237295 -0.05326777 0.1221976 0.9910753 -0.05190175 0.1197175 0.9914504 -0.398654 0.9078572 0.1298858 -0.3581379 0.8345176 0.4187096 -0.3676953 0.8479169 0.3818862 -0.3198214 0.7375439 0.5947633 -0.2457969 0.6084077 0.7546019 -0.3962185 0.9146811 -0.07980877 -0.3962276 0.9146748 0.07983583 -0.3771558 0.8919254 0.249445 -0.4150686 0.9007618 -0.1278532 -0.3379579 0.8477662 -0.4087507 -0.3773268 0.8921716 -0.2483029 -0.2330332 0.5853846 -0.776544 -0.3305506 0.7189741 -0.6114022 -0.2498842 0.572111 -0.7811831 -0.2424408 0.5592434 -0.7927606 -0.1527695 0.3524031 -0.923295 -0.1520005 0.3510273 -0.9239457 -0.05322927 0.1222266 -0.9910738 0.301025 -0.7319905 -0.6112069 0.1835669 -0.3812579 -0.9060605 0.2393621 -0.5593104 -0.7936484 0.1622892 -0.3817672 -0.909899 0.1526984 -0.3517904 -0.9235403 0.05263429 -0.1219239 -0.9911429 0.05195742 -0.119855 -0.9914309 -0.0521205 0.1202637 -0.9913729 0.3901862 -0.9115843 -0.1294943 0.3638343 -0.8302656 -0.4222366 0.3673517 -0.8477011 -0.3826952 0.3200463 -0.7385499 -0.5933924 0.2756402 -0.5938498 -0.7558869 0.3966119 -0.9147667 0.07681822 0.3966078 -0.9147676 -0.07682806 0.3932912 -0.8858272 -0.2462365 0.3738133 -0.9183406 0.1300544 0.3875932 -0.8253042 0.4106636 0.3932515 -0.8856769 0.2468397 0.05207592 -0.120131 0.9913913 0.05273514 -0.1221438 0.9911105 0.1526539 -0.351511 0.9236541 0.1533278 -0.3535858 0.9227501 0.2416643 -0.5573167 0.7943529 0.2465093 -0.5732823 0.7813966 0.2989273 -0.7339934 0.6098329 0.2679629 -0.5704595 0.7763839 0.3195326 -0.7373389 0.5951726 0.7191023 0.6949042 0 0.9981053 0.06152963 0 0.9909244 -0.1344116 -0.001563847 0.9505636 -0.310418 0.008347988 0.9468113 -0.3217096 0.007168292 0.9015578 -0.43264 -0.004059851 0.8662502 -0.4996105 0 0.6965714 -0.7174875 0 0.7406787 -0.6714953 -0.02212023 0.5442407 -0.8370289 0.05643373 0.5442407 -0.8370289 0.05643373 0.5442408 -0.8370289 0.05643373 0.9506107 -0.3103858 0 0.976424 -0.2063351 -0.06341958 0.9419597 -0.3351497 -0.01966285 0.9419597 -0.3351496 -0.01966291 0.9419597 -0.3351497 -0.01966285 0.5809054 0.8139498 0.005896389 0.7391262 0.6735119 -0.008621215 0.7947568 0.6055013 -0.04159229 0.8682084 0.4962 0 0.9859461 0.1670634 0 0.9551785 0.2832832 -0.08593422 0.9984847 0.05502796 4.65253e-4 0.5844507 0.8114077 0.005905151 0.4234835 0.9054576 -0.02843326 0.3988875 0.9167929 -0.01948338 -0.2527499 0.9656263 0.06069201 0.01808589 0.9995739 -0.02291166 -0.04736459 0.9988777 0 0.2352589 0.9719328 0 0.2968174 0.9549282 -0.003414332 0.3016424 0.9534202 0.001372635 0.2329583 0.9724868 0 -0.0473634 0.9988778 0 0.42363 0.9058353 0 0.5449415 0.838185 0.02201831 0.4104105 0.9118738 0.007035136 0.9905919 -0.1368404 -0.001564145 0.9965699 0.08272254 0.002370595 0.9858964 0.1670577 0.01000553 0.955658 0.2944791 0 0.7954525 0.6060159 0 0.8665724 0.4985893 0.02147144 0.7246086 0.6891607 1.40213e-4 -0.04736047 0.998878 0 -0.505263 0.8629654 0 -0.8483958 0.5293625 0 -0.9972671 0.07388067 0 -0.9972733 0.073798 0 -0.9586483 -0.2845939 0 -0.9178392 -0.3969138 -0.005538523 -0.8637483 -0.5039237 0 -0.6270902 -0.7789468 0 -0.6270694 -0.7789634 0 -0.1934368 -0.9811128 0 -0.1934366 -0.9811128 0 0.2842798 -0.9587414 0 0.2842686 -0.9587448 0 0.6965948 -0.7174648 0 0.6965716 -0.7174874 0 0.8662549 -0.4996024 0 0.9031559 -0.4293102 0.001514494 0.9472346 0.3205411 0 0.8814384 0.4722993 0 0.8814329 0.4723095 0 0.791889 0.6106652 0 0.7918953 0.6106569 0 0.6805036 0.7327448 0 0.6805164 0.7327328 0 0.5504398 0.8348749 0 0.4056846 0.9140132 0 0.4056849 0.914013 0 0.2496432 0.968338 0 0.2496466 0.9683371 0 0.08690112 0.996217 0 0.08690005 0.9962171 0 -0.07830798 0.9969293 0 -0.07830703 0.9969293 0 -0.2412643 0.9704595 0 -0.2412614 0.9704602 0 -0.3977922 0.9174757 0 -0.3977971 0.9174736 0 -0.5434141 0.8394648 0 -0.5434027 0.8394722 0 -0.6740299 0.7387042 0 -0.6740235 0.73871 0 -0.7863995 0.6177183 0 -0.7863933 0.6177263 0 -0.87755 0.479485 0 -0.9443742 0.3288733 0 -0.9856926 0.1685535 0 -0.9856905 0.1685659 0 -0.9999905 0.004368126 0 -0.9999905 0.004355192 0 -0.9870669 -0.1603096 0 -0.987069 -0.1602969 0 -0.9472389 -0.3205286 0 -0.947235 -0.3205401 0 -0.8814321 -0.4723108 0 -0.8814375 -0.4723008 0 -0.7918782 -0.6106791 0 -0.7918785 -0.6106787 0 -0.6804828 -0.7327642 0 -0.5504811 -0.8348477 0 -0.5504693 -0.8348554 0 -0.4056095 -0.9140466 0 -0.4056143 -0.9140444 0 -0.2496007 -0.9683489 0 -0.2495977 -0.9683497 0 -0.08712011 -0.9961979 0 -0.08711904 -0.9961979 0 0.07839506 -0.9969224 0 0.07839411 -0.9969225 0 0.2413071 -0.9704489 0 0.2413073 -0.9704489 0 0.397751 -0.9174934 0 0.3977514 -0.9174934 0 0.5432871 -0.839547 0 0.543293 -0.8395432 0 0.6741484 -0.738596 0 0.6741422 -0.7386017 0 0.786361 -0.6177673 0 0.7863674 -0.6177593 0 0.8775447 -0.4794951 0 0.9443781 -0.3288617 0 0.9856195 -0.1689802 0 0.9856151 -0.1690052 0 0.9999924 -0.003915846 0 0.9999923 -0.00392878 0 0.987069 0.1602964 0 0.987067 0.160309 0 0.9472386 0.3205297 0 -0.8806294 -0.4738059 0 -0.9479221 -0.3185023 0 -0.9479221 -0.3185024 0 -0.9881227 -0.1536669 0 -0.9881207 -0.1536797 0 -0.9998847 0.01519244 0 -0.9998848 0.01517921 0 -0.9828306 0.1845108 0 -0.982833 0.1844979 0 -0.9377149 0.3474059 0 -0.865318 0.5012233 0 -0.8653124 0.5012331 0 -0.7680756 0.6403594 0 -0.7680758 0.6403589 0 -0.6490652 0.7607328 0 -0.6490586 0.7607384 0 -0.5110729 0.8595374 0 -0.5110789 0.8595339 0 -0.3586446 0.9334742 0 -0.358649 0.9334725 0 -0.1951744 0.9807686 0 -0.1951746 0.9807686 0 -0.02724516 0.9996289 0 -0.02724552 0.9996289 0 0.1424852 0.9897969 0 0.1424871 0.9897966 0 0.3076447 0.9515014 0 0.3076408 0.9515026 0 0.46375 0.8859661 0 0.4637612 0.8859602 0 0.6070429 0.794669 0 0.607056 0.7946591 0 0.7325364 0.680728 0 0.7325431 0.6807206 0 0.8371688 0.5469446 0 0.8371629 0.5469537 0 0.9175702 0.3975739 0 0.9175655 0.3975847 0 0.9714645 0.2371851 0 0.9714707 0.23716 0 0.9975995 0.06924808 0 0.9975995 0.06924802 0 0.994983 -0.1000439 0 0.9949845 -0.1000307 0 0.9636837 -0.2670466 0 0.9636872 -0.2670341 0 0.904808 -0.4258201 0 0.9048081 -0.4258197 0 0.8196191 -0.572909 0 0.8196191 -0.5729088 0 0.7111601 -0.7030301 0 0.7111535 -0.7030369 0 0.5822174 -0.8130332 0 0.4362084 -0.8998458 0 0.4362136 -0.8998432 0 0.2780717 -0.9605604 0 0.2780684 -0.9605613 0 0.1116603 -0.9937465 0 0.1116588 -0.9937466 0 -0.05788987 -0.998323 0 -0.05789071 -0.998323 0 -0.2257874 -0.9741767 0 -0.2257905 -0.9741759 0 -0.3870773 -0.9220473 0 -0.387082 -0.9220454 0 -0.5374276 -0.8433099 0 -0.6723371 -0.7402452 0 -0.6723436 -0.7402392 0 -0.787451 -0.6163772 0 -0.7874447 -0.6163853 0 -0.8806293 -0.473806 0 -1.91508e-6 0 -1 -2.17288e-6 0 -1 4.85267e-6 0 -1 -2.17373e-6 0 -1 4.8564e-6 0 -1 2.17761e-6 0 -1 4.84574e-6 0 -1 -2.17909e-6 0 -1 -2.18631e-6 0 -1 1.0962e-6 0 -1 1.65003e-6 0 -1 -2.3939e-6 0 -1 1.37884e-7 0 -1 1.18769e-6 0 -1 -1.11172e-6 0 -1 1.18253e-6 0 -1 1.17116e-6 0 -1 -4.4049e-6 0 -1 4.3305e-6 0 -1 2.48479e-6 0 -1 -2.51367e-6 0 -1 -1.27146e-6 0 -1 -3.22258e-7 0 -1 -1.03251e-6 0 -1 5.11139e-7 0 -1 -1.51856e-6 0 -1 2.00173e-6 0 -1 -1.9818e-6 0 -1 5.53759e-6 0 -1 -1.95823e-6 0 -1 3.87513e-6 0 -1 0.58731 -0.8093263 0.007621347 -0.66323 -0.7484158 0 -0.5234902 -0.8520317 0 -0.5234895 -0.8520322 0 -0.3678098 -0.9299011 0 -0.3678097 -0.9299012 0 -0.02766442 -0.9996173 0 -0.02766442 -0.9996173 0 0.3159764 -0.9487671 0 0.3159762 -0.9487672 0 0.6222994 -0.7827794 0 -0.587288 0.8093422 0.007621467 0.6632205 0.7484241 0 0.5235027 0.852024 0 0.523502 0.8520244 0 0.3677949 0.929907 0 0.3677948 0.929907 0 0.02768158 0.9996168 0 0.02768158 0.9996169 0 -0.3159919 0.9487619 0 -0.3159917 0.948762 0 -0.6222892 0.7827875 0 -0.9796788 0.2005729 0 -0.9796791 0.2005717 0 -0.9996282 0.02726811 0 -0.9891806 -0.1467034 0 -0.9891805 -0.1467043 0 -0.9487076 -0.3161548 0 -0.9487077 -0.3161547 0 -0.7836043 -0.6212486 0.003809869 -0.6632304 -0.7484154 0 0.9796782 -0.2005763 0 0.9796784 -0.2005751 0 0.9996282 -0.02726763 0 0.9996282 -0.02726763 0 0.9891802 0.1467058 0 0.9891801 0.1467069 0 0.9487094 0.3161495 0 0.7836043 0.6212486 0.003813266 0.6632207 0.7484239 0 -5.60588e-6 0 1 -1.1763e-5 0 1 5.60991e-6 0 1 1.17387e-5 0 1 1.40664e-6 0 1 1.03412e-6 0 1 2.82014e-6 0 1 -2.82652e-6 0 1 2.9162e-6 0 1 -5.68751e-6 0 1 1.4516e-6 0 1 -2.89593e-6 0 1 5.75771e-6 0 1 -1.14548e-5 0 1 5.74501e-6 0 1 1.13947e-5 0 1 -1.16149e-5 0 1 1.12816e-5 0 1 1.1803e-5 0 1 -1.10358e-5 0 1 6.1065e-6 0 1 3.07851e-6 0 1 -5.37449e-6 0 1 7.77208e-7 0 1 -6.56237e-7 0 1 2.6059e-6 0 1 -5.16956e-6 0 1 5.08295e-6 0 1 1.00652e-5 0 1 -9.98801e-6 0 1 -9.89081e-6 0 1 -7.57539e-7 0 -1 4.93587e-7 0 -1 1.75121e-7 0 -1 -2.85858e-6 0 -1 2.82665e-6 0 -1 -2.8278e-6 0 -1 1.03611e-5 0 -1 -7.59624e-6 0 -1 -1.59683e-6 0 -1 1.46355e-6 0 -1 -9.68842e-7 0 -1 1.28116e-7 0 -1 3.40599e-6 0 -1 0 0 -1 -6.38309e-6 0 -1 7.18168e-7 0 -1 -2.06516e-6 0 -1 1.25694e-6 0 -1 -2.79808e-6 0 -1 -8.00024e-7 0 -1 -5.82284e-7 0 -1 5.78297e-7 0 -1 1.22766e-6 0 -1 -1.1928e-6 0 -1 5.08527e-7 0 -1 7.97357e-7 0 -1 3.21353e-6 0 -1 -5.14848e-6 0 -1 1.42372e-6 0 -1 -5.61891e-7 0 -1 3.03185e-6 0 -1 -3.28442e-6 0 -1 1.71663e-6 0 -1 -1.11875e-6 0 -1 -7.68682e-7 0 -1 -3.03988e-6 0 -1 1.7451e-6 0 -1 8.55087e-7 0 -1 -3.25679e-6 0 -1 -2.14552e-6 0 -1 1.2031e-6 0 -1 -1.14626e-5 0 -1 1.55685e-6 0 -1 -1.41471e-5 0 -1 1.59563e-6 0 -1 -1.11136e-5 0 -1 7.61684e-7 0 -1 -6.24688e-6 0 -1 -1.08771e-6 0 -1 -1.08802e-6 0 -1 -3.88179e-7 0 -1 -1.20816e-6 0 -1 1.39946e-6 0 -1 1.59585e-6 0 -1 1.18471e-6 0 -1 8.54097e-7 0 -1 2.15274e-6 0 -1 -4.86025e-6 0 -1 9.90225e-7 0 -1 -4.62832e-6 0 -1 4.47824e-6 0 -1 6.47273e-7 0 -1 2.0385e-6 0 -1 2.9693e-6 0 -1 4.90904e-6 0 -1 3.06565e-7 0 -1 3.50191e-7 0 -1 9.19896e-7 0 -1 -8.99091e-7 0 -1 -1.44556e-6 0 -1 -3.04607e-6 0 -1 5.35717e-7 0 -1 2.55009e-6 0 -1 -4.14581e-6 0 -1 1.08771e-6 0 -1 5.20648e-7 0 -1 2.03875e-6 0 -1 -6.59979e-7 0 -1 1.3999e-6 0 -1 -3.23683e-6 0 -1 4.08262e-7 0 -1 6.2475e-6 0 -1 -6.04075e-7 0 -1 -3.91751e-6 0 -1 1.70663e-6 0 -1 -3.39309e-7 0 -1 0.9891754 0.1467375 0 0.7833867 0.6215348 0 0.7833853 0.6215365 0 0.367243 0.9301251 0 0.3677876 0.92991 -1.64907e-4 0.622374 -0.7827202 0 0.929845 -0.3679518 0 0.9298568 -0.367922 3.75245e-6 0.9298756 -0.3678743 0 0.9891756 0.1467363 0 -0.7834017 -0.6215158 0 -0.3677626 -0.9299198 0 -0.367762 -0.92992 0 0.1475293 -0.9890577 0 0.1468122 -0.9891644 -1.19945e-4 0.146415 -0.9892234 0 0.6223725 -0.7827212 0 0.3687723 0.9295199 0 -0.1468095 0.9891648 0 -0.1468097 0.9891648 0 -0.6214351 0.7834657 0 -0.621436 0.783465 0 -0.9300677 0.3673883 0 -0.9300683 0.3673866 0 -0.989188 -0.1466529 0 -0.9891756 -0.1467371 1.31201e-5 -0.9891673 -0.1467922 0 -0.7834026 -0.6215146 0 -1.25813e-6 0 1 7.91149e-7 0 1 2.43027e-7 0 1 -1.67388e-6 0 1 6.70354e-6 0 1 -1.38596e-5 0 1 1.56014e-6 0 1 -2.85119e-6 0 1 -1.1417e-6 0 1 3.83342e-6 0 1 -1.94704e-6 0 1 -3.08868e-7 0 1 -6.1823e-6 0 1 2.24433e-6 0 1 1.07182e-6 0 1 4.92669e-6 0 1 1.32956e-6 0 1 -2.05479e-7 0 1 -5.03123e-7 0 1 -4.21102e-6 0 1 1.5081e-6 0 1 -5.48241e-7 0 1 8.3711e-6 0 1 1.60023e-6 0 1 3.14043e-6 0 1 5.38677e-5 0 1 -1.56094e-6 0 1 1.60018e-6 0 1 3.09146e-6 0 1 -6.11098e-6 0 1 1.52827e-6 0 1 6.28836e-6 0 1 1.66946e-6 0 1 1.23484e-6 0 1 -1.60133e-6 0 1 -1.89245e-6 0 1 3.66989e-6 0 1 1.54166e-6 0 1 2.37932e-6 0 1 5.04568e-6 0 1 -2.58353e-6 0 1 -1.14574e-6 0 1 3.78962e-7 0 1 -2.98278e-6 0 1 -4.39748e-6 0 1 2.13979e-6 0 1 1.45579e-6 0 1 -2.92499e-6 0 1 2.4795e-6 0 1 1.06838e-5 0 1 -1.36935e-6 0 1 7.14204e-6 0 1 2.53455e-7 0 1 -2.4843e-6 0 1 3.39335e-7 0 1 3.03116e-6 0 1 -3.67743e-6 0 1 6.75877e-6 0 1 -2.4656e-5 0 1 3.38021e-6 0 1 5.26023e-7 0 1 -1.59221e-6 0 1 1.84393e-6 0 1 -5.26023e-6 0 1 1.82818e-6 0 1 2.74051e-6 0 1 -1.4537e-6 0 1 -2.71621e-5 0 1 8.14046e-7 0 1 -3.64559e-6 0 1 -7.79952e-7 0 1 -4.27073e-7 0 1 1.54927e-6 0 1 1.02736e-6 0 1 -5.66322e-6 0 1 9.88517e-7 0 1 -5.42124e-6 0 1 1.31893e-6 0 1 4.22019e-6 0 1 9.58001e-7 0 1 -4.23227e-6 0 1 9.15577e-7 0 1 -1.6236e-6 0 1 1.33573e-6 0 1 -6.34389e-7 0 1 -1.21421e-6 0 1 2.38796e-6 0 1 3.20982e-6 0 1 -1.64117e-6 0 1 -5.93261e-6 0 1 -4.95843e-7 0 1 1.19134e-6 0 1 -1.57098e-6 0 1 2.01613e-6 0 1 -1.21889e-6 0 1 -1.00299e-6 0 1 -9.32557e-6 0 1 1.78378e-6 0 1 2.84863e-7 0 1 1.12688e-6 0 1 -7.12318e-7 0 1 5.70745e-7 0 1 -1.81876e-6 0 1 1.05828e-6 0 1 2.68575e-6 0 1 -4.19527e-6 0 1 -8.1034e-5 0 1 1.07937e-5 0 1 1.12633e-6 0 1 -4.9298e-6 0 1 1.86252e-5 0 1 -9.54723e-7 0 1 2.13445e-7 0 1 -4.06583e-7 0 1 1.12046e-6 0 1 -9.17984e-7 0 1 -5.88545e-7 0 1 2.43551e-6 0 1 -2.00835e-6 0 1 2.81634e-6 0 1 1.47581e-6 0 1 -7.55184e-6 0 1 2.55723e-6 0 1 -1.42954e-6 0 1 6.1448e-7 0 1 -2.78155e-6 0 1 -2.70229e-6 0 1 2.72379e-6 0 1 2.0602e-6 0 1 1.26744e-6 0 1 -3.97501e-6 0 1 2.34958e-6 0 1 2.14818e-7 0 1 -1.87688e-6 0 1 -9.87362e-5 0 1 2.60514e-7 0 1 1.36528e-6 0 1 -6.26906e-7 0 1 5.70839e-7 0 1 -1.0151e-6 0 1 -4.0451e-7 0 1 1.76193e-5 0 1 -1.08932e-5 0 1 -4.4835e-6 0 1 -6.56382e-7 0 1 -1.17142e-6 0 1 4.33035e-7 0 1 1.05886e-5 0 1 8.85294e-7 0 1 -7.86837e-7 0 1 1.28813e-5 0 1 1.17133e-6 0 1 -3.18826e-6 0 1 -1.80095e-6 0 1 -3.15376e-7 0 1 3.17452e-6 0 -1 5.87089e-6 0 -1 -6.2729e-6 0 -1 -5.9138e-6 0 -1 -0.420199 -0.8126138 -0.4038463 0.8802711 -0.248979 -0.4038963 0.9139583 0.04259532 -0.4035665 0.05387234 0.8956829 -0.441418 0.0672419 0.9016737 -0.4271572 0.0256837 0.9119548 -0.4094859 0.0730977 0.9022783 -0.4249126 0.08505851 0.904913 -0.4170101 0.09330922 0.90606 -0.4127332 0.116176 0.9069424 -0.404918 0.1066782 0.9099625 -0.4007343 0.09822613 0.9128685 -0.396261 0.08734709 0.91851 -0.3856294 0.07112342 0.9328082 -0.3532854 0.06982636 0.9349967 -0.3477147 -0.07915544 0.9115781 -0.4034353 -0.07903474 0.9116643 -0.4032642 0.005518257 0.9145978 -0.4043272 -0.2245326 0.8870946 -0.4032972 -0.2254947 0.8867409 -0.4035379 -0.07788401 0.9116656 -0.403485 -0.364277 0.839432 -0.4033069 -0.3640623 0.8396483 -0.40305 -0.2247581 0.8871793 -0.402985 -0.6108849 0.6808772 -0.4040125 -0.4937106 0.7700499 -0.4040706 -0.4937834 0.7700402 -0.4040003 -0.4939752 0.7698877 -0.4040565 -0.3630854 0.8395843 -0.4040635 -0.7362936 0.5408405 -0.4066489 -0.7338644 0.5511777 -0.397047 -0.7306109 0.5618531 -0.3879805 -0.7262398 0.585508 -0.360217 -0.7338544 0.6049199 -0.3090789 -0.728469 0.5796023 -0.3652316 -0.7253844 0.5511584 -0.4123615 -0.7104361 0.5626665 -0.4227141 -0.7030155 0.5666586 -0.4297293 -0.6944171 0.5848677 -0.4191836 -0.68318 0.6043521 -0.4099069 -0.6718498 0.6203043 -0.4047722 -0.6718851 0.6202451 -0.4048042 -0.6110413 0.6808544 -0.4038141 -0.61401 0.688556 -0.3858528 -0.6668432 0.6247441 -0.4062204 -0.6670486 0.6244425 -0.4063468 -0.2247217 0.8876723 -0.4019182 -0.3641794 0.840106 -0.4019891 -0.3637852 0.8396798 -0.4032348 -0.494067 0.7702612 -0.4032313 -0.4936439 0.7699419 -0.4043578 -0.6109188 0.6806658 -0.4043172 0.0102325 0.914314 -0.404877 -0.01264011 0.9142822 -0.4048807 -0.08021241 0.9181119 -0.3881194 -0.08223623 0.9111176 -0.4038591 -0.2242209 0.8869599 -0.4037661 0.748902 -0.4949728 -0.4406219 0.7474415 -0.5089187 -0.4270049 0.7757105 -0.4795319 -0.4102713 0.7451601 -0.5138075 -0.4251335 0.7412137 -0.5263513 -0.4166012 0.7378938 -0.5346387 -0.4119154 0.729502 -0.5519627 -0.4039358 0.7344144 -0.547455 -0.4011589 0.740862 -0.5419108 -0.3968077 0.7530313 -0.5340865 -0.384312 0.7715932 -0.5278546 -0.3549841 0.7753697 -0.527823 -0.3467054 0.8290277 -0.3870634 -0.4036027 0.8283011 -0.3885557 -0.4036607 0.7892192 -0.4620266 -0.4045547 0.9120535 -0.06782716 -0.4044229 0.9214809 -0.106036 -0.3736703 0.9036693 -0.1410555 -0.4043332 0.8804695 -0.2489744 -0.4034667 0.8804392 -0.2489945 -0.4035201 0.8292317 -0.3866919 -0.4035397 0.8289664 -0.3871024 -0.4036909 0.8735071 0.2708253 -0.4045232 0.8953186 0.188749 -0.4034582 0.8952838 0.1886395 -0.4035868 0.8952488 0.1887292 -0.4036225 0.9139616 0.04259836 -0.4035587 0.8373742 0.3642167 -0.4076161 0.8442296 0.3599691 -0.3971129 0.8516296 0.3521192 -0.3882513 0.8701093 0.3362812 -0.3603123 0.8908892 0.3331743 -0.3087254 0.8662847 0.3411018 -0.3649663 0.8399255 0.3534037 -0.4118629 0.8425745 0.3337615 -0.4226955 0.8423259 0.3255089 -0.429571 0.8547055 0.3076455 -0.4181302 0.8641836 0.2912673 -0.410305 0.9030392 0.1874699 -0.3864911 0.8749687 0.2628979 -0.4065889 0.8741888 0.2656641 -0.4064686 0.8953506 0.188633 -0.4034413 0.9140473 0.04260253 -0.4033642 0.9139561 0.04256904 -0.4035742 0.9088571 -0.1045632 -0.4037891 0.8020623 -0.05964887 -0.5942543 0.9035407 -0.1410235 -0.4046316 0.787392 -0.4653323 -0.4043263 0.7962825 -0.4498803 -0.4044034 0.8355875 -0.3901829 -0.3867182 0.8299307 -0.3843189 -0.4043686 0.880234 -0.2489855 -0.4039733 -0.8034498 -0.4009076 -0.4401609 -0.8145574 -0.3928617 -0.4267975 -0.8029856 -0.432776 -0.4097793 -0.8164585 -0.3895674 -0.4261841 -0.8264588 -0.3787352 -0.4165641 -0.831462 -0.3722749 -0.4124106 -0.8435986 -0.3526218 -0.4049684 -0.8435986 -0.3526218 -0.4049685 -0.8435986 -0.3526218 -0.4049685 -0.8413354 -0.3625826 -0.4008598 -0.8397069 -0.3709998 -0.3965495 -0.8390164 -0.3848062 -0.3846759 -0.8428844 -0.4041388 -0.3552716 -0.8447738 -0.407526 -0.3468136 -0.7952505 -0.4516381 -0.4044749 -0.7498022 -0.5244543 -0.4034158 -0.7498 -0.5243898 -0.4035039 -0.6558885 -0.6379715 -0.403488 -0.6559109 -0.637952 -0.4034824 -0.6556597 -0.6382451 -0.4034271 -0.5448195 -0.7349026 -0.4038439 -0.5452234 -0.7349061 -0.4032919 -0.5451126 -0.7349299 -0.4033986 -0.2030261 -0.8918904 -0.4041188 -0.2843407 -0.8698831 -0.4030556 -0.284299 -0.8699343 -0.4029744 -0.2826364 -0.8704432 -0.4030449 -0.4199426 -0.8130905 -0.4031529 -0.09948569 -0.9081861 -0.4065721 -0.110018 -0.9111537 -0.3971081 -0.1220405 -0.9140114 -0.386897 -0.1439529 -0.9215922 -0.3604792 -0.1576851 -0.9388689 -0.3060404 -0.1576852 -0.9388689 -0.3060404 -0.1576851 -0.9388689 -0.3060404 -0.1374346 -0.9205332 -0.3656916 -0.11445 -0.9037057 -0.4125739 -0.1326401 -0.896245 -0.4232631 -0.1389015 -0.8923461 -0.4294472 -0.1594472 -0.8940315 -0.4186699 -0.1804775 -0.8940802 -0.4099372 -0.2890958 -0.8756968 -0.3867542 -0.2153323 -0.8884007 -0.4054334 -0.2056042 -0.8907306 -0.4053712 -0.6562358 -0.6385916 -0.4019397 -0.5455218 -0.735582 -0.4016531 -0.5454474 -0.7353117 -0.4022487 -0.4202076 -0.8135104 -0.4020279 -0.420045 -0.8122199 -0.4047976 -0.2838994 -0.8691919 -0.4048541 -0.7973812 -0.4485584 -0.4037062 -0.7872973 -0.4661445 -0.4035748 -0.7558866 -0.5286111 -0.3862715 -0.7478371 -0.5266317 -0.4042261 -0.6557749 -0.6376239 -0.4042215 0.8386907 0.3677425 -0.4017007 0.8346667 0.3737609 -0.4045173 0.7894501 0.4625009 -0.4035613 0.7895796 0.4623615 -0.4034675 0.7051649 0.5830627 -0.4034606 0.7050276 0.5831716 -0.4035431 0.6022887 0.6887729 -0.4035348 0.6023018 0.6887642 -0.40353 0.4843202 0.7762696 -0.4035339 0.4841546 0.7763349 -0.403607 0.353401 0.8439142 -0.4036296 0.3531731 0.8439602 -0.4037327 0.213047 0.8897249 -0.4037333 0.2133876 0.8897201 -0.403564 0.1151375 0.9072468 -0.4045325 0.1068991 0.9070141 -0.4073057 -0.09784489 -0.9099693 -0.402967 -0.09350532 -0.9096787 -0.40465 0.005743622 -0.9148734 -0.4037003 0.005552411 -0.914923 -0.4035902 0.1526947 -0.9021017 -0.4036049 0.152307 -0.9022603 -0.403397 0.2951682 -0.8661026 -0.403413 0.2953221 -0.8660192 -0.4034795 0.4302313 -0.8075304 -0.4034796 0.4304254 -0.8073567 -0.4036203 0.5541815 -0.7280008 -0.4036059 0.5541312 -0.728058 -0.4035719 0.6637973 -0.6296844 -0.4035726 0.6638044 -0.6296702 -0.403583 0.7283031 -0.5531038 -0.4045377 0.7341043 -0.5423138 -0.4086399 -0.7383501 0.541189 -0.4024348 -0.7408825 0.5360993 -0.4045872 -0.795191 0.4525234 -0.4036009 -0.7952099 0.4524551 -0.4036403 -0.857491 0.3190665 -0.403616 -0.8574827 0.3191474 -0.4035696 -0.897598 0.1773439 -0.4035677 -0.8975991 0.1773446 -0.4035652 -0.9144207 0.0310682 -0.4035711 -0.9144244 0.03109788 -0.4035602 -0.9075723 -0.1160014 -0.4035546 -0.9075551 -0.1160369 -0.4035831 -0.8771936 -0.26008 -0.403596 -0.8772454 -0.2599806 -0.4035477 -0.8431231 -0.3542947 -0.4044979 -0.8378695 -0.3627803 -0.407879 2.61163e-6 0 1 2.79842e-6 0 1 6.48374e-6 0 1 -1.40734e-6 0 1 1.06038e-6 0 1 7.0881e-7 0 1 -1.42968e-6 0 1 7.90779e-7 0 1 6.17162e-6 0 1 -5.88887e-6 0 1 6.02301e-6 0 1 5.83158e-6 0 1 -6.25438e-6 0 1 6.33104e-6 0 1 -3.20119e-6 0 1 -3.23767e-6 0 1 -4.21159e-7 0 1 1.25544e-7 0 1 3.47299e-6 0 1 -1.32539e-6 0 1 -7.19549e-6 0 1 2.58275e-6 0 1 -5.03383e-6 0 1 -4.97275e-6 0 1 4.90745e-6 0 1 1.58613e-5 0 1 -4.84093e-6 0 1 -0.732899 0.4881424 0.4738946 0.6754428 0.3114966 0.6683914 0.04619944 -0.9132995 0.4046599 0.1960407 -0.8932027 0.4046693 0.1959937 -0.8936032 0.4038065 0.340615 -0.8491129 0.4037188 0.3405816 -0.848853 0.404293 0.4758004 -0.7812367 0.4040833 0.4758965 -0.7818041 0.4028711 0.5981568 -0.6927418 0.4028863 0.5980164 -0.6924268 0.4036355 0.7353433 -0.5460308 0.4013984 0.7216289 -0.5436951 0.4285412 0.6736738 -0.5246379 0.5204986 0.6865212 -0.4989638 0.5288894 0.5862352 -0.4555863 0.6699026 0.7408164 -0.5369179 0.4036214 0.7307866 -0.5426037 0.4141644 0.7364324 -0.5391959 0.408577 0.7417311 -0.5342793 0.4054389 0.7296779 -0.558744 0.3941769 0.7262079 -0.5793936 0.370034 0.730783 -0.6071545 0.311961 0.6992627 -0.615016 0.3643996 0.6615509 -0.631288 0.4047541 0.8427529 0.3533232 0.4061162 0.8463053 0.3467171 0.4044189 0.8374383 0.3793138 0.3934696 0.8404983 0.3633461 0.4019234 0.842473 0.3570966 0.4033876 0.8403819 0.3568214 0.4079666 0.8344475 0.3625628 0.4150247 0.8059173 0.3720537 0.4605144 0.7965401 0.2603002 0.545681 0.7815691 0.3312346 0.5286147 0.3942657 0.8264287 0.4019579 0.5251844 0.7499834 0.4021273 0.5247434 0.7496938 0.4032415 0.6407434 0.6532222 0.4034212 0.6405271 0.6531208 0.4039285 0.739418 0.5386547 0.4038716 0.7395856 0.5386994 0.403505 0.7880434 0.4640139 0.4045723 0.8423757 0.4216557 0.3355737 0.8539545 0.4390974 0.2792047 0.8386864 0.3991459 0.3705235 0.259934 0.9042603 0.3387443 0.2644172 0.8759312 0.4035195 0.3938306 0.8260242 0.403214 0.08648848 0.7818537 0.6174339 0.0859605 0.8761581 0.4742973 0.08194172 0.8944035 0.4396908 0.07793444 0.9015522 0.4255936 0.06374657 0.9124539 0.4041835 0.07950723 0.9151617 0.395168 0.09094208 0.9184042 0.3850496 0.1068128 0.9266039 0.3605502 0.1065164 0.9263156 0.3613778 0.1631366 0.9006489 0.4027633 0.1934273 0.8946458 0.4027342 -0.6928558 0.6006051 0.3990292 -0.6937729 0.5867075 0.4176765 -0.690162 0.5737717 0.440979 -0.6902383 0.5735927 0.4410924 -0.6902281 0.5733174 0.4414662 -0.7450125 0.5306347 0.4042071 -0.7551097 0.5161177 0.4042671 -0.724383 0.5832801 0.3674966 -0.7039113 0.5848346 0.4030849 -0.7543092 0.5172809 0.404275 -0.7639832 0.5068202 0.3993284 -0.9067769 -0.1217914 0.4036369 -0.9145027 0.02915048 0.4035286 -0.9144982 0.02915096 0.4035387 -0.8972537 0.1792821 0.403477 -0.8971732 0.1792257 0.4036813 -0.855373 0.3244488 0.4038196 -0.8555363 0.324594 0.4033566 -0.8083478 0.4280722 0.4041386 -0.8294655 0.4836475 0.2794138 -0.8016671 0.4896361 0.3429087 -0.7764619 0.4985017 0.3854908 -0.8663098 -0.3107428 0.3910834 -0.8918846 -0.2947329 0.3430373 -0.9175212 -0.2826377 0.2797694 -0.8844016 -0.2334311 0.4041582 -0.9068707 -0.1217713 0.4034322 -0.8139521 -0.4207902 0.4005217 -0.8241418 -0.4123283 0.3882986 -0.8239619 -0.4124458 0.3885556 -0.8446364 -0.3505497 0.404604 -0.8534097 -0.3287087 0.4045277 -0.8259093 -0.309356 0.4713521 -0.8525058 -0.3303696 0.4050799 -0.8180152 -0.4094613 0.4039711 -0.7995901 -0.3879192 0.4584477 -0.8017897 -0.4016208 0.4425315 -0.8056622 -0.4067584 0.4306462 -0.8039582 -0.4019142 0.4383106 -0.8039583 -0.4019143 0.4383105 -0.8039582 -0.4019142 0.4383106 -0.1378689 -0.901082 0.4111487 -0.1324391 -0.9082818 0.396843 -0.1209961 -0.9144702 0.3861399 0.06069117 -0.9439972 0.3243239 -0.01573002 -0.9150666 0.402996 -0.1046082 -0.909653 0.4019808 -0.09225678 -0.9450796 0.3135495 -0.1097173 -0.9227581 0.3694316 -0.1468979 -0.9034609 0.4027152 -0.1292104 -0.8965483 0.4236813 -0.117433 -0.8812266 0.4578746 -0.0926944 -0.7778343 0.621596 0.7427303 -0.5332555 0.4049572 0.7441372 -0.5315686 0.404592 0.7904108 -0.4609389 0.4034676 0.7904505 -0.4609 0.4034346 0.8555122 -0.3245363 0.4034541 0.8554933 -0.3245785 0.4034602 0.8555036 -0.3244677 0.4035276 -0.1448863 -0.9031404 0.4041603 -0.2562141 -0.8785407 0.4031383 -0.2527732 -0.8793575 0.4035297 -0.3938739 -0.8259508 0.4033223 -0.3939911 -0.8258604 0.4033929 -0.3939012 -0.8258965 0.4034069 -0.2525846 -0.8794756 0.4033902 -0.8095281 -0.4175245 0.4127197 -0.8106118 -0.4238656 0.4040379 -0.7396431 -0.5385299 0.4036257 -0.7395862 -0.538695 0.4035096 -0.6408587 -0.6530511 0.4035151 -0.6407074 -0.6533197 0.4033206 -0.5221266 -0.751532 0.4032166 -0.52468 -0.7496086 0.403482 -0.5247715 -0.7495788 0.4034188 -0.5304028 -0.7458317 0.4029987 -0.7105481 0.5879747 0.3865324 -0.6937217 0.5962919 0.4039632 -0.5979631 0.6925239 0.4035479 -0.5981042 0.6924679 0.4034349 -0.4759501 0.781472 0.4034515 -0.3404077 0.8491853 0.4037411 -0.3406354 0.8491654 0.403591 -0.342344 0.8483971 0.403761 -0.475572 0.7815701 0.4037073 0.07220208 0.9070659 0.4147508 0.06379151 0.9124445 0.4041977 -0.04678565 0.9138774 0.4032856 -0.04622179 0.9137413 0.403659 -0.1959924 0.8936596 0.4036827 -0.1961326 0.893646 0.4036446 -0.1962643 0.8935784 0.4037302 -0.3413897 0.8487715 0.4037822 0.8453614 0.3487762 0.4046223 0.8744528 0.2692863 0.4035061 0.8744165 0.2693604 0.4035356 0.8744071 0.2694427 0.403501 0.9068346 0.1218445 0.4034909 0.9068323 0.1218008 0.4035094 0.9068443 0.1218438 0.4034693 0.9068377 0.1215264 0.40358 0.9145135 -0.02915012 0.4035039 0.91452 -0.02912163 0.4034913 0.8972608 -0.1792437 0.4034783 0.8972287 -0.1793098 0.4035205 0.8555437 -0.3243641 0.4035258 4.39661e-6 0 1 -8.88652e-6 0 1 8.92061e-6 0 1 8.62411e-6 0 1 -9.1088e-6 0 1 8.82122e-6 0 1 4.42509e-6 0 1 4.44429e-6 0 1 4.45983e-6 0 1 -4.48157e-6 0 1 1.97399e-6 0 1 4.30886e-6 0 1 -1.13827e-6 0 1 -2.30253e-6 0 1 -4.19717e-6 0 1 -3.10801e-6 0 1 1.02405e-6 0 1 2.02239e-6 0 1 -4.4101e-6 0 1 4.42917e-6 0 1 -1.09718e-6 0 1 -4.33666e-6 0 1 -2.15428e-6 0 1 9.10283e-6 0 1 -8.55169e-6 0 1 -1.8631e-5 0 1 8.38842e-6 0 1 -1.88751e-5 0 1 8.29105e-6 0 1 8.17822e-6 0 1 -1.94795e-5 0 1 8.07781e-6 0 1 0.9810083 -0.1939663 0 0.9994236 -0.03394991 0 0.9994235 -0.03395009 0 0.9919263 0.1268162 0 0.9919265 0.1268143 0 0.9586846 0.2844713 0 0.958685 0.28447 0 0.9009342 0.4339557 0 0.9009347 0.4339547 0 0.8193774 0.5732545 0 0.8193764 0.5732561 0 0.7168749 0.6972019 0 0.5949372 0.8037723 0 0.4595279 0.8881635 0 0.4595278 0.8881635 0 0.3109719 0.9504191 0 0.1536324 0.9881281 0 0.1536318 0.9881283 0 -0.006234824 0.9999806 0 -0.006234824 0.9999806 0 -0.1661405 0.9861021 0 -0.1661393 0.9861024 0 -0.322279 0.9466449 0 -0.3222802 0.9466443 0 -0.4707461 0.8822689 0 -0.4707457 0.882269 0 -0.6057641 0.7956444 0 -0.7256025 0.6881141 0 -0.8266359 0.5627372 0 -0.8266353 0.5627381 0 -0.9060169 0.4232416 0 -0.9060174 0.4232405 0 -0.9623064 0.2719677 0 -0.9623067 0.2719665 0 -0.9934402 0.1143535 0 -0.9934403 0.1143522 0 -0.9989166 -0.04653584 0 -0.9989166 -0.04653841 0 -0.9784882 -0.2063028 0 -0.9784877 -0.206305 0 -0.9327995 -0.360396 0 -0.9327988 -0.3603977 0 -0.8629087 -0.5053598 0 -0.862908 -0.5053611 0 -0.770616 -0.6372999 0 -0.7706139 -0.6373023 0 -0.6583107 -0.7527463 0 -0.6583105 -0.7527466 0 -0.5294471 -0.848343 0 -0.5294474 -0.8483428 0 -0.3859826 -0.9225061 0 -0.2323565 -0.9726308 0 -0.2323553 -0.972631 0 -0.07492578 -0.9971891 0 -0.07492607 -0.9971891 0 0.0874136 -0.9961722 0 0.08741295 -0.9961723 0 0.2448504 -0.9695609 0 0.2448515 -0.9695606 0 0.3972617 -0.9177054 0 0.3972643 -0.9177044 0 0.5405093 -0.841338 0 0.6673535 -0.7447412 0 0.7788869 -0.6271644 0 0.7788853 -0.6271665 0 0.8691873 -0.4944831 0 0.8691879 -0.4944821 0 0.9371734 -0.348864 0 0.9371738 -0.3488629 0 -6.51754e-6 0 1 -1.82916e-6 0 1 5.28583e-5 0 1 2.90495e-5 0 1 2.58147e-6 0 1 0.4309023 -0.5636937 0.7046791 0.3727277 -0.5499488 0.7474158 -0.5278503 -0.434388 0.7298501 -0.5199072 -0.4803082 0.7063998 -0.4182335 -0.5737271 0.7042146 -0.418145 -0.5737316 0.7042634 -0.4179409 -0.5743482 0.7038819 -0.2589908 -0.6614634 0.7038394 -0.2578936 -0.6613574 0.7043417 -0.2581946 -0.6609073 0.7046539 -0.08063733 -0.704952 0.7046562 -0.08166718 -0.7053943 0.7040948 -0.08077359 -0.7060678 0.7035226 0.1014133 -0.7034513 0.7034712 0.1005778 -0.7026594 0.7043819 0.1018766 -0.7030772 0.7037782 0.2776549 -0.6539678 0.7037286 0.2767796 -0.6535432 0.7044675 0.2768042 -0.653504 0.7044942 -2.64452e-5 0 1 4.57232e-6 0 1 -4.97202e-6 0 1 -2.58116e-6 0 1 -0.9934467 0.114297 -1.04804e-5 -0.9934482 0.1142835 1.35967e-5 -0.3724133 0.5499839 0.7475467 -0.4269345 0.5576832 0.7118402 0.5278599 0.4343968 0.729838 0.5197734 0.4809827 0.7060391 0.5208473 0.4793295 0.706372 0.4179379 0.5739322 0.7042229 0.4183546 0.5740211 0.7039029 0.4180251 0.5742172 0.7039388 0.2587318 0.6616114 0.7037956 0.2577788 0.6610576 0.7046652 0.2581225 0.6608542 0.7047302 0.0816043 0.7047549 0.7047421 0.08077132 0.706103 0.7034875 -0.09255242 0.7040736 0.70407 -0.1013799 0.703096 0.703831 -0.1014658 0.7031656 0.7037492 -0.276643 0.654324 0.703796 -0.2770913 0.6541141 0.7038147 -0.2770799 0.6541028 0.7038297 -0.3979454 0.585821 0.7060122 0.9934482 -0.1142836 -1.46991e-5 0.9934467 -0.114297 1.16449e-5 3.28838e-6 0 1 1.06181e-6 0 1 2.09661e-6 0 1 -4.24527e-6 0 1 3.15049e-6 0 1 -2.11079e-6 0 1 -7.18928e-6 0 1 6.68699e-6 0 1 -1.06175e-6 0 1 2.61605e-7 0 1 -2.65445e-7 0 1 -2.45283e-6 0 1 3.34207e-6 0 1 2.2121e-6 0 1 -3.15113e-6 0 1 -0.2328124 0.9725217 0 0.4526351 0.8916959 0 0.6081941 0.7937867 -0.001616775 0.7446756 0.6673713 0.008592724 0.7536686 0.6572147 0.007244884 0.8270844 0.5620622 -0.004214525 0.8683655 0.495925 0 0.9694163 0.2454224 0 0.9500772 0.311099 -0.02389305 0.9973229 0.04209208 0.05979347 0.7447049 0.667394 0 0.6668677 0.7424306 -0.06390959 0.7605458 0.6489635 -0.02041506 -0.409422 0.9123293 0.005398511 -0.211814 0.9772695 -0.008910417 -0.1266449 0.9910932 -0.04117441 0.003012239 0.9999955 0 0.3482874 0.9373879 0 0.2334239 0.9686399 -0.08514779 0.4489099 0.893577 -2.71271e-4 -0.4110299 0.9116057 0.005442321 -0.5724844 0.8194089 -0.02882152 -0.5958094 0.8028922 -0.0193777 -0.9616577 0.2676956 0.05961275 -0.8555569 0.5171857 -0.02326732 -0.8884245 0.4590228 0 -0.7273173 0.6863013 0 -0.6778156 0.7352225 -0.003731489 -0.6759119 0.7369813 0.001354813 -0.726499 0.6871675 0 -0.8884246 0.4590228 0 -0.5727235 0.8197488 0 -0.4518057 0.8918369 0.02232867 -0.5860736 0.8102278 0.006979048 0.610767 0.7918089 -0.001617014 0.4280905 0.9037333 0.00222367 0.3482723 0.93734 0.01000398 0.2227341 0.9748793 0 -0.1267526 0.9919345 0 1.85386e-4 0.9997752 0.02120435 -0.2354074 0.9718968 -4.16016e-5 -0.8884246 0.4590225 0 -0.9999803 -0.006295204 0 -0.8826379 -0.4700537 0 -0.882638 -0.4700534 0 -0.5627694 -0.826614 0 -0.5627692 -0.826614 0 -0.2323767 -0.9726259 0 -0.1142152 -0.9934406 -0.005555629 0.00556302 -0.9999846 0 0.3607119 -0.9326773 0 0.3607122 -0.9326772 0 0.7524468 -0.658653 0 0.7524468 -0.6586531 0 0.9724158 -0.2332545 0 0.9724159 -0.233254 0 0.9694163 0.2454221 0 0.9694162 0.2454224 0 0.8666097 0.4989867 0 0.8265454 0.5628684 0.001440167 0.9177383 -0.1055732 0.3828979 -0.7988442 0.09189754 -0.5944769 -0.9177804 0.1055766 -0.3827959 -0.7887772 0.07553756 0.6100202 -0.4166122 0.06493073 0.9067626 -0.6048013 0.0666179 0.7935853 -0.4125916 0.04444056 0.9098315 -0.3804123 0.04395687 0.9237717 -0.132148 0.01496249 0.9911171 -0.1296024 0.01491034 0.991454 -0.9854031 0.1087532 0.1309716 -0.9013709 0.107125 0.4195891 -0.9176859 0.105569 0.3830246 -0.7988874 0.09190374 0.5944181 -0.6488707 0.09141266 0.7553878 -0.9903531 0.1139584 -0.07883119 -0.9903535 0.1139535 0.0788325 -0.9617109 0.119094 0.2468379 -0.9871068 0.09137207 -0.1314206 -0.9030831 0.1311172 -0.4089613 -0.9617688 0.1190889 -0.2466145 -0.6234508 0.09095668 -0.7765541 -0.7886661 0.07319813 -0.6104488 -0.6176743 0.06954574 -0.783353 -0.6046853 0.06955593 -0.7934215 -0.3824088 0.04398936 -0.9229456 -0.3804662 0.04395765 -0.9237495 -0.1321301 0.01499849 -0.9911189 0.7852172 -0.1055028 -0.6101666 0.4205058 -0.03139573 -0.9067466 0.6040585 -0.07244199 -0.7936409 0.4121498 -0.05043685 -0.9097191 0.3805076 -0.04356074 -0.9237514 0.1320286 -0.01538193 -0.9911266 0.1300248 -0.01495921 -0.9913979 -0.1299879 0.01495498 -0.9914029 0.9844017 -0.1178991 -0.130588 0.9021226 -0.100323 -0.4196549 0.9177147 -0.1055741 -0.3829541 0.7988885 -0.09190124 -0.5944169 0.6527042 -0.05832839 -0.7553642 0.9903853 -0.1139319 0.07846349 0.9903854 -0.1139304 -0.0784648 0.9636464 -0.1024038 -0.2467775 0.9821059 -0.135227 0.1310795 0.9092002 -0.07733887 0.4091134 0.9637742 -0.1024474 0.2462598 0.1301836 -0.01497751 0.9913768 0.1323313 -0.01543378 0.9910854 0.3806577 -0.04356545 0.9236893 0.3828474 -0.0440365 0.9227614 0.6046424 -0.06955373 0.7934545 0.6174829 -0.07255041 0.7832314 0.7848344 -0.1078472 0.6102492 0.6278244 -0.05299133 0.7765491 0.7987481 -0.09188377 0.5946083 -0.5606663 0.8280419 0 -0.6812229 0.7294098 -0.062424 -0.6482889 0.7613945 0 -0.829123 0.5590664 0 -0.8293775 0.5586885 2.13801e-4 -0.7345308 -0.6785753 0 -0.8295111 0.5584904 0 -0.9494321 0.3139725 0 -0.9494318 0.3139736 0 -0.9989305 0.04623705 0 -0.9989305 0.04623794 0 -0.9743686 -0.2249575 0 -0.9743685 -0.2249581 0 -0.8768634 -0.4807397 0 -0.8775379 -0.4795073 -2.88527e-4 -0.8776662 -0.4792726 0 -0.7898213 -0.6133371 0 -0.715237 -0.6984392 -0.02487665 -0.70569 -0.7084626 -0.009082555 -0.5890415 -0.8080453 0.009645104 0.6228969 -0.7673026 -0.1524676 0.5197655 -0.854309 0 0.5609825 -0.8277092 -0.01400303 0.5383109 -0.8427464 0 0.7457195 -0.6662601 0 0.7455713 -0.6664258 -2.29821e-4 0.7447968 -0.6672914 0 0.8978858 -0.4402286 0 0.8978842 -0.4402318 0 0.9833322 -0.181818 0 0.983332 -0.1818193 0 0.9959206 0.09023422 0 0.9959205 0.09023517 0 0.934682 0.3554852 0 0.9346746 0.3555047 1.60269e-5 0.9346652 0.3555293 0 0.8304426 0.5571043 0 0.803413 0.5939944 -0.04121214 0.7478809 0.6638329 0 0.1297475 -0.9908856 0.03621172 0.1751483 -0.9842255 0.02497076 0.2547543 -0.9668644 0.01653617 0.3570542 -0.9340317 0.00986272 0.1382942 -0.9903912 -3.83932e-4 0.1211138 -0.9926372 -0.001689493 0.09234374 -0.9957054 -0.006583213 -0.3145424 -0.9492183 -0.00690937 -0.2780919 -0.9603422 -0.02019762 0.05344283 -0.9983681 -0.02012455 0.001924991 -0.9986044 -0.05277907 0.02201724 -0.999222 -0.03272151 -0.08335781 -0.9965197 0 -0.2482346 -0.9686999 0 -0.1594639 -0.9797824 -0.1208216 -0.2293441 -0.9719672 -0.05178064 -0.3456068 -0.9383786 -0.001323103 -0.3494578 -0.9369516 -0.001035749 -0.5639894 -0.8257223 0.009951353 -0.4601814 -0.8876551 0.01736843 -0.3965603 -0.9176746 0.02476805 -0.3503091 -0.9359071 0.03689801 -0.3076764 -0.9495113 0.06134843 -0.363878 -0.9314392 -0.003703236 -0.2087274 -0.9779738 4.99668e-4 -0.1134651 -0.9918982 0.05712789 -0.1551339 -0.9844642 0.08224189 -0.1132664 -0.9901598 0.08218514 -0.07831263 -0.9962443 0.0369386 0.1410846 -0.9856823 -0.09233438 0.02994942 -0.9922528 0.120571 0.08441632 -0.9945593 0.06103789 -0.5883615 -0.8085404 0.009647965 -0.5008444 -0.865465 -0.01119345 -0.3645883 -0.931164 0.002997279 -0.4979332 -0.8671583 0.009963035 -0.5025698 -0.864478 0.01008158 -0.573282 0.8193548 0.00235182 -0.5619183 0.8271896 0.002353608 -0.4185844 0.9081606 -0.005620956 -0.3900459 0.9207888 0.003510057 -0.1567583 0.9876312 0.003421187 -0.3892853 0.9207615 -0.02560108 -0.1585358 0.9873463 -0.00370115 -0.1428207 0.9897478 0.001259207 -0.130276 0.991477 0.001266062 0.1145617 0.9934156 -0.001122057 0.1136501 0.9935199 -0.001402437 0.3638355 0.9314626 0.001092612 0.3776516 0.9259473 0.001095712 0.364204 0.9313169 -0.002077937 0.379198 0.9253088 -0.003574371 0.5885475 0.8084557 0.003394722 0.5886619 0.8083722 0.003399014 0.6134337 0.7897261 -0.005656719 0.7358317 0.6771603 0.002391576 0.7339642 0.6791841 0.002394437 0.2917473 -0.9564433 0.009992301 0.2916895 -0.9564611 0.009972572 0.1434089 -0.9896595 0.002827465 0.2906649 -0.9567583 -0.01129585 0.3899571 -0.9207813 0.009771287 0.3899986 -0.9207636 0.009774565 -0.2153658 -0.9765334 0 -0.5085905 -0.8610086 0 -0.508589 -0.8610095 0 -0.8149126 -0.579584 0 -0.8149134 -0.5795828 0 -0.9801388 -0.1983129 0 -0.980139 -0.1983119 0 -0.9760707 0.2174536 0 -0.9760711 0.2174521 0 -0.8032284 0.5956712 0 -0.8032264 0.5956739 0 -0.4917131 0.8707574 0 -0.4917129 0.8707575 0 -0.09380722 0.9955904 0 -0.0938065 0.9955905 0 0.3175382 0.9482456 0 0.3175376 0.9482457 0 0.6767055 0.7362538 0 0.6767029 0.7362563 0 0.9174867 0.3977668 0 0.9174873 0.3977653 0 0.9999518 -0.009819209 0 0.9999518 -0.009819209 0 0.9094318 -0.4158532 0 0.9094306 -0.4158558 0 0.6615322 -0.7499169 0 0.6615313 -0.7499176 0 0.3005347 -0.9537709 0 0.3005362 -0.9537704 0 -0.01197439 -0.9999284 0 -0.1141831 -0.9929152 -0.0328918 -0.09499627 0.9954777 1.88431e-4 -0.09463471 0.9955121 0 -0.4923068 0.8704218 0 -0.491357 0.8709582 -3.03528e-4 -0.4912768 0.8710035 -2.79618e-4 -0.4926839 0.8702085 0 -0.8032159 0.5956881 0 -0.8032175 0.5956859 0 -0.9760733 0.2174416 0 -0.9760732 0.2174424 0 -0.9801369 -0.1983224 0 -0.9801366 -0.1983234 0 -0.8143886 -0.58032 0 -0.8145143 -0.5801435 -8.08045e-5 -0.8146594 -0.5799399 0 -0.5135372 -0.8580673 0 -0.508589 -0.8610095 3.76845e-4 -0.5080201 -0.8613454 0 -0.2167539 -0.9762263 0 -0.1142033 -0.9932653 -0.01953989 -0.2183893 -0.9735476 -0.06716585 -0.009551346 -0.9999544 0 0.2994271 -0.9541193 0 0.6618593 -0.7496282 0 0.6615417 -0.7499084 -1.21175e-4 0.661265 -0.7501524 0 0.9096356 -0.4154074 0 0.9096354 -0.4154077 0 0.9999519 -0.009818792 0 0.9999518 -0.009818971 0 0.9174911 0.3977563 0 -0.09634 0.9953486 0 0.3186165 0.9478838 0 0.3186179 0.9478833 0 0.6767363 0.7362255 0 0.6767037 0.7362555 1.34546e-5 0.6766181 0.7363342 0 0.9174911 0.3977565 0 -0.2176769 -0.9760209 0 -0.5085898 -0.8610091 0 -0.4908111 0.871266 3.16438e-4 -0.4892866 0.8721231 0 -0.9801342 -0.1983354 0 -0.9801344 -0.1983347 0 -0.8151547 -0.5792436 0 -0.8149129 -0.5795835 1.41272e-4 -0.8146335 -0.5799761 0 -0.5085894 -0.8610093 0 -0.005739331 -0.9976631 -0.068084 -0.1142221 -0.9932699 -0.01919013 -0.01224613 -0.999925 0 0.3001027 -0.953907 0 0.2994298 -0.9541183 -4.2402e-4 0.293535 -0.9559484 0 0.6618472 -0.7496389 0 0.6622167 -0.7493125 1.47985e-4 0.6625373 -0.7490289 0 0.9094262 -0.4158656 0 0.9094268 -0.4158643 0 0.9999519 -0.009807586 0 -0.4913684 0.8709519 0 -0.09497994 0.9954792 0 -0.09498006 0.9954792 0 0.3174611 0.9482714 0 0.3186178 0.9478833 -1.88419e-4 0.318927 0.9477794 0 0.6755307 0.7373319 0 0.6758225 0.7370645 1.10441e-4 0.6764369 0.7365007 -5.82437e-5 0.6766741 0.7362827 0 -0.5076997 -0.8615341 0 -0.8149133 -0.5795829 0 -0.8149125 -0.5795841 0 -0.9801346 -0.1983339 0 -0.9801341 -0.1983362 0 -0.803218 0.5956854 0 -0.8032152 0.5956891 0 -0.4917233 0.8707515 0 -0.4917206 0.8707531 0 -0.09379023 0.9955921 0 -0.09379011 0.9955921 0 0.6767036 0.7362555 0 0.9174823 0.3977767 0 0.9174829 0.3977752 0 0.9999514 -0.009866535 0 0.9096393 -0.415399 0 0.9096375 -0.4154031 0 0.6615533 -0.7498982 0 0.6615544 -0.7498973 0 0.2994273 -0.9541192 0 0.2994269 -0.9541193 0 -0.1104124 -0.9938848 -0.001556336 -0.1104124 -0.9938848 -0.001556336 -0.1104124 -0.9938848 -0.001551151 -0.01002633 -0.9999487 -0.001511931 -0.114283 -0.9928789 -0.03362727 -0.2176422 -0.9760286 0 -0.5076977 -0.8615354 0 0.3174594 0.9482719 0 0.3174599 0.9482717 0 0.3176134 0.9482203 0 0.6767047 0.7362546 0 -0.5085895 -0.8610091 0 -0.8032161 0.5956878 -6.72978e-5 -0.8032551 0.5956352 0 -0.9760733 0.217442 0 -0.9801343 -0.1983352 0 -0.9801344 -0.1983345 0 -0.8149484 -0.5795336 0 -0.8149185 -0.5795755 1.00907e-5 -0.8148219 -0.5797115 0 -0.1141605 -0.9928921 -0.03365743 -0.005752921 -0.9999828 0.001160979 0.3001024 -0.9539071 0 0.3005188 -0.953776 2.42207e-4 0.3041563 -0.9526222 0 0.6608041 -0.7505585 0 0.6615484 -0.7499025 1.61568e-4 0.661782 -0.7496964 0 0.9094236 -0.4158712 0 0.9094232 -0.4158719 0 0.999952 -0.009807467 0 -0.7996153 0.6005127 0 -0.4907971 0.8712739 0 -0.4907969 0.8712741 0 -0.09499746 0.9954776 0 -0.09499788 0.9954776 0 0.3186142 0.9478845 -1.615e-4 0.3189231 0.9477806 0 0.6755675 0.7372983 0 0.6760529 0.7368531 1.61586e-4 0.676408 0.7365272 0 0.9157744 0.4016931 0 0.9174909 0.3977568 -2.69206e-5 0.917509 0.397715 0 0.999952 -0.009807407 0 -0.09497892 0.9954793 1.61513e-4 -0.4923376 0.8704044 0 -0.4917134 0.8707572 -2.28783e-4 -0.4912525 0.8710173 0 -0.7990783 0.601227 0 -0.8032159 0.5956881 -4.03787e-5 -0.8032613 0.5956267 0 -0.9760729 0.217444 0 -0.9801363 -0.1983249 0 -0.9801368 -0.1983225 0 -0.8144171 -0.5802801 0 -0.814515 -0.5801426 -8.41716e-5 -0.513665 -0.8579909 0 -0.5085897 -0.861009 3.49928e-4 -0.5080048 -0.8613543 0 -0.2167527 -0.9762266 0 -0.218883 -0.9757511 3.86883e-4 -0.1141605 -0.9928911 -0.03368431 -0.009551346 -0.9999545 0 0.6607384 -0.7506164 0 0.6615408 -0.7499093 1.61567e-4 0.6617963 -0.7496838 0 0.9096352 -0.4154081 0 0.9999517 -0.009831011 0 -0.09625601 0.9953567 0 0.3186014 0.9478889 0 0.3186011 0.9478889 0 0.6767051 0.7362542 0 0.6767033 0.736256 0 0.9153618 0.4026325 0 0.9174867 0.3977668 -4.03807e-5 0.9999517 -0.009831011 0 -0.1568452 0.9876233 0 -0.5191956 0.8546556 0 -0.5192019 0.8546516 0 -0.520313 0.8539757 0 -0.5181257 0.8553045 2.92183e-4 -0.5176172 0.8556123 0 -0.8034524 0.5953691 0 -0.8034535 0.5953677 0 -0.968904 0.2474369 0 -0.9687181 0.2481641 -6.98079e-5 -0.9686924 0.2482642 0 -0.9911224 -0.1329526 0 -0.9906415 -0.1364898 -3.19652e-5 -0.8657396 -0.5004948 0 -0.8657388 -0.5004961 0 -0.7766126 -0.6299785 0 -0.7777113 -0.6286218 0 -0.7777125 -0.6286202 0 -0.4809792 -0.8767321 0 -0.4809803 -0.8767315 0 0.6143776 -0.7890121 0 0.6143797 -0.7890105 0 -3.67197e-6 0 1 -0.9997687 -0.0215106 0 -0.9337556 0.3579113 1.27165e-5 -0.9997687 -0.02151072 0 -0.9172115 -0.3984009 0 -0.9172421 -0.3983302 1.67225e-5 -0.9174686 -0.3978083 -1.00422e-4 -0.9175394 -0.3976449 0 -0.6992484 -0.7148789 0 -0.6992502 -0.714877 0 -0.6983775 -0.7157297 0 -0.6983758 -0.7157314 0 -0.3770519 -0.9261922 0 -0.3770531 -0.9261916 0 -0.6660385 0.2405527 0.7060647 -0.6661525 0.2404468 0.7059931 -0.6662202 0.2402989 0.7059796 -0.6660611 0.2404934 0.7060634 -0.6951669 0.1350596 0.7060467 -0.6951553 0.1350384 0.7060621 -0.695163 0.1350218 0.7060579 -0.7076843 0.02638375 0.706036 -0.7076757 0.02636277 0.7060455 -0.7076995 0.02630859 0.7060235 -0.7032966 -0.08300697 0.706034 -0.7032971 -0.082942 0.706041 -0.7033104 -0.08283108 0.7060408 0.1918405 -0.9814261 0 0.1936765 -0.9810655 -3.16654e-4 0.1942509 -0.9809519 0 0.1936222 -0.9810762 -2.82202e-4 1.68784e-7 0 1 -4.36651e-6 0 1 -0.5413207 -0.4565922 0.7060421 -0.5404387 -0.4577019 0.7059993 -0.5413126 -0.4566114 0.706036 -0.541275 -0.4568109 0.7059357 -0.464772 -0.5344594 0.7059322 -0.4646106 -0.5346447 0.7058982 -0.4646729 -0.5343942 0.7060467 -0.4641901 -0.5347841 0.7060692 -0.3763161 -0.5998578 0.7060857 -0.3762494 -0.5999812 0.7060163 -0.2800775 -0.65033 0.7061356 -0.2799198 -0.6505274 0.7060163 -0.2797893 -0.6505517 0.7060456 -0.3765162 -0.5997722 0.7060517 1.08397e-6 0 1 6.28087e-7 0 1 -1.62425e-5 0 1 7.58157e-6 0 1 0.124929 -0.6969437 0.7061603 0.1246353 -0.6971781 0.7059808 0.1252452 -0.6971441 0.7059063 0.2307156 -0.6696917 0.7058919 0.2304152 -0.6696851 0.7059963 0.2307886 -0.6694539 0.7060936 0.2314853 -0.669295 0.7060162 0.3305669 -0.6262938 0.7060322 0.3308932 -0.6261694 0.7059898 0.3310042 -0.62603 0.7060615 0.422438 -0.5685601 0.7058935 0.4234876 -0.5677274 0.7059347 0.4235739 -0.5675247 0.7060459 0.3311387 -0.6259783 0.7060441 1.57558e-6 0 1 -1.49971e-6 0 1 2.29082e-6 0 1 0.8657432 0.5004885 0 0.1568303 -0.9876255 0 0.5183425 -0.8551731 0 0.5183459 -0.8551711 0 0.8037198 -0.595008 0 0.8033834 -0.5954623 -2.74332e-4 0.8029688 -0.5960212 -1.67062e-4 0.8039495 -0.5946975 0 0.9687169 -0.2481682 0 0.9687173 -0.2481669 0 0.9911225 0.1329522 0 0.9906415 0.1364898 3.19652e-5 -0.4109591 -0.9116539 0 -0.4109284 -0.9116675 4.26913e-4 -0.4108327 -0.9117108 4.08833e-4 0.6660316 -0.2405483 0.7060726 0.6661392 -0.240442 0.7060073 0.6662437 -0.2403138 0.7059524 0.666077 -0.2404953 0.7060478 0.6951534 -0.135057 0.7060605 0.6951571 -0.1350381 0.7060604 0.7033145 0.08283013 0.7060368 0.7033178 0.08291226 0.7060239 0.7033069 0.08294457 0.706031 0.7032914 0.08300602 0.7060391 0.7076923 -0.02630794 0.7060309 0.7076775 -0.02636319 0.7060437 0.7076948 -0.02638411 0.7060255 0.6951589 -0.1350225 0.7060617 -0.1936611 0.9810684 -3.41013e-4 -0.1942259 0.9809569 0 -0.1936228 0.9810761 -2.64564e-4 0.9174353 0.3978852 0 0.9337557 -0.3579111 1.16265e-5 0.9997685 0.02151924 0 0.9997686 0.02151066 -6.3553e-6 0.9997699 0.02144896 0 0.9174353 0.397885 0 0.698978 0.7151432 0 0.6990796 0.7150439 6.97641e-5 0.6992652 0.7148624 0 0.3770394 0.9261972 0 0.5839914 -0.8117599 0 0.5840076 -0.8117482 7.75972e-5 0.5841944 -0.8116138 0 0.5841364 -0.8116557 0 0.280075 0.6503389 0.7061284 0.2799219 0.6505199 0.7060225 0.2797944 0.6505637 0.7060326 0.3766659 0.5996834 0.7060472 0.3763182 0.5998793 0.7060663 0.3762251 0.5999419 0.7060626 0.4642165 0.5347679 0.706064 0.4646824 0.5344051 0.7060323 0.4645952 0.5346339 0.7059164 0.4648429 0.5344794 0.7058703 0.5416129 0.4564498 0.7059101 0.5411297 0.4566946 0.7061224 0.5409739 0.4570106 0.7060373 0.540376 0.4576444 0.7060847 -0.5038213 -0.8635839 -0.01967352 -0.5316283 -0.8468618 0.0140134 -0.5312255 -0.8471149 0.01400029 -0.6389455 -0.7690874 -0.01591223 -0.6561364 -0.754584 0.009389996 -0.6561678 -0.7545568 0.009380161 -0.7567573 -0.6536169 -0.01017349 -0.7642093 -0.644958 0.003662645 -0.7631033 -0.6462661 0.003687024 -0.8541839 -0.5199558 -0.004011929 -0.9763894 -0.2144409 -0.0260539 -0.992864 -0.1169316 0.02341246 -0.9909288 -0.1168644 -0.06635469 -0.9990158 0.03713703 0.02425497 -0.9931564 0.114257 0.02420473 -0.9961263 0.03713768 -0.07970774 -0.9813662 0.1906138 0.02422475 -0.9813566 0.1906641 0.02421951 -0.9607428 0.2760778 -0.02747017 -0.9403085 0.3395159 0.02343136 -0.9403439 0.3394176 0.02343255 -0.9022135 0.430509 -0.02594166 -0.8889759 0.4579539 0 -0.8193324 0.5733188 0 -0.7158042 0.6983011 0 -0.7136363 0.7005048 -0.004022538 -0.596261 0.8027822 0.003684878 -0.5981263 0.8013935 0.003667712 -0.5888363 0.8081868 -0.0102989 -0.4675392 0.8839227 0.009364366 -0.4671996 0.8841026 0.009340345 -0.4477201 0.8940436 -0.01526266 -0.3267987 0.9449856 0.0143156 -0.3253195 0.945496 0.01430183 -0.2943993 0.9554855 -0.01940381 -0.1767886 0.9840749 0.01850825 -0.1764101 0.9841428 0.01850223 -0.1328296 0.9908635 -0.02336561 0.2992548 0.9541732 0 0.3954716 0.9182917 0.0185154 0.3950185 0.9184865 0.01851665 0.5038213 0.8635833 -0.01969587 0.5316284 0.846862 0.01400482 0.5312254 0.8471146 0.0140227 0.6389499 0.7690837 -0.01591217 0.6561355 0.7545845 0.009403824 0.6562042 0.7545248 0.009398162 0.7567571 0.6536167 -0.0101884 0.7642062 0.6449617 0.003677785 0.7631034 0.6462661 0.003674268 0.8541819 0.519959 -0.004019379 0.9763894 0.2144409 -0.02605301 0.9928643 0.1169295 0.02341204 0.9909288 0.1168652 -0.06635344 0.9990159 -0.03713643 0.02425456 0.9990118 -0.03724712 0.02425503 0.9930661 -0.1141951 -0.02791476 0.9813631 -0.1906162 0.02433407 0.9813538 -0.1906635 0.02433943 0.960712 -0.2761937 -0.02738106 0.9403094 -0.3395132 0.02343446 0.9403442 -0.3394176 0.02342247 0.9022131 -0.4305097 -0.02594172 0.8889741 -0.4579576 0 0.8193342 -0.5733162 0 0.8193348 -0.5733153 0 0.7158014 -0.6983041 0 0.7136336 -0.7005077 -0.004017889 0.5963758 -0.8026971 0.003661394 0.5981223 -0.8013965 0.003667712 0.5888364 -0.808187 -0.01028025 0.4675884 -0.8838968 0.009358942 0.4671943 -0.8841053 0.009340345 0.44772 -0.8940435 -0.0152738 0.3268336 -0.9449737 0.01430386 0.3253118 -0.9454984 0.01432126 0.2944049 -0.9554834 -0.01942241 0.1767887 -0.984075 0.01850092 0.1764094 -0.9841426 0.01852345 0.1328235 -0.9908635 -0.02340292 -0.2992355 -0.9541793 0 -0.3954792 -0.9182887 0.01849961 -0.3950188 -0.9184872 0.01848447 -9.7045e-6 0 1 2.80934e-6 0 1 -1.54363e-6 0 1 0.7766037 0.6299895 0 0.7766053 0.6299877 0 0.7777669 0.6285529 0 0.4809681 0.8767383 0 0.4809668 0.8767388 0 -0.6143348 0.7890455 0 -0.6143368 0.789044 0 0.9950166 0.09970951 4.00196e-5 0.9950238 0.09963792 8.94093e-5 0.9950123 0.09975248 0 0.3691779 0.9293587 0 -0.1472682 0.9890967 0 -0.1472683 0.9890966 0 -0.9299748 0.3676235 0 -0.9299752 0.3676223 0 -0.9891442 -0.1469483 0 -0.9891443 -0.1469478 0 -0.7838715 -0.6209231 0 -0.7838702 -0.6209248 0 -0.3671283 -0.9301704 0 0.9891963 0.1465979 0 0.782961 0.6220709 0 0.7829614 0.6220704 0 0.3691778 0.9293588 0 0.14837 -0.988932 0 0.1483705 -0.9889319 0 0.9891974 0.1465901 0 0.9891968 0.1465933 0 0.7829473 0.6220883 0 0.7829464 0.6220893 0 0.3691332 0.9293766 0 -0.3670971 -0.9301827 0 -0.3692085 -0.9293466 0 0.1473038 -0.9890913 0 0.1473039 -0.9890914 0 0.9299747 -0.3676237 0 0.9299752 -0.3676225 0 0.9891435 0.1469535 0 0.9891434 0.1469539 0 0.7838845 0.6209067 0 0.7838858 0.6209051 0 0.3670976 0.9301825 0 -0.9299723 0.3676298 0 -0.989197 -0.1465925 0 -0.9891971 -0.1465917 0 -0.7829465 -0.622089 0 -0.782947 -0.6220885 0 -0.3692084 -0.9293467 0 0.9299762 -0.3676196 6.42172e-5 0.9296305 -0.368493 0 0.3671278 0.9301706 0 -0.1484201 0.9889245 0 -0.1484207 0.9889243 0 -0.9892992 -0.1459013 0 -0.9891965 -0.1465954 -5.73911e-5 -0.9891614 -0.1468325 0 -0.7829617 -0.6220701 0 -0.7829607 -0.6220712 0 -0.3690876 -0.9293947 0 -0.3690894 -0.9293939 0 0.1472681 -0.9890966 0 0.9300914 -0.3673282 0 3.35435e-5 0 -1 2.23491e-6 0 -1 -4.88281e-6 0 -1 -2.03543e-7 0 -1 -8.78364e-6 0 -1 -2.98929e-7 0 -1 5.84331e-6 0 -1 3.50123e-6 0 -1 -3.54088e-6 0 -1 5.88429e-6 0 -1 -3.50118e-6 0 -1 1.942e-6 0 -1 -1.62043e-6 0 -1 6.34276e-6 0 -1 -2.55086e-6 0 -1 4.22754e-6 0 -1 -7.02484e-6 0 -1 -2.2063e-6 0 -1 -4.74792e-6 0 -1 -8.79569e-6 0 -1 -5.38283e-6 0 -1 1.55775e-6 0 -1 -4.7837e-6 0 -1 2.2839e-6 0 -1 3.84462e-6 0 -1 -5.10376e-6 0 -1 6.34639e-6 0 -1 -2.26183e-5 0 -1 1.39896e-6 0 -1 -3.24136e-6 0 -1 5.16579e-6 0 -1 -5.23472e-6 0 -1 1.43332e-6 0 -1 -1.03814e-6 0 -1 5.52685e-5 0 -1 -3.54922e-6 0 -1 -8.79941e-6 0 -1 1.77271e-5 0 -1 -2.89144e-6 0 -1 2.69713e-5 0 -1 5.9208e-6 0 -1 -7.67212e-6 0 -1 7.32156e-6 0 -1 6.75584e-6 0 -1 -7.80196e-6 0 -1 -1.05226e-5 0 -1 -1.51258e-5 0 -1 1.27095e-5 0 -1 -1.56318e-5 0 -1 2.6812e-6 0 -1 -2.93083e-6 0 -1 -5.71742e-6 0 -1 2.45194e-6 0 -1 -5.23127e-6 0 -1 2.63432e-6 0 -1 -2.65078e-6 0 -1 -2.65215e-6 0 -1 3.19497e-6 0 -1 -1.36169e-5 0 -1 -1.3365e-6 0 -1 3.61679e-6 0 -1 -3.53923e-6 0 -1 -5.81278e-6 0 -1 -1.3102e-4 0 -1 -1.30729e-4 0 -1 -1.30895e-4 0 -1 -9.63644e-7 0 -1 -7.10389e-6 0 -1 1.08333e-5 0 -1 -1.4332e-5 0 -1 8.05127e-6 0 -1 -6.45128e-6 0 -1 3.6904e-7 0 -1 2.65083e-6 0 -1 -1.32553e-6 0 -1 6.2837e-6 0 -1 8.05172e-6 0 -1 -1.47728e-5 0 -1 -1.0834e-5 0 -1 -8.07269e-6 0 -1 9.70859e-6 0 -1 -9.11876e-6 0 -1 1.51647e-6 0 -1 1.36173e-5 0 -1 -4.90292e-6 0 -1 -1.56161e-4 0 -1 1.75858e-6 0 -1 -1.42304e-5 0 -1 -4.68727e-6 0 -1 6.96786e-6 0 -1 5.89623e-5 0 -1 3.75038e-6 0 -1 4.45537e-6 0 -1 4.27637e-7 0 -1 -1.9756e-6 0 -1 -4.68516e-6 0 -1 2.40004e-6 0 -1 -1.59497e-5 0 -1 -2.77236e-6 0 -1 4.02876e-5 0 -1 3.64618e-5 0 -1 -3.24305e-6 0 -1 0 0 -1 -9.36835e-7 0 -1 -2.98258e-5 0 -1 -3.03722e-6 0 -1 4.15987e-6 0 -1 -2.40052e-6 0 -1 -8.27048e-7 0 -1 2.39436e-6 0 -1 -1.60102e-6 0 -1 -3.78095e-6 0 -1 5.25597e-6 0 -1 6.93616e-6 0 -1 -1.82976e-5 0 -1 2.28745e-6 0 -1 -6.10203e-6 0 -1 3.84809e-6 0 -1 -1.77693e-4 0 -1 -1.77853e-4 0 -1 -1.77789e-4 0 -1 9.30129e-6 0 -1 -1.49679e-6 0 -1 2.75908e-6 0 -1 -2.63115e-6 0 -1 7.05577e-7 0 -1 2.99742e-5 0 -1 1.17327e-5 0 -1 -4.16056e-6 0 -1 2.1815e-6 0 -1 4.04053e-6 0 -1 -1.43008e-6 0 -1 -6.42264e-7 0 -1 -7.80214e-6 0 -1 1.20908e-6 0 -1 1.52618e-6 0 -1 -9.34286e-7 0 -1 -4.11265e-6 0 -1 1.25318e-6 0 -1 -1.21044e-6 0 -1 2.9002e-6 0 -1 2.81215e-6 0 -1 -3.77134e-6 0 -1 3.73871e-6 0 -1 -3.4211e-6 0 -1 -5.50491e-6 0 -1 7.5798e-7 0 -1 -4.11807e-6 0 -1 1.71396e-6 0 -1 1.01165e-5 0 -1 -1.01953e-5 0 -1 3.03956e-5 0 -1 5.14785e-6 0 -1 0 0 -1 -4.70945e-7 0 -1 -2.332e-5 0 -1 8.4317e-6 0 -1 2.54412e-6 0 -1 -6.76782e-6 0 -1 2.65506e-6 0 -1 -4.06987e-6 0 -1 2.5505e-6 0 -1 -1.21997e-5 0 -1 -3.38128e-6 0 -1 4.37598e-5 0 -1 -5.09341e-6 0 -1 -1.91688e-5 0 -1 3.71096e-6 0 -1 -1.29587e-5 0 -1 1.2578e-5 0 -1 -2.12527e-6 0 -1 -1.01239e-6 0 -1 1.44253e-5 0 -1 -5.49233e-6 0 -1 -5.93328e-7 0 -1 8.66431e-6 0 -1 -7.09784e-6 0 -1 -8.51591e-7 0 -1 7.01951e-6 0 -1 -1.03955e-6 0 -1 2.81453e-6 0 -1 -2.75743e-6 0 -1 9.58765e-7 0 -1 3.65129e-6 0 -1 6.96076e-6 0 -1 1.21669e-5 0 -1 1.0799e-5 0 -1 8.42681e-7 0 -1 -2.84498e-6 0 -1 2.30436e-6 0 -1 -2.81474e-6 0 -1 -3.67301e-6 0 -1 -3.49006e-6 0 -1 1.70379e-6 0 -1 -1.09361e-6 0 -1 1.36132e-5 0 -1 -1.58378e-5 0 -1 2.28804e-6 0 -1 1.67029e-5 0 -1 -6.46688e-6 0 -1 2.59032e-6 0 -1 4.20156e-6 0 -1 -7.05358e-6 0 -1 -8.40972e-6 0 -1 -3.23612e-6 0 -1 -4.16965e-6 0 -1 -2.75646e-6 0 -1 -0.1484159 0.9889251 0 -0.148415 0.9889252 0 -0.929978 0.3676156 0 -0.7829349 -0.6221038 0 -0.3691341 -0.9293763 0 0.1473032 -0.9890914 0 0.6224904 -0.7826275 0 0.9891445 0.146947 0 0.9891443 0.1469475 0 0.7838665 0.6209294 0 -6.44197e-6 0 1 -4.11171e-6 0 1 -9.4611e-7 0 1 -3.3997e-6 0 1 1.46086e-6 0 1 -1.46107e-6 0 1 8.34943e-7 0 1 -1.26447e-6 0 1 -1.06479e-6 0 1 -4.32175e-6 0 1 4.92799e-7 0 1 -4.65341e-6 0 1 3.21676e-6 0 1 9.70699e-6 0 1 5.06298e-6 0 1 3.38937e-5 0 1 1.03714e-6 0 1 2.68693e-6 0 1 -7.12181e-6 0 1 5.45066e-6 0 1 8.27508e-7 0 1 1.98498e-6 0 1 1.97117e-6 0 1 -7.71755e-6 0 1 1.15651e-5 0 1 4.59779e-6 0 1 4.16583e-6 0 1 -9.16758e-6 0 1 -4.49107e-6 0 1 3.30643e-5 0 1 1.04541e-5 0 1 -1.44429e-6 0 1 -1.73582e-6 0 1 -2.8595e-6 0 1 7.19751e-6 0 1 0 0 1 -4.3997e-6 0 1 2.92405e-6 0 1 -8.69021e-7 0 1 7.5589e-7 0 1 -4.25771e-6 0 1 6.95062e-6 0 1 -9.84686e-6 0 1 8.7868e-6 0 1 -1.1672e-5 0 1 1.83972e-5 0 1 -7.96381e-6 0 1 3.37792e-6 0 1 1.87395e-6 0 1 -1.38864e-6 0 1 8.611e-6 0 1 -5.27454e-6 0 1 2.16202e-5 0 1 1.05226e-5 0 1 -7.80202e-6 0 1 -1.00898e-6 0 1 -1.33982e-6 0 1 1.94589e-6 0 1 4.02194e-6 0 1 -1.8318e-6 0 1 -4.6813e-6 0 1 1.55322e-6 0 1 4.45545e-6 0 1 -4.01606e-6 0 1 1.8594e-6 0 1 2.65078e-6 0 1 -2.89419e-6 0 1 1.19851e-6 0 1 -2.43974e-5 0 1 -3.58187e-6 0 1 4.48962e-6 0 1 -8.98053e-6 0 1 4.06552e-7 0 1 1.92883e-6 0 1 -2.00096e-6 0 1 -1.02111e-5 0 1 1.45866e-5 0 1 -1.14411e-5 0 1 2.70516e-6 0 1 -7.4958e-6 0 1 -2.73907e-6 0 1 -5.33538e-6 0 1 -2.89288e-6 0 1 2.27128e-5 0 1 -1.88009e-5 0 1 1.44249e-6 0 1 2.44069e-5 0 1 -2.28728e-6 0 1 1.27807e-6 0 1 -3.0385e-6 0 1 -4.28449e-6 0 1 9.07853e-6 0 1 -2.00199e-6 0 1 -3.85797e-6 0 1 1.62612e-6 0 1 -4.48758e-6 0 1 -3.05521e-6 0 1 -7.21193e-7 0 1 7.69787e-6 0 1 3.03398e-6 0 1 3.79202e-6 0 1 -8.07181e-6 0 1 9.29645e-6 0 1 -2.03239e-6 0 1 5.96705e-6 0 1 -1.08464e-6 0 1 2.43203e-6 0 1 7.47742e-6 0 1 -2.70227e-6 0 1 3.3771e-6 0 1 -1.05162e-5 0 1 2.16313e-5 0 1 -3.4211e-6 0 1 -2.56335e-5 0 1 -3.728e-6 0 1 1.04901e-5 0 1 -1.42453e-5 0 1 4.38227e-6 0 1 9.53383e-7 0 1 2.46665e-6 0 1 -5.17341e-6 0 1 -1.79634e-6 0 1 -8.44024e-6 0 1 1.15719e-6 0 1 8.13948e-6 0 1 -2.36855e-5 0 1 8.74585e-5 0 1 -1.01763e-5 0 1 -3.02967e-6 0 1 7.58311e-6 0 1 -7.61823e-6 0 1 5.09362e-6 0 1 -4.37522e-5 0 1 1.01442e-5 0 1 -2.65601e-6 0 1 3.26951e-6 0 1 1.58819e-6 0 1 -1.10259e-6 0 1 1.7618e-5 0 1 -3.59092e-6 0 1 7.36768e-6 0 1 -9.60209e-6 0 1 9.35769e-6 0 1 -2.52382e-6 0 1 7.64503e-6 0 1 -4.38335e-6 0 1 2.17983e-6 0 1 -4.04536e-6 0 1 2.39427e-6 0 1 -3.24305e-6 0 1 4.86457e-6 0 1 -3.24423e-6 0 1 1.24495e-6 0 1 -2.46678e-6 0 1 4.0408e-6 0 1 -8.07077e-6 0 1 2.56312e-5 0 1 3.72823e-6 0 1 -7.58495e-7 0 1 -2.03477e-6 0 1 1.47388e-5 0 1 -3.44885e-6 0 1 3.04077e-6 0 1 2.63999e-5 0 1 1.46037e-5 0 1 -5.75612e-6 0 1 2.10211e-6 0 1 -4.79791e-6 0 1 7.36247e-6 0 1 -6.59339e-6 0 1 7.73629e-6 0 1 -6.22169e-6 0 1 4.18284e-6 0 1 -1.97999e-5 0 1 2.16158e-6 0 1 7.73742e-6 0 1 5.71037e-6 0 1 -1.72876e-6 0 1 -8.3675e-6 0 1 -5.4908e-6 0 1 6.3336e-6 0 1 6.59387e-6 0 1 -9.10084e-6 0 1 7.30951e-6 0 1 5.96481e-5 0 1 -3.48948e-6 0 1 -5.72303e-6 0 1 -5.49913e-6 0 1 2.92767e-6 0 1 1.1254e-6 0 1 -9.67717e-6 0 1 1.12914e-5 0 1 -1.46628e-6 0 1 -2.04925e-6 0 1 7.07908e-6 0 1 6.7627e-6 0 1 -4.205e-6 0 1 7.04106e-6 0 1 -5.72254e-6 0 1 -5.96516e-5 0 1 -0.4223859 0.5686554 0.7058479 -0.4225643 0.5684278 0.7059245 -0.4240019 0.5670807 0.7061458 -0.4235839 0.5675318 0.7060343 -0.4235268 0.5675512 0.706053 -0.3310787 0.6259484 0.7060989 -0.3310067 0.6260214 0.7060679 -0.3309005 0.6261713 0.7059848 -0.330577 0.6262996 0.7060225 -0.2314653 0.6692893 0.7060281 -0.2307759 0.6694541 0.7060975 -0.2304223 0.6696859 0.7059933 -0.2307217 0.6696836 0.7058976 -0.1252486 0.6971518 0.7058981 -0.1246294 0.6971732 0.7059866 -0.1249297 0.6969473 0.7061566 -0.7528559 -0.6581855 3.96939e-5 -0.7528995 -0.6581357 0 -0.7529764 -0.6580477 -5.99888e-5 -0.7531378 -0.6578629 -8.94061e-5 -0.7529574 -0.6580693 0 0.1512004 -0.9885031 0 -0.9976102 0.06909322 0 0.9284688 0.3714103 0 0.7769551 0.6295561 0 0.2776545 0.960681 0 -0.1715118 0.9851821 0 -0.8046543 -0.5937438 0 0.127726 -0.9918095 0 0.1083008 -0.9941182 0 -0.1139461 -0.993487 0 -0.3489509 -0.937141 0 -0.2634832 -0.9646641 0 -0.2454718 -0.969376 -0.007334113 -0.3506906 -0.9364722 0.005996763 -0.9104542 -0.4127733 -0.02629542 -0.9289527 -0.3701984 0 -0.8480042 -0.5299896 0 -0.9585067 -0.2850705 0 -0.9804049 -0.1966152 0.01219719 -0.9708806 -0.2395635 -5.05693e-4 -0.9585214 -0.2850205 0 -0.94403 -0.3298599 0 -0.9440298 -0.3298604 0 -0.8902828 0.4546467 -0.02632886 -0.8684877 0.4957109 0 -0.943135 0.33241 0 -0.9091978 0.4133848 0.04972505 -0.9439682 0.3300365 0 -0.8232545 0.5676726 0 -0.5754262 0.8178538 0 -0.6136518 0.7895768 0 -0.08080977 0.9958595 0.04163682 -0.1999034 0.9794577 -0.02648204 -0.07530009 0.997161 0 0.201169 0.9795562 -8.33235e-4 0.2026254 0.9792563 0 0.02672523 0.9996429 0 0.02479314 0.999692 -0.001087486 -0.07530003 0.997161 0 -0.1110571 0.9938141 0 -0.111057 0.9938141 0 0.3340895 0.9425414 0 0.2776501 0.9606823 0 0.3340899 0.9425413 0 0.3062891 0.9518995 0.008615016 0.4176356 0.9085161 -0.0133816 0.390904 0.9204315 0 0.7356705 0.6773396 0 0.8913753 0.4532651 -9.66703e-4 0.8921478 0.4517437 0 0.7979947 0.6026645 0 0.9451257 0.3267071 0 0.9942328 0.107243 0 0.9284894 0.3713589 0 0.9451259 0.3267067 0 0.9583241 0.2853983 -0.01275843 0.9706872 0.2403466 0 0.980904 0.1944931 0 0.9939751 0.1095989 0.001347124 0.9942333 0.1072399 3.77962e-5 0.9282345 -0.3719959 0 0.9101943 -0.4141804 -9.28861e-4 0.8907467 -0.4538601 0.02411478 0.8445422 -0.5354893 0 0.7055036 -0.7086795 0.006179332 0.7144168 -0.6997205 0 0.7930944 -0.6090989 0 0.8205513 -0.5714314 -0.01272112 0.8445422 -0.5354891 0 0.8713802 -0.4906085 0 0.871366 -0.4906337 0 -0.1715111 0.9851822 0 -0.3269896 0.945028 0 -0.3280078 0.944675 9.96181e-5 -0.5286519 0.8488388 0 -0.5286526 0.8488383 0 -0.5754261 0.8178539 0 -0.6137014 0.7895381 -4.84822e-4 -0.6403752 0.7679752 0.01157611 -0.6827483 0.7306537 0 -0.7649564 0.6440822 0 -0.766137 0.6426766 -0.001020014 -0.8232359 0.5676994 0 -0.8463292 0.5326602 0 -0.8463307 0.5326579 0 -0.3282086 0.9446053 0 -0.4910761 0.8711166 0 -0.4504255 0.8927974 -0.005462944 -0.491818 0.8706147 -0.01205384 -0.4812147 0.8764719 -0.01514542 -0.9439418 0.3301121 3.35439e-5 -0.943992 0.3299685 0 -0.9788293 0.2046789 0 -0.9872539 0.1586936 -0.01209509 -0.9884132 -0.1517875 0 -0.9884129 -0.1517898 0 -0.9998003 -0.01998728 0 -0.9997631 -0.02176415 -5.91368e-5 -0.9997981 -0.02007681 -8.9283e-4 -0.9976116 0.06907343 0 -0.9932686 0.1158351 0 -0.9932686 0.1158345 0 -0.7101684 -0.7040319 0 -0.6072241 -0.7945302 -7.33952e-4 -0.6063767 -0.7951774 -5.87391e-4 -0.8545181 -0.5193739 0.007063269 -0.8046495 -0.5937502 0 -0.7702123 -0.6377876 0 -0.7397336 -0.6727924 -0.01202237 -0.7101672 -0.7040331 0 -0.6636444 -0.7480483 0 -0.6636329 -0.7480584 0 -0.3769876 -0.9262184 0 -0.6075739 -0.7942633 0 -0.4566295 -0.8896571 0 -0.4577038 -0.8891048 -2.17554e-4 -0.4559961 -0.8899813 -8.96066e-4 -0.3769849 -0.9262194 0 -0.3304784 -0.9438137 0 -0.3304777 -0.9438139 0 0.2439189 -0.9697956 -3.62596e-4 0.2422726 -0.9702078 -9.34977e-4 0.1511992 -0.9885033 0 0.1277239 -0.9918099 0 0.1022396 -0.9947563 0.002655625 0.0370537 -0.9992997 -0.005235314 0.01782017 -0.9998413 0 -0.1139461 -0.993487 0 0.4999677 -0.8660441 0 0.6478763 -0.7617456 0 0.6478737 -0.7617478 0 0.5674031 -0.8234402 0 0.6048351 -0.7959592 -0.02496856 0.2420051 -0.9702751 0 0.4112249 -0.911534 0 0.4096642 -0.9122363 -6.70908e-4 0.4119427 -0.9112093 -0.001007676 0.49997 -0.8660428 0 0.5314377 -0.8470975 0 0.5314377 -0.8470974 0 0.9878306 -0.1555343 0 0.9994204 -0.02305763 -0.02504587 0.9975737 -0.06961995 0 0.9942506 0.1070783 0 0.9282328 -0.372 0 0.9694188 -0.2454126 0 0.9686788 -0.2483174 -9.97448e-5 0.9691109 -0.2466235 -9.63255e-4 0.9878354 -0.1555033 0 0.9936314 -0.11268 0 0.9936314 -0.1126804 0 0.6820453 0.7312451 -0.009740293 0.6762151 0.7366054 -0.01206815 0.6414291 0.7671622 -0.005554974 0.8297565 0.5572758 0.03078722 0.77701 0.6294881 -6.40854e-4 0.7356451 0.6773672 0 0.7076033 0.70661 0 0.7076022 0.7066112 0 0.6766862 0.7362715 0 0.5342198 0.8453457 0 0.5339711 0.8455028 1.28082e-4 0.5327015 0.8463032 0 0.3908948 0.9204354 0 0.944621 0.3281635 2.72626e-4 0.9446768 0.3280028 0 0.9446772 0.3280016 0 -0.1328657 0.9911341 0 -0.1328659 0.9911341 0 -0.2944544 0.9556655 0 -0.2944547 0.9556654 0 -0.7136416 0.7005111 0 -0.7136417 0.7005109 0 -0.8193332 0.5733178 0 -0.8193324 0.5733188 0 -0.9611054 0.2761824 0 -0.9611054 0.2761822 0 -0.9934475 0.1142901 0 -0.9934474 0.1142907 0 -0.8541899 -0.5199613 0 -0.8541902 -0.5199607 0 -0.6390262 -0.7691851 0 -0.6390266 -0.7691846 0 0.1328594 -0.991135 0 0.1328595 -0.991135 0 0.2944604 -0.9556638 0 0.2944606 -0.9556636 0 0.7136382 -0.7005145 0 0.7136386 -0.7005141 0 0.8193352 -0.5733149 0 0.8193347 -0.5733156 0 0.9610721 -0.2762978 0 0.9610722 -0.2762976 0 0.9934532 -0.1142407 0 0.993453 -0.1142414 0 0.8541882 0.5199642 0 0.8541885 0.5199636 0 0.6390298 0.769182 0 0.6390306 0.7691813 0 -0.02947801 -0.9995655 0 -0.1983037 -0.9801406 0 -0.1983037 -0.9801406 0 -0.3609002 -0.9326045 0 -0.3609 -0.9326045 0 -0.5132395 -0.8582454 0 -0.5132397 -0.8582454 0 -0.6511256 -0.75897 0 -0.6511259 -0.7589699 0 -0.7699708 -0.6380792 0 -0.7699714 -0.6380785 0 -0.8666357 -0.4989416 0 -0.8666355 -0.4989418 0 -0.9385095 -0.3452534 0 -0.9385097 -0.3452532 0 -0.9833762 -0.18158 0 -0.9833762 -0.1815807 0 -0.9999179 -0.01281696 0 -0.9999179 -0.0128178 0 -0.9877014 0.1563524 0 -0.9877014 0.1563523 0 -0.9470585 0.3210612 0 -0.9470585 0.321061 0 -0.8792428 0.476374 0 -0.8792432 0.4763731 0 -0.7860624 0.6181471 0 -0.7860628 0.6181466 0 -0.6700997 0.7422711 0 -0.6700993 0.7422715 0 -0.5351141 0.8447799 0 -0.5351148 0.8447795 0 -0.3849729 0.9229279 0 -0.3849731 0.9229278 0 -0.2233231 0.9747445 0 -0.2233232 0.9747444 0 -0.05493664 0.9984899 0 -0.05493664 0.9984899 0 0.1143433 0.9934413 0 0.1143434 0.9934413 0 0.2805048 0.9598527 0 0.2805049 0.9598526 0 0.438628 0.8986687 0 0.4386283 0.8986685 0 0.5842409 0.8115803 0 0.5842414 0.81158 0 0.7129358 0.7012293 0 0.7129366 0.7012284 0 0.8213033 0.570492 0 0.9058578 0.4235821 0 0.9058584 0.4235808 0 0.9644445 0.2642856 0 0.9644448 0.2642847 0 0.99523 0.09755694 0 0.9952299 0.09755766 0 0.9974045 -0.07200253 0 0.9974045 -0.07200253 0 0.970869 -0.2396115 0 0.970869 -0.2396113 0 0.9164437 -0.4001636 0 0.9164439 -0.4001633 0 0.8356475 -0.5492663 0 0.8356474 -0.5492665 0 0.7307415 -0.6826544 0 0.6050953 -0.7961531 0 0.6050949 -0.7961534 0 0.461443 -0.8871699 0 0.461443 -0.8871699 0 0.3050608 -0.9523329 0 0.305061 -0.9523329 0 0.1398004 -0.9901797 0 0.1398005 -0.9901797 0 3.03445e-7 0 -1 -1.21359e-6 0 -1 4.81649e-6 0 -1 4.39955e-6 0 -1 -4.78667e-6 0 -1 4.414e-6 0 -1 -4.77222e-6 0 -1 -4.7293e-6 0 -1 2.23254e-6 0 -1 -1.12783e-6 0 -1 -4.27692e-7 0 -1 -1.15029e-6 0 -1 5.71925e-7 0 -1 8.52366e-7 0 -1 1.12796e-6 0 -1 2.23886e-6 0 -1 -4.78103e-6 0 -1 -4.25427e-6 0 -1 -1.97885e-6 0 -1 1.95808e-6 0 -1 0.4265837 0.8831449 0.1951448 0.426549 0.8832452 0.1947663 0.426549 0.8832452 0.1947663 0.426549 0.8832453 0.1947662 0.3129528 0.9296287 0.1945532 0.3130532 0.9296577 0.1942532 0.3071426 0.9323672 0.19067 0.1928101 0.9624547 0.191064 0.1933109 0.9618685 0.1934941 0.07145476 0.9784591 0.1936805 0.07102 0.9784378 0.1939476 0.07248163 0.9774517 0.1983296 -0.05209994 0.9788603 0.1977829 -0.0526964 0.9792664 0.1956028 -0.04948705 0.9787257 0.199116 -0.1736486 0.9645624 0.1986592 -0.174131 0.9648014 0.1970703 -0.2968468 0.9344446 0.1967114 -0.2939842 0.9357243 0.1949191 -0.2948864 0.9359502 0.1924563 -0.408918 0.892045 0.1924629 -0.4058855 0.8912734 0.2022096 -0.4105744 0.8908174 0.1946104 -0.5172044 0.8335327 0.1942241 -0.51804 0.8336087 0.1916539 -0.6192086 0.7613292 0.1922465 -0.6169842 0.761394 0.1990219 -0.7074852 0.6781754 0.1988536 -0.707208 0.6787757 0.1977887 -0.7084566 0.6782822 0.1949939 -0.7884157 0.5835367 0.1946426 -0.7883463 0.5845776 0.1917793 -0.7862487 0.5868166 0.1935442 -0.8554009 0.480637 0.1930738 -0.854177 0.4811978 0.1970542 -0.908324 0.368745 0.1974205 -0.9081645 0.3695634 0.1966226 -0.9082911 0.3694619 0.1962276 -0.9470857 0.2541739 0.1960218 -0.9463611 0.2546691 0.1988575 -0.9477809 0.2518997 0.1955965 -0.9716662 0.132749 0.1955571 -0.9724265 0.1319941 0.1922613 -0.9812591 0.01074165 0.1923933 -0.9811087 0.009460449 0.1932259 -0.9813235 0.009179353 0.1921457 -0.9746944 -0.1137337 0.1924465 -0.9741213 -0.1127947 0.1958705 -0.9742807 -0.1136588 0.1945733 -0.9523259 -0.2352575 0.1942404 -0.9523138 -0.2353476 0.1941907 -0.9159494 -0.351201 0.194151 -0.9162189 -0.3520377 0.1913437 -0.8657835 -0.4621929 0.1918249 -0.8636639 -0.4641999 0.1964774 -0.8636412 -0.4648077 0.1951349 -0.7990917 -0.5686756 0.1950911 -0.79923 -0.5686424 0.1946205 -0.7956975 -0.5748218 0.190907 -0.7219229 -0.6650737 0.1910613 -0.7220535 -0.6639538 0.1944333 -0.6333804 -0.7489717 0.1946043 -0.6324554 -0.7494933 0.1956017 -0.6326371 -0.7490594 0.1966731 -0.53359 -0.8224601 0.1970813 -0.5333546 -0.8231071 0.1950068 -0.534813 -0.82161 0.1973121 -0.4257586 -0.8830105 0.1975401 -0.4254078 -0.883796 0.1947641 -0.3166453 -0.9283679 0.1945992 -0.3128926 -0.9291685 0.1968358 -0.3119544 -0.9303799 0.1925555 -0.1927536 -0.9622051 0.1923734 -0.1947343 -0.9598801 0.2017644 -0.1902677 -0.9624463 0.193637 -0.07113933 -0.978483 0.1936756 -0.07217794 -0.9775601 0.1979057 0.05209529 -0.9787731 0.1982154 0.05174541 -0.978541 0.199449 0.1759417 -0.9639315 0.1997014 0.1737534 -0.9651187 0.1958461 0.1726841 -0.9648312 0.198194 0.2945283 -0.9347884 0.1985545 0.2935637 -0.9359834 0.1943074 0.297044 -0.9353225 0.1921895 0.4095132 -0.891762 0.1925088 0.4080654 -0.891384 0.1972745 0.5180416 -0.8322453 0.1974864 0.5164191 -0.8338431 0.1949799 0.5191161 -0.8337113 0.1882658 0.6197016 -0.7619208 0.1882733 0.6170544 -0.7620366 0.1963272 0.6148962 -0.7631373 0.198807 0.7070344 -0.6786091 0.1989776 0.7082684 -0.6784546 0.1950776 0.7899437 -0.5814257 0.1947645 0.7882079 -0.5844374 0.1927731 0.7879283 -0.5845456 0.1935858 0.8553816 -0.4806848 0.1930404 0.8547028 -0.480957 0.1953541 0.8563871 -0.4794255 0.1917093 0.9090466 -0.3699822 0.1916965 0.9078348 -0.3706133 0.1961675 0.9471012 -0.2541506 0.1959765 0.9487227 -0.2529079 0.189639 0.97245 -0.1357637 0.189498 0.9715909 -0.1311621 0.1969966 0.9712557 -0.13163 0.1983332 0.98005 -0.009184956 0.1985394 0.9802421 -0.009451866 0.1975759 0.9800692 -0.01060861 0.198373 0.9736477 0.1120036 0.1986592 0.9743372 0.1131484 0.1945881 0.9520116 0.2365481 0.194214 0.9525892 0.2353976 0.1927738 0.952434 0.2348624 0.1941891 0.9154275 0.3525788 0.1941155 0.9152655 0.3520011 0.1959192 0.915413 0.3508996 0.1972019 0.8641841 0.4628753 0.1973133 0.8645589 0.4652953 0.1898374 0.8046446 0.56246 0.1902258 0.8046447 0.5624601 0.1902259 0.7983313 0.5695859 0.1955479 0.7983763 0.569467 0.1957107 0.722061 0.6636241 0.195528 0.7220296 0.6643161 0.1932805 0.7223075 0.6636961 0.1943694 0.6327772 0.7495012 0.1945276 0.6325618 0.7503314 0.192012 0.5330488 0.8240504 0.1918336 0.5336141 0.8223963 0.1972826 0.4251504 0.8833288 0.1974274 0.6118884 0.562353 0.556194 0.6131172 0.5652102 0.5519283 0.6787397 0.4842362 0.5521121 0.6779057 0.4828246 0.5543684 0.733404 0.3928487 0.5547869 0.7330912 0.3924599 0.5554752 0.7759234 0.2987993 0.5555735 0.7755969 0.2985241 0.556177 0.8067581 0.1993816 0.556227 0.8054033 0.1982935 0.5585744 0.8242253 0.09483629 0.558264 0.827794 0.09697508 0.5525875 0.8335555 -0.008019626 0.5523778 0.8331992 -0.008198618 0.5529121 0.8258386 -0.1114501 0.5527835 0.8243134 -0.1118965 0.5549654 0.8034698 -0.2156484 0.5549163 0.8036836 -0.2155506 0.5546447 0.7705298 -0.3136021 0.5549213 0.770326 -0.3135915 0.5552099 0.7249799 -0.407369 0.555387 0.7248622 -0.4073935 0.5555226 0.6680018 -0.4952848 0.5553978 0.6662578 -0.4949213 0.5578114 0.5989248 -0.5748507 0.5575265 0.6017886 -0.5758569 0.5533891 0.5256463 -0.6463851 0.5530664 0.5241178 -0.6455951 0.5554347 0.4377018 -0.706781 0.5557677 0.4390803 -0.7076919 0.5535166 0.3475962 -0.7569305 0.5533834 0.3466715 -0.7561061 0.5550878 0.2488995 -0.7935805 0.5552287 0.2498906 -0.7947551 0.5530996 0.1475633 -0.8196271 0.5535671 0.1471896 -0.8190857 0.5544674 0.04423195 -0.8310278 0.5544697 0.04512059 -0.8327339 0.551832 -0.06045711 -0.8316513 0.5519973 -0.06137114 -0.8292557 0.5554896 -0.1633132 -0.8152681 0.5555779 -0.1634646 -0.8145388 0.5566022 -0.2650746 -0.7872017 0.5568205 -0.2647514 -0.790168 0.5527578 -0.3620213 -0.7508759 0.5523823 -0.3620122 -0.7499659 0.5536229 -0.4530642 -0.6983957 0.5540543 -0.453179 -0.6988447 0.553394 -0.5370075 -0.6363055 0.5538396 -0.5364722 -0.6345473 0.5563699 -0.6111819 -0.5630714 0.556244 -0.6115058 -0.5637248 0.5552253 -0.6773533 -0.4819464 0.555806 -0.6779057 -0.4828246 0.5543684 -0.7328498 -0.393857 0.5548044 -0.732524 -0.3935311 0.5554655 -0.7763901 -0.2976626 0.5555316 -0.7781762 -0.2995553 0.5520041 -0.8095516 -0.200006 0.5519276 -0.8082472 -0.1989937 0.5542004 -0.8269844 -0.09651154 0.5538795 -0.8249746 -0.09527015 0.5570822 -0.8305546 0.008028268 0.5568794 -0.8302922 0.008131861 0.5572692 -0.8228191 0.1123561 0.5570862 -0.8243449 0.1119391 0.5549101 -0.8035182 0.2156238 0.5548558 -0.8037111 0.2155961 0.5545871 -0.7706254 0.3136258 0.5547751 -0.7703844 0.313577 0.5551372 -0.7249964 0.4074369 0.5553156 -0.7248427 0.4073442 0.5555841 -0.6679615 0.4952924 0.5554394 -0.6688011 0.4954465 0.5542906 -0.6004019 0.5762685 0.5544658 -0.6032922 0.5772956 0.5502439 -0.5268186 0.6478036 0.5502843 -0.5234338 0.6460673 0.5555307 -0.4383468 0.7065062 0.5556089 -0.4382553 0.7063241 0.5559124 -0.3465777 0.7560228 0.55526 -0.3466593 0.7561597 0.5550225 -0.2493091 0.7934733 0.5551983 -0.2496091 0.7937604 0.5546529 -0.1474512 0.8190943 0.5543851 -0.1474308 0.8190733 0.5544214 -0.04423338 0.8310161 0.5544869 -0.04503977 0.8325816 0.5520682 0.0603789 0.8319308 0.5515846 0.06137543 0.8291847 0.555595 0.1633 0.8151182 0.5558016 0.1634641 0.8146222 0.5564802 0.2650746 0.7872017 0.5568205 0.2648601 0.7891137 0.5542101 0.3619487 0.7494286 0.5543915 0.3620477 0.7513411 0.551732 0.4530015 0.7003624 0.5516179 0.4526988 0.6981043 0.5547201 0.5369001 0.6359726 0.554326 0.5364722 0.6345473 0.5563699 0.4099491 0.3779041 0.8301387 0.4090446 0.3763061 0.83131 0.4526652 0.3224161 0.8313496 0.4531142 0.3229635 0.8308924 0.4907203 0.2626681 0.8307822 0.4927923 0.2647998 0.8288769 0.522155 0.2009767 0.8288321 0.521654 0.2005633 0.8292475 0.5427728 0.1336504 0.8291776 0.542638 0.1335014 0.8292897 0.5550034 0.06506192 0.8292999 0.5521303 0.06372696 0.8313189 0.5554491 -0.00545752 0.8315327 0.554997 -0.005599677 0.8318335 0.5497757 -0.07465898 0.8319693 0.5496722 -0.07466369 0.8320372 0.5360152 -0.1437968 0.8318715 0.5381867 -0.1436896 0.8304869 0.5160431 -0.2100384 0.8304117 0.5156804 -0.2100367 0.8306373 0.4855359 -0.2728916 0.8305331 0.4858807 -0.2729566 0.83031 0.4475716 -0.3324916 0.830138 0.4465903 -0.3321213 0.8308144 0.4020351 -0.3846881 0.8308929 0.401086 -0.3842369 0.8315599 0.349954 -0.4310828 0.831685 0.349477 -0.4307853 0.8320395 0.2925499 -0.4715145 0.8319187 0.2931719 -0.4720665 0.8313866 0.2314631 -0.5048646 0.8315867 0.2322902 -0.5057408 0.8308234 0.1669679 -0.5310775 0.8307096 0.1670379 -0.5311231 0.8306664 0.09847408 -0.547985 0.8306717 0.09829986 -0.5476779 0.8308947 0.03011417 -0.5556306 0.8308838 0.02995264 -0.5551664 0.8311998 -0.04104059 -0.5546387 0.8310785 -0.04046171 -0.5570732 0.8294771 -0.1099348 -0.5478244 0.8293389 -0.110008 -0.5471981 0.8297424 -0.1773532 -0.5293584 0.8296539 -0.1773034 -0.5281455 0.8304373 -0.2421448 -0.5016773 0.8304733 -0.2421218 -0.5011181 0.8308176 -0.302713 -0.4668235 0.8309276 -0.3031254 -0.4683074 0.8299417 -0.3601864 -0.4260319 0.8299173 -0.3602032 -0.4260316 0.8299102 -0.4100274 -0.3779764 0.8300672 -0.4101344 -0.3782135 0.8299062 -0.4546545 -0.323833 0.8297118 -0.4535124 -0.3223441 0.8309158 -0.4903529 -0.2633882 0.8307712 -0.4904087 -0.2635583 0.8306843 -0.5195059 -0.1999189 0.8307503 -0.5190013 -0.1995434 0.831156 -0.5399528 -0.132956 0.8311281 -0.5397998 -0.1328424 0.8312455 -0.5522216 -0.06378102 0.8312541 -0.554998 -0.06500577 0.8293079 -0.5584052 0.005448222 0.8295506 -0.5579718 0.005669057 0.8298406 -0.552677 0.07501465 0.8300127 -0.5525729 0.07505774 0.8300781 -0.5387815 0.1445389 0.8299537 -0.5378673 0.1445486 0.8305448 -0.5159814 0.2100516 0.8304466 -0.5157015 0.210006 0.830632 -0.4855205 0.2728829 0.830545 -0.4843627 0.2726724 0.8312898 -0.4465346 0.3307664 0.8313848 -0.4450606 0.3303003 0.8323598 -0.4005022 0.3832594 0.8322923 -0.401575 0.3838218 0.8315158 -0.3496052 0.4314926 0.8316192 -0.3506187 0.4321928 0.8308286 -0.2933806 0.4728915 0.830844 -0.2927044 0.4722467 0.8314489 -0.2314587 0.5048931 0.8315708 -0.2322902 0.5057408 0.8308234 -0.1669679 0.5310775 0.8307096 -0.1670474 0.5311222 0.8306651 -0.09863013 0.5479345 0.8306864 -0.09845983 0.5476257 0.8309103 -0.03006446 0.5556294 0.8308863 -0.02996045 0.5553114 0.8311028 0.04103451 0.554427 0.8312202 0.04045164 0.5568273 0.8296428 0.1098157 0.547267 0.8297225 0.1098099 0.5471811 0.8297799 0.1776204 0.5292348 0.8296756 0.1776086 0.5281487 0.8303699 0.2418622 0.5019519 0.8303896 0.2417183 0.5012646 0.8308466 0.3026957 0.4668263 0.8309324 0.3026658 0.4666547 0.8310397 0.3589585 0.4245413 0.8312121 0.3596991 0.4264194 0.8299296 0.1432849 0.131799 0.9808662 0.1432149 0.1317176 0.9808874 0.1585026 0.1129698 0.9808745 0.1587429 0.1133124 0.9807961 0.1718654 0.09232211 0.9807848 0.1710984 0.09163957 0.980983 0.1811656 0.06965649 0.9809827 0.182065 0.0703119 0.9807693 0.1894814 0.04664325 0.9807758 0.1891786 0.04643249 0.9808443 0.193519 0.02233743 0.9808423 0.1935485 0.02238321 0.9808354 0.1950051 -0.001964151 0.9808003 0.1959889 -0.001716315 0.9806047 0.1942226 -0.02636921 0.980603 0.1932749 -0.02650719 0.9807866 0.1884204 -0.05030184 0.9807994 0.1885963 -0.05030113 0.9807657 0.180746 -0.07360994 0.9807714 0.1803317 -0.07357287 0.9808505 0.1697903 -0.09537714 0.980854 0.1691538 -0.09522473 0.9809788 0.1557694 -0.1158285 0.980979 0.1572726 -0.1164318 0.9806677 0.1413495 -0.1354156 0.9806544 0.1418452 -0.1357092 0.9805423 0.1236763 -0.1524239 0.9805464 0.1229559 -0.1519418 0.9807118 0.1030854 -0.1659573 0.9807301 0.103305 -0.1662031 0.9806655 0.08175265 -0.1779491 0.9806379 0.08114832 -0.1772725 0.9808106 0.05849832 -0.1860051 0.9808058 0.05827426 -0.1856789 0.980881 0.0343706 -0.1915761 0.9808758 0.03472542 -0.1922957 0.9807224 0.01051616 -0.1949871 0.9807495 0.01052695 -0.1949989 0.980747 -0.01414149 -0.194666 0.9807676 -0.01423054 -0.1942237 0.980854 -0.03838467 -0.1908981 0.9808591 -0.03835767 -0.1911031 0.9808202 -0.0620017 -0.1846924 0.9808387 -0.06201213 -0.1846781 0.9808408 -0.08474713 -0.1753799 0.9808465 -0.08468031 -0.1751269 0.9808976 -0.1057208 -0.1633252 0.9808915 -0.105738 -0.1633524 0.9808852 -0.1255751 -0.1485283 0.9809028 -0.1259626 -0.1493978 0.980721 -0.1437987 -0.1326063 0.9806823 -0.1432037 -0.1316971 0.9808917 -0.158648 -0.112754 0.9808759 -0.1588882 -0.1130808 0.9807993 -0.171833 -0.09231531 0.9807912 -0.1719323 -0.0924319 0.9807628 -0.1822619 -0.07007044 0.9807502 -0.182171 -0.07001727 0.9807708 -0.1895486 -0.04664027 0.980763 -0.1891244 -0.04643929 0.9808544 -0.1934275 -0.0226556 0.980853 -0.1935354 -0.02271634 0.9808303 -0.1950276 0.001954555 0.9807958 -0.1947104 0.00205022 0.9808587 -0.1930051 0.02620387 0.9808479 -0.1920875 0.02634435 0.9810242 -0.187213 0.05030202 0.9810306 -0.1885886 0.05030924 0.9807668 -0.180746 0.07360994 0.9807714 -0.1803248 0.0735498 0.9808535 -0.1697205 0.09552425 0.9808517 -0.1707701 0.09579807 0.9806429 -0.1572465 0.1166922 0.9806408 -0.1570907 0.1166329 0.9806729 -0.1415588 0.1352427 0.9806481 -0.141188 0.1350905 0.9807225 -0.1231791 0.1518113 0.980704 -0.122466 0.1513466 0.9808651 -0.1026042 0.1654963 0.9808585 -0.1038078 0.1666646 0.980534 -0.08194845 0.1784282 0.9805346 -0.08103072 0.1773384 0.9808084 -0.05850285 0.1860194 0.9808028 -0.05826497 0.1856493 0.9808872 -0.03444796 0.1915643 0.9808754 -0.03468114 0.1920405 0.9807741 -0.01051205 0.1949213 0.9807626 -0.01052397 0.1949211 0.9807625 0.01415026 0.1947769 0.9807456 0.01423507 0.1942953 0.9808399 0.03836208 0.1911313 0.9808146 0.03836077 0.1911184 0.9808171 0.06211072 0.184683 0.9808336 0.0621258 0.1850166 0.9807698 0.08484685 0.1759207 0.980741 0.08468705 0.1751409 0.9808944 0.1058892 0.1632521 0.9808855 0.1060925 0.1639001 0.9807555 0.1259374 0.149258 0.9807456 0.1256185 0.1486553 0.9808781 0.5213344 0.8531461 -0.01877087 0.3128124 0.949804 0.004552125 0.3190535 0.9477258 0.004555165 0.3598626 0.932761 -0.02135318 0.4347712 0.9004744 0.01095318 0.4337252 0.9009788 0.0109418 0.1970191 0.9803723 -0.007329702 0.188326 0.982002 -0.01433724 0.07284951 0.9973037 0.008855938 0.07394862 0.9972227 0.008859097 0.01010662 0.9996898 -0.02276718 -0.05372798 0.9985159 0.008904933 -0.1691125 0.9855571 -0.008854866 -0.1775936 0.9839652 -0.01653045 -0.05049228 0.9986849 0.008889257 -0.341935 0.9394856 -0.02115416 -0.3004854 0.9537738 0.004903733 -0.3028005 0.9530414 0.004895746 -0.5044674 0.8632246 -0.01886898 -0.4186226 0.908106 0.009941637 -0.4143843 0.9100479 0.009937047 -0.6505007 0.7592681 -0.01899528 -0.6295624 0.77695 0 -0.5278307 0.8493497 0 -0.8011431 0.5984473 0.005564093 -0.8037966 0.5948783 0.005548298 -0.7755183 0.6309516 -0.02171725 -0.7222603 0.6915457 0.01022964 -0.721939 0.691881 0.01023608 -0.8712685 0.4907557 -0.007082402 -0.8759096 0.4822487 -0.01478803 -0.9264877 0.37623 0.008471012 -0.9262417 0.3768353 0.008458077 -0.9476633 0.3184914 -0.02230834 -0.9656088 0.259873 0.008098065 -0.9894678 0.1445485 -0.007695734 -0.9907754 0.1344705 -0.01678615 -0.9664089 0.2568826 0.008089661 -0.9991284 -0.03586316 -0.0213657 -0.9999409 0.009350717 0.005562782 -0.9999212 0.01126313 0.005561828 -0.9768906 -0.2128723 -0.0192458 -0.9932222 -0.1157949 0.01006144 -0.9933081 -0.1150557 0.01005768 -0.9232925 -0.3836414 -0.01871949 -0.9334512 -0.3587045 0 -0.9708043 -0.2398726 0 -0.8400375 -0.5421022 -0.02150094 -0.8804867 -0.4739665 0.00995171 -0.8821201 -0.4709193 0.009949266 -0.6457213 -0.7635239 0.008681535 -0.735987 -0.6768035 -0.01612973 -0.7291576 -0.6843092 -0.007090806 -0.810856 -0.5852193 0.005564928 -0.814706 -0.5798476 0.00554645 -0.6452155 -0.7639513 0.008693575 -0.5962679 -0.8024781 -0.02221751 -0.5437651 -0.8391833 0.009544432 -0.5456082 -0.8379858 0.009572148 -0.4417802 -0.8970125 -0.01410472 -0.4336901 -0.9010353 -0.006960451 -0.2755439 -0.9610498 -0.02142465 -0.3179141 -0.9481068 0.004913449 -0.3228199 -0.9464476 0.004927515 -0.09981501 -0.9948382 -0.01827466 -0.1939679 -0.9809566 0.01002728 -0.1988148 -0.9799858 0.010028 0.07960277 -0.9966521 -0.01865255 0.05280679 -0.9986047 0 -0.07363766 -0.9972851 0 0.2566927 -0.9662553 -0.02144128 0.1761545 -0.9842974 0.01132595 0.1795461 -0.9836843 0.011339 0.5284848 -0.8488892 0.009545207 0.4161787 -0.9091463 -0.01576149 0.4246475 -0.9053282 -0.007447898 0.3027247 -0.9530614 0.005643784 0.3004963 -0.9537664 0.00564301 0.5285761 -0.8488324 0.009542107 0.5806552 -0.8138634 -0.02158629 0.6293232 -0.7770953 0.008680224 0.6274505 -0.7786082 0.008672833 0.7153811 -0.6985749 -0.01493889 0.722136 -0.6917127 -0.007297515 0.8294318 -0.5581845 -0.02174741 0.8031073 -0.5958086 0.005556404 0.805471 -0.5926094 0.005562484 0.9151677 -0.4026435 -0.01860982 0.8725271 -0.4884648 0.009932637 0.8714464 -0.4903904 0.009921967 0.9725524 -0.2319614 -0.01832914 0.9662585 -0.2575741 0 0.9258008 -0.3780121 0 0.9982559 -0.05495047 -0.02157664 0.9908741 -0.1344156 0.01005852 0.9903162 -0.1384655 0.01005995 0.9903163 -0.1384655 0.01005709 0.9903163 -0.1384655 0.01005995 0.970379 0.2414141 0.009160161 0.970379 0.2414141 0.009160161 0.970379 0.2414141 0.009160161 0.9931973 0.1153117 -0.01619786 0.9921919 0.124461 -0.00804311 0.9999229 -0.01111352 0.005546033 0.9999229 -0.01111358 0.005546331 0.9999229 -0.01111352 0.005546092 0.9999408 -0.0093683 0.005545914 0.9708672 0.2394434 0.009164452 0.9539209 0.2992678 -0.02176719 0.933324 0.3589096 0.009498775 0.9337996 0.3576707 0.009493589 0.9337996 0.3576707 0.009493589 0.9337996 0.3576706 0.009497642 0.885203 0.4649966 -0.01392304 0.8805689 0.4738804 -0.005968451 0.7874305 0.6160535 -0.02077293 0.8140749 0.5807332 0.005569994 0.8197678 0.5726692 0.005560517 0.54429 0.8388973 0 0.6445631 0.7645511 0 0.6648768 0.7467172 -0.01877212 0.7363466 0.6765154 0.01098412 0.7358178 0.6770904 0.01099228 -0.9745549 -0.2241491 0 0.9837711 0.1794283 0 -0.1133761 0.9935522 0 0.9958114 0.09123969 0.005941569 0.2567525 -0.9664772 0 0.4246601 -0.9053528 0 0.4246702 -0.9053483 0 0.5808087 -0.8140401 0 0.5808205 -0.8140317 0 0.7154765 -0.6986368 0 0.7154499 -0.698664 0 0.829639 -0.5583003 0 0.8296264 -0.558319 0 0.9153302 -0.4027042 0 0.9153301 -0.4027045 0 0.9727196 -0.2319843 0 0.9984887 -0.05495887 0 0.9922243 0.1244635 0 0.06915575 -0.997606 0 -0.9908978 -0.1338552 0.01429611 -0.3420086 0.9396969 0 -0.5045713 0.8633701 0 -0.5045596 0.8633769 0 -0.6506224 0.7594015 0 -0.650609 0.759413 0 -0.7756832 0.6311225 0 -0.7757089 0.6310911 0 -0.8760067 0.4822991 0 -0.8760065 0.4822995 0 -0.9479008 0.3185657 0 -0.947893 0.3185892 0 -0.9894981 0.1445456 0 -0.9894944 0.1445713 0 -0.999357 -0.03585529 0 -0.9993552 -0.0359075 0 -0.9770722 -0.2129086 0 -0.9745656 -0.2241029 0 -0.923451 -0.3837165 0 -0.9234392 -0.3837449 0 -0.8402345 -0.5422233 0 -0.8402197 -0.5422463 0 -0.7291927 -0.6843085 0 -0.7291761 -0.6843262 0 -0.5964122 -0.8026784 0 -0.4418165 -0.8971056 0 -0.2756201 -0.9612668 0 -0.2756114 -0.9612691 0 -0.09983587 -0.995004 0 -0.09983265 -0.9950043 0 0.06915569 -0.997606 0 0.07961642 -0.9968243 0.001638591 0.152735 -0.9882672 0 0.2567464 -0.9664789 0 0.9837569 0.179506 0 0.9541404 0.2993597 0 0.9541404 0.2993595 0 0.8852816 0.4650554 0 0.8852818 0.4650552 0 0.7875917 0.6161976 0 0.7876079 0.6161769 0 0.6649816 0.7468598 0 0.6649819 0.7468596 0 0.5214164 0.8533024 0 0.5214166 0.8533022 0 0.3599413 0.9329751 0 0.3599526 0.9329707 0 0.1883484 0.9821023 0 0.1883425 0.9821034 0 0.01010936 0.9999489 0 0.010109 0.999949 0 -0.1133699 0.9935529 0 -0.1691176 0.9855887 0.003772914 -0.2023187 0.9793198 0 -0.3420006 0.9396998 0 -5.65282e-6 0 1 -4.06972e-6 0 1 5.73947e-6 0 1 -2.8704e-6 0 1 -1.435e-6 0 1 5.44093e-6 0 1 -4.29829e-6 0 1 5.4452e-6 0 1 -2.85466e-6 0 1 -1.09851e-5 0 1 1.13523e-5 0 1 -1.10525e-5 0 1 -1.12067e-5 0 1 -5.65944e-6 0 1 -5.69269e-6 0 1 2.87515e-6 0 1 -1.44242e-6 0 1 -2.91416e-6 0 1 2.00047e-6 0 1 5.27872e-6 0 1 5.24857e-6 0 1 5.21094e-6 0 1 -1.02526e-5 0 1 1.00755e-5 0 1 9.80113e-6 0 1 1.31815e-5 0 1 0.6678009 0.7443401 0 0.5188225 0.854882 0 0.5188252 0.8548804 0 0.3530558 0.9356024 0 0.1756615 0.9844506 0 -0.008240044 0.9999661 0 -0.008240282 0.9999661 0 -0.1931723 0.9811649 0 -0.1931777 0.9811637 0 -0.368756 0.9295263 0 -0.3687431 0.9295313 0 -0.5336021 0.8457357 0 -0.5335867 0.8457455 0 -0.6807173 0.7325462 0 -0.6807212 0.7325427 0 -0.8026711 0.5964219 0 -0.8026961 0.5963885 0 -0.8990857 0.4377729 0 -0.8990744 0.437796 0 -0.9641913 0.265208 0 -0.9964979 0.08361816 0 -0.9964956 0.08364593 0 -0.9948514 -0.1013448 0 -0.9948486 -0.1013724 0 -0.9595859 -0.2814164 0 -0.9595935 -0.2813901 0 -0.8910924 -0.4538222 0 -0.8911139 -0.4537796 0 -0.7930021 -0.609219 0 -0.7930158 -0.609201 0 -0.6672151 -0.7448652 0 -0.6671969 -0.7448815 0 -0.5188353 -0.8548743 0 -0.5188252 -0.8548804 0 -0.3534333 -0.9354597 0 -0.3534522 -0.9354527 0 -0.1754627 -0.9844861 0 -0.1754726 -0.9844844 0 0.008249223 -0.999966 0 0.008248805 -0.999966 0 0.1931638 -0.9811666 0 0.1931601 -0.9811673 0 0.3687652 -0.9295226 0 0.3687524 -0.9295278 0 0.5335944 -0.8457406 0 0.5335816 -0.8457487 0 0.680725 -0.7325391 0 0.8026686 -0.5964253 0 0.8026935 -0.5963919 0 0.8995599 -0.4367975 0 0.8995375 -0.4368437 0 0.9638911 -0.2662971 0 0.9638837 -0.2663237 0 0.9964979 -0.08361816 0 0.9964956 -0.08364593 0 0.9948485 0.1013731 0 0.9948486 0.1013724 0 0.9595929 0.281392 0 0.9595847 0.2814203 0 0.8911054 0.4537966 0 0.8910939 0.4538193 0 0.792461 0.6099227 0 0.7924472 0.6099405 0 0.6677866 0.7443528 0 -1.08525e-5 0 -1 -1.08825e-5 0 -1 1.09125e-5 0 -1 5.47705e-6 0 -1 -5.4851e-6 0 -1 2.75695e-6 0 -1 2.07825e-6 0 -1 5.62531e-6 0 -1 -2.78087e-6 0 -1 -5.59835e-6 0 -1 -2.78956e-6 0 -1 3.47562e-7 0 -1 1.15343e-5 0 -1 -1.16299e-5 0 -1 1.06367e-5 0 -1 -1.18146e-5 0 -1 1.05065e-5 0 -1 -6.17772e-6 0 -1 -6.27762e-6 0 -1 -3.1652e-6 0 -1 -1.59748e-6 0 -1 2.44829e-6 0 -1 2.42756e-6 0 -1 -1.33454e-5 0 -1 2.40025e-6 0 -1 -1.35311e-5 0 -1 -0.5281634 -0.8491429 0 -0.6589208 -0.7522124 0 -0.6589457 -0.7521905 0 -0.7702876 -0.6376968 0 -0.7702383 -0.6377563 0 -0.8631151 -0.5050073 0 -0.8630713 -0.5050821 0 -0.9327257 -0.3605868 0 -0.9326915 -0.3606754 0 -0.9783757 -0.2068359 0 -0.9783654 -0.2068845 0 -0.9989603 -0.04559075 0 -0.9934921 0.1139016 0 -0.9935034 0.1138028 0 -0.962398 0.2716436 0 -0.9623714 0.2717376 0 -0.9057186 0.4238796 0 -0.9056988 0.423922 0 -0.8272542 0.5618279 0 -0.8272065 0.5618982 0 -0.7244605 0.6893163 0 -0.7245092 0.6892653 0 -0.6052879 0.7960067 0 -0.6052859 0.7960082 0 -0.4702667 0.8825244 0 -0.4702863 0.8825139 0 -0.3230368 0.9463865 0 -0.3230675 0.946376 0 -0.1677414 0.9858311 0 -0.1677489 0.9858298 0 -0.006216645 0.9999807 0 -0.006216347 0.9999807 0 0.1553238 0.9878637 0 0.1553152 0.987865 0 0.310626 0.9505322 0 0.3106416 0.9505272 0 0.457964 0.8889707 0 0.4579411 0.8889826 0 0.5970295 0.8022193 0 0.5970055 0.8022373 0 0.7163618 0.6977291 0 0.7163351 0.6977564 0 0.8194531 0.5731464 0 0.8194049 0.5732152 0 0.9013711 0.4330476 0 0.9013503 0.4330909 0 0.9581546 0.2862514 0 0.9581819 0.2861599 0 0.9919955 0.126273 0 0.9919893 0.1263225 0 0.9993829 -0.03512787 0 0.9993829 -0.03512799 0 0.9812096 -0.1929452 0 0.9812 -0.1929942 0 0.937615 -0.3476753 0 0.9375983 -0.3477204 0 0.8691398 -0.4945666 0 0.8691174 -0.4946058 0 0.7786479 -0.6274611 0 0.7786467 -0.6274628 0 0.6666597 -0.7453623 0 0.6666811 -0.7453432 0 0.5407613 -0.8411762 0 0.5407602 -0.8411769 0 0.3976623 -0.917532 0 0.3976792 -0.9175245 0 0.2444682 -0.9696573 0 0.2444801 -0.9696543 0 0.08700245 -0.9962082 0 0.08699768 -0.9962086 0 -0.07463967 -0.9972106 0 -0.0746355 -0.9972109 0 -0.231827 -0.9727571 0 -0.2318142 -0.9727601 0 -0.3873839 -0.9219185 0 -0.3874005 -0.9219115 0 -0.528142 -0.8491562 0 -0.5264636 -0.8501977 0 -0.6602064 -0.7510842 0 -0.6602275 -0.7510657 0 -0.7746199 -0.6324271 0 -0.7746194 -0.6324278 0 -0.8678679 -0.4967951 0 -0.8678867 -0.4967622 0 -0.9380642 -0.3464617 0 -0.9380497 -0.3465009 0 -0.9825128 -0.1861956 0 -0.9825047 -0.1862384 0 -0.9997069 -0.02420938 0 -0.999707 -0.02420938 0 -0.9898269 0.1422774 0 -0.9898206 0.1423208 0 -0.9529849 0.3030179 0 -0.9529975 0.3029782 0 -0.8907606 0.454473 0 -0.8907603 0.4544736 0 -0.8030669 0.595889 0 -0.8030664 0.5958896 0 -0.6941412 0.7198389 0 -0.6941406 0.7198396 0 -0.5665272 0.824043 0 -0.5665267 0.8240434 0 -0.422233 0.9064874 0 -0.2681047 0.9633898 0 -0.2680931 0.9633931 0 -0.1059442 0.9943722 0 0.05898362 0.998259 0 0.05898094 0.9982591 0 0.2239792 0.974594 0 0.2239695 0.9745963 0 0.3799885 0.9249913 0 0.5271349 0.8497817 0 0.5271344 0.849782 0 0.6602283 0.751065 0 0.6602275 0.7510657 0 0.7746371 0.6324061 0 0.774615 0.6324332 0 0.8678708 0.4967901 0 0.8678705 0.4967907 0 0.9380642 0.3464617 0 0.9380497 0.3465009 0 0.9822373 0.1876433 0 0.9822373 0.1876434 0 0.9997421 0.02271354 0 0.9997421 0.0227136 0 0.9898271 -0.1422759 0 0.9898271 -0.1422759 0 0.9534161 -0.3016588 0 0.9534287 -0.3016189 0 0.8901354 -0.4556961 0 0.890153 -0.4556618 0 0.8030918 -0.5958553 0 0.8030706 -0.595884 0 0.6948894 -0.7191167 0 0.6948887 -0.7191174 0 0.5658204 -0.8245286 0 0.5658403 -0.824515 0 0.42279 -0.9062278 0 0.2677285 -0.9634945 0 0.2677397 -0.9634914 0 0.1059349 -0.9943731 0 0.1059442 -0.9943722 0 -0.05907446 -0.9982536 0 -0.05907177 -0.9982538 0 -0.2239804 -0.9745937 0 -0.2239803 -0.9745938 0 -0.3799791 -0.9249952 0 -0.3799939 -0.924989 0 -0.5264642 -0.8501974 0 -0.3577637 0.9337904 0.006379961 -0.1001508 0.9949175 -0.0104438 -0.4537143 0.8911473 0 -0.5268313 0.8480275 -0.05743002 -0.3516941 0.9360932 0.006386101 -0.9353291 0.3523716 -0.03152346 -0.8991525 0.4376357 0 -0.7447013 0.667398 0 -0.8007191 0.595745 -0.06274574 -0.6805459 0.7327054 0 -0.08124196 0.9966945 0 0.2644991 0.9643859 0 0.2644998 0.9643858 0 0.5961642 0.8028626 0 0.8458565 0.5334106 0 0.8458379 0.5334402 0 0.9812471 0.1927543 0 0.9812472 0.1927539 0 0.9845412 -0.1751533 0 0.9845412 -0.1751529 0 0.8546017 -0.5192843 0 0.6097194 -0.7926174 0 0.609699 -0.7926331 0 0.2817505 -0.9594878 0 -0.08385962 -0.9964776 0 -0.0838598 -0.9964776 0 -0.4376026 -0.8991685 0 -0.4376021 -0.8991687 0 -0.7332615 -0.6799467 0 -0.9292994 -0.3693274 0 -0.9292995 -0.369327 0 -0.9927718 -0.1200172 0 -0.9995915 -0.008736968 -0.02721142 -0.9978985 0.06479716 0 -0.964425 0.2643567 0 -0.9891544 -0.1468801 0 -0.7839226 -0.6208587 0 -0.7828034 -0.6222689 4.75569e-4 -0.6213082 0.7835663 0 -0.9314116 0.3639677 0 -0.9299649 0.3676481 -6.21939e-4 -0.9291568 0.3696858 0 -0.9891718 -0.146763 0 -0.1468294 0.9891617 -4.77923e-4 -0.1414293 0.9899485 0 -0.621279 0.7835894 0 0.7835918 0.6212763 0 0.3691134 0.9293844 0 0.3676691 0.9299568 2.39788e-4 0.3668397 0.9302842 0 -0.1482545 0.9889492 0 0.989163 0.1468214 2.66144e-4 0.9887316 0.149699 0 0.7835626 0.6213131 0 0.9889062 0.1485422 0 0.9889062 0.1485422 0 0.9889062 0.1485423 0 0.98942 0.1450796 -3.23153e-4 0.6213079 -0.7835665 1.53685e-4 -0.780637 -0.6249847 -3.47943e-7 -0.7806371 -0.6249848 0 -0.7806371 -0.6249848 0 -0.368172 -0.9297577 0 0.1487011 -0.9888823 0 0.1468182 -0.9891636 -1.79924e-4 0.1463347 -0.9892352 0 0.6208816 -0.7839044 0 0.03128945 0.01352363 -0.9994189 0.168096 0.05178844 -0.9844094 0.1234026 0.0633524 -0.9903325 0.3671705 0.1506537 -0.9178723 0.3539035 0.1534996 -0.9225997 0.5575472 0.2418449 -0.7941362 0.557986 0.2416659 -0.7938824 0.7288339 0.3155059 -0.6076655 0.7278645 0.3159563 -0.6085926 0.8467927 0.3675949 -0.3844685 0.8478068 0.3668601 -0.3829326 0.9098033 0.393218 -0.1328074 0.9092708 0.3939992 -0.1341316 0.9103657 0.3944305 0.1251359 0.9105018 0.3937012 0.1264362 0.8487204 0.366779 0.3809816 0.117052 0.05072176 0.9918297 0.117123 0.05070179 0.9918224 0.3495617 0.1509561 0.9246723 0.3487749 0.1510601 0.9249525 0.5579984 0.2416949 0.7938649 0.5575453 0.2417303 0.7941725 0.7289394 0.3152346 0.6076797 0.7272772 0.3156888 0.609433 0.8491104 0.3685893 0.3783563 0.4937725 -0.77003 -0.4040329 0.6555237 0.6375339 -0.4047707 0.4201171 0.8128431 -0.4034696 -0.748938 0.4949903 -0.4405414 -0.7475335 0.5087245 -0.4270753 -0.7750931 0.4801464 -0.4107192 -0.745379 0.5132703 -0.4253985 -0.7413858 0.5259217 -0.4168375 -0.7383741 0.5333649 -0.4127054 -0.7335283 0.5481974 -0.4017662 -0.7334882 0.5484129 -0.4015449 -0.740665 0.5421987 -0.3967821 -0.7523174 0.534732 -0.3848122 -0.7724627 0.5279384 -0.3529624 -0.7750895 0.5278997 -0.3472152 -0.8290169 0.3869643 -0.4037197 -0.8290559 0.3871661 -0.4034465 -0.7899724 0.460777 -0.40451 -0.8802187 0.2489694 -0.4040167 -0.8801616 0.2492748 -0.4039525 -0.8277708 0.3895002 -0.403838 -0.9089146 0.1045939 -0.4036514 -0.9088873 0.1044898 -0.4037399 -0.8804209 0.2487862 -0.4036884 -0.8952183 -0.188407 -0.4038401 -0.9138518 -0.04279267 -0.4037868 -0.9137374 -0.04259312 -0.4040666 -0.9136906 -0.04300028 -0.4041293 -0.9086013 0.1053532 -0.4041591 -0.8364696 -0.3675318 -0.406496 -0.8440625 -0.3601588 -0.3972961 -0.8514714 -0.3522778 -0.3884543 -0.8701588 -0.3364972 -0.359991 -0.8898921 -0.3336201 -0.3111106 -0.8661944 -0.3412368 -0.3650546 -0.8398615 -0.3532807 -0.4120991 -0.8425589 -0.3329572 -0.4233603 -0.842341 -0.3256948 -0.4294005 -0.8535279 -0.3096101 -0.4190844 -0.8649928 -0.2898525 -0.4096011 -0.871324 -0.2760189 -0.4057194 -0.8739014 -0.269886 -0.4042993 -0.8954038 -0.1887978 -0.4032462 -0.9029105 -0.1875174 -0.3867685 -0.8738899 -0.2654116 -0.4072753 -0.8743669 -0.2638029 -0.4072965 -0.9085313 0.1046392 -0.4045017 -0.9136381 -0.04225754 -0.4043262 -0.9147009 -0.04271501 -0.4018679 -0.8960227 -0.1885765 -0.4019732 -0.7868503 0.466948 -0.4035172 -0.8012662 0.4417244 -0.4035494 -0.8350036 0.3900033 -0.3881577 -0.8293589 0.3841317 -0.4057175 -0.8795772 0.2488829 -0.4054642 0.8044708 0.3999072 -0.4392049 0.8145139 0.3926102 -0.4271117 0.8028033 0.4331197 -0.4097734 0.7948702 0.4523332 -0.4044454 0.8177636 0.3882691 -0.4248645 0.8260388 0.3792627 -0.416917 0.8303257 0.3737465 -0.4133677 0.8434324 0.3530836 -0.4049124 0.8411338 0.3633232 -0.4006125 0.8394439 0.3723247 -0.395864 0.8388617 0.3844606 -0.3853586 0.8429896 0.4048668 -0.3541913 0.8442869 0.40721 -0.3483673 0.7495878 0.5248233 -0.4033344 0.7495878 0.5248233 -0.4033345 0.7495879 0.5248232 -0.4033345 0.7498485 0.5244448 -0.4033421 0.7498483 0.5246647 -0.4030565 0.7498474 0.524673 -0.4030475 0.6559799 0.6381485 -0.4030595 0.6559897 0.6381023 -0.4031167 0.5451931 0.7349802 -0.4031979 0.5893995 0.7319985 -0.3417406 0.5150373 0.7558444 -0.404272 0.2017018 0.8919552 -0.4046387 0.2842512 0.8696423 -0.403638 0.2842316 0.8696669 -0.4035986 0.2845587 0.8696152 -0.4034796 0.4201189 0.812842 -0.40347 0.1019066 0.9076579 -0.4071512 0.1101279 0.9111297 -0.3971328 0.1212574 0.9137713 -0.3877097 0.1437929 0.92164 -0.3604214 0.1567152 0.9378738 -0.3095691 0.1378589 0.920845 -0.3647459 0.1145838 0.9038969 -0.4121174 0.1319311 0.8967368 -0.4224424 0.1392474 0.8922219 -0.4295932 0.160954 0.8940166 -0.4181246 0.179892 0.8940295 -0.410305 0.289324 0.8759712 -0.3859615 0.2081369 0.8896604 -0.4064278 0.2064948 0.8900983 -0.4063068 0.2843901 0.8697861 -0.4032302 0.4202058 0.8129768 -0.4031076 0.4201828 0.8129439 -0.4031981 0.5452063 0.7350391 -0.403073 0.452688 0.6648163 -0.5942162 0.5733858 0.7119277 -0.4054477 0.7971175 0.4480531 -0.4047868 0.7882312 0.4634988 -0.404797 0.6558589 0.6382973 -0.4030209 -0.06298398 -0.8992783 -0.4328182 -0.08126944 -0.904243 -0.4192134 -0.09401553 -0.9061247 -0.412431 -0.1111912 -0.9086092 -0.4025744 -0.1017281 -0.911736 -0.3979811 -0.09333842 -0.9152932 -0.3918246 -0.03155487 -0.9220046 -0.3858912 -0.03155487 -0.9220045 -0.3858912 -0.03155487 -0.9220046 -0.3858912 -0.06988465 -0.9358717 -0.3453411 -0.07313704 -0.9311987 -0.3570993 -0.08589124 -0.9197289 -0.3830426 -0.03442502 -0.8866775 -0.4611054 -0.06750494 -0.905125 -0.4197523 -0.005485355 -0.9146079 -0.4043048 0.07917368 -0.9116541 -0.4032599 0.07897216 -0.9115446 -0.4035468 0.2246631 -0.8869311 -0.4035835 0.2244503 -0.8871554 -0.403209 0.2262077 -0.8868436 -0.4029126 0.3642349 -0.8390793 -0.4040781 0.3635794 -0.8401622 -0.4024146 0.3640219 -0.8397928 -0.4027857 0.6720894 -0.6199242 -0.4049566 0.6110878 -0.6807662 -0.4038925 0.6109011 -0.6807796 -0.4041523 0.6118566 -0.6798727 -0.4042335 0.4935784 -0.7700317 -0.4042667 0.7362101 -0.5410847 -0.4064752 0.7340623 -0.5508453 -0.3971423 0.7309377 -0.5611967 -0.3883147 0.7261825 -0.585117 -0.360967 0.7336651 -0.6039784 -0.3113613 0.7286061 -0.5804088 -0.3636741 0.7262123 -0.5504689 -0.4118251 0.7099611 -0.5630367 -0.4230189 0.7029243 -0.5667937 -0.4297004 0.6936516 -0.5863364 -0.4183983 0.6836575 -0.6037409 -0.4100115 0.6138288 -0.6885059 -0.3862304 0.6683236 -0.6223665 -0.4074353 0.6683236 -0.6223665 -0.4074353 0.6683236 -0.6223666 -0.4074353 0.6661221 -0.624737 -0.4074128 0.2247793 -0.8875961 -0.4020543 0.3640491 -0.8400554 -0.4022129 0.3638692 -0.839863 -0.4027771 0.494264 -0.7704274 -0.4026722 0.4933365 -0.7697231 -0.4051487 0.6106324 -0.6803492 -0.4052814 -0.003851652 -0.9143472 -0.4049128 0.01266336 -0.914304 -0.4048307 0.08019357 -0.9180848 -0.3881872 0.08190518 -0.9121944 -0.4014885 0.2248124 -0.8876505 -0.4019154 0.09946751 0.9101111 -0.4022488 0.09378015 0.9097218 -0.4044893 -0.005751848 0.9149417 -0.403545 -0.152438 0.9021662 -0.4035579 -0.1524315 0.9021685 -0.403555 -0.2951489 0.8660402 -0.4035612 -0.2951642 0.866028 -0.403576 -0.4302854 0.8074445 -0.4035941 -0.4301859 0.8075299 -0.4035292 -0.554342 0.7279181 -0.4035348 -0.5544038 0.7278513 -0.4035703 -0.6638193 0.6296631 -0.4035695 -0.7279365 0.5536876 -0.404399 -0.7336074 0.5431713 -0.4083935 0.7388426 -0.5402956 -0.4027311 0.7408075 -0.5363067 -0.4044495 0.7951182 -0.4527568 -0.4034831 0.7952665 -0.4522639 -0.4037432 0.8574904 -0.318942 -0.4037153 0.8574188 -0.3194584 -0.4034591 0.8976539 -0.1773035 -0.4034612 0.8976509 -0.1773133 -0.4034636 0.9144631 -0.03118187 -0.4034665 0.9075524 0.1161586 -0.403554 0.9075325 0.1162267 -0.4035794 0.8772542 0.2598552 -0.4036092 0.8771752 0.2599919 -0.4036928 0.8432407 0.3538424 -0.404649 0.8375944 0.3630167 -0.4082337 -0.8392302 -0.3668477 -0.4013916 -0.8346929 -0.3737128 -0.4045078 -0.7895538 -0.4623342 -0.4035491 -0.7895491 -0.4623279 -0.4035655 -0.7050387 -0.5831623 -0.4035372 -0.7049583 -0.5832263 -0.4035851 -0.6024104 -0.6886407 -0.4035787 -0.6024758 -0.6886069 -0.4035387 -0.4841872 -0.7763526 -0.4035337 -0.4839911 -0.7764156 -0.4036479 -0.3534047 -0.8439059 -0.4036435 -0.3532245 -0.8439397 -0.4037305 -0.2130885 -0.8897153 -0.4037325 -0.11593 -0.9071309 -0.4045664 -0.1055331 -0.9069628 -0.4077759 2.98736e-6 0 1 -1.7487e-6 0 1 -1.74909e-6 0 1 -7.59616e-7 0 1 -5.68059e-6 0 1 6.25665e-6 0 1 -5.81625e-6 0 1 5.8572e-6 0 1 5.97429e-6 0 1 1.53367e-6 0 1 1.26804e-6 0 1 7.14939e-7 0 1 2.76781e-6 0 1 6.64275e-6 0 1 -5.47969e-6 0 1 -6.84182e-6 0 1 5.35424e-6 0 1 -5.23396e-6 0 1 -5.16733e-6 0 1 4.97334e-6 0 1 4.90408e-6 0 1 7.92393e-6 0 1 -0.7870784 -0.3904126 0.4775832 0.8145347 -0.4168434 0.4034538 0.8719808 -0.276915 0.4036926 0.8714028 -0.2764696 0.4052428 0.905059 -0.1294022 0.4051213 0.9051938 -0.1295021 0.4047883 0.914185 0.021223 0.4047414 0.9147281 0.02103203 0.4035224 0.8985623 0.1715466 0.4039279 0.8985542 0.1715598 0.4039402 0.8395158 0.3655064 0.4020178 0.8319249 0.3532825 0.4278931 0.7924641 0.3220878 0.5179383 0.7784996 0.3435013 0.525305 0.6948826 0.2813687 0.6617929 0.8373973 0.3693581 0.4029151 0.8352552 0.36102 0.4147452 0.8349987 0.3705819 0.4067509 0.8348393 0.3712543 0.4064648 0.8490728 0.3523261 0.3936266 0.8649355 0.3392927 0.3698203 0.8910422 0.3294267 0.312285 0.8819519 0.2979763 0.3652002 0.8772873 0.2573462 0.4051418 0.09127801 0.9148323 0.3933832 0.07774734 0.923134 0.3765358 0.1033223 0.9102326 0.4010006 0.1073746 0.9091704 0.402343 0.1223467 0.9061417 0.4048933 0.1087037 0.9057001 0.409745 0.09986162 0.9022973 0.4193894 0.08051151 0.8747315 0.4778733 0.1188157 0.8526016 0.5088746 0.07174563 0.7911252 0.607432 -0.5181586 0.7543134 0.4031414 -0.3870785 0.8292805 0.4030686 -0.3870304 0.8285636 0.4045861 -0.2450536 0.8810114 0.4046821 -0.2449645 0.881968 0.4026475 -0.09679317 0.9102668 0.4025489 -0.09698706 0.9095281 0.4041685 -0.007342159 0.9141641 0.405278 0.05614292 0.9398636 0.336904 0.03962689 0.9707619 0.2367514 0.06468194 0.9365572 0.3444952 -0.6531739 0.6771593 0.3388497 -0.6261245 0.6667653 0.4042182 -0.5180628 0.7539686 0.4039089 -0.6326329 0.4649344 0.6193639 -0.7159386 0.5123407 0.4742773 -0.7336412 0.5179913 0.4398359 -0.7433784 0.5180787 0.4230638 -0.7590989 0.5091733 0.4056003 -0.753059 0.5256447 0.395727 -0.749921 0.5382184 0.384629 -0.7490785 0.55565 0.3607417 -0.7490417 0.5555194 0.3610191 -0.6948934 0.5940812 0.4052046 -0.6788671 0.6123302 0.4052053 -0.8664122 -0.2998918 0.3992428 -0.8540713 -0.3080308 0.4191411 -0.8416964 -0.3112031 0.4412481 -0.8424364 -0.3103979 0.4404022 -0.8422677 -0.3105862 0.4405922 -0.8323386 -0.381429 0.4021498 -0.8323386 -0.3814289 0.4021499 -0.8323386 -0.381429 0.4021498 -0.8254269 -0.3960931 0.4022199 -0.8254269 -0.3960931 0.4022199 -0.8254269 -0.3960931 0.4022198 -0.867339 -0.3363726 0.3668467 -0.858128 -0.3172776 0.4036723 -0.8248382 -0.3946645 0.4048233 -0.8213357 -0.4059497 0.4007652 -0.3479006 -0.8460106 0.404019 -0.4821868 -0.7772428 0.4042147 -0.4824396 -0.7774236 0.4035649 -0.603908 -0.6873762 0.4034963 -0.6042613 -0.6875677 0.40264 -0.709249 -0.5787513 0.4025084 -0.7084154 -0.5784789 0.4043634 -0.7743971 -0.4857823 0.4053699 -0.8333095 -0.4763026 0.2805907 -0.8248388 -0.4497663 0.3425658 -0.8200852 -0.4248018 0.3834106 -0.1639668 -0.9055894 0.3911815 -0.1906005 -0.9197367 0.3431559 -0.2139666 -0.9358977 0.2798463 -0.2400412 -0.8825106 0.4044201 -0.3480667 -0.8461818 0.4035171 -0.04205417 -0.9151916 0.400819 -0.05500358 -0.9199582 0.3881385 -0.0546925 -0.9197919 0.3885766 -0.1192163 -0.9066464 0.4046972 -0.1419628 -0.9033671 0.4046907 -0.1447624 -0.8679565 0.4750742 -0.1447623 -0.8679565 0.4750742 -0.1447623 -0.8679565 0.4750742 -0.1394818 -0.9038598 0.4044533 -0.05434834 -0.9135029 0.403186 -0.06403785 -0.8860813 0.4590852 -0.05317783 -0.8949047 0.4430776 -0.0503233 -0.9016122 0.429608 -0.05389195 -0.897514 0.4376807 0.7109452 -0.5707859 0.4108046 0.7200983 -0.5689371 0.3972014 0.7309215 -0.5623149 0.3867245 0.8474087 -0.4195536 0.3253817 0.7837879 -0.4713756 0.4043287 0.7350775 -0.5451717 0.4030495 0.7736083 -0.5524666 0.3103399 0.7436838 -0.5566757 0.370198 0.7083458 -0.5804125 0.4017059 0.7113925 -0.5601089 0.4244984 0.7040786 -0.5423166 0.4584389 0.628682 -0.4708305 0.6189328 0.833321 0.3763357 0.4049043 0.8324797 0.3785742 0.4045482 0.7943526 0.454168 0.4034047 0.7943816 0.4540501 0.4034805 0.7084762 0.5790565 0.4034293 0.7086696 0.578761 0.4035137 0.7087983 0.5786609 0.4034311 0.7095974 -0.5770205 0.4043748 0.636735 -0.6570549 0.4035437 0.6353351 -0.6585415 0.4033268 0.5181857 -0.7541073 0.4034919 0.5181144 -0.7541331 0.4035355 0.5181944 -0.7540725 0.4035457 0.6349798 -0.6587283 0.4035813 -0.043675 -0.9095299 0.4133375 -0.03828257 -0.9139872 0.4039331 0.09675669 -0.9098696 0.4034546 0.09673357 -0.9098636 0.4034735 0.2451596 -0.8815447 0.4034548 0.245141 -0.881547 0.403461 0.3878747 -0.8287241 0.4034473 0.3869166 -0.8291423 0.4035079 0.3869271 -0.8291282 0.403527 0.3854789 -0.8297979 0.403536 0.3854789 -0.829798 0.403536 0.3854791 -0.829798 0.4035361 -0.864468 -0.3219972 0.3860217 -0.8632295 -0.3026378 0.4040363 -0.8987062 -0.1715863 0.4035906 -0.8987264 -0.171738 0.4034811 -0.9147405 -0.0212301 0.4034837 -0.9057888 0.1296897 0.4033946 -0.9056887 0.1299163 0.4035465 -0.9059222 0.1274008 0.4038245 -0.9146437 -0.02089393 0.4037209 -0.7490251 0.516453 0.4150153 -0.7580037 0.5117831 0.4043619 -0.8147301 0.4164618 0.4034532 -0.8144135 0.4167768 0.4037671 -0.8717811 0.2774015 0.4037896 -0.8721328 0.2765442 0.4036184 -0.8720983 0.2769459 0.4034175 -0.9057751 0.1295522 0.4034698 0.2041222 0.8919659 0.4033995 0.2040536 0.8919915 0.4033775 0.2036905 0.8920249 0.4034869 0.1196972 0.9066155 0.4046245 0.1207389 0.9065757 0.4044042 0.3479669 0.8462651 0.4034283 0.3483512 0.8461532 0.4033315 0.3477492 0.8462606 0.4036256 0.347439 0.8464256 0.4035469 0.4825639 0.777349 0.4035599 0.482352 0.7775911 0.4033468 0.604035 0.6873398 0.4033681 0.6041017 0.6872224 0.4034681 0.7087413 0.5787248 0.4034397 -8.42466e-7 0 1 -8.55286e-6 0 1 -8.87123e-6 0 1 8.74818e-7 0 1 -1.67477e-6 0 1 -7.73893e-6 0 1 1.68693e-6 0 1 6.25532e-7 0 1 -2.42319e-6 0 1 2.60841e-6 0 1 -9.2923e-6 0 1 1.94809e-6 0 1 -1.85062e-6 0 1 -9.96166e-7 0 1 1.92625e-6 0 1 -4.10074e-6 0 1 -1.82671e-6 0 1 -9.60639e-6 0 1 1.4474e-6 0 1 -2.66116e-6 0 1 1.54628e-6 0 1 -1.2153e-5 0 1 -1.13076e-6 0 1 3.69505e-6 0 1 1.39495e-6 0 1 -1.64472e-6 0 1 2.79297e-6 0 1 1.56706e-6 0 1 1.79366e-5 0 1 6.02141e-6 0 1 -7.68176e-6 0 1 1.11271e-6 0 1 -7.75675e-6 0 1 2.74907e-6 0 1 -5.6852e-6 0 1 4.19407e-6 0 1 1.28074e-5 0 1 -1.91512e-5 0 1 1.14837e-5 0 1 5.73163e-7 0 1 -2.51705e-6 0 1 -4.84767e-7 0 1 1.51618e-6 0 1 -5.74026e-6 0 1 2.58506e-6 0 1 2.4391e-6 0 1 -2.2909e-6 0 1 -4.40199e-6 0 1 2.83046e-6 0 1 -8.796e-7 0 1 -5.43667e-6 0 1 -2.92299e-6 0 1 3.30177e-6 0 1 -2.67174e-6 0 1 3.57274e-6 0 1 -1.59714e-5 0 1 2.97803e-6 0 1 2.24233e-5 0 1 -3.3824e-6 0 1 1.0692e-5 0 1 5.96331e-6 0 1 -8.41978e-6 0 1 -4.05489e-6 0 1 1.30019e-6 0 1 -2.05477e-6 0 1 2.90989e-6 0 1 -1.3793e-7 0 1 -1.28048e-6 0 1 1.45317e-6 0 1 5.81504e-6 0 1 -5.36583e-6 0 1 -6.62189e-7 0 1 3.02936e-6 0 1 -4.20808e-6 0 1 -2.90833e-5 0 1 -6.55686e-6 0 1 3.89761e-7 0 1 4.27715e-7 0 1 2.26224e-6 0 1 1.54745e-6 0 1 -3.0874e-6 0 1 9.58159e-7 0 1 -1.57387e-6 0 1 -1.96861e-6 0 1 3.83795e-6 0 1 -1.97868e-6 0 1 -4.75747e-6 0 1 -7.35692e-7 0 1 -5.28792e-7 0 1 -7.73591e-7 0 1 2.42408e-6 0 1 3.96341e-6 0 1 -2.23534e-6 0 1 1.60697e-6 0 1 -1.23655e-6 0 1 -1.48543e-6 0 1 -4.76172e-6 0 1 4.1828e-6 0 1 1.61708e-5 0 1 -4.88072e-6 0 1 -2.88937e-6 0 1 2.23246e-6 0 1 2.28165e-6 0 1 -7.2758e-6 0 1 1.99946e-6 0 1 -1.05856e-6 0 1 -2.24745e-6 0 1 -3.84852e-7 0 1 -6.70148e-7 0 1 -1.78298e-6 0 1 4.46766e-6 0 1 -2.25506e-6 0 1 4.02771e-5 0 1 -1.08029e-5 0 1 -1.68697e-6 0 1 -5.24141e-5 0 1 4.671e-7 0 1 -3.25457e-6 0 1 -3.53048e-6 0 1 1.19124e-6 0 1 5.24433e-7 0 1 -7.03227e-7 0 1 -3.68971e-7 0 1 -1.39573e-6 0 1 -1.42911e-6 0 1 -4.39327e-6 0 1 1.36911e-5 0 1 2.72771e-6 0 1 1.75324e-6 0 1 -1.02921e-6 0 1 -1.2679e-6 0 1 -1.98444e-6 0 1 -5.78315e-6 0 1 1.47062e-5 0 1 -4.19287e-6 0 1 1.78451e-6 0 1 1.43102e-6 0 1 -3.54117e-6 0 1 -4.91932e-5 0 1 1.36501e-6 0 1 -7.10126e-7 0 1 8.93387e-7 0 1 3.24069e-6 0 1 -1.23425e-6 0 1 -1.74808e-6 0 1 2.85545e-6 0 1 3.05728e-6 0 1 3.08856e-6 0 1 -1.50553e-5 0 1 -3.02825e-6 0 1 1.52166e-6 0 1 3.78352e-6 0 1 -2.20181e-6 0 1 -8.22253e-6 0 1 1.31264e-6 0 1 1.17234e-6 0 1 -4.37315e-6 0 1 1.76658e-6 0 1 1.46182e-5 0 1 4.72521e-6 0 1 5.38793e-5 0 1 -6.84744e-5 0 1 2.3403e-6 0 1 -4.08017e-6 0 1 7.66382e-7 0 1 -6.5687e-7 0 1 -6.29168e-7 0 1 6.16523e-5 0 1 0 0 1 1.80304e-5 0 1 1.92986e-7 0 1 2.2535e-6 0 1 -0.9293707 -0.369148 0 -0.8873787 -0.4565098 -0.06448245 -0.9472429 -0.3203645 -0.009879767 -0.4377422 -0.8985356 -0.03187179 -0.519131 -0.8546947 0 -0.7330006 -0.6802281 0 -0.6663107 -0.7429814 -0.06331419 -0.7932635 -0.6088786 0 -0.08371829 -0.9960641 -0.02911221 -0.1883319 -0.9821056 0 -0.352755 -0.9357158 0 -0.9767361 -0.2144451 0 -0.9767361 -0.2144451 0 -0.9767361 -0.2144451 0 -0.9999623 -0.008698046 0 -0.9999618 -0.008740305 0 -0.9357842 0.3525734 0 -0.9357839 0.3525743 0 -0.7446981 0.6674016 0 -0.4537332 0.8911377 0 -0.4537327 0.8911378 0 -0.1001483 0.9949726 0 -0.1001527 0.9949722 0 0.2654995 0.9641111 0 0.2655103 0.9641081 0 0.5954636 0.8033823 0 0.8458734 0.533384 0 0.8458352 0.5334444 0 0.9845381 -0.1751711 0 0.9845452 -0.1751306 0 0.8546704 -0.519171 0 0.8546888 -0.5191407 0 0.2818663 -0.9594537 0 0.2818549 -0.959457 0 0.07386034 -0.9972686 0 -0.03020042 -0.9994999 -0.009384274 -9.1507e-7 0 1 -4.97423e-6 0 1 1.45679e-5 0 1 -3.26103e-6 0 1 0.7038593 0.09159499 0.7044093 0.6624724 0.04758268 0.7475736 0.1122786 -0.6742641 0.7299051 0.1566964 -0.6905717 0.7060857 0.2869948 -0.6497252 0.7039114 0.2878661 -0.6487672 0.7044389 0.2873967 -0.6486755 0.704715 0.4433787 -0.5538967 0.7047085 0.4431893 -0.554296 0.7045134 0.4437915 -0.554246 0.7041737 0.570136 -0.4231924 0.7041684 0.5701819 -0.4228604 0.7043308 0.5708213 -0.4225742 0.7039845 0.659686 -0.2635169 0.7038276 0.6586126 -0.2638318 0.7047144 0.6594999 -0.2630417 0.7041797 0.7047801 -0.08726817 0.7040379 0.7048383 -0.08720874 0.7039869 0.7046527 -0.087511 0.7041352 -0.6624099 -0.04746431 0.7476366 -0.6961423 -0.09057348 0.7121674 -0.1122742 0.674283 0.7298883 -0.1561413 0.6903798 0.7063963 -0.1570254 0.6903911 0.7061893 -0.2878225 0.6491094 0.7041414 -0.2879039 0.6488345 0.7043616 -0.2847176 0.6501398 0.7044532 -0.4434322 0.5538513 0.7047104 -0.4434135 0.5545791 0.7041494 -0.4435971 0.5541496 0.7043719 -0.570304 0.4229933 0.7041521 -0.5698817 0.4229876 0.7044972 -0.6618011 0.2573439 0.7041261 -0.6593049 0.2633646 0.7042416 -0.6586478 0.2635532 0.7047856 -0.7043744 0.08592838 0.7046084 -0.7042444 0.08718508 0.704584 -0.7046805 0.08688163 0.7041854 -0.7060002 -0.05120897 0.7063578 0.5956907 0.803214 9.31527e-6 0.5956903 0.8032144 -4.40955e-6 -0.966134 -0.2580411 0 -0.03042781 0.9995371 0 -0.2062869 0.9784496 0.009061813 0.2715863 0.9624142 0 0.2043864 0.9785922 -0.0241549 0.4698895 0.8805059 0.0625568 -0.2062798 0.978493 0 -0.317693 0.9457168 -0.06849014 -0.1785224 0.9837816 -0.01742863 -0.9219474 0.3851419 -0.04097181 -0.8721245 0.4892841 0 -0.6363468 0.7714031 0 -0.7116268 0.6985411 -0.07501816 -0.534691 0.8450477 0 -0.9958322 -0.08638572 -0.02925348 -0.9991329 0.04163366 0 -0.9635531 0.2675172 0 -0.8413714 -0.5404576 0 -0.7275238 -0.6839934 0.05350029 -0.7275238 -0.6839934 0.05350035 -0.7275237 -0.6839935 0.05350041 -0.8715766 -0.48983 -0.02051436 -0.8413553 -0.5404826 0 -0.9592079 -0.2827016 0 -0.9857073 -0.1682943 -0.007635414 -0.9857073 -0.1682943 -0.007635414 -0.9857073 -0.1682942 -0.007635414 -0.9962591 -0.08641755 0 -0.9978302 0.06152045 0.02345865 -0.9945171 -0.1043923 0.006180346 -0.3304633 0.9438189 0 -0.5359337 0.84426 0 -0.6363357 0.7713494 0.00986135 -0.7202494 0.6937152 0 -0.9227117 0.3854909 0 -0.8733681 0.4866985 0.01878005 -0.9635528 0.2675182 0 -0.8413634 -0.5404701 0 -0.494476 -0.8691913 0 -0.4944939 -0.8691812 0 -0.03485208 -0.9993926 0 0.4343597 -0.9007396 0 0.43436 -0.9007394 0 0.7248065 -0.6889526 0 0.8031576 -0.59574 -0.005629956 0.8694542 -0.4940139 0 0.988178 -0.1533112 0 0.988178 -0.1533111 0 0.946866 0.3216283 0 0.9468534 0.3216656 0 0.6880536 0.72566 0 0.6880537 0.7256598 0 0.2715855 0.9624143 0 0.2715965 0.9624112 0 -0.1331033 0.9910975 0.003059148 1.68599e-6 0 1 4.49576e-7 0 1 -1.51068e-6 0 1 1.05034e-6 0 1 -6.70394e-6 0 1 2.12422e-6 0 1 -6.73782e-6 0 1 2.09673e-6 0 1 -2.12435e-6 0 1 -2.10135e-6 0 1 5.37182e-7 0 1 -2.55885e-6 0 1 1.91817e-6 0 1 -2.12321e-6 0 1 -2.08955e-6 0 1 2.12357e-6 0 1 -0.5956903 -0.8032144 -3.67463e-6 -0.9974443 -0.07144969 0 -0.9721735 -0.2256461 -0.06295096 -0.9835413 -0.1806836 0 -0.8987178 -0.4385276 0 -0.8987869 -0.438386 -7.47989e-5 0.2212823 -0.9752098 0 -0.8988238 -0.4383104 0 -0.7463645 -0.6655374 0 -0.7463515 -0.665552 0 -0.5395383 -0.8419612 0 -0.5395286 -0.8419674 0 -0.2923293 -0.9563177 0 -0.2923222 -0.95632 0 -0.02335816 -0.9997273 0 -0.02350538 -0.9997238 -4.27561e-5 -0.02353376 -0.9997231 0 0.1356964 -0.9907506 0 0.2466018 -0.9687957 -0.02494877 0.2603561 -0.9654728 -0.008787274 0.4040356 -0.9146902 0.009849905 0.9756623 0.1565644 -0.1535279 0.999741 0.02276074 0 0.9973267 0.07172214 -0.01397871 0.9989957 0.04480904 0 0.9498108 0.3128249 0 0.9497804 0.3129172 1.14241e-4 0.9496182 0.3134095 0 0.8303535 0.557237 0 0.8303403 0.5572568 0 0.6490963 0.7607063 0 0.6491023 0.7607012 0 0.4202607 0.9074034 0 0.4202749 0.9073969 0 0.1584753 0.9873631 0 0.1592846 0.9872325 -7.37012e-4 0.1608641 0.9869766 0 -0.0676279 0.9977107 0 -0.1129997 0.9927434 -0.04112941 -0.2011117 0.9795684 0 0.9277088 -0.3719065 0.03228253 0.9497705 -0.3122761 0.02049165 0.987512 -0.1572256 0.01001036 0.9255309 -0.3786722 -2.79979e-4 0.9255309 -0.3786722 -2.79947e-4 0.9255309 -0.3786722 -2.80003e-4 0.9228948 -0.3850517 -6.64916e-4 0.9142359 -0.4051694 -0.003247499 0.8960695 -0.443674 -0.01458811 0.8759049 -0.4808949 -0.03912478 0.8579589 -0.5133891 -0.01839756 0.8159824 -0.5780768 0 0.7891255 -0.6142321 0 0.7145062 -0.6991055 -0.02706503 0.7415373 -0.6669688 -0.07262986 0.7023881 -0.7113479 -0.02520549 0.6591344 -0.7520117 -0.004515767 0.6344098 -0.7729965 -7.95684e-4 0.6364566 -0.771312 -9.64364e-4 0.4356213 -0.9000753 0.009922683 0.517718 -0.855407 0.01571685 0.517718 -0.8554071 0.01571685 0.517718 -0.8554071 0.01571679 0.5798982 -0.814387 0.02218151 0.6299241 -0.7759883 0.03221631 0.6247726 -0.7802846 0.02855652 0.7159841 -0.6980906 -0.006020367 0.7579032 -0.6522735 0.01106154 0.8012584 -0.5946841 0.06584721 0.7799425 -0.6205537 0.08125847 0.8010659 -0.5930223 0.08135133 0.8282356 -0.5597571 0.02641701 0.9261127 -0.3710315 -0.06819826 0.8847047 -0.4563424 0.09512746 0.9110684 -0.4091189 0.05075496 0.405059 -0.9142376 0.009845316 0.500063 -0.8659138 -0.01141911 0.6249012 -0.780699 0.002757966 0.4985514 -0.8668029 0.009960651 0.4952015 -0.8687201 0.01005005 0.4952015 -0.8687201 0.01005005 0.4952015 -0.8687201 0.01005005 -0.9962931 -0.0859946 0.002262771 -0.9973664 -0.07249283 0.002262115 -0.9957599 0.09181416 -0.005697965 -0.9924831 0.1223377 0.003285348 -0.934212 0.3567038 0.003211081 -0.9923071 0.1210526 -0.02594262 -0.9340863 0.3570279 -0.003744602 -0.9284256 0.3715169 0.001112341 -0.9320175 0.3624117 0.001113951 -0.8033323 0.5955295 -0.001445174 -0.8029844 0.595999 -0.001248836 -0.6245865 0.7809547 0.001248538 -0.6245865 0.7809547 0.001249372 -0.6245866 0.7809547 0.001248538 -0.6125074 0.7904641 0.001248955 -0.6249889 0.7806307 -0.002229869 -0.6127803 0.7902448 -0.003664851 -0.4012518 0.9159612 0.003477275 -0.4053466 0.9141565 0.003478169 -0.3768306 0.9262655 -0.005577087 -0.2218301 0.9750827 0.002303838 -0.220565 0.9753696 0.002304971 0.9751756 -0.2212007 0.01014703 0.973759 -0.2273617 0.01000928 0.9288421 -0.3704641 0.002971231 0.9739711 -0.2263961 -0.01118612 0.9923846 -0.1227852 0.009828448 0.9923141 -0.1233537 0.009828984 0.7362698 -0.6766882 0 0.0948593 -0.9954907 0 -0.3185375 -0.9479104 0 -0.318539 -0.9479098 0 -0.67612 -0.7367916 0 -0.676095 -0.7368145 0 -0.917366 -0.3980448 0 -0.9173862 -0.3979983 0 -0.9999415 0.01081645 0 -0.9999416 0.01081639 0 -0.9097514 0.4151535 0 -0.6618813 0.7496088 0 -0.6619079 0.7495852 0 0.8144702 0.5802056 0 0.8144447 0.5802412 0 0.9760391 -0.2175957 0 0.9760505 -0.2175444 0 0.8604593 -0.5095191 0 0.8022421 -0.5960601 -0.03347051 -0.909938 0.4147445 2.69105e-4 -0.9097335 0.4151928 0 -0.9999356 0.01135236 0 -0.9999513 0.009867608 4.11632e-4 -0.9999656 0.008301794 1.08764e-4 -0.999961 0.008834362 0 -0.917856 -0.3969137 0 -0.9178364 -0.396959 0 -0.317669 -0.9482017 0 -0.3176675 -0.9482023 0 0.09438133 -0.9955362 0 0.09378993 -0.995592 -2.01897e-4 0.09309858 -0.995657 0 0.4937546 -0.8696014 0 0.4918275 -0.8706927 -1.21146e-4 0.4916861 -0.8707726 0 0.7350611 -0.678001 0 0.7380984 -0.6746926 -8.3917e-4 0.8024377 -0.5957933 -0.03352916 0.8606486 -0.5091993 0 0.9799949 0.199023 0 0.9801058 0.1984761 -2.10336e-4 0.9802407 0.1978085 0 0.5072163 0.8618188 0 0.5072386 0.8618057 0 -0.9107882 0.4128739 0 -0.661229 0.7501842 0 -0.6612023 0.7502077 0 -0.3009096 0.9536527 0 -0.299579 0.9540714 -6.5316e-4 -0.2960004 0.9551879 0 0.7363314 -0.6766212 0 0.4909633 -0.8711803 0 -0.9999536 0.009632647 -1.13776e-4 -0.999961 0.008834064 0 -0.9174044 -0.3979566 0 -0.9173847 -0.3980018 0 -0.3183829 -0.9479622 0 -0.3183977 -0.9479573 0 0.09497964 -0.9954792 1.95144e-4 0.09565699 -0.9954144 0 0.4909415 -0.8711926 0 0.8605925 -0.5047718 -0.06772029 0.8032791 -0.5952823 -0.01954478 0.8611232 -0.5083963 0 0.9759078 -0.2181837 0 0.9760384 -0.2175981 3.76326e-4 0.9772832 -0.2119376 0 0.9799731 0.1991299 0 0.980106 0.1984748 -2.10334e-4 0.815026 0.5794245 0 0.815027 0.5794229 0 0.114257 0.9934513 0 -0.9999515 0.009851574 0 -0.9093034 0.4161339 0 -0.6633275 0.7483292 0 -0.6618167 0.7496656 -2.69393e-4 -0.6614087 0.7500258 0 -0.3016878 0.9534069 0 -0.300436 0.953802 3.30773e-4 -0.2993414 0.9541461 1.338e-4 -0.3000472 0.9539244 0 0.1142513 0.9934519 0 0.09498602 -0.9954787 0 -0.9173945 -0.3979791 0 -0.9999535 0.009644269 0 -0.9999541 0.009590327 0 -0.9094908 0.4157242 0 -0.909501 0.4157019 0 0.8480098 -0.5299797 -0.001058459 0.8480097 -0.52998 -0.001058459 0.8480097 -0.5299798 -0.001058459 0.8612092 -0.5082496 -0.001050889 0.8023419 -0.5959248 -0.03348362 0.736358 -0.6765922 0 0.8065651 -0.5911453 0 0.814076 0.5807584 0 0.8140506 0.5807941 0 0.1142631 0.9934506 0 -0.2995783 0.9540718 0 -0.6614713 0.7499705 0 -0.6614421 0.7499963 0 -0.6609971 0.7503885 0 -0.6610232 0.7503654 0 0.4918594 -0.8706746 0 -0.9173945 -0.3979791 3.70119e-4 -0.9176219 -0.3974545 0 -0.3173123 -0.9483212 0 -0.3173027 -0.9483243 0 0.09496122 -0.995481 0 0.09377586 -0.9955932 -5.7201e-4 0.09004944 -0.9959373 0 0.4918698 -0.8706689 0 0.860578 -0.5047962 -0.06772357 0.8032897 -0.5952682 -0.01953172 0.9759019 -0.2182099 0 0.9760446 -0.2175703 3.74222e-4 0.9807525 0.195255 0 0.9801213 0.1983989 5.16594e-4 0.9798988 0.1994954 0 -0.8947347 -0.4465982 0 -0.8947349 -0.4465977 0 -0.8947348 -0.4465979 0 -0.9999539 0.009605765 0 -0.9092915 0.41616 0 -0.6618215 0.7496615 -2.76126e-4 -0.6614316 0.7500056 0 -0.3008463 0.9536727 0 -0.3003233 0.9538375 1.47919e-4 -0.2999274 0.9539621 0 0.1101112 0.9939193 0 0.1101112 0.9939193 0 0.1101112 0.9939193 0 0.1142509 0.993452 -2.69257e-5 -0.9094908 0.4157242 -2.9587e-4 -0.9097464 0.4151645 0 -0.9999349 0.01141637 0 -0.9999535 0.009640753 4.73056e-4 -0.9999656 0.008296489 0 -0.9379463 -0.3467805 0 -0.937946 -0.3467816 -1.35646e-7 -0.9379456 -0.3467826 0 -0.9178168 -0.3970044 -3.56825e-4 -0.9176235 -0.3974508 0 -0.6761741 -0.7367419 0 -0.3184337 -0.9479452 0 0.09480202 -0.9954962 0 0.09473747 -0.9955024 -2.69164e-5 0.09453207 -0.9955219 0 0.4884908 -0.8725692 0 0.4910618 -0.8711248 1.88293e-4 0.491369 -0.8709517 0 0.7375345 -0.6753095 0 0.7375912 -0.6752477 -1.61512e-5 0.8030129 -0.5950362 -0.0332033 0.8606444 -0.5092067 0 0.9798187 0.1998886 0 0.980111 0.19845 -2.38942e-4 0.9802169 0.1979267 0 0.814636 0.5799726 0 -0.908638 0.4175849 0 -0.661834 0.7496505 0 -0.6618224 0.7496607 0 0.1141284 0.993466 -1.34474e-5 0.1141653 0.9934619 0 -0.9339566 0.3573867 0 -0.9997829 -0.02083778 4.91193e-6 -0.9997798 -0.02098405 0 -0.9997935 -0.02032709 0 -0.9997912 -0.02044123 0 -0.9339647 0.3573654 0 -0.9997824 -0.0208652 0 -0.6941558 -0.7198249 0 -0.6987656 -0.7153506 -5.81113e-4 -0.6993719 -0.714758 0 -0.3420277 -0.9396899 0 -0.377295 -0.9260932 3.2577e-4 -0.3777345 -0.9259141 0 1.21535e-6 0 1 3.14401e-6 0 1 -1.44574e-6 0 1 1.84114e-6 0 1 -1.28642e-6 0 1 -0.541134 -0.4566975 0.7061172 -0.5410913 -0.4568903 0.7060253 -0.5414326 -0.4562781 0.7061593 -0.5413056 -0.4566273 0.706031 -0.4644621 -0.5346543 0.7059886 -0.4646512 -0.5345821 0.7059187 -0.4647586 -0.5343955 0.7059894 -0.3764494 -0.5998716 0.7060028 -0.3764836 -0.5998522 0.706001 -0.3764942 -0.5998568 0.7059915 -0.2801477 -0.6504186 0.7060263 -0.2801609 -0.6504099 0.7060289 -0.2798382 -0.6504951 0.7060785 -0.2798485 -0.6504765 0.7060915 0.9463676 -0.323092 0 0.9463842 -0.3230433 6.08826e-6 0.9463092 -0.3232631 0 0.9464817 -0.3227576 1.49947e-4 -0.4809607 -0.8767421 0 -0.95714 -0.2896258 0 -0.7768417 -0.6296961 0 -0.7770099 -0.6294885 -1.80142e-4 -0.7892585 -0.6140611 0 -0.7892587 -0.6140611 0 -0.7892585 -0.6140611 0 -0.1182377 -0.9929854 0 -0.113404 -0.9935489 -4.67615e-4 -0.1135738 -0.9935294 -5.08555e-4 -0.1146146 -0.9934101 0 0.2700705 -0.9628406 0 0.2700629 -0.9628427 0 0.265269 -0.9641745 0 0.2652406 -0.9641823 0 0.613874 -0.7894041 0 0.6138646 -0.7894114 0 0.8662651 -0.4995846 0 -0.9950917 -0.09895783 0 -0.9953917 -0.09588533 0.001276135 -0.995056 -0.09931492 4.42834e-4 -0.9949889 -0.09998542 3.0317e-5 0.1248558 -0.696944 0.7061728 0.1274758 -0.6968767 0.7057711 0.1245455 -0.6970307 0.7061421 0.1249543 -0.6971945 0.7059081 0.2312802 -0.6694631 0.705924 0.2308445 -0.6696666 0.7058736 0.2304766 -0.6695966 0.7060602 0.2299432 -0.6698663 0.7059782 0.3313138 -0.6259115 0.7060212 0.3314692 -0.6258273 0.7060229 0.3305736 -0.6261324 0.7061724 0.423488 -0.5676957 0.70596 0.4234683 -0.5677172 0.7059545 0.4236531 -0.5675332 0.7059916 0.3309373 -0.6261303 0.7060038 0.7533317 0.6576408 0 0.7528465 0.6581961 -1.33958e-4 0.7526605 0.658409 0 0.7528076 0.6582408 -9.70232e-5 0.8658244 0.5003481 0 0.1574639 -0.9875248 0 0.157463 -0.987525 0 0.1545615 -0.9879832 0 0.1545295 -0.9879882 0 0.5184733 -0.8550938 0 0.5184342 -0.8551176 0 0.8032418 -0.5956531 0 0.8032186 -0.5956845 0 0.9689123 -0.2474051 0 0.9907273 0.1358659 0 0.9907273 0.1358659 0 0.9907273 0.1358659 0 0.9907642 0.1355964 0 0.9906837 0.1361832 0 0.9906837 0.1361837 0 0.8658043 0.5003829 0 5.79068e-7 0 1 8.68645e-7 0 1 0.6660438 -0.2407506 0.7059922 0.6664922 -0.2399073 0.705856 0.6955371 -0.1344408 0.7058002 0.6950601 -0.1352329 0.7061187 0.6950676 -0.1355594 0.7060487 0.6951416 -0.1353799 0.7060104 0.7076399 -0.02668321 0.7060693 0.7077467 -0.02627247 0.7059777 0.7077167 -0.02618825 0.7060108 0.7033681 0.0838266 0.7058658 0.7034389 0.08283853 0.7059119 0.7032366 0.08310681 0.7060819 0.7076044 -0.02734047 0.7060797 -0.1917497 0.9814439 0 -0.193608 0.9810789 -3.28731e-4 -0.1941569 0.9809706 0 -0.1936694 0.9810668 -2.38162e-4 0.9336001 -0.3583165 0 0.9336158 -0.358276 0 0.9170812 0.3987007 0 0.9172822 0.3982379 -2.5268e-4 0.9180817 0.3963915 6.67326e-5 0.9182819 0.3959273 0 0.371412 0.9284682 0 0.3714123 0.9284681 0 0.3714117 0.9284683 0 0.3773207 0.9260827 -5.81769e-5 0.3773476 0.9260717 0 -2.98918e-6 0 1 -1.14687e-6 0 1 1.57549e-6 0 1 -1.0817e-6 0 1 3.67923e-6 0 1 -2.62551e-6 0 1 0.5412449 0.4566587 0.7060572 0.5411931 0.4568706 0.7059599 0.5412155 0.4568613 0.7059488 0.5412419 0.4567814 0.7059801 0.4648453 0.534324 0.7059864 0.4645999 0.5344234 0.7060727 0.2798431 0.6505909 0.7059882 0.2799199 0.6505448 0.7060002 0.2798684 0.6505607 0.706006 0.2798437 0.6505669 0.7060101 0.3766065 0.5997614 0.7060127 0.3766287 0.5997564 0.7060051 0.3767419 0.5997128 0.7059817 0.464447 0.5347051 0.70596 -0.947405 0.320037 0 -0.946369 0.3230875 5.78508e-4 -0.9460006 0.3241649 0 -0.9463359 0.3231847 4.80641e-4 0.1141885 0.9934591 0 0.9570984 0.2897632 0 0.7767716 0.6297826 0 0.7769992 0.6295016 2.73251e-4 0.7957462 0.6056302 0 0.795746 0.6056306 0 0.7957459 0.6056308 0 0.4811985 0.8766117 0 0.4812056 0.8766079 0 0.4812581 0.8765791 0 -0.2697584 0.9629281 0 -0.2695748 0.9629795 8.13995e-5 -0.2692358 0.9630743 0 -0.6137341 0.7895128 0 -0.6137549 0.7894967 0 -0.4235786 0.5675002 0.7060629 -0.4234216 0.5675488 0.7061181 -0.4234838 0.5674882 0.7061294 -0.3311261 0.6258868 0.7061312 -0.330971 0.6260648 0.7060462 -0.3307988 0.6261128 0.7060843 -0.3309748 0.6259961 0.7061053 -0.2312201 0.6692671 0.7061294 -0.230582 0.6695887 0.7060332 -0.2307026 0.6695986 0.7059844 -0.2309938 0.6694805 0.7060013 -0.1247709 0.6971098 0.7060242 -0.1248213 0.6970767 0.7060479 -0.1247023 0.6970627 0.7060828 -0.1242603 0.6971614 0.7060633 0.9950375 0.09949958 -4.9175e-4 0.9949483 0.1003842 -9.96686e-4 0.9950814 0.09906047 0 -0.8657149 -0.5005376 0 -0.157473 0.9875234 0 -0.1574785 0.9875224 0 -0.1545112 0.987991 0 -0.1545119 0.9879909 0 -0.5184694 0.8550962 0 -0.5184591 0.8551024 0 -0.8037268 0.5949985 0 -0.8037168 0.5950121 0 -0.9686607 0.2483879 0 -0.9686551 0.2484098 0 -0.9907783 -0.1354937 0 -0.9906839 -0.1361822 0 0.9291725 -0.3696467 0 0.9295042 -0.3688116 0 0.9295042 -0.3688116 0 0.9295042 -0.3688116 0 0.9292262 -0.3695115 0 -0.6213763 0.7835124 0 -0.622698 0.7824623 0 -0.6226963 0.7824636 0 -0.930161 0.3671518 0 0.9295049 -0.3688097 0 0.7843797 0.6202811 3.03927e-5 0.7846934 0.6198841 0 -0.929558 0.3686758 0 -0.9294955 0.3688336 0 -0.9294955 0.3688337 0 -0.9294955 0.3688336 0 -0.9303683 0.3666266 0 -0.9303947 0.3665596 0 -0.3763539 -0.926476 0 -0.3693056 -0.9293079 -6.21448e-4 -0.3669738 -0.9302314 0 0.6229757 -0.7822414 0 0.6230134 -0.7822112 0 0.6228722 -0.7823237 0 0.6227834 -0.7823944 0 0.9301034 -0.367298 0 0.9301403 -0.3672044 0 0.7843093 0.6203701 0 -8.38476e-6 0 -1 -2.98173e-6 0 -1 -3.8956e-5 0 -1 2.7036e-6 0 -1 -2.19414e-6 0 -1 6.43437e-5 0 -1 2.52169e-6 0 -1 -3.4976e-6 0 -1 -1.77209e-6 0 -1 1.74231e-6 0 -1 -2.3418e-5 0 -1 -1.77255e-6 0 -1 -2.51788e-6 0 -1 3.50133e-6 0 -1 1.17069e-6 0 -1 3.17203e-6 0 -1 4.80496e-6 0 -1 -5.59472e-6 0 -1 -2.60749e-6 0 -1 1.69189e-5 0 -1 -1.40837e-5 0 -1 1.38504e-5 0 -1 3.10707e-6 0 -1 -1.18367e-6 0 -1 8.82768e-6 0 -1 -3.53787e-6 0 -1 8.80258e-6 0 -1 3.83458e-6 0 -1 -2.28303e-6 0 -1 -9.60681e-7 0 -1 -3.24179e-6 0 -1 -2.09778e-6 0 -1 2.61597e-6 0 -1 5.16017e-6 0 -1 -1.09904e-6 0 -1 -5.91695e-6 0 -1 1.37246e-6 0 -1 -3.94677e-6 0 -1 1.92089e-6 0 -1 9.60892e-6 0 -1 -3.6615e-6 0 -1 3.38501e-5 0 -1 1.38397e-5 0 -1 -7.04781e-6 0 -1 -2.65273e-6 0 -1 1.97772e-6 0 -1 4.82458e-6 0 -1 -1.05126e-5 0 -1 1.0816e-5 0 -1 -3.74302e-6 0 -1 2.77966e-6 0 -1 -1.00973e-5 0 -1 -9.77234e-7 0 -1 9.00074e-6 0 -1 -2.9248e-6 0 -1 -1.70219e-6 0 -1 -1.83906e-6 0 -1 -2.508e-6 0 -1 2.10431e-6 0 -1 -6.38056e-6 0 -1 2.59255e-5 0 -1 1.02142e-5 0 -1 -1.66128e-6 0 -1 -2.69291e-6 0 -1 2.9967e-4 0 -1 1.43488e-5 0 -1 1.09288e-5 0 -1 1.30768e-6 0 -1 1.28003e-5 0 -1 1.39736e-6 0 -1 -2.14708e-6 0 -1 -2.89613e-6 0 -1 -1.43135e-5 0 -1 4.88316e-6 0 -1 -2.0695e-6 0 -1 1.70119e-6 0 -1 -4.03656e-6 0 -1 2.59196e-6 0 -1 -1.82714e-5 0 -1 -2.58218e-6 0 -1 2.59771e-5 0 -1 2.56172e-5 0 -1 2.55781e-5 0 -1 8.80133e-7 0 -1 -7.45414e-7 0 -1 -6.7781e-6 0 -1 9.29005e-6 0 -1 -2.23483e-5 0 -1 -2.97874e-6 0 -1 3.76727e-6 0 -1 2.5456e-6 0 -1 1.04891e-5 0 -1 -3.99568e-6 0 -1 -5.44307e-5 0 -1 -2.43266e-6 0 -1 1.82282e-5 0 -1 -1.6211e-6 0 -1 5.55519e-6 0 -1 2.02684e-5 0 -1 1.67414e-5 0 -1 -3.21663e-6 0 -1 3.55353e-6 0 -1 -6.07362e-6 0 -1 8.17127e-6 0 -1 -2.02118e-5 0 -1 1.62665e-5 0 -1 -8.53976e-6 0 -1 9.57263e-6 0 -1 1.66549e-5 0 -1 1.77547e-6 0 -1 4.14952e-6 0 -1 -8.09402e-6 0 -1 6.06689e-6 0 -1 8.52591e-7 0 -1 -6.09607e-6 0 -1 1.92594e-6 0 -1 -2.98796e-6 0 -1 0 0 -1 -3.09928e-6 0 -1 -8.32898e-6 0 -1 -2.62812e-6 0 -1 4.3643e-6 0 -1 -4.03916e-6 0 -1 -2.5699e-6 0 -1 -2.82127e-6 0 -1 -1.0308e-5 0 -1 2.90027e-6 0 -1 -2.81218e-6 0 -1 6.00658e-6 0 -1 -1.37699e-6 0 -1 2.33551e-6 0 -1 -2.9263e-6 0 -1 -1.17152e-5 0 -1 5.58017e-6 0 -1 6.06884e-6 0 -1 -3.74348e-6 0 -1 4.10236e-6 0 -1 -2.50702e-6 0 -1 -1.98277e-5 0 -1 -6.0715e-6 0 -1 5.06455e-6 0 -1 2.42795e-6 0 -1 2.54395e-4 0 -1 3.14933e-6 0 -1 -2.69234e-6 0 -1 -1.29504e-6 0 -1 2.33758e-6 0 -1 3.50592e-6 0 -1 -2.54996e-6 0 -1 1.0963e-5 0 -1 -2.65791e-6 0 -1 2.03427e-6 0 -1 -4.08017e-6 0 -1 -1.96179e-6 0 -1 -3.81045e-6 0 -1 -1.62726e-5 0 -1 1.01725e-6 0 -1 -1.43173e-5 0 -1 -3.55923e-6 0 -1 1.81525e-6 0 -1 7.41774e-6 0 -1 8.57427e-6 0 -1 3.76325e-6 0 -1 4.74305e-6 0 -1 3.40731e-6 0 -1 -3.16153e-5 0 -1 8.07494e-6 0 -1 -5.03724e-6 0 -1 8.92019e-5 0 -1 1.46741e-6 0 -1 -3.68674e-6 0 -1 -2.11263e-6 0 -1 -3.53317e-6 0 -1 5.76244e-7 0 -1 -1.40951e-6 0 -1 -1.50531e-6 0 -1 -6.39525e-6 0 -1 1.10422e-5 0 -1 1.70307e-6 0 -1 1.68913e-5 0 -1 2.3911e-6 0 -1 2.11335e-6 0 -1 4.49394e-6 0 -1 2.64711e-6 0 -1 1.29271e-5 0 -1 1.04456e-6 0 -1 -4.17112e-6 0 -1 -1.76566e-6 0 -1 -1.10411e-5 0 -1 2.39856e-6 0 -1 1.50578e-6 0 -1 -1.83845e-6 0 -1 -0.9283958 0.3715932 0 -0.9308297 0.3654531 0 -0.9308304 0.3654515 0 -0.7832227 -0.6217414 0 0.6213387 -0.7835422 0 0.6178674 -0.7862823 0 0.9891105 0.1471754 0 0.9891104 0.147176 0 0.7834764 0.6214217 0 0.3692871 0.9293155 0 -0.9285207 0.3712806 0 1.28548e-5 0 1 -1.28789e-5 0 1 -4.3473e-6 0 1 -2.51453e-6 0 1 -8.63547e-6 0 1 4.08644e-6 0 1 2.12896e-6 0 1 1.17642e-5 0 1 8.20506e-6 0 1 -2.54034e-6 0 1 -1.18713e-6 0 1 -1.8117e-6 0 1 2.14524e-6 0 1 4.84496e-6 0 1 -4.08483e-6 0 1 -9.33756e-7 0 1 -2.23268e-6 0 1 9.76425e-6 0 1 -7.24218e-5 0 1 2.3322e-4 0 1 2.33238e-4 0 1 2.33248e-4 0 1 2.51246e-6 0 1 -4.14662e-6 0 1 6.71689e-7 0 1 1.16861e-6 0 1 -3.56766e-6 0 1 2.33579e-5 0 1 -1.75513e-5 0 1 2.88877e-6 0 1 2.95685e-6 0 1 1.986e-6 0 1 -3.98928e-6 0 1 7.58684e-6 0 1 -2.28653e-6 0 1 -1.98924e-6 0 1 1.12247e-6 0 1 8.5253e-6 0 1 -7.19321e-5 0 1 -2.8884e-6 0 1 3.02335e-6 0 1 6.93462e-6 0 1 -2.85708e-6 0 1 -8.34927e-6 0 1 2.61473e-6 0 1 2.07302e-6 0 1 -3.59821e-6 0 1 -9.98339e-7 0 1 6.04833e-6 0 1 -1.44414e-6 0 1 3.67943e-6 0 1 -1.06472e-6 0 1 4.43451e-6 0 1 -3.69071e-6 0 1 3.94465e-6 0 1 -1.96744e-6 0 1 5.78583e-6 0 1 8.80468e-6 0 1 -1.74911e-5 0 1 -7.96178e-6 0 1 -4.45297e-6 0 1 2.6407e-6 0 1 1.05126e-5 0 1 -3.90229e-6 0 1 1.14379e-5 0 1 -1.00696e-6 0 1 4.38002e-6 0 1 -1.95392e-6 0 1 2.27475e-6 0 1 5.02719e-7 0 1 1.98719e-6 0 1 -2.87449e-6 0 1 1.83246e-6 0 1 -2.63428e-6 0 1 -9.39585e-6 0 1 -1.17947e-5 0 1 2.70991e-6 0 1 -1.18014e-5 0 1 -6.83673e-6 0 1 1.05194e-6 0 1 9.48969e-6 0 1 -3.74229e-6 0 1 5.56932e-6 0 1 -4.00115e-6 0 1 3.85737e-6 0 1 -1.94641e-6 0 1 1.08209e-5 0 1 -2.84933e-6 0 1 -3.58747e-6 0 1 5.61808e-6 0 1 6.0715e-6 0 1 7.31157e-7 0 1 -1.21144e-6 0 1 7.71778e-7 0 1 -2.57284e-6 0 1 -2.25888e-6 0 1 2.93376e-5 0 1 -2.2777e-5 0 1 1.93397e-6 0 1 2.89744e-6 0 1 -2.62269e-6 0 1 -6.06654e-6 0 1 1.62514e-5 0 1 -4.57955e-6 0 1 -9.15706e-6 0 1 4.79363e-6 0 1 -1.44753e-6 0 1 2.32375e-6 0 1 3.36827e-6 0 1 1.4482e-6 0 1 -1.13746e-6 0 1 9.6499e-7 0 1 1.62616e-6 0 1 7.63881e-7 0 1 -7.33267e-6 0 1 5.57625e-6 0 1 -8.00461e-7 0 1 1.92444e-6 0 1 2.36771e-6 0 1 -5.91455e-6 0 1 2.97697e-6 0 1 -8.70716e-6 0 1 2.79345e-6 0 1 -3.81185e-6 0 1 -1.08103e-5 0 1 5.27643e-6 0 1 9.05823e-7 0 1 -1.49203e-6 0 1 1.66112e-6 0 1 1.97724e-6 0 1 -4.99211e-6 0 1 1.21536e-6 0 1 3.59162e-6 0 1 1.69033e-6 0 1 1.40946e-5 0 1 -1.28034e-5 0 1 -1.06571e-5 0 1 -2.296e-6 0 1 2.67333e-6 0 1 1.31479e-6 0 1 -4.73898e-6 0 1 4.39389e-6 0 1 -1.0308e-5 0 1 -8.81686e-6 0 1 6.58077e-6 0 1 -1.29239e-6 0 1 -2.22013e-6 0 1 -3.01765e-6 0 1 -2.091e-5 0 1 2.04238e-5 0 1 4.21902e-6 0 1 4.62984e-6 0 1 -1.78294e-6 0 1 -4.20946e-6 0 1 -1.0529e-5 0 1 8.92293e-6 0 1 -1.35172e-5 0 1 1.99106e-6 0 1 8.21972e-6 0 1 3.17628e-6 0 1 -2.20471e-6 0 1 -2.94846e-5 0 1 9.77571e-7 0 1 2.92788e-6 0 1 -1.18792e-4 0 1 9.91513e-6 0 1 -4.80197e-6 0 1 -1.0963e-5 0 1 1.16217e-5 0 1 -8.07441e-6 0 1 1.76382e-6 0 1 -2.97647e-6 0 1 1.82282e-5 0 1 4.97812e-6 0 1 -6.58189e-6 0 1 -1.48845e-5 0 1 5.55932e-6 0 1 -4.3154e-6 0 1 -6.00477e-6 0 1 2.84508e-6 0 1 -4.78771e-6 0 1 4.0391e-6 0 1 -2.37001e-6 0 1 -4.04565e-6 0 1 1.57868e-5 0 1 -3.05429e-6 0 1 -2.35999e-5 0 1 2.92039e-5 0 1 -1.21999e-5 0 1 1.32121e-5 0 1 -9.08628e-6 0 1 -6.58293e-6 0 1 3.87501e-6 0 1 -6.19894e-6 0 1 -6.61481e-6 0 1 -1.13289e-5 0 1 -6.95575e-6 0 1 1.04447e-5 0 1 -2.49451e-5 0 1 5.31553e-6 0 1 6.60397e-6 0 1 -4.55349e-6 0 1 1.39538e-5 0 1 1.65053e-6 0 1 -2.85477e-5 0 1 4.84332e-6 0 1 -2.2497e-6 0 1 3.37724e-6 0 1 -1.71989e-6 0 1 -3.52985e-6 0 1 1.41247e-5 0 1 1.37414e-6 0 1 2.25621e-6 0 1 -6.9772e-6 0 1 -2.98151e-5 0 1 -0.6659879 0.2402657 0.70621 -0.6660471 0.2407518 0.7059885 -0.6658856 0.2410843 0.7060275 -0.695154 0.1350765 0.7060562 -0.6952706 0.1348844 0.7059781 -0.6952813 0.1348452 0.705975 -0.6951552 0.1353084 0.7060105 -0.7076419 0.02668315 0.7060673 -0.7077495 0.02627259 0.7059749 -0.7077124 0.02620422 0.7060146 -0.7076364 0.02734172 0.7060477 -0.7032362 -0.08298683 0.7060964 -0.7032848 -0.08309876 0.7060348 -0.7032738 -0.08311265 0.7060442 -0.7051222 -0.0755732 0.7050471 -0.7033306 -0.08209609 0.7061065 0.4108359 0.9117093 3.39517e-4 0.4121188 0.9111295 0.0011276 -2.24885e-6 0 1 -4.5496e-6 0 1 5.90913e-6 0 1 1.36262e-6 0 1 -2.94542e-6 0 1 -7.72845e-7 0 -1 -2.61295e-6 0 -1 -1.08921e-6 0 -1 -3.71659e-6 0 -1 1.96163e-6 0 -1 -8.72649e-7 0 -1 1.8557e-6 0 -1 -9.26447e-7 0 -1 0 0 -1 1.8432e-6 0 -1 7.23929e-6 0 -1 -3.63975e-6 0 -1 9.30835e-7 0 -1 -5.5673e-7 0 -1 -1.72542e-6 0 -1 9.44194e-7 0 -1 -8.57951e-7 0 -1 0 0 -1 -8.46218e-7 0 -1 7.80652e-6 0 -1 -3.33485e-6 0 -1 8.1105e-6 0 -1 -6.46341e-6 0 -1 8.50282e-6 0 -1 -6.24204e-6 0 -1 0.4960908 -0.868046 -0.01975238 0.4672358 -0.8840146 0.01446187 0.467979 -0.8836214 0.01445692 0.346591 -0.9378889 -0.01546001 0.3254471 -0.9455088 0.009859085 0.3265302 -0.9451354 0.009855866 0.1872989 -0.9822534 -0.009873211 0.1764118 -0.98431 0.003570497 0.1799079 -0.983677 0.003580927 0.02308857 -0.9997248 -0.004161238 0.01988899 -0.9998022 0 -0.1416042 -0.9899234 0 -0.1416063 -0.9899231 0 -0.2729892 -0.9620172 0 -0.3022339 -0.9528769 -0.02608358 -0.3950964 -0.9183398 0.02347284 -0.4554238 -0.8899675 0.02339035 -0.3947472 -0.9164277 -0.06584113 -0.53145 -0.8467409 0.02431029 -0.5314046 -0.8467694 0.02431017 -0.5952937 -0.8030204 -0.02799445 -0.6560472 -0.7543182 0.02462095 -0.6555919 -0.7547142 0.02461504 -0.719576 -0.6938768 -0.02730607 -0.7641416 -0.6446239 0.02340197 -0.7638397 -0.6449812 0.02341353 -0.8239095 -0.5661193 -0.02611935 -0.8411798 -0.5407557 0 -0.9062922 -0.4226519 0 -0.9625093 -0.2712489 0 -0.9633344 -0.2682737 -0.004025936 -0.994294 -0.1065942 0.004158258 -0.9930839 -0.1173334 0.004160046 -0.9943746 -0.1054077 -0.01041185 -0.9992097 0.03861749 0.009429514 -0.999268 0.03707653 0.009428977 -0.9981211 0.05926609 -0.01555633 -0.9814915 0.1909711 0.0142979 -0.9815943 0.1904415 0.01430392 -0.9746132 0.2229775 -0.0202564 -0.9401595 0.3402571 0.01803737 -0.9405035 0.339305 0.01804113 -0.9246697 0.3800438 -0.02351051 -0.8497308 0.527217 0 -0.8497318 0.5272154 0 -0.751302 0.6599587 0 -0.675828 0.7370594 0 -0.6320915 0.7745496 -0.02309918 -0.598033 0.8012691 0.018013 -0.5979662 0.8013189 0.01801711 -0.4961879 0.8679835 -0.0200566 -0.467316 0.8839761 0.01420915 -0.467372 0.8839469 0.01419365 -0.3466196 0.9378769 -0.01555669 -0.3255863 0.9454637 0.009598255 -0.3260852 0.9452916 0.009607732 -0.1874697 0.982218 -0.01014894 -0.1762552 0.9843376 0.003692865 -0.1755826 0.9844579 0.003682017 -0.02326053 0.9997219 -0.003915131 -0.0202586 0.9997948 0 0.1415847 0.9899262 0 0.1415851 0.9899261 0 0.2734304 0.9618919 0 0.3025545 0.9527783 -0.02596944 0.3950264 0.9183725 0.02337253 0.4552244 0.8900708 0.02334129 0.3943217 0.9165852 -0.06619721 0.5315873 0.8466547 0.02430939 0.5317991 0.8465218 0.02430391 0.5954349 0.8029218 -0.02781957 0.6555716 0.754743 0.02427029 0.6561652 0.7542268 0.02427262 0.7196617 0.69379 -0.02724826 0.764006 0.6447923 0.0231927 0.7638961 0.6449224 0.02318978 0.8239526 0.5660431 -0.02640724 0.8414096 0.5403979 0 0.9061264 0.4230071 0 0.9626262 0.2708339 0 0.9634459 0.2678734 -0.004006743 0.992946 0.1185143 0.003560185 0.992946 0.1185143 0.003560185 0.992946 0.1185143 0.003560185 0.9930842 0.1173505 0.003576874 0.9943286 0.1058353 -0.01047211 0.9992097 -0.03861749 0.009428918 0.999268 -0.03707629 0.009429454 0.9981211 -0.0592662 -0.01555705 0.9814739 -0.1910611 0.01430773 0.981489 -0.1909838 0.0143097 0.9746278 -0.2229659 -0.01967334 0.9407558 -0.3386047 0.01804178 0.9405035 -0.3393051 0.01803582 0.9246645 -0.3800566 -0.02351033 0.849513 -0.5275678 0 0.8495135 -0.5275669 0 0.7513596 -0.659893 0 0.7513604 -0.6598921 0 0.6763941 -0.73654 0 0.6323614 -0.7743244 -0.02325493 0.5978032 -0.8014306 0.01845556 0.5981085 -0.8012025 0.01845866 1.5788e-6 0 1 -2.87845e-6 0 1 -1.12424e-6 0 1 0.9352239 -0.3540571 0 0.9352238 -0.3540571 0 0.9352238 -0.3540571 0 -0.5563641 -0.8309386 0 0.1520037 0.98838 0 -0.6947409 0.7192601 0 0.112044 -0.9937033 0 0.6519717 -0.7582433 0 0.9225713 -0.3858267 0 0.9148666 -0.4037563 0 0.8031383 -0.5957926 0 0.6369829 -0.770878 0 0.7038658 -0.710333 0 -0.09770578 -0.9948651 -0.02640312 -0.1440283 -0.9895736 0 0.03502875 -0.9993863 0 -0.2296348 -0.9732769 0 -0.3199189 -0.9473668 0.01216953 -0.2778896 -0.9606129 -5.39718e-4 -0.2295307 -0.9733015 0 -0.1866596 -0.9824247 0 -0.186658 -0.982425 0 -0.8387038 -0.5439576 -0.02619814 -0.8632421 -0.5047903 0 -0.7595788 -0.6504154 0 -0.8171345 -0.573891 0.05422449 -0.8171347 -0.5738909 0.05422317 -0.8171346 -0.573891 0.05422449 -0.7578575 -0.6524202 0 -0.9136396 -0.4065252 0 -0.9950199 -0.09967768 0 -0.9950198 -0.09967797 0 -0.9950199 -0.09967732 0 -0.9905509 -0.1371456 0 -0.9389346 0.344096 0 -0.9481545 0.3167268 -0.02621614 -0.9037389 0.42614 0.04075247 -0.8890846 0.4577431 0 -0.7476719 0.6640679 -8.33603e-4 -0.7466987 0.6651625 0 -0.852533 0.5226734 0 -0.8532541 0.5214949 -7.83645e-4 -0.8892729 0.4573771 0 -0.8892729 0.4573771 0 -0.889273 0.4573771 0 -0.9165164 0.3999972 0 -0.9165146 0.4000012 0 -0.6489029 0.7608713 0 -0.6946949 0.7193046 0 -0.648896 0.7608773 0 -0.6707453 0.7416386 0.008549332 -0.57817 0.8158085 -0.01326972 -0.6015964 0.7988002 0 -0.2007001 0.9796528 0 -0.06728327 0.9972506 0.03105509 -0.1229619 0.9924115 0 0.05483531 0.9984954 0 0.05296742 0.9985958 -0.001062572 0.1899429 0.9817951 0 0.404656 0.9144691 0 0.1520755 0.9883689 0 0.1899413 0.9817956 0 0.2320731 0.9726155 -0.01269572 0.2770665 0.9608508 0 0.3112179 0.9503386 0 0.4020141 0.9156323 0.001519143 0.4046297 0.9144807 -4.82633e-5 0.786249 0.6179098 0 0.8138336 0.5810973 -9.40163e-4 0.8385486 0.5442903 0.02417922 0.8856295 0.4643925 0 0.966514 0.2565424 0.006052553 0.9632781 0.2685059 0 0.9241878 0.3819383 0 0.9050474 0.4251152 -0.01289588 0.8856504 0.4643526 0 0.8619194 0.5070455 0 0.8619193 0.5070455 0 0.8619194 0.5070455 0 0.8621706 0.506618 0 -0.9389299 0.3441085 0 -0.9821178 0.1882676 0 -0.9821078 0.1883198 -8.89442e-7 -0.9994543 -0.03303581 0 -0.9994547 -0.03302109 0 -0.9950345 -0.09953147 0 -0.9950345 -0.09953147 0 -0.9950345 -0.09953147 0 -0.9905462 -0.1371791 -3.92732e-4 -0.9852825 -0.1705485 0.01147371 -0.9742656 -0.2254033 0 -0.9402076 -0.3406022 0 -0.9397479 -0.3418676 -7.36945e-4 -0.9138382 -0.4060788 0 -0.8840945 -0.4673081 0 -0.8841131 -0.4672732 0 -0.9821089 0.1883141 0 -0.999962 0.008722007 0 -0.99839 0.05644023 -0.005661487 -0.9998761 0.009967446 -0.01218801 -0.9993718 0.03072834 -0.01765793 -0.7577375 -0.6525595 -7.04317e-5 -0.7578998 -0.6523711 0 -0.6665527 -0.745458 0 -0.631113 -0.7755975 -0.01204556 -0.362609 -0.9319414 0 -0.3626039 -0.9319434 0 -0.4845488 -0.8747642 0 -0.4810627 -0.8766863 -1.34183e-4 -0.4823842 -0.8759593 -8.83985e-4 -0.5566915 -0.8307193 0 -0.5971113 -0.8021584 0 -0.5971276 -0.8021464 0 0.2550853 -0.9669186 0 0.3840474 -0.923313 -9.21909e-4 0.3855443 -0.9226891 -6.96172e-4 0.02257198 -0.9997203 0.007069408 0.1120516 -0.9937024 0 0.1671948 -0.9859239 0 0.2129898 -0.9769797 -0.01208359 0.2550829 -0.9669193 0 0.2991247 -0.9542141 0 0.2986793 -0.9543536 0 0.2986793 -0.9543536 0 0.2986793 -0.9543536 0 0.6061819 -0.7953261 0 0.7171126 -0.696918 -0.007414937 0.6565926 -0.7542408 0.002662241 0.6369739 -0.7708854 0 0.6061831 -0.7953253 0 0.5427516 -0.8398929 -7.97475e-4 0.5413572 -0.8407928 -2.28488e-4 0.5424223 -0.8401061 0 0.3838864 -0.9233803 0 0.9617088 -0.2740733 -1.91296e-4 0.9611953 -0.2758676 -8.32871e-4 0.9353852 -0.3536307 0 0.922569 -0.3858324 0 0.9123784 -0.4093392 0.002653121 0.8843038 -0.4668845 -0.005088567 0.8754743 -0.4832648 0 0.8031311 -0.5958023 0 0.9997014 -0.02443861 0 0.9833695 0.1816161 0 0.983364 0.1816465 0 0.9967881 0.08008456 0 0.9916245 0.126672 -0.02520215 0.9614173 -0.2750943 0 0.9950702 -0.09917408 0 0.9948771 -0.1010891 -7.48956e-4 0.9948983 -0.1008803 -7.80155e-4 0.9996845 -0.02512073 0 0.9996845 -0.02512073 0 0.9996845 -0.02512073 0 0.9993262 0.03670579 0 0.9993261 0.0367065 0 0.6278033 0.7783721 0 0.6278033 0.7783721 0 0.6278033 0.7783721 0 0.5195635 0.8540601 -0.02520585 0.5592067 0.8290283 0 0.4044345 0.9145671 0 0.7862628 0.6178922 0 0.6993355 0.7147936 0 0.6992872 0.714841 3.62643e-6 0.6978948 0.7161998 -9.55884e-4 0.6277565 0.7784098 0 0.5946894 0.8039556 0 0.5947099 0.8039405 0 -0.2982174 0.9544292 -0.01146292 -0.2996727 0.9539676 -0.01192224 -0.3437194 0.9390569 -0.005398035 -0.1551302 0.9878941 0 -0.156531 0.9876731 -4.56133e-4 -0.2008153 0.9796291 0 -0.2586955 0.965959 0 -0.2586885 0.9659609 0 -0.3006253 0.9537423 0 -0.4651578 0.8852278 0 -0.465242 0.8851836 3.82403e-5 -0.4655991 0.8849958 0 -0.6017096 0.7987149 0 -0.2561852 0.9666277 -3.72795e-4 -0.2564429 0.9665594 0 -0.2564321 0.9665623 0 -0.7513039 0.6599565 0 -0.8497299 0.5272184 0 -0.8497358 0.5272089 0 -0.9748162 0.2230102 0 -0.9748134 0.2230222 0 -0.9982437 0.05924153 0 -0.994429 -0.1054084 0 -0.9633457 -0.2682636 0 -0.9633424 -0.2682753 0 -0.9062947 -0.4226465 0 -0.9062948 -0.4226464 0 -0.8241883 -0.566316 0 -0.8241944 -0.566307 0 -0.7198334 -0.694147 0 -0.7198402 -0.6941399 0 -0.5955264 -0.8033358 0 -0.5955328 -0.803331 0 -0.455559 -0.8902056 0 -0.4555594 -0.8902055 0 -0.3023346 -0.953202 0 -0.302342 -0.9531995 0 -0.1416062 -0.9899231 0 -0.1416044 -0.9899234 0 0.02308899 -0.9997335 0 0.1873114 -0.9823006 0 0.346632 -0.9380013 0 0.3466361 -0.9379997 0 0.4961857 -0.8682165 0 0.496186 -0.8682163 0 0.6325201 -0.774544 0 0.6325333 -0.7745333 0 0.7513616 -0.6598908 0 0.751362 -0.6598904 0 0.8495086 -0.5275748 0 0.8495146 -0.5275653 0 0.9748134 -0.2230225 0 0.9748162 -0.22301 0 0.9982429 -0.0592544 0 0.9943829 0.1058427 0 0.9634555 0.2678688 0 0.9634555 0.2678685 0 0.9061263 0.4230073 0 0.9061264 0.4230072 0 0.8242429 0.5662364 0 0.8242311 0.5662536 0 0.7199342 0.6940424 0 0.719928 0.6940488 0 0.5956645 0.8032335 0 0.5956712 0.8032284 0 0.4553481 0.8903136 0 0.4553536 0.8903108 0 0.3026537 0.9531006 0 0.3026577 0.9530994 0 0.141586 0.9899259 0 0.1415841 0.9899263 0 -0.02326095 0.9997295 0 -0.1874781 0.9822688 0 -0.1874805 0.9822683 0 -0.3466577 0.9379917 0 -0.3466619 0.9379903 0 -0.4962859 0.8681591 0 -0.4962862 0.8681589 0 -0.6322587 0.7747575 0 -0.6322589 0.7747572 0 -0.7513037 0.6599566 0 0.8507159 -0.5256258 0 0.7499266 -0.661521 0 0.7499203 -0.6615283 0 0.6271427 -0.7789044 0 0.4865433 -0.8736565 0 0.4865378 -0.8736596 0 0.3319018 -0.943314 0 0.167689 -0.98584 0 0.1676891 -0.98584 0 -0.001294434 -0.9999992 0 -0.001294434 -0.9999992 0 -0.1703245 -0.9853881 0 -0.1703225 -0.9853885 0 -0.3344064 -0.942429 0 -0.3344066 -0.9424289 0 -0.4888802 -0.872351 0 -0.4888806 -0.8723507 0 -0.629266 -0.77719 0 -0.6292601 -0.7771949 0 -0.7515476 -0.659679 0 -0.7515478 -0.6596788 0 -0.8522852 -0.5230775 0 -0.8522854 -0.5230771 0 -0.928355 -0.3716948 0 -0.9778273 -0.2094131 0 -0.97783 -0.2094005 0 -0.9991554 -0.04109394 0 -0.9991554 -0.04109394 0 -0.9917473 0.1282079 0 -0.9917457 0.1282209 0 -0.9557134 0.2942994 0 -0.9557096 0.2943112 0 -0.8924514 0.4511437 0 -0.8924567 0.4511331 0 -0.8031005 0.5958436 0 -0.8030942 0.5958522 0 -0.6910686 0.7227892 0 -0.6910752 0.7227829 0 -0.5587186 0.8293573 0 -0.5587128 0.8293613 0 -0.4109361 0.9116643 0 -0.4109412 0.9116619 0 -0.2505128 0.9681134 0 -0.250513 0.9681133 0 -0.08352279 0.9965059 0 -0.08352392 0.9965058 0 0.08622199 0.996276 0 0.08622086 0.9962761 0 0.2532408 0.9674032 0 0.253241 0.9674032 0 0.413133 0.9106707 0 0.4131233 0.9106752 0 0.5610814 0.8277606 0 0.5610756 0.8277646 0 0.6926733 0.7212514 0 0.6926672 0.7212574 0 0.8050066 0.593266 0 0.805013 0.5932574 0 0.8934412 0.4491803 0 0.8934412 0.4491801 0 0.956505 0.2917159 0 0.9565014 0.2917279 0 0.9920914 0.1255182 0 0.9920897 0.125531 0 0.9990413 -0.04377835 0 0.9990419 -0.04376512 0 0.9772393 -0.2121403 0 0.9772366 -0.2121527 0 0.9274513 -0.3739442 0 0.927456 -0.3739325 0 0.8507277 -0.5256068 0 4.56483e-6 0 -1 -4.53959e-6 0 -1 -2.3274e-6 0 -1 -1.1836e-6 0 -1 -5.96944e-7 0 -1 9.47757e-7 0 -1 -2.45932e-6 0 -1 1.6098e-6 0 -1 -2.12737e-6 0 -1 2.10672e-6 0 -1 -5.08606e-6 0 -1 -5.14806e-6 0 -1 -4.04698e-6 0 -1 4.00503e-6 0 -1 -3.91733e-6 0 -1 3.82772e-6 0 -1 5.82751e-6 0 -1 -2.84095e-6 0 -1 -5.43677e-7 0 -1 5.43488e-7 0 -1 2.72118e-7 0 -1 -1.20913e-6 0 -1 1.09199e-6 0 -1 -4.52829e-7 0 -1 2.19838e-6 0 -1 -4.68551e-6 0 -1 4.66156e-6 0 -1 -0.2589547 0.4831879 -0.8363444 0.2589656 0.4831928 -0.8363382 0.2589251 0.4831791 -0.8363587 0.7071309 0.3537189 -0.6122491 0.7071416 0.3537071 -0.6122435 0.9659102 0.1294915 -0.2241639 0.9659731 0.1293212 -0.2239909 0.9659087 -0.1294397 0.2242004 0.9658468 -0.1296116 0.2243676 0.7071335 -0.3537148 0.6122483 0.7076274 -0.3532859 0.6119253 0.2587768 -0.4829423 0.8365414 0.2588075 -0.4829621 0.8365204 -0.2588062 -0.4829527 0.8365262 -0.2587779 -0.4829533 0.8365346 -0.7071415 -0.3535186 0.6123526 -0.7076078 -0.3534802 0.6118359 -0.9659157 -0.1294814 0.2241463 -0.9658449 -0.1295706 0.2243994 -0.9659104 0.1294485 -0.224188 -0.9659786 0.1293648 -0.2239424 -0.7071433 0.3537122 -0.6122387 -0.7071187 0.3537213 -0.6122617 -0.2589351 0.4831889 -0.8363499 -0.9848079 0.08681976 -0.1503862 -0.9848076 0.08682876 -0.1503827 0.9848073 -0.08682537 0.150386 0.984808 -0.08681595 0.1503872 0.9990463 0.02182281 -0.03782188 0.9990459 0.02184236 -0.03782117 0.886987 0.2308967 -0.399926 0.8869844 0.2308938 -0.3999335 0.608943 0.3966014 -0.6869468 0.6089418 0.3965904 -0.6869541 0.21654 0.4881184 -0.8454886 0.2154532 0.4885061 -0.8455423 0 0.5002459 -0.8658835 0 0.5002519 -0.86588 1.14148e-5 -0.8660284 -0.4999949 -1.50614e-4 -0.8660181 -0.5000127 -1.1327e-5 -0.866032 -0.4999887 4.08844e-5 -0.8660114 -0.5000245 -4.35072e-5 -0.8660311 -0.4999903 -1.89987e-5 -0.8660307 -0.4999909 -8.38035e-6 -0.866014 -0.50002 -2.5536e-5 -0.8660283 -0.4999951 -9.42359e-5 -0.8660189 -0.5000115 -6.55822e-6 -0.8660262 -0.4999988 -1.25465e-5 -0.8660207 -0.5000082 1.42236e-4 -0.8661414 -0.4997991 -3.72612e-5 -0.8659995 -0.500045 6.02029e-5 -0.8660296 -0.4999928 1.21674e-4 -0.8660327 -0.4999876 4.7042e-5 -0.8660284 -0.4999948 0 -0.8660071 -0.5000317 -5.06248e-7 -0.8660247 -0.5000014 -5.59145e-5 -0.8660136 -0.5000205 -2.53037e-5 -0.8660218 -0.5000064 0 -0.8660491 -0.4999591 -2.80697e-5 -0.8660228 -0.5000048 2.2569e-6 -0.8660235 -0.5000034 -6.95756e-7 -0.8660266 -0.4999979 6.82993e-4 -0.8659208 -0.5001807 -4.10798e-5 -0.8659872 -0.5000663 1.1892e-5 -0.8660498 -0.4999579 0 -0.8660312 -0.4999899 -1.37363e-5 -0.8660386 -0.4999772 -1.12503e-4 -0.8661109 -0.4998521 3.83744e-5 -0.8659917 -0.5000584 3.53201e-5 -0.8659827 -0.5000741 -2.45829e-5 -0.8660407 -0.4999735 0 -0.8660115 -0.5000241 1.17603e-4 -0.8660309 -0.4999905 -6.104e-5 -0.8660182 -0.5000126 9.71404e-5 -0.8660187 -0.5000119 4.66698e-5 -0.8660271 -0.4999973 -9.89533e-5 -0.8660262 -0.4999986 1.88179e-4 -0.866 -0.500044 1.62388e-5 -0.8660301 -0.4999919 4.00916e-5 -0.866064 -0.4999333 1.16099e-5 -0.8660338 -0.4999856 2.81419e-5 -0.8660373 -0.4999794 -3.52768e-5 -0.8659671 -0.5001012 0 -0.8660213 -0.5000072 3.73177e-5 -0.8659745 -0.5000884 0.001094937 -0.8649384 -0.5018771 7.93614e-5 -0.8660921 -0.4998846 -1.09731e-4 -0.8662543 -0.4996033 9.33436e-5 -0.8660386 -0.4999773 3.04161e-4 -0.8658614 -0.5002841 1.39586e-4 -0.8660364 -0.4999809 9.92767e-5 -0.86603 -0.4999923 -0.001286327 -0.8663761 -0.4993906 6.34024e-5 -0.8661524 -0.4997801 -2.81172e-4 -0.8658041 -0.5003832 -2.76682e-4 -0.8658065 -0.500379 -0.2587934 0.4829789 -0.8365151 0.2587912 0.4829801 -0.8365151 0.2587927 0.4829739 -0.8365182 0.7071419 0.3535506 -0.6123335 0.7071463 0.3535357 -0.6123372 0.9659144 0.1294327 -0.2241799 0.9659137 0.1294393 -0.2241795 0.9659124 -0.1294409 0.224184 0.9659127 -0.1294343 0.2241861 0.7071097 -0.3535616 0.6123644 0.7071512 -0.3535147 0.6123436 0.2588661 -0.4829397 0.8365153 0.2587912 -0.4829763 0.8365173 -0.2588664 -0.4829674 0.836499 -0.2587937 -0.4829472 0.8365333 -0.7071095 -0.3535436 0.612375 -0.7071506 -0.3535357 0.6123322 -0.9659143 -0.1294345 0.2241796 -0.9659143 -0.1294344 0.2241794 -0.9659155 0.1294329 -0.224175 -0.9659147 0.1294394 -0.2241746 -0.7071444 0.3535416 -0.6123358 -0.7071429 0.3535476 -0.6123342 -0.2587915 0.4829804 -0.8365148 3.6734e-5 0.86601 0.5000268 -4.35839e-6 0.8660289 0.4999942 9.93977e-6 0.8660131 0.5000215 -8.69702e-6 0.8660275 0.4999966 -8.15455e-5 0.8660227 0.5000048 4.44054e-5 0.866025 0.5000008 -8.9965e-4 0.8653136 0.5012301 -1.02501e-4 0.8661172 0.499841 0 0.8662373 0.4996331 -1.43009e-5 0.8660366 0.4999806 -1.39636e-5 0.8660365 0.4999807 -1.50416e-7 0.8660282 0.4999952 -1.16637e-4 0.8660321 0.4999886 -4.24996e-5 0.8660317 0.4999891 4.57861e-5 0.8660281 0.4999954 5.08944e-5 0.8660196 0.50001 -1.55815e-6 0.8660339 0.4999853 -1.32967e-5 0.8660249 0.5000009 -2.81541e-5 0.8660555 0.4999479 -1.69658e-5 0.8660336 0.4999859 -1.00024e-5 0.8660356 0.4999824 2.10578e-5 0.866003 0.5000391 4.00912e-5 0.8660154 0.5000173 -4.71728e-5 0.8659949 0.5000529 1.28135e-5 0.8660522 0.4999538 0 0.866029 0.4999938 -1.10931e-5 0.8660641 0.4999331 3.57546e-5 0.8659859 0.5000686 -3.74504e-5 0.866037 0.4999799 -4.73915e-5 0.8659923 0.5000574 7.40441e-5 0.8660777 0.4999095 2.33363e-5 0.8660377 0.4999786 -9.99692e-5 0.8659614 0.500111 5.58654e-6 0.8660326 0.4999877 -1.84335e-5 0.8660248 0.5000011 9.61244e-5 0.8660261 0.4999988 -2.10043e-5 0.8660162 0.500016 -4.21889e-5 0.8660334 0.4999864 -9.55628e-5 0.8660417 0.4999717 4.73975e-5 0.8660244 0.5000019 1.01107e-4 0.866099 0.4998728 8.11187e-4 0.8652896 0.5012717 -0.001207709 0.8670801 0.4981675 -8.63882e-4 0.8667789 0.498692 2.81172e-4 0.8658041 0.5003832 -4.16102e-5 0.8660325 0.4999879 -4.62294e-5 0.8660254 0.5000002 3.54167e-5 0.8660255 0.5 -0.001081287 0.8650148 0.5017452 -3.10244e-4 0.8658614 0.5002841 7.58558e-4 0.8667809 0.4986885 2.26301e-4 0.8661831 0.4997268 2.46964e-4 0.866197 0.4997027 7.29982e-5 0.8660143 0.5000195 -1.50083e-4 0.8660423 0.4999709 6.66998e-4 0.865055 0.5016769 -1.54655e-4 0.8663028 0.4995194 8.00216e-5 0.8660166 0.5000152 -0.2587553 0.482984 -0.8365239 0.2587524 0.4829797 -0.8365272 0.258757 0.4829809 -0.8365253 0.7071248 0.3535485 -0.6123545 0.707121 0.3535571 -0.612354 0.9659156 0.1294342 -0.2241741 0.9659167 0.1294276 -0.2241728 0.9659135 -0.1294343 0.2241827 0.9659163 -0.129429 0.2241734 0.7071071 -0.3535512 0.6123734 0.7071262 -0.3535316 0.6123626 0.2588676 -0.4829373 0.8365162 0.2587881 -0.4829788 0.8365167 -0.2588673 -0.482969 0.836498 -0.2587913 -0.4829526 0.8365309 -0.7071084 -0.3535442 0.612376 -0.7071233 -0.353542 0.61236 -0.9659149 -0.1294291 0.2241802 -0.9659182 -0.1294279 0.2241663 -0.965918 0.1294277 -0.2241678 -0.9659178 0.1294278 -0.224168 -0.7071231 0.3535494 -0.612356 -0.7071227 0.3535562 -0.6123526 -0.2587559 0.4829797 -0.8365262 0 0.1301818 0.9914902 0 -0.3831374 0.9236914 0 -0.3831335 0.923693 0 -0.7935547 0.608499 0 -0.9915039 0.1300771 0 -0.9236952 -0.3831284 0 -0.9236913 -0.3831377 0 -0.6085823 -0.7934907 0 -0.6085771 -0.7934948 0 -0.1301219 -0.9914981 0 -0.1301205 -0.9914982 0 0.3831374 -0.9236914 0 0.3831335 -0.923693 0 0.7935298 -0.6085314 0 0.991504 -0.1300765 0 0.9236952 0.3831284 0 0.9236913 0.3831377 0 0.6085823 0.7934907 0 0.6085823 0.7934908 -0.627451 0.1595387 0.7621369 -0.4599846 0.6294215 0.626293 -0.4600039 0.6293361 0.6263645 -0.1684635 0.9316555 0.3219289 -0.1684645 0.9316583 0.32192 0.1687306 0.9832059 -0.06954216 0.1684525 0.9833039 -0.06882792 0.4599952 0.7705197 -0.4412525 0.4601348 0.7701513 -0.4417499 0.6274107 0.3521245 -0.6945245 0.6273966 0.3520348 -0.6945827 0.6274483 -0.1595206 -0.7621431 0.6274374 -0.1595471 -0.7621464 0.4597675 -0.629669 -0.6262035 0.460085 -0.6293322 -0.6263089 0.1685541 -0.931623 -0.3219755 0.168452 -0.9316604 -0.3219205 -0.1682584 -0.983327 0.0689736 -0.1688407 -0.9832022 0.0693289 -0.4600824 -0.7703388 0.4414774 -0.4599695 -0.7704424 0.4414142 -0.627399 -0.3522757 0.6944583 -0.6275243 -0.352036 0.6944667 -0.6274936 0.1600028 0.7620047 -0.5047923 0.1481953 0.8504251 -0.3701031 0.6208078 0.6911017 -0.3701057 0.620724 0.6911754 -0.1355052 0.9285182 0.3456768 -0.135492 0.9285361 0.3456336 0.1354144 0.9864488 -0.09263837 0.1354337 0.9864373 -0.09273248 0.3701508 0.7787172 -0.5065452 0.3701213 0.7789117 -0.5062677 0.5048386 0.3637152 -0.7828469 0.5048223 0.3635922 -0.7829145 0.5048434 -0.147906 -0.8504453 0.5048559 -0.1478828 -0.8504418 0.3700875 -0.6207957 -0.6911209 0.3699953 -0.6209176 -0.6910607 0.1355081 -0.9285253 -0.3456567 0.1354836 -0.9285389 -0.3456296 -0.13573 -0.9863542 0.09318089 -0.1352914 -0.9864495 0.09280908 -0.3699004 -0.7790141 0.5062716 -0.3701534 -0.7787724 0.5064583 -0.5048041 -0.363716 0.7828688 -0.5047156 -0.3638973 0.7828416 -0.5047435 0.1478914 0.850507 -0.3696899 0.1389343 0.9187092 -0.2709687 0.614143 0.7412182 -0.2709878 0.6143506 0.7410392 -0.09923845 0.9261149 0.3639546 -0.09924393 0.926088 0.3640216 0.09924983 0.9888506 -0.1110143 0.0992878 0.9887856 -0.1115568 0.2709485 0.7854956 -0.5564023 0.2709522 0.7856396 -0.5561972 0.3697087 0.3726463 -0.8511465 0.3697016 0.3726588 -0.8511441 0.3697514 -0.138919 -0.9186868 0.3697042 -0.1390224 -0.9186902 0.2710281 -0.6142979 -0.7410681 0.2708845 -0.6144829 -0.7409673 0.0991699 -0.9261097 -0.3639866 0.09926855 -0.9260607 -0.3640843 -0.09924602 -0.9888527 0.1109983 -0.09914004 -0.9888771 0.1108763 -0.271081 -0.7853839 0.5564955 -0.2709414 -0.785544 0.5563375 -0.3696355 -0.3728615 0.851084 -0.369726 -0.3726581 0.8511338 -0.3697362 0.1391507 0.9186578 -0.2255364 0.1329003 0.9651275 -0.1653604 0.6098729 0.7750555 -0.1653878 0.6100103 0.7749416 -0.06069892 0.924439 0.3764682 -0.06064939 0.9242493 0.3769415 0.0606746 0.9904289 -0.1239728 0.06066393 0.99041 -0.1241292 0.1653267 0.7901007 -0.5902611 0.1653624 0.7902838 -0.5900059 0.2255746 0.3787991 -0.8975675 0.2255905 0.3788572 -0.897539 0.2255164 -0.1329086 -0.965131 0.2255556 -0.1328171 -0.9651344 0.1653307 -0.60996 -0.7749934 0.1653048 -0.6100172 -0.7749539 0.06058627 -0.9244152 -0.3765447 0.06085294 -0.924233 -0.3769488 -0.06032061 -0.9905226 0.1233955 -0.06073975 -0.9904129 0.1240684 -0.1654121 -0.7900432 0.5903139 -0.1654726 -0.7899651 0.5904016 -0.2255996 -0.3788042 0.8975591 -0.2255833 -0.3788633 0.8975383 -0.2255237 0.1328368 0.9651392 -0.07580572 0.1298065 0.9886374 -0.05557769 0.607722 0.7922027 -0.05554509 0.6076459 0.7922635 -0.02037703 0.9234074 0.38328 -0.02044177 0.9234969 0.383061 0.0203126 0.9912478 -0.1304425 0.02040565 0.991297 -0.1300534 0.05558371 0.7925485 -0.6072704 0.05548334 0.7923099 -0.607591 0.07575708 0.3819626 -0.9210675 0.0757777 0.3820292 -0.9210383 0.07579916 -0.1297014 -0.9886516 0.07578331 -0.1297447 -0.9886472 0.0554949 -0.6077155 -0.7922136 0.05552423 -0.6076399 -0.7922694 0.02034795 -0.9234065 -0.3832838 0.02024167 -0.9235005 -0.3830629 -0.02052116 -0.9912472 0.1304152 -0.02037417 -0.991298 0.1300516 -0.05558598 -0.7922439 0.6076676 -0.05552315 -0.7923347 0.6075549 -0.07576423 -0.3819558 0.9210698 -0.0757389 -0.3820336 0.9210397 -0.07580006 0.1297854 0.9886406 0.7072209 -0.09224015 0.7009497 0.7073113 -0.09255808 0.7008165 0.7071351 -0.09258317 0.700991 0.7069558 -0.09239196 0.701197 0.7068313 -0.09247159 0.701312 0.7072724 -0.09253638 0.7008587 0.7070947 -0.0929625 0.7009816 0.7072268 -0.09287279 0.7008602 0.7072293 -0.09203511 0.7009681 0.7071782 -0.09215754 0.7010036 0.7071642 -0.09207743 0.7010283 0.7070952 -0.0928632 0.7009942 0.7071114 -0.09285849 0.7009785 0.7070298 -0.09262627 0.7010915 0.7071341 -0.0925976 0.7009901 0.7073622 -0.09281587 0.7007311 0.7076315 -0.09255528 0.7004935 0.7068057 -0.09247362 0.7013376 0.7066646 -0.09280341 0.7014362 0.7071761 -0.09243512 0.7009691 0.7071799 -0.09218454 0.7009984 0.7068165 -0.09282851 0.7012798 0.7070055 -0.09329938 0.7010268 0.7071276 -0.09219056 0.7010502 0.6273905 0.352293 -0.6944572 0.459854 0.7705332 -0.4413765 0.4598764 0.7704668 -0.4414689 0.1685402 0.9832623 -0.06920683 0.1686624 0.9832246 -0.06944507 -0.168502 0.9316402 0.3219532 -0.1687374 0.9314402 0.3224078 -0.4601536 0.6290143 0.6265778 -0.4599736 0.6294789 0.6262433 -0.6274212 0.1600798 0.7620481 -0.6274188 0.1599528 0.7620767 -0.6274401 -0.3522322 0.6944432 -0.6274154 -0.3522893 0.6944366 -0.4600566 -0.7702491 0.4416608 -0.4598613 -0.7704584 0.4414992 -0.1684641 -0.9832689 0.06929796 -0.1686574 -0.983224 0.0694639 0.1684994 -0.9316335 -0.3219738 0.1689468 -0.9314458 -0.3222821 0.4600321 -0.6293702 -0.6263095 0.4599013 -0.6295194 -0.6262558 0.627387 -0.1600006 -0.7620929 0.6274211 -0.159959 -0.7620734 0.6273815 0.3521741 -0.6945257 0.5048256 0.3638244 -0.7828045 0.3700963 0.7790291 -0.5061051 0.3702137 0.7786189 -0.5066503 0.1356922 0.9863564 -0.09321331 0.1356173 0.9863874 -0.09299367 -0.1358022 0.9283043 0.3461346 -0.1358818 0.9282088 0.346359 -0.3699595 0.6209394 0.6910602 -0.3699048 0.6211199 0.6909273 -0.5048156 0.1482269 0.8504059 -0.5047823 0.1478066 0.8504987 -0.5046909 -0.3639172 0.7828482 -0.5048541 -0.3634322 0.7829684 -0.3699776 -0.7790144 0.5062148 -0.3701535 -0.7787962 0.5064217 -0.1357707 -0.9863515 0.09315091 -0.1356191 -0.9863882 0.09298294 0.1358245 -0.9282991 -0.3461393 0.1353484 -0.9285356 -0.3456915 0.3699035 -0.6209823 -0.6910517 0.3703385 -0.6203737 -0.6913653 0.5048051 -0.1482257 -0.8504123 0.5047827 -0.1482928 -0.8504139 0.5048287 0.3639107 -0.7827625 0.3697112 0.3727501 -0.8511 0.2711415 0.7852327 -0.5566795 0.2711275 0.7853907 -0.5564633 0.09934008 0.9888075 -0.1113169 0.09932136 0.9888237 -0.1111896 -0.0995388 0.9257857 0.3647094 -0.0994094 0.9260677 0.364028 -0.2710382 0.6144812 0.7409124 -0.2710641 0.614188 0.741146 -0.3696967 0.138877 0.9187152 -0.3697119 0.1391056 0.9186745 -0.3697856 -0.3725314 0.8511634 -0.3697278 -0.3727521 0.8510918 -0.2711644 -0.7853562 0.5564942 -0.2708055 -0.7858682 0.5559458 -0.09920537 -0.9888125 0.1113922 -0.09967297 -0.9886898 0.1120623 0.09920626 -0.9261237 -0.363941 0.09928381 -0.9260685 -0.3640602 0.2711945 -0.6137978 -0.7414216 0.2709203 -0.6142539 -0.741144 0.3696739 -0.139231 -0.9186708 0.3697308 -0.1390095 -0.9186815 0.3697144 0.3727803 -0.8510853 0.2255132 0.3787166 -0.8976178 0.165288 0.7898955 -0.5905463 0.1653074 0.7900912 -0.590279 0.06055015 0.990475 -0.1236645 0.06054878 0.9904984 -0.1234784 -0.06054592 0.9244168 0.3765474 -0.06054854 0.9243489 0.3767136 -0.1652985 0.6097227 0.7751868 -0.1653116 0.6099689 0.7749903 -0.2255493 0.1329461 0.9651181 -0.2255295 0.1328325 0.9651383 -0.2254822 -0.3788259 0.8975794 -0.2255223 -0.3787135 0.8976168 -0.1652125 -0.7903622 0.5899429 -0.1653764 -0.790091 0.59026 -0.06084597 -0.990343 0.1245738 -0.06035453 -0.990504 0.1235284 0.06073117 -0.924439 -0.3764631 0.06039649 -0.9247233 -0.3758179 0.1653208 -0.6097635 -0.7751501 0.1654787 -0.6094524 -0.775361 0.2255697 -0.132862 -0.9651249 0.2255704 -0.1328464 -0.9651269 0.2255408 0.3788391 -0.8975592 0.07583689 0.3820818 -0.9210116 0.05563598 0.7924125 -0.6074433 0.05560106 0.7922921 -0.6076034 0.02039229 0.991335 -0.1297653 0.02030718 0.9912593 -0.1303559 -0.0204367 0.9235208 0.3830037 -0.02038812 0.9233794 0.3833472 -0.05554169 0.607752 0.7921822 -0.05555355 0.6078326 0.7921196 -0.07580393 0.1297203 0.9886488 -0.07579153 0.129667 0.9886567 -0.07583671 -0.3817939 0.921131 -0.07578694 -0.3819966 0.921051 -0.0555374 -0.7924186 0.6074441 -0.05556929 -0.7923248 0.6075637 -0.02034783 -0.991333 0.1297879 -0.02051347 -0.9912521 0.1303787 0.0201615 -0.9238707 -0.3821734 0.02054882 -0.9233816 -0.3833331 0.05568099 -0.6072243 -0.7925771 0.05548822 -0.6077842 -0.7921613 0.07579088 -0.1297218 -0.9886497 0.07577627 -0.1297726 -0.9886441 0.07576042 0.3817896 -0.921139 0 0.3831907 -0.9236693 0 -0.1301413 -0.9914956 0 -0.1301434 -0.9914952 0 -0.6087143 -0.7933895 0 -0.9235764 -0.3834146 0 -0.9914616 0.1303994 0 -0.9914637 0.1303833 0 -0.7935485 0.608507 0 -0.7935643 0.6084864 0 -0.3831048 0.9237049 0 -0.3830989 0.9237073 0 0.1300423 0.9915084 0 0.1300464 0.991508 0 0.6087812 0.7933382 0 0.6087654 0.7933503 0 0.9235764 0.3834146 0 0.9235821 0.3834007 0 0.9914659 -0.1303672 0 0.9914616 -0.1303994 0 0.7935218 -0.6085419 -1 7.27527e-6 0 -1 -9.70167e-6 0 -1 7.27823e-6 0 -1 4.85197e-6 0 -1 -1.45444e-5 0 -1 9.70026e-6 0 -1 -9.70327e-6 0 -1 -4.85201e-6 0 -1 -7.27491e-6 0 -1 9.70393e-6 0 -0.2588233 -0.4829784 0.8365062 0.258748 -0.4829815 0.8365276 0.2588227 -0.4829496 0.836523 0.7071955 -0.353497 0.6123026 0.7071515 -0.3535443 0.6123261 0.9659064 -0.1294479 0.2242059 0.9659076 -0.1294465 0.2242015 0.9659178 0.1294217 -0.2241714 0.965916 0.1294362 -0.2241708 0.7071233 0.3535496 -0.6123556 0.7071168 0.3535584 -0.612358 0.2588798 0.4829652 -0.8364962 0.2588839 0.482967 -0.8364939 -0.258881 0.482971 -0.8364925 -0.2588899 0.4829559 -0.8364984 -0.7071233 0.3535496 -0.6123556 -0.7071168 0.3535584 -0.612358 -0.965918 0.1294215 -0.224171 -0.965916 0.1294362 -0.2241708 -0.9659057 -0.1294547 0.2242048 -0.9659091 -0.1294324 0.2242026 -0.7071934 -0.3535201 0.6122916 -0.7071545 -0.353518 0.6123378 -0.2587518 -0.4829515 0.8365437 0.2587503 -0.4829802 0.8365276 0.2588253 -0.4829469 0.8365237 0.7071964 -0.3534938 0.6123034 0.9659082 -0.1294334 0.2242062 0.9659057 -0.1294611 0.224201 0.9659151 0.1294436 -0.2241708 0.9659188 0.1294143 -0.2241714 0.7071224 0.3535528 -0.6123548 0.7071187 0.3535519 -0.6123596 0.2588819 0.4829654 -0.8364955 0.258889 0.4829616 -0.8364955 -0.258879 0.4829709 -0.8364932 -0.258889 0.4829616 -0.8364955 -0.9659175 0.1294251 -0.2241709 -0.9659061 -0.1294511 0.2242049 -0.9659082 -0.1294397 0.2242025 -0.2587495 -0.4829528 0.8365437 0.2589677 0.4831797 -0.836345 0.2589229 0.4831922 -0.8363518 0.7071336 0.3537095 -0.6122514 0.7071394 0.3537146 -0.6122417 0.9659129 0.129496 -0.2241496 0.9659766 0.1293132 -0.223981 0.9659121 -0.129436 0.2241884 0.9658481 -0.1296203 0.2243573 0.7071272 -0.3537223 0.6122514 0.7076296 -0.3532785 0.6119271 0.2587745 -0.4829561 0.836534 0.2588097 -0.482949 0.8365273 -0.258807 -0.4829478 0.8365288 -0.7071462 -0.3535166 0.6123481 -0.7076114 -0.353482 0.6118305 -0.9659116 -0.1295064 0.2241496 -0.9658468 -0.1295452 0.2244063 -0.9659122 0.1294232 -0.2241948 -0.965974 0.1293897 -0.2239477 -0.707148 0.3537104 -0.6122343 -0.7071245 0.3537157 -0.6122583 -0.2589349 0.4831905 -0.8363491 -0.258753 0.4829865 -0.8365232 0.2587543 0.4829799 -0.8365266 0.2587585 0.4829835 -0.8365231 0.965917 0.1294344 -0.2241676 0.9659187 0.1294211 -0.2241682 0.9659138 -0.1294412 0.2241776 0.9659192 -0.1294157 0.224169 0.707108 -0.3535482 0.6123741 0.7071245 -0.3535376 0.6123611 0.2588682 -0.4829452 0.8365113 0.2587904 -0.4829764 0.8365175 -0.2588643 -0.4829635 0.836502 -0.7071092 -0.3535412 0.6123768 -0.9659138 -0.1294289 0.2241851 -0.9659163 -0.1294344 0.2241711 -0.9659163 0.1294275 -0.2241743 -0.9659158 0.1294344 -0.2241726 -0.7071223 0.3535524 -0.6123552 -0.7071244 0.3535503 -0.612354 -0.2587549 0.4829743 -0.8365296 0 0.5000084 -0.8660207 0 0.5000117 -0.8660187 -0.2306654 0.4865685 -0.8426415 -0.2306281 0.4864966 -0.8426932 -0.2304394 0.486548 -0.8427152 -0.2305905 0.4865242 -0.8426876 -0.6428475 0.3829818 -0.6633793 -0.6429141 0.3829721 -0.6633203 -0.9181898 0.1980727 -0.3430667 -0.9181727 0.198093 -0.343101 -0.9848079 0.08681964 -0.1503858 -0.9848077 0.08682167 -0.1503853 0 0.5002455 -0.8658837 0 0.5002515 -0.8658802 0.9990462 0.02183806 -0.03781485 0.9990466 0.02182203 -0.03781354 0.886985 0.2308886 -0.3999352 0.8869816 0.2308982 -0.3999373 0.6089406 0.3965947 -0.6869527 0.2165364 0.4881273 -0.8454844 0.2154518 0.488498 -0.8455473 0.9848074 -0.0868234 0.1503862 0.9848079 -0.08682423 0.1503832 0.9848077 -0.08682692 0.1503829 0.9848078 -0.08681905 0.1503868 -0.9848083 0.0868234 -0.1503803 -0.9848063 0.0868296 -0.1503902 -0.9848063 0.08682864 -0.1503908 0 -0.5000132 0.8660179 -1 -5.51218e-7 0 0 0.8660252 0.5000005 4.34848e-5 0.866032 0.4999888 -1.79667e-5 0.8660389 0.4999768 0 0.8660259 0.4999994 2.23976e-5 0.8660237 0.5000029 6.99726e-5 0.8660046 0.5000361 -2.44969e-5 0.8660299 0.4999923 3.67666e-6 0.8660269 0.4999974 -5.87076e-5 0.8660029 0.5000391 -2.55142e-5 0.8660387 0.4999772 -1.88773e-6 0.8660249 0.5000009 3.15793e-5 0.8660316 0.4999892 -4.99033e-5 0.8660259 0.4999993 0 0.865995 0.5000529 0 0.8660107 0.5000255 0 0.8660228 0.5000046 0 0.8660255 0.5 0 0.8660286 0.4999945 2.99622e-5 0.866018 0.5000128 4.77621e-4 0.8659178 0.5001863 -1.90727e-5 0.8660326 0.4999876 1.05262e-5 0.8660335 0.4999859 1.69691e-5 0.8660433 0.499969 -3.60268e-5 0.8659517 0.5001279 0 0.8660321 0.4999883 1.23806e-4 0.8660269 0.4999975 9.9233e-5 0.8660324 0.499988 1.08404e-4 0.866038 0.4999783 1.70864e-5 0.8660274 0.4999969 -1.08926e-4 0.8660197 0.5000098 6.91378e-5 0.866036 0.4999818 -1.23261e-4 0.8660299 0.4999922 1.77645e-5 0.8660375 0.4999791 -1.23037e-4 0.8659909 0.50006 -6.55765e-5 0.865994 0.5000546 0 0.8660321 0.4999886 1.51404e-4 0.8659707 0.5000949 1.60974e-5 0.8660268 0.4999978 -1.00911e-4 0.866064 0.4999331 0 0.8660339 0.4999852 1.0728e-5 0.8660278 0.4999957 -8.99657e-4 0.865326 0.5012087 -1.025e-4 0.8661016 0.499868 0 0.8662366 0.499634 4.32128e-5 0.8660234 0.5000035 -4.01272e-5 0.8660373 0.4999795 -4.28627e-5 0.8660321 0.4999887 1.01106e-4 0.866101 0.4998691 8.11187e-4 0.8652833 0.5012825 -0.001207709 0.867114 0.4981084 -8.63862e-4 0.8667666 0.4987134 1.47346e-4 0.866038 0.4999783 2.9409e-5 0.8660249 0.5000008 -2.16554e-4 0.8660282 0.4999951 5.57059e-5 0.8660217 0.5000064 -1.44608e-4 0.8660367 0.4999805 6.67008e-4 0.8650504 0.5016845 -1.54657e-4 0.8663072 0.4995115 8.00208e-5 0.8660119 0.5000234 2.26305e-4 0.8661971 0.4997025 7.58567e-4 0.8667797 0.4986907 -3.07201e-4 0.8658724 0.500265 -0.001077711 0.8649974 0.5017753 3.49934e-5 0.8660247 0.5000014 4.72942e-5 0.8660233 0.5000036 -4.49376e-4 0.8660287 0.4999943 1.41362e-4 0.8660282 0.4999952 0 0.866028 0.4999954 0 0.8660252 0.5000004 -3.66139e-5 0.8660429 0.4999699 6.57849e-5 0.8660182 0.5000126 -8.25378e-6 0.8660159 0.5000167 1.09689e-5 0.8660236 0.5000033 -1.04062e-5 0.8660362 0.4999813 -6.5794e-5 0.8660216 0.5000069 4.01468e-5 0.8660086 0.5000291 3.51336e-6 0.8660246 0.5000014 -1.07909e-5 0.8660271 0.499997 -4.7173e-5 0.8659996 0.5000448 0 0.8660327 0.4999877 2.45716e-5 0.8660136 0.5000205 -1.55931e-5 0.8660439 0.4999681 -4.24996e-5 0.866033 0.4999868 4.73973e-5 0.8660256 0.4999997 4.57347e-5 0.8660262 0.4999986 -4.24994e-5 0.8660327 0.4999874 -4.73911e-5 0.8659845 0.500071 7.40439e-5 0.8660816 0.4999026 2.33366e-5 0.8660352 0.4999831 -9.99678e-5 0.8659611 0.5001116 5.58661e-6 0.8660288 0.4999941 -1.2865e-5 0.8660279 0.4999957 6.75005e-5 0.8660098 0.500027 -1.18411e-5 0.866029 0.4999937 -8.30727e-5 0.8660316 0.4999892 7.58316e-5 0.8660059 0.5000338 -5.52991e-5 0.8660347 0.4999842 -9.30459e-5 0.8660554 0.499948 1.56483e-4 0.8660048 0.500036 -1.16637e-4 0.8660327 0.4999877 -4.30431e-5 0.8660051 0.5000351 1.72169e-4 0.8660778 0.4999093 -4.0714e-5 0.8660092 0.5000282 -1.46186e-5 0.8660253 0.5000002 0 0.8660255 0.4999999 0 0.8660212 0.5000073 2.52475e-4 0.8660915 0.4998857 0.258793 0.4829802 -0.8365144 0.2587919 0.4829791 -0.8365154 0.7071436 0.3535447 -0.612335 0.7071429 0.3535476 -0.6123342 0.9659164 0.1294261 -0.2241752 0.9659147 0.1294394 -0.2241746 0.9659143 -0.1294344 0.2241793 0.9659143 -0.1294345 0.2241796 0.2588667 -0.4829357 0.8365173 0.2587918 -0.4829842 0.8365125 -0.2588658 -0.4829714 0.8364971 -0.2587922 -0.4829444 0.8365353 -0.7071104 -0.3535406 0.6123758 -0.7071489 -0.3535416 0.6123307 -0.9659122 -0.129441 0.2241842 -0.9659128 -0.1294342 0.2241859 -0.9659135 0.1294394 -0.2241797 -0.9659137 0.1294393 -0.2241795 -0.7071436 0.3535447 -0.612335 -0.7071446 0.3535416 -0.6123356 -0.2587904 0.4829751 -0.8365182 0.004782617 -0.8630204 -0.5051465 0.004782676 -0.86302 -0.5051472 0.004782676 -0.8630202 -0.5051468 9.65875e-5 -0.8660237 -0.5000031 -1.18074e-4 -0.8660843 -0.4998981 7.28063e-5 -0.8659985 -0.5000467 -5.41822e-6 -0.8660266 -0.4999979 2.31104e-5 -0.8660339 -0.4999853 -1.48832e-5 -0.8660312 -0.4999899 -6.38448e-5 -0.8660069 -0.5000323 -1.18417e-4 -0.865988 -0.5000651 1.27176e-4 -0.866057 -0.4999455 1.74379e-4 -0.8658894 -0.5002357 -1.6018e-4 -0.8661561 -0.4997737 0 -0.8660326 -0.4999878 0 -0.8660383 -0.4999778 0 -0.866043 -0.4999697 0 -0.8659831 -0.5000734 1.17476e-4 -0.8664494 -0.499265 0 -0.8660351 -0.4999832 5.00517e-4 -0.865958 -0.5001168 -1.27423e-5 -0.8660253 -0.5000003 -1.00461e-4 -0.8660358 -0.4999819 -1.10595e-4 -0.8660296 -0.4999928 0 -0.8660232 -0.5000041 0 -0.8662799 -0.4995591 -1.74593e-5 -0.8659799 -0.5000789 -1.72983e-4 -0.8660188 -0.5000116 1.7255e-4 -0.8660464 -0.4999637 -3.99052e-4 -0.8659418 -0.5001446 -1.09098e-4 -0.8660019 -0.5000408 1.37622e-4 -0.8660486 -0.4999599 1.95057e-6 -0.866024 -0.5000025 -3.49341e-5 -0.8660207 -0.500008 1.00784e-4 -0.8659849 -0.5000701 3.35033e-5 -0.8660179 -0.5000131 -1.47228e-4 -0.8660693 -0.4999241 0 -0.8660174 -0.500014 9.25082e-5 -0.8660827 -0.4999008 -3.07215e-5 -0.8660085 -0.5000294 -3.30495e-5 -0.8660041 -0.5000371 6.96736e-5 -0.8661674 -0.4997543 0 -0.8659924 -0.5000573 6.82878e-4 -0.865958 -0.5001162 0 -0.8660264 -0.4999983 0 -0.8660248 -0.5000013 1.96437e-5 -0.8660262 -0.4999986 6.08195e-5 -0.8660105 -0.5000261 3.06204e-5 -0.8660338 -0.4999856 -2.48974e-5 -0.8660308 -0.4999907 9.71405e-5 -0.8660199 -0.5000096 4.667e-5 -0.8660272 -0.4999969 -9.8952e-5 -0.8660281 -0.4999954 -8.10785e-6 -0.8660235 -0.5000035 -6.10299e-6 -0.8660203 -0.500009 9.4912e-5 -0.8660477 -0.4999613 -1.04358e-4 -0.8660363 -0.4999813 0 -0.8660225 -0.5000051 7.84111e-5 -0.8660501 -0.4999574 -4.93291e-5 -0.8660187 -0.5000119 6.104e-5 -0.8660182 -0.5000126 -2.57069e-5 -0.8660157 -0.5000168 9.15608e-6 -0.8660419 -0.4999715 -4.17906e-6 -0.8660258 -0.4999994 -8.77482e-5 -0.8660078 -0.5000306 1.67162e-5 -0.8660383 -0.4999775 0 -0.8660309 -0.4999907 -1.37362e-5 -0.8660385 -0.4999775 -1.12505e-4 -0.8661282 -0.499822 3.8374e-5 -0.8659829 -0.5000737 3.53198e-5 -0.8659844 -0.5000709 -2.45832e-5 -0.8660529 -0.4999526 9.30674e-5 -0.8660182 -0.5000126 -1.28405e-4 -0.866028 -0.4999955 1.23779e-5 -0.8660378 -0.4999787 5.94819e-5 -0.8660269 -0.4999975 -7.70794e-6 -0.8660218 -0.5000065 1.41706e-5 -0.866033 -0.4999869 -2.2597e-5 -0.8660047 -0.500036 -1.34862e-4 -0.8660299 -0.4999924 1.15521e-4 -0.8659943 -0.5000538 -6.10389e-5 -0.8660234 -0.5000036 -2.86599e-5 -0.8660167 -0.5000152 -2.22611e-5 -0.8660424 -0.4999706 0 -0.8660102 -0.5000266 -6.91377e-5 -0.8660343 -0.4999847 -2.24436e-5 -0.8660265 -0.4999982 0 -0.8660271 -0.4999971 -5.00949e-5 -0.866046 -0.4999645 6.54599e-5 -0.866007 -0.500032 4.93933e-5 -0.8660299 -0.4999923 4.33955e-5 -0.8660303 -0.4999915 1.16663e-5 -0.8660236 -0.5000033 -5.05448e-5 -0.8660195 -0.5000101 -2.53411e-5 -0.8660219 -0.5000062 0 -0.8660548 -0.4999491 -2.80697e-5 -0.8660194 -0.5000107 -0.001286447 -0.8663532 -0.4994304 6.34022e-5 -0.8661535 -0.4997781 -2.81173e-4 -0.8658025 -0.500386 -2.7668e-4 -0.8658086 -0.5003752 -3.52765e-5 -0.8659695 -0.500097 0 -0.8660207 -0.5000082 3.73177e-5 -0.8659744 -0.5000886 7.93606e-5 -0.8660981 -0.4998741 -1.09731e-4 -0.8662527 -0.4996063 9.33438e-5 -0.8660316 -0.4999893 3.04159e-4 -0.8658629 -0.5002815 1.36057e-4 -0.8660395 -0.4999756 -0.9659096 0.1294413 -0.2241956 -0.9659098 0.1294388 -0.2241965 -0.707138 0.3535447 -0.6123415 -0.7071451 0.3535448 -0.6123332 -0.2587917 0.4829777 -0.8365162 -0.2587869 0.4829779 -0.8365177 7.82331e-7 0 -1 -2.92119e-6 0 -1 3.9043e-7 0 -1 -7.87948e-7 0 -1 -7.82914e-7 0 -1 -1.17545e-6 0 -1 -2.34577e-6 0 -1 1.171e-6 0 -1 6.25735e-6 0 -1 -7.33155e-7 0 -1 -6.31868e-6 0 -1 3.4886e-6 0 -1 -2.35115e-6 0 -1 -3.20641e-6 0 -1 1.17507e-6 0 -1 1.17317e-6 0 -1 -1.17514e-6 0 -1 1.16833e-6 0 -1 -1.17418e-6 0 -1 -1.17242e-6 0 -1 3.12492e-6 0 -1 -1.17509e-6 0 -1 -2.32749e-6 0 -1 1.17552e-6 0 -1 -1.17221e-6 0 -1 -1.17001e-6 0 -1 -1.17478e-6 0 -1 -1.16644e-6 0 -1 -1.17502e-6 0 -1 4.68467e-6 0 -1 -1.17285e-6 0 -1 -7.34423e-7 0 -1 -1.46121e-7 0 -1 2.64186e-6 0 -1 0.5343608 -0.8452566 0 0.4647474 -0.8854433 0 0.4647262 -0.8854545 0 0.3544158 -0.9350879 0 0.3544151 -0.9350882 0 0.200143 -0.9797668 0 0.200148 -0.9797658 0 -0.1206238 -0.9926983 0 -0.120624 -0.9926984 0 -0.2783072 -0.9604922 0 -0.428579 -0.9035043 0 -0.5679989 -0.8230293 0 -0.6928598 -0.7210724 0 -0.6928606 -0.7210716 0 -0.7993753 -0.6008322 0 -0.7993746 -0.6008329 0 -0.9485246 -0.3167034 0 -0.9870802 -0.1602277 0 -0.9870762 -0.1602519 0 -0.9870761 0.1602522 0 -0.9870801 0.1602275 0 -0.9485248 0.316703 0 -0.7993753 0.6008322 0 -0.7993746 0.6008329 0 -0.6928598 0.7210724 0 -0.6928606 0.7210716 0 -0.568 0.8230286 0 -0.4285784 0.9035046 0 -0.2783072 0.9604922 0 -0.1206238 0.9926983 0 -0.120624 0.9926984 0 0.200148 0.9797658 0 0.200143 0.9797668 0 0.3544158 0.9350879 0 0.3544151 0.9350882 0 0.4999584 0.8660495 0 0.4999475 0.8660557 0 0.6325898 0.774487 0 0.7483958 0.6632525 0 0.7484207 0.6632243 0 0.8452619 0.5343523 0 0.8452615 0.534353 0 0.9199631 0.3920052 0 0.9199628 0.3920057 0 0.9709564 0.2392566 0 0.9967508 -0.08054751 0 0.970957 -0.239254 0 0.9709627 -0.2392311 0 0.9199602 -0.392012 0 0.91996 -0.3920125 0 0.8452619 -0.5343523 0 0.8452615 -0.534353 0 0.7484207 -0.6632243 0 0.7483958 -0.6632525 0 0.6325898 -0.774487 0 -0.4906942 0.5106728 -0.7059976 -0.490669 0.5107461 -0.7059621 -0.5661773 0.425553 -0.7059378 -0.5661763 0.4255463 -0.7059425 -0.6271263 0.3291599 -0.7059507 -0.6271351 0.3291168 -0.705963 -0.6717846 0.2242974 -0.7059717 -0.6717402 0.2241094 -0.7060737 -0.6990053 0.1134831 -0.7060547 -0.69907 0.1136129 -0.7059698 -0.6990909 -0.1134969 -0.7059677 -0.6989744 -0.1135985 -0.7060668 -0.6716866 -0.2242646 -0.7060754 -0.6718482 -0.2241442 -0.7059599 -0.627113 -0.329153 -0.7059658 -0.627148 -0.3291295 -0.7059456 -0.5661784 -0.4255443 -0.705942 -0.5661803 -0.4255558 -0.7059335 -0.4907157 -0.5107094 -0.7059562 -0.4906651 -0.5107234 -0.7059811 -0.4022644 -0.5828658 -0.7060105 -0.4023599 -0.5828751 -0.7059485 -0.3035508 -0.6399239 -0.7059422 -0.303593 -0.6399476 -0.7059025 -0.08543777 -0.7031525 -0.7058873 -0.08535641 -0.7031099 -0.7059397 0.02860313 -0.7076776 -0.7059563 0.02864587 -0.7076351 -0.7059972 0.1417523 -0.693903 -0.705978 0.1416665 -0.6940068 -0.7058933 0.2510368 -0.6623157 -0.7059168 0.251146 -0.6621471 -0.7060361 0.3287053 -0.626317 -0.7068804 0.3285644 -0.6264693 -0.706811 0.3780002 -0.5979418 -0.7068109 0.3782575 -0.5976092 -0.7069544 0.4479495 -0.5484279 -0.7060936 0.4478704 -0.5487769 -0.7058725 0.5301187 -0.469789 -0.7058843 0.5301508 -0.4695655 -0.7060089 0.5986186 -0.3784298 -0.7060075 0.5986328 -0.378544 -0.7059344 0.6515546 -0.277638 -0.7059701 0.6515831 -0.2777088 -0.7059159 0.6877219 -0.1694611 -0.705919 0.6877508 -0.1695178 -0.7058773 0.7060456 -0.05704188 -0.7058655 0.7059635 -0.05689048 -0.7059597 0.7060602 0.05691379 -0.705861 0.68777 0.169462 -0.7058718 0.6877152 0.1695211 -0.7059111 0.6515935 0.277637 -0.7059347 0.6515381 0.2777029 -0.7059598 0.5986733 0.3784633 -0.7059432 0.5985698 0.3785042 -0.706009 0.5300287 0.4697079 -0.7060058 0.5302623 0.4696643 -0.7058594 0.4480832 0.5485789 -0.7058914 0.4477286 0.5486134 -0.7060896 0.3540257 0.6132718 -0.7060903 0.3541301 0.6133069 -0.7060075 0.2510005 0.6622289 -0.7060111 0.251197 0.6622867 -0.705887 0.1417673 0.6939682 -0.7059109 0.1416552 0.6939334 -0.7059676 0.02860903 0.7076441 -0.7059897 0.02864736 0.7076871 -0.705945 -0.08543211 0.7030929 -0.7059475 -0.08554857 0.7029867 -0.7060391 -0.1970996 0.6802089 -0.7060224 -0.1969629 0.6803782 -0.7058975 -0.3035625 0.639962 -0.7059026 -0.3035772 0.6398835 -0.7059674 -0.4022911 0.5829122 -0.7059571 -0.4023349 0.5828294 -0.7060005 -3.52247e-6 0 -1 6.29691e-6 0 -1 -6.25193e-6 0 -1 1.46882e-7 0 -1 2.0447e-6 0 -1 1.17445e-6 0 -1 1.17058e-6 0 -1 -1.17503e-6 0 -1 3.1411e-6 0 -1 -6.26002e-6 0 -1 5.25819e-6 0 -1 -5.84123e-6 0 -1 -2.34563e-6 0 -1 1.56708e-6 0 -1 1.16966e-6 0 -1 -1.17361e-6 0 -1 2.34574e-6 0 -1 3.13605e-6 0 -1 6.25383e-6 0 -1 -3.51848e-6 0 -1 2.34234e-6 0 -1 -1.16877e-6 0 -1 -1.46788e-6 0 -1 -1.16471e-6 0 -1 1.17338e-6 0 -1 1.1722e-6 0 -1 -5.85985e-7 0 -1 -0.5343608 -0.8452566 0 -0.4647114 -0.8854623 0 -0.5343381 -0.8452709 0 -0.7484082 -0.6632385 0 -0.8452733 -0.5343343 0 -0.9709564 -0.239257 0 -0.9709623 -0.2392329 0 -0.9709628 0.2392303 0 -0.9709568 0.2392547 0 -0.8452728 0.534335 0 -0.7484082 0.6632385 0 -0.3544075 0.9350911 0 -0.3544235 0.9350851 0 0.4285882 0.9035001 0 0.5680106 0.8230212 0 0.6928472 0.7210844 0 0.692848 -0.7210837 0 0.4285888 -0.9034997 0 -0.3544241 -0.9350848 0 -0.3544068 -0.9350913 0 -0.4647327 -0.885451 0 0.1971592 0.6803359 -0.7058833 0.08543854 0.7031458 -0.7058939 -0.02860367 0.7076642 -0.7059697 -0.02864551 0.7076425 -0.7059898 -0.141665 0.6940144 -0.705886 -0.2510415 0.6623281 -0.7059034 -0.2511382 0.6621416 -0.706044 -0.3540601 0.6133303 -0.7060223 -0.3540977 0.6132328 -0.7060881 -0.5301287 0.4697979 -0.7058709 -0.5301452 0.4695606 -0.7060163 -0.5986217 0.3784184 -0.7060111 -0.6515522 0.2776503 -0.7059675 -0.6515858 0.2776951 -0.7059188 -0.6877235 0.1694481 -0.7059206 -0.6877473 0.1695467 -0.7058736 -0.7060461 0.05702859 -0.7058659 -0.7059659 0.05687576 -0.7059584 -0.7059479 -0.05702149 -0.7059646 -0.7060642 -0.05688428 -0.7058594 -0.6877685 -0.169475 -0.7058703 -0.6515886 -0.2776616 -0.7059294 -0.6515435 -0.2776755 -0.7059656 -0.5985606 -0.3784835 -0.706028 -0.5300254 -0.4697182 -0.7060014 -0.5302604 -0.4696477 -0.7058718 -0.44808 -0.5485882 -0.7058863 -0.4477275 -0.5485972 -0.7061029 -0.3779234 -0.5978307 -0.7069458 -0.3783206 -0.5977564 -0.7067961 -0.3287399 -0.6263552 -0.7068305 -0.3285371 -0.6264185 -0.7068688 -0.2509959 -0.6622301 -0.7060115 -0.14177 -0.6939813 -0.7058975 -0.1416537 -0.6939411 -0.7059603 -0.02864766 -0.7076797 -0.7059524 0.08543294 -0.7030861 -0.7059541 0.08555036 -0.7030014 -0.7060242 0.1970942 -0.6802033 -0.7060294 0.3035652 -0.6399541 -0.7059087 0.3035743 -0.6398923 -0.7059607 0.4906908 -0.5106827 -0.7059927 0.4906727 -0.5107351 -0.7059675 0.5661799 -0.4255341 -0.705947 0.6271254 -0.3291266 -0.705967 0.6717354 -0.224093 -0.7060835 0.6989921 -0.1134809 -0.706068 0.6990725 -0.1136282 -0.7059648 0.6989622 0.1136114 -0.7060768 0.6716906 0.2242393 -0.7060797 0.671846 0.2241584 -0.7059575 0.6271384 0.3291393 -0.7059496 0.5661751 0.4255418 -0.7059462 0.5661779 0.4255391 -0.7059455 0.490719 0.5106995 -0.7059611 0.4906615 0.5107344 -0.7059758 0.3035482 0.6399318 -0.7059361 0.3035959 0.6399388 -0.7059093 -0.8946021 0.02478754 -0.4461758 -0.8945521 0.02489346 -0.4462701 -0.8946939 0.02523207 -0.4459667 -0.8945932 0.02491527 -0.4461866 -0.8945786 0.02489942 -0.4462164 -0.8945891 0.02460694 -0.4462118 -0.8946143 0.02493613 -0.446143 -0.8945958 0.02479994 -0.4461876 -0.8945114 0.02500402 -0.4463456 -0.894594 0.02491784 -0.4461847 -0.8945774 0.02489554 -0.4462191 0.8946157 -0.02478599 -0.4461486 0.894605 -0.02489495 -0.446164 0.8944541 -0.02521711 -0.4464484 0.8945658 -0.0249145 -0.4462412 0.8945995 -0.02489995 -0.4461748 0.8945167 -0.02460497 -0.4463569 0.8946143 -0.02493613 -0.446143 0.8945814 -0.02479726 -0.4462167 0.8946317 -0.02500736 -0.4461042 0.8945804 -0.0249198 -0.4462118 0.8945838 -0.02489799 -0.4462062 0.9984734 0.05480784 0.006867289 0.9953616 0.09620571 0 0.9840863 0.1776913 0 0.9758026 0.2185443 0.006910026 0.9658347 0.2591591 0 0.9414177 0.3372428 0 0.9267284 0.37567 0.006820678 0.9105287 0.4134461 0 0.8729292 0.4878471 0 0.8520171 0.5234693 0.006850183 0.8296916 0.5582221 0 0.7796101 0.6262653 0 0.7535049 0.6574081 0.006712257 0.726242 0.6874392 0 0.668673 0.7435566 0 0.6370927 0.7707564 0.006908714 0.6044086 0.7966745 0 0.5326451 0.8463388 0 0.4996806 0.8661865 0.006356418 0.4661141 0.8847246 0 0.3889784 0.9212469 0 0.3503867 0.93658 0.006873786 0.3112056 0.9503427 0 0.2332969 0.9724056 0 0.1924429 0.9812838 0.006916821 0.151252 0.9884952 0 0.06909066 0.9976104 0 0.02809727 0.9995821 0.006804764 -0.01294249 0.9999163 0 -0.09504908 0.9954726 0 -0.1383675 0.9903546 0.007220327 -0.1813983 0.9834097 0 -0.2551586 0.9668992 0 -0.2983917 0.9544147 0.007424056 -0.3409413 0.9400846 0 -0.4110933 0.9115933 0 -0.450091 0.8929541 0.007147669 -0.4882063 0.8727282 0 -0.5576682 0.830064 0 -0.5922964 0.8056894 0.007039427 -0.6258425 0.7799495 0 -0.6871496 0.726516 0 -0.716188 0.6978747 0.006752312 -0.7440975 0.668071 0 -0.7981087 0.6025136 0 -0.8216404 0.5699673 0.006674826 -0.8439528 0.5364174 0 -0.8858289 0.4640123 0 -0.9045491 0.4263126 0.00696814 -0.9216559 0.3880083 0 -0.9497462 0.313021 0 -0.9620199 0.2728917 0.006928384 -0.9726147 0.2324237 0 -0.9885208 0.1510851 0 -0.9938868 0.1101923 0.006840109 -0.9976097 0.06910061 0 -0.999909 -0.01349312 0 -0.9984734 -0.05480784 0.006867289 -0.9953616 -0.09620571 0 -0.9840863 -0.1776913 0 -0.975801 -0.2185512 0.006918728 -0.9658303 -0.2591754 0 -0.9414251 -0.3372222 0 -0.926733 -0.3756587 0.00682044 -0.9105287 -0.4134461 0 -0.8729292 -0.4878471 0 -0.8520172 -0.5234694 0.006838917 -0.8296916 -0.5582221 0 -0.7795849 -0.6262966 0 -0.7535047 -0.6574082 0.006712257 -0.7262729 -0.6874065 0 -0.668673 -0.7435566 0 -0.6370926 -0.7707563 0.00691998 -0.6044086 -0.7966745 0 -0.5357308 -0.8443888 0 -0.4996786 -0.8661829 0.006964981 -0.4627318 -0.8864984 0 -0.3889784 -0.9212469 0 -0.3503867 -0.9365798 0.006885051 -0.3112056 -0.9503427 0 -0.2332969 -0.9724056 0 -0.1924118 -0.9812899 0.006916821 -0.1511892 -0.988505 0 -0.06915473 -0.9976059 0 -0.02812945 -0.9995812 0.006793498 0.01294249 -0.9999163 0 0.09511291 -0.9954665 0 0.1383677 -0.9903546 0.007220327 0.1813361 -0.9834212 0 0.2552188 -0.9668834 0 0.2983918 -0.9544144 0.007446587 0.3408845 -0.9401052 0 0.4111466 -0.9115692 0 0.4500913 -0.8929539 0.007147669 0.4881566 -0.8727561 0 0.5576682 -0.830064 0 0.5923176 -0.8056743 0.006994247 0.6258814 -0.7799183 0 0.6871158 -0.726548 0 0.7161721 -0.6978908 0.006786286 0.7440975 -0.668071 0 0.7981087 -0.6025136 0 0.8216405 -0.5699673 0.00666356 0.8439528 -0.5364174 0 0.8858289 -0.4640123 0 0.9045549 -0.4263002 0.006973564 0.9216656 -0.3879852 0 0.9497462 -0.313021 0 0.9620174 -0.2729002 0.006928563 0.9726112 -0.2324383 0 0.9885208 -0.1510851 0 0.9938868 -0.1101923 0.006838023 0.9976097 -0.06910061 0 0.999909 0.01349312 0 0.6571268 0.1187816 -0.7443624 0.6575747 0.1171927 -0.7442187 0.6575747 0.1171926 -0.7442187 0.6575741 0.1171926 -0.7442193 0.6452169 0.1723106 -0.7443146 0.6457052 0.1727445 -0.7437904 0.6292685 0.2257279 -0.7436855 0.6292686 0.2257279 -0.7436854 0.6292685 0.225728 -0.7436854 0.6291862 0.2258615 -0.7437146 0.6295183 0.2257401 -0.7434704 0.6086522 0.2772573 -0.7434185 0.6086294 0.2771643 -0.7434718 0.6090013 0.2766695 -0.7433515 0.5839675 0.3262531 -0.743331 0.5839222 0.3259494 -0.7434998 0.5536022 0.3752775 -0.7434322 0.5536023 0.3752776 -0.7434322 0.5536022 0.3752776 -0.7434322 0.5536883 0.3725034 -0.7447621 0.5537742 0.3725199 -0.7446899 0.5211315 0.4168057 -0.7447786 0.5219775 0.4169927 -0.7440811 0.5229384 0.4165476 -0.7436556 0.4846466 0.4600956 -0.7439286 0.4846467 0.4600955 -0.7439286 0.4834815 0.4561795 -0.7470916 0.450225 0.4885424 -0.7474114 0.4457428 0.4982016 -0.7437127 0.4457428 0.4982016 -0.7437127 0.4457428 0.4982015 -0.7437127 0.4443087 0.4979965 -0.7447076 0.4013711 0.5331668 -0.7447379 0.4021498 0.5334185 -0.7441373 0.4034222 0.5334118 -0.7434532 0.3595588 0.5640035 -0.7433825 0.3595588 0.5640034 -0.7433825 0.3595588 0.5640034 -0.7433825 0.3595902 0.5640119 -0.7433609 0.3135611 0.5904767 -0.743651 0.310518 0.593604 -0.7424372 0.3071446 0.5916749 -0.7453745 0.258848 0.6140244 -0.7456353 0.258848 0.6140244 -0.7456352 0.258848 0.6140243 -0.7456352 0.2602254 0.6151741 -0.7442067 0.2602254 0.6151741 -0.7442067 0.2590556 0.614865 -0.7448701 0.20833 0.6340247 -0.7447223 0.208595 0.6324462 -0.7459893 0.208595 0.6324462 -0.7459893 0.208595 0.6324462 -0.7459893 0.1563291 0.6470969 -0.7462083 0.1563292 0.6470971 -0.7462081 0.1563292 0.6470971 -0.7462081 0.1530544 0.6487812 -0.7454242 0.1581358 0.65388 -0.7398879 0.1038805 0.6647072 -0.7398468 0.1038804 0.6647072 -0.7398468 0.1011532 0.6611701 -0.7433856 0.09809315 0.6592051 -0.7455377 0.04525667 0.665045 -0.7454308 0.04426884 0.6668393 -0.7438855 -0.00910443 0.6685476 -0.7436136 -0.008826792 0.6681099 -0.7440103 -0.05897378 0.6652427 -0.7442945 -0.06218558 0.6675573 -0.7419571 -0.06701093 0.6618248 -0.7466576 -0.1174108 0.6548525 -0.7465808 -0.1212291 0.6593778 -0.7419734 -0.1182241 0.6602614 -0.7416725 -0.118224 0.6602614 -0.7416725 -0.1182238 0.6602614 -0.7416725 -0.1728915 0.6478651 -0.7418755 -0.1712214 0.6461942 -0.7437179 -0.227769 0.6282497 -0.7439245 -0.2268011 0.6281605 -0.7442954 -0.2261642 0.6295946 -0.7432768 -0.2756188 0.609503 -0.7433305 -0.2786816 0.6114702 -0.7405679 -0.2773168 0.6127647 -0.74001 -0.3283717 0.5867573 -0.7401945 -0.3251509 0.5846648 -0.7432658 -0.3737221 0.554902 -0.7432466 -0.3747494 0.5547093 -0.7428732 -0.3749374 0.5534945 -0.743684 -0.4167187 0.5228868 -0.7435961 -0.4167187 0.5228868 -0.743596 -0.4167187 0.5228868 -0.743596 -0.4165138 0.5217536 -0.7445062 -0.4174756 0.5193629 -0.7456382 -0.4583035 0.4842182 -0.7453125 -0.4590386 0.4843487 -0.7447751 -0.4972507 0.4453384 -0.7445909 -0.497664 0.4452254 -0.7443823 -0.497664 0.4452254 -0.7443823 -0.4983962 0.4488048 -0.7417382 -0.4983963 0.4488048 -0.7417382 -0.4983963 0.4488048 -0.7417381 -0.533962 0.4056509 -0.7418437 -0.5330684 0.4035828 -0.7436122 -0.5335354 0.398015 -0.7462735 -0.5619702 0.3576801 -0.7458248 -0.5663244 0.3579316 -0.7424027 -0.5926783 0.3116011 -0.7427229 -0.5928041 0.3116269 -0.7426116 -0.5914026 0.3092417 -0.7447232 -0.6151127 0.259601 -0.7444755 -0.6161212 0.2609803 -0.7431581 -0.6154906 0.2579111 -0.7447504 -0.6154906 0.2579112 -0.7447504 -0.6154905 0.2579111 -0.7447505 -0.6342743 0.2082 -0.7445461 -0.6337603 0.2082868 -0.7449595 -0.6478424 0.1598964 -0.7448043 -0.6478434 0.1598967 -0.7448033 -0.6478434 0.1598968 -0.7448033 -0.6499826 0.1548516 -0.7440052 -0.65006 0.1549025 -0.7439269 -0.6606289 0.1010645 -0.7438786 -0.6614473 0.1017702 -0.7430547 -0.6614474 0.1017701 -0.7430547 -0.6614474 0.1017701 -0.7430547 -0.6608118 0.1009545 -0.7437312 -0.6670135 0.04608714 -0.7436189 -0.666711 0.04620015 -0.7438831 -0.6682577 -0.00901103 -0.7438753 -0.668441 -0.009049773 -0.7437102 -0.6655145 -0.06457352 -0.7435864 -0.665306 -0.06406074 -0.7438173 -0.6653899 -0.06391376 -0.7437549 -0.6578025 -0.1193922 -0.7436676 -0.657141 -0.1187796 -0.7443501 -0.6577 -0.1172141 -0.7441046 -0.6577 -0.1172142 -0.7441046 -0.6576998 -0.117214 -0.7441048 -0.6452169 -0.1723106 -0.7443146 -0.6456841 -0.1727486 -0.7438078 -0.6292446 -0.2256507 -0.7437291 -0.6292447 -0.2256507 -0.7437291 -0.6292446 -0.2256507 -0.7437291 -0.6293102 -0.225882 -0.7436035 -0.6295183 -0.2257401 -0.7434704 -0.6087245 -0.2773087 -0.74334 -0.6085416 -0.2771294 -0.7435567 -0.6091997 -0.2766163 -0.7432088 -0.5841262 -0.3263418 -0.7431674 -0.5838062 -0.3258846 -0.7436193 -0.5534324 -0.3751781 -0.7436088 -0.5537433 -0.3725405 -0.7447027 -0.5538829 -0.3725931 -0.7445725 -0.5212168 -0.4168561 -0.7446907 -0.5218873 -0.4169154 -0.7441877 -0.5218873 -0.4169154 -0.7441876 -0.5227759 -0.416428 -0.7438368 -0.4847613 -0.4602215 -0.743776 -0.4835694 -0.4563512 -0.74693 -0.4501039 -0.4883978 -0.7475788 -0.4459459 -0.4983709 -0.7434775 -0.4441515 -0.4978202 -0.7449191 -0.4011579 -0.5328837 -0.7450553 -0.4022375 -0.5335333 -0.7440077 -0.4022375 -0.5335333 -0.7440076 -0.4022375 -0.5335333 -0.7440076 -0.4034222 -0.5334118 -0.7434532 -0.3595004 -0.563961 -0.743443 -0.359495 -0.5638625 -0.7435203 -0.3137459 -0.5904673 -0.7435804 -0.3137459 -0.5904675 -0.7435804 -0.3137459 -0.5904675 -0.7435804 -0.3105592 -0.5936828 -0.742357 -0.3070458 -0.5914846 -0.7455662 -0.2589693 -0.6141665 -0.745476 -0.2601301 -0.6150903 -0.7443094 -0.2591524 -0.6148484 -0.74485 -0.2082243 -0.6338593 -0.7448927 -0.2085755 -0.6323757 -0.7460545 -0.1568651 -0.6469548 -0.7462191 -0.153068 -0.6486037 -0.745576 -0.1581764 -0.6540733 -0.7397084 -0.1038206 -0.664642 -0.7399137 -0.1011276 -0.6610032 -0.7435375 -0.09807145 -0.6590595 -0.7456693 -0.04519748 -0.6648657 -0.7455943 -0.04429596 -0.6671642 -0.7435926 0.009057521 -0.6683594 -0.7437834 0.009057462 -0.6683596 -0.7437832 0.009057462 -0.6683596 -0.7437832 0.00887686 -0.6681067 -0.7440126 0.05897885 -0.6654393 -0.7441183 0.06215488 -0.6676475 -0.7418785 0.06700676 -0.661783 -0.7466949 0.1174108 -0.6548525 -0.7465808 0.1211729 -0.6590718 -0.7422543 0.1188275 -0.6600733 -0.7417435 0.1188272 -0.6600733 -0.7417435 0.1729749 -0.6478555 -0.7418646 0.1712193 -0.6460178 -0.7438716 0.2277299 -0.6284896 -0.7437339 0.2268101 -0.6283406 -0.7441407 0.2268101 -0.6283406 -0.7441407 0.2268101 -0.6283405 -0.7441407 0.2261392 -0.6295251 -0.7433433 0.2756135 -0.609468 -0.7433613 0.2756147 -0.6094675 -0.7433612 0.2756147 -0.6094675 -0.7433612 0.278737 -0.6115919 -0.7404465 0.2773168 -0.6127647 -0.74001 0.3284025 -0.5867507 -0.7401862 0.3251891 -0.5847435 -0.7431872 0.3736237 -0.5547834 -0.7433848 0.3747566 -0.5547075 -0.7428708 0.3748003 -0.5534014 -0.7438223 0.4166904 -0.5228178 -0.7436603 0.4164156 -0.5215563 -0.7446994 0.4175583 -0.5197111 -0.7453493 0.4583484 -0.4842056 -0.7452931 0.4591775 -0.4845128 -0.7445827 0.4973425 -0.4453985 -0.7444936 0.4974766 -0.4450567 -0.7446084 0.4985219 -0.449 -0.7415356 0.533962 -0.4056509 -0.7418437 0.5328018 -0.403331 -0.7439398 0.5335289 -0.3980169 -0.7462772 0.561786 -0.3575918 -0.7460058 0.5663244 -0.3579316 -0.7424027 0.5926403 -0.3117864 -0.7426754 0.5928044 -0.3116256 -0.742612 0.5915039 -0.3092593 -0.7446354 0.6151127 -0.259601 -0.7444755 0.6163259 -0.2610669 -0.7429579 0.6153945 -0.2578783 -0.7448413 0.6342743 -0.2082 -0.7445461 0.6337182 -0.208273 -0.7449991 0.6479063 -0.1599103 -0.7447457 0.647907 -0.1599106 -0.7447451 0.647907 -0.1599105 -0.7447451 0.6498966 -0.1548311 -0.7440845 0.65006 -0.1549025 -0.7439269 0.6606289 -0.1010645 -0.7438786 0.6615199 -0.1017708 -0.74299 0.6611449 -0.1010205 -0.7434261 0.6669583 -0.04608178 -0.7436687 0.6666274 -0.04619377 -0.7439585 0.6683685 0.00901252 -0.7437758 0.6684012 0.009049117 -0.7437459 0.6654899 0.06457114 -0.7436086 0.6653246 0.06405937 -0.7438008 0.6653422 0.06391024 -0.7437979 0.6578229 0.1194049 -0.7436475 0.8742781 -0.06047886 -0.4816432 0.8761392 0.01186162 -0.4819123 0.8761554 0.01184779 -0.4818832 0.8719581 0.08395302 -0.4823286 0.8722196 0.08421427 -0.4818102 0.8622452 0.1558604 -0.4819136 0.8627017 0.1563181 -0.4809476 0.8470763 0.2266167 -0.4807357 0.8465887 0.2259309 -0.481916 0.824755 0.2960603 -0.4817962 0.8249816 0.2966404 -0.481051 0.8249816 0.2966404 -0.4810509 0.8249816 0.2966404 -0.481051 0.7980636 0.3634394 -0.4806311 0.7972465 0.3618653 -0.4831683 0.7643953 0.4266877 -0.4833607 0.7645711 0.4270542 -0.4827585 0.7264958 0.4887935 -0.4829958 0.7264976 0.4887146 -0.4830728 0.6837311 0.546881 -0.4831491 0.6843401 0.5498165 -0.4789368 0.6385802 0.6025806 -0.4786566 0.6385802 0.6025806 -0.4786565 0.6385802 0.6025806 -0.4786565 0.6384027 0.6010618 -0.480798 0.5846804 0.6534788 -0.4807436 0.5846806 0.6550841 -0.4785535 0.5282822 0.7017853 -0.4779282 0.5282822 0.7017853 -0.4779282 0.5282822 0.7017853 -0.4779282 0.5284497 0.6977904 -0.4835592 0.4705306 0.7380408 -0.4836288 0.4705307 0.7380408 -0.4836287 0.4705306 0.7380408 -0.4836287 0.4699502 0.7427049 -0.4770076 0.4073777 0.7787533 -0.4770607 0.407834 0.777095 -0.4793692 0.3409545 0.8085661 -0.4795529 0.3419502 0.8055511 -0.4838983 0.2740659 0.8309397 -0.4841769 0.2737989 0.8317814 -0.4828809 0.2009812 0.8519548 -0.4835077 0.2015427 0.8512722 -0.4844753 0.1350557 0.8641858 -0.484709 0.1333679 0.8669382 -0.4802408 0.0581063 0.8753051 -0.4800676 0.0581063 0.8753051 -0.4800675 0.0581063 0.8753051 -0.4800676 0.0607478 0.8715775 -0.4864797 -0.01154708 0.873592 -0.4865221 -0.01142621 0.8735358 -0.486626 -0.08101963 0.8696044 -0.4870566 -0.08101427 0.8696049 -0.4870566 -0.08101433 0.8696049 -0.4870566 -0.08376228 0.8725546 -0.4812819 -0.1585023 0.8621215 -0.4812729 -0.1585023 0.8621215 -0.4812728 -0.1585023 0.8621216 -0.4812729 -0.1555917 0.859706 -0.486515 -0.2237716 0.8445375 -0.4865005 -0.2288861 0.8480975 -0.4778512 -0.2983307 0.8262903 -0.4777483 -0.2923507 0.8227075 -0.487528 -0.3620848 0.794517 -0.4874807 -0.3646745 0.7958174 -0.4834122 -0.4255315 0.7651868 -0.4831277 -0.4267412 0.7655879 -0.4814221 -0.4907472 0.7264037 -0.4811496 -0.4905012 0.7261762 -0.4817435 -0.5461938 0.685329 -0.4816603 -0.5451324 0.6850852 -0.4832071 -0.5451323 0.6850852 -0.483207 -0.5451323 0.6850852 -0.4832071 -0.602231 0.6354677 -0.4832169 -0.6022311 0.6354678 -0.4832169 -0.602231 0.6354677 -0.4832169 -0.6045544 0.6358358 -0.4798197 -0.6539502 0.5850383 -0.4796659 -0.6511631 0.5848455 -0.4836759 -0.6511656 0.5848427 -0.4836759 -0.6511631 0.5848455 -0.483676 -0.6969694 0.5294948 -0.4836 -0.7011996 0.5293615 -0.4775936 -0.7424385 0.4692437 -0.4781166 -0.739078 0.4696601 -0.4828905 -0.775089 0.4074599 -0.482922 -0.7773936 0.4069898 -0.4796025 -0.8081869 0.3411027 -0.4800863 -0.8075489 0.3413438 -0.4809879 -0.8328369 0.2737157 -0.4811055 -0.8320896 0.2740185 -0.482225 -0.8522073 0.2030271 -0.4822064 -0.8516126 0.2033255 -0.4831303 -0.8657377 0.1324434 -0.4826561 -0.8660494 0.1322219 -0.4821577 -0.8741084 0.06056946 -0.4819397 -0.8742413 0.06047636 -0.4817104 -0.8761817 -0.01186215 -0.4818352 -0.8761554 -0.01184779 -0.4818832 -0.8719235 -0.08395612 -0.4823907 -0.8722199 -0.08421415 -0.4818096 -0.8622994 -0.1558581 -0.4818176 -0.8626652 -0.1563115 -0.4810152 -0.8470574 -0.2266295 -0.4807628 -0.8465065 -0.2258993 -0.4820751 -0.8465065 -0.2258993 -0.4820751 -0.8465064 -0.2258992 -0.4820751 -0.8246275 -0.2959985 -0.4820522 -0.8251124 -0.2967101 -0.4807834 -0.7980636 -0.3634394 -0.4806311 -0.7974051 -0.3619076 -0.4828749 -0.7643296 -0.4266511 -0.4834969 -0.7645711 -0.4270542 -0.4827585 -0.7264958 -0.4887935 -0.4829958 -0.7264668 -0.488694 -0.4831399 -0.6837652 -0.5469779 -0.482991 -0.6837652 -0.5469779 -0.482991 -0.6843527 -0.5498731 -0.478854 -0.6385313 -0.6024795 -0.4788488 -0.6385313 -0.6024795 -0.4788488 -0.638368 -0.6009777 -0.4809495 -0.5845239 -0.6532292 -0.4812729 -0.5847183 -0.6551952 -0.4783554 -0.5847183 -0.6551952 -0.4783553 -0.5847183 -0.6551952 -0.4783554 -0.5283675 -0.7018963 -0.4776708 -0.5284497 -0.6977904 -0.4835592 -0.4705006 -0.7379634 -0.483776 -0.4699437 -0.7426078 -0.4771651 -0.4073777 -0.7787533 -0.4770607 -0.4077706 -0.777158 -0.4793209 -0.4077706 -0.777158 -0.4793209 -0.3409545 -0.8085661 -0.4795529 -0.3418766 -0.8055064 -0.4840245 -0.2740659 -0.8309397 -0.4841769 -0.2737916 -0.831593 -0.4832093 -0.2010746 -0.8520909 -0.4832289 -0.2015336 -0.851222 -0.4845671 -0.1349984 -0.8641927 -0.4847128 -0.1334016 -0.8671573 -0.4798356 -0.05809569 -0.8751661 -0.4803219 -0.06069856 -0.8717336 -0.4862062 0.01161146 -0.87373 -0.4862728 0.0116077 -0.87373 -0.4862728 0.0116077 -0.87373 -0.4862728 0.0113663 -0.8733389 -0.4869804 0.08096313 -0.8696911 -0.4869111 0.08375966 -0.8725271 -0.4813324 0.1585431 -0.8623376 -0.4808721 0.1556318 -0.8596256 -0.4866443 0.2238278 -0.8445135 -0.4865163 0.2238272 -0.8445137 -0.4865163 0.2238271 -0.8445137 -0.4865163 0.2288613 -0.8482427 -0.4776056 0.2288613 -0.8482427 -0.4776055 0.2288613 -0.8482426 -0.4776055 0.2982748 -0.8263053 -0.477757 0.2924162 -0.8227382 -0.4874368 0.3620848 -0.794517 -0.4874807 0.3646348 -0.79585 -0.4833883 0.4254581 -0.765055 -0.4834008 0.4267683 -0.7656365 -0.481321 0.4906632 -0.7262793 -0.481423 0.4905737 -0.7262833 -0.4815081 0.5462353 -0.6852851 -0.4816756 0.5462353 -0.6852852 -0.4816756 0.5462353 -0.6852851 -0.4816756 0.5450424 -0.6849606 -0.4834851 0.6022467 -0.6354852 -0.4831745 0.6022467 -0.6354852 -0.4831743 0.6022467 -0.6354853 -0.4831744 0.6046051 -0.6358892 -0.4796849 0.6538384 -0.5849383 -0.4799402 0.6512204 -0.5848999 -0.4835331 0.6968492 -0.5294035 -0.4838732 0.7011114 -0.5292949 -0.4777967 0.7423753 -0.4692038 -0.478254 0.7390154 -0.4696204 -0.483025 0.7751557 -0.4074949 -0.4827851 0.7774263 -0.4070069 -0.4795349 0.8082561 -0.3411319 -0.4799493 0.8075829 -0.3413582 -0.4809204 0.8327654 -0.2736922 -0.4812425 0.8320896 -0.2740185 -0.482225 0.8522073 -0.2030271 -0.4822064 0.8516126 -0.2033255 -0.4831303 0.8657377 -0.1324434 -0.4826561 0.8660859 -0.1322275 -0.4820905 0.8741084 -0.06056946 -0.4819397 0.9835504 -0.06812608 -0.1672946 0.9859099 0.0133289 -0.1667449 0.9858943 0.01330369 -0.1668401 0.9814016 0.09474998 -0.1669538 0.9814305 0.09486073 -0.1667205 0.9702245 0.1757878 -0.1666228 0.9700596 0.1751614 -0.168235 0.9523187 0.254144 -0.1688195 0.9525423 0.2555945 -0.1653319 0.9281327 0.3337197 -0.1649271 0.9280335 0.3324536 -0.1680132 0.8976122 0.4074015 -0.1682749 0.8976119 0.4075884 -0.1678228 0.8606098 0.480686 -0.1682016 0.860593 0.4809404 -0.1675596 0.8605929 0.4809404 -0.1675596 0.860593 0.4809404 -0.1675596 0.8180267 0.5502895 -0.1673734 0.8180469 0.5503849 -0.1669602 0.8180469 0.5503849 -0.1669601 0.818047 0.550385 -0.1669602 0.7685295 0.6174733 -0.1675982 0.7685295 0.6174733 -0.1675982 0.7685295 0.6174733 -0.1675982 0.7686004 0.6174281 -0.1674396 0.7177942 0.6758061 -0.1675042 0.7167445 0.6784597 -0.1611518 0.6572294 0.7363674 -0.1606627 0.6589816 0.7327863 -0.1696097 0.5949482 0.7855993 -0.1699135 0.5949482 0.7855993 -0.1699135 0.5949481 0.7855992 -0.1699135 0.5953851 0.7847819 -0.1721453 0.5266939 0.8323818 -0.1724358 0.5253603 0.8343492 -0.1669073 0.5253603 0.8343493 -0.1669073 0.5253604 0.8343492 -0.1669072 0.4582292 0.8731045 -0.1664774 0.4592736 0.8717637 -0.170575 0.3850284 0.9070166 -0.170511 0.3836011 0.9085094 -0.1657136 0.3836011 0.9085094 -0.1657135 0.3836011 0.9085094 -0.1657136 0.3083374 0.9367126 -0.1658245 0.3083374 0.9367126 -0.1658244 0.3083374 0.9367126 -0.1658244 0.3070952 0.9377893 -0.1619993 0.3070954 0.9377893 -0.1619993 0.3070953 0.9377893 -0.1619994 0.227348 0.9602717 -0.1618374 0.229928 0.9583835 -0.1692167 0.1498533 0.9740923 -0.1693763 0.1498534 0.9740923 -0.1693761 0.1498534 0.9740923 -0.1693761 0.1491259 0.9746025 -0.1670673 0.06854796 0.9835343 -0.1672166 0.06813061 0.9837449 -0.166145 0.06812769 0.9837452 -0.166145 0.06813061 0.9837449 -0.166145 -0.01289457 0.9859503 -0.1665406 -0.01276129 0.9859565 -0.1665142 -0.09421819 0.9814639 -0.1668879 -0.09370291 0.9813852 -0.1676393 -0.1755592 0.9700462 -0.1678971 -0.1790789 0.9708395 -0.1593788 -0.2572329 0.9531319 -0.1592822 -0.2512863 0.952215 -0.1736147 -0.2512863 0.952215 -0.1736147 -0.2512862 0.9522149 -0.1736147 -0.3297765 0.9280651 -0.1730394 -0.3297765 0.9280651 -0.1730393 -0.3297766 0.9280651 -0.1730393 -0.3367093 0.9284369 -0.1569452 -0.4113835 0.8977582 -0.1574606 -0.4049382 0.8979719 -0.172255 -0.479614 0.8604397 -0.1720871 -0.4812061 0.8602426 -0.1685925 -0.5517467 0.816838 -0.1683781 -0.549099 0.8173237 -0.1745632 -0.6131519 0.7705522 -0.1740521 -0.6173477 0.7693806 -0.16412 -0.6797215 0.7148776 -0.1640997 -0.6770681 0.7158582 -0.1706631 -0.6770653 0.7158609 -0.1706631 -0.6770681 0.7158582 -0.1706632 -0.7331267 0.6584569 -0.1701758 -0.7332929 0.6583755 -0.1697742 -0.7865322 0.5937817 -0.169678 -0.786554 0.5937943 -0.169532 -0.8318216 0.5285862 -0.1693208 -0.831712 0.5286429 -0.1696823 -0.8731831 0.457143 -0.1690314 -0.8730042 0.4572893 -0.1695588 -0.8730043 0.4572893 -0.1695588 -0.8730043 0.4572893 -0.1695589 -0.9078291 0.3837311 -0.1691063 -0.9089333 0.382653 -0.1655814 -0.9366803 0.3084475 -0.165802 -0.9365323 0.3086618 -0.1662389 -0.9365323 0.3086619 -0.1662388 -0.9365323 0.3086618 -0.1662389 -0.9590904 0.228991 -0.1664593 -0.9589481 0.2291646 -0.1670397 -0.9746677 0.1488034 -0.1669747 -0.9745776 0.148954 -0.1673657 -0.9835992 0.068039 -0.1670432 -0.983554 0.06812632 -0.1672734 -0.9859091 -0.0133289 -0.1667503 -0.9858978 -0.01330375 -0.166819 -0.9813944 -0.09474927 -0.1669964 -0.9814233 -0.09486007 -0.166763 -0.9702103 -0.1757853 -0.1667082 -0.9700701 -0.1751633 -0.1681716 -0.9523187 -0.254144 -0.1688195 -0.9525372 -0.2556081 -0.1653407 -0.9281236 -0.3337402 -0.1649372 -0.9280175 -0.3324279 -0.1681526 -0.8976653 -0.4074121 -0.1679658 -0.8976654 -0.4074121 -0.1679658 -0.8976653 -0.4074119 -0.1679657 -0.8976185 -0.4075915 -0.1677805 -0.8606605 -0.4807143 -0.1678611 -0.8605938 -0.4809653 -0.1674836 -0.8180028 -0.5502734 -0.1675438 -0.8179994 -0.5503572 -0.1672845 -0.7685573 -0.617526 -0.1672763 -0.768566 -0.6174433 -0.1675419 -0.7685659 -0.6174433 -0.1675418 -0.7685659 -0.6174434 -0.1675419 -0.7178213 -0.6757767 -0.1675067 -0.7178213 -0.6757767 -0.1675066 -0.7178213 -0.6757767 -0.1675067 -0.7168267 -0.6784754 -0.160719 -0.6571921 -0.7363994 -0.1606696 -0.6589459 -0.7327451 -0.1699264 -0.5949133 -0.7855541 -0.1702442 -0.595357 -0.784743 -0.1724195 -0.5267095 -0.8323026 -0.1727699 -0.5274081 -0.8312809 -0.1755361 -0.4574605 -0.8716397 -0.1759951 -0.4559507 -0.8735084 -0.1705644 -0.4559508 -0.8735083 -0.1705643 -0.4559507 -0.8735083 -0.1705644 -0.3850057 -0.9070276 -0.1705042 -0.3850057 -0.9070276 -0.1705041 -0.3850057 -0.9070276 -0.1705041 -0.3835687 -0.9084374 -0.1661821 -0.3083982 -0.936695 -0.1658111 -0.3070968 -0.9378001 -0.1619337 -0.227348 -0.9602717 -0.1618374 -0.2299342 -0.9583917 -0.1691612 -0.2299342 -0.9583917 -0.1691612 -0.2299342 -0.9583917 -0.1691613 -0.1498567 -0.974113 -0.1692538 -0.1498567 -0.974113 -0.1692537 -0.1498567 -0.9741131 -0.1692537 -0.1490665 -0.9746318 -0.1669497 -0.06848311 -0.9835405 -0.1672074 -0.06848424 -0.9835404 -0.1672074 -0.06848424 -0.9835404 -0.1672074 -0.06819063 -0.9836964 -0.1664083 0.01283085 -0.9859511 -0.1665407 0.01276177 -0.9859011 -0.1668418 0.01276177 -0.9859012 -0.1668416 0.01276171 -0.9859011 -0.1668418 0.09422391 -0.9814829 -0.1667734 0.09421938 -0.9814833 -0.1667733 0.09421944 -0.9814833 -0.1667733 0.09376168 -0.9813303 -0.1679269 0.1756332 -0.9700921 -0.1675545 0.1790045 -0.9707829 -0.1598056 0.2571571 -0.9530948 -0.1596268 0.2513688 -0.9522942 -0.1730594 0.3298378 -0.9280194 -0.1731676 0.3366351 -0.9284165 -0.1572251 0.4113155 -0.897749 -0.1576911 0.4113104 -0.8977513 -0.1576908 0.4113104 -0.8977513 -0.1576909 0.4049871 -0.8979323 -0.1723456 0.479614 -0.8604397 -0.1720871 0.4811846 -0.8603014 -0.1683535 0.5517467 -0.816838 -0.1683781 0.549124 -0.817361 -0.1743099 0.6131519 -0.7705522 -0.1740521 0.6174393 -0.7694124 -0.1636258 0.6797605 -0.7149186 -0.1637592 0.6769923 -0.7158542 -0.1709802 0.733083 -0.6584175 -0.1705165 0.7332767 -0.6583608 -0.1699013 0.7865788 -0.5938168 -0.1693382 0.786525 -0.5937724 -0.1697432 0.8318464 -0.528602 -0.1691504 0.8317458 -0.5286644 -0.1694493 0.8731573 -0.4571294 -0.1692016 0.8729993 -0.4573017 -0.1695508 0.9078022 -0.3837197 -0.1692765 0.9089592 -0.3826405 -0.1654673 0.9367032 -0.3084618 -0.1656455 0.9367032 -0.3084618 -0.1656454 0.9367033 -0.3084619 -0.1656455 0.9365051 -0.3086584 -0.1663976 0.9590764 -0.2289877 -0.1665444 0.958948 -0.2291749 -0.1670255 0.9746677 -0.1488034 -0.1669747 0.9745883 -0.1489556 -0.1673023 0.9835992 -0.068039 -0.1670432 -0.07356983 -0.4944361 -0.866095 -0.1174607 -0.4856967 -0.8661996 -0.229834 -0.4427732 -0.8666766 -0.3323928 -0.3725531 -0.8664406 -0.4548246 -0.2065032 -0.8663089 -0.4914711 -0.08758628 -0.8664784 -0.4982475 -0.04785621 -0.8657132 -0.4983663 -0.006720125 -0.8669405 -0.4947754 0.07558995 -0.8657271 -0.4854097 0.1156668 -0.8666018 -0.4423485 0.2313016 -0.8665031 -0.3130633 0.3894551 -0.8662079 -0.2058563 0.454804 -0.8664736 -0.08794575 0.4909265 -0.8667508 -0.08794575 0.4909265 -0.8667508 -0.08794564 0.4909265 -0.8667508 -0.05041283 0.4978531 -0.865795 -0.006796896 0.4990278 -0.8665593 0.07357513 0.4944718 -0.8660741 0.1174691 0.4857317 -0.8661788 0.2298159 0.4427382 -0.8666992 0.332335 0.3724884 -0.8664905 0.4546514 0.2065398 -0.8663911 0.4546514 0.2065398 -0.866391 0.4914711 0.08758628 -0.8664784 0.4982467 0.04785621 -0.8657137 0.4983663 0.006720125 -0.8669405 0.4947242 -0.07559251 -0.8657562 0.4854796 -0.1156834 -0.8665604 0.4423511 -0.2312768 -0.8665082 0.3128228 -0.3893631 -0.8663362 0.2059456 -0.4550014 -0.8663488 0.08830553 -0.490863 -0.8667501 0.08830553 -0.4908629 -0.8667501 0.08830547 -0.490863 -0.8667501 0.05041515 -0.4978762 -0.8657816 0.006764471 -0.4991173 -0.866508 -0.2230219 0.06666874 -0.9725311 0.2231861 -0.06677168 -0.9724863 -0.07334232 0.2261162 -0.9713354 -0.0317052 0.3419892 -0.9391689 -0.06110286 0.2258821 -0.9722365 -0.04383641 0.2975322 -0.9537048 0.1145674 0.2355909 -0.9650759 -0.07096111 0.2304173 -0.9705012 0.09300965 0.1912854 -0.9771178 0.1030474 0.1469609 -0.98376 0.1134723 0.1369192 -0.9840616 0.09960168 0.1470575 -0.9841005 0.2275591 0.07253414 -0.9710592 0.3472435 0.02752548 -0.937371 0.2273793 0.05599021 -0.9721954 0.2273792 0.05599015 -0.9721955 0.2273792 0.05599015 -0.9721955 0.2943354 0.03675276 -0.9549953 0.2355271 -0.1132769 -0.9652436 0.2260392 0.05312871 -0.9726684 0.1918624 -0.09229075 -0.9770728 0.1471431 -0.1025226 -0.9837877 0.1370705 -0.1132438 -0.9840669 0.1431796 -0.1043381 -0.9841815 0.07326734 -0.225885 -0.9713948 0.03168541 -0.3418794 -0.9392096 0.03168535 -0.3418794 -0.9392096 0.03168535 -0.3418793 -0.9392096 0.0612508 -0.2258801 -0.9722276 0.04392951 -0.2975027 -0.9537099 0.04392945 -0.2975027 -0.9537099 0.04392945 -0.2975027 -0.9537099 -0.1145568 -0.235569 -0.9650825 0.07117176 -0.2303853 -0.9704933 0.07117176 -0.2303853 -0.9704933 0.0711717 -0.2303854 -0.9704933 -0.09307473 -0.1913997 -0.9770892 -0.1030417 -0.1469981 -0.9837551 -0.1134956 -0.1369473 -0.984055 -0.09962761 -0.1470958 -0.9840921 -0.227501 -0.07251566 -0.9710741 -0.3475065 -0.02758902 -0.9372717 -0.3475065 -0.02758896 -0.9372717 -0.3475064 -0.02758902 -0.9372717 -0.2274959 -0.05607223 -0.9721633 -0.294401 -0.03671997 -0.9549763 -0.294401 -0.03671991 -0.9549764 -0.2944008 -0.03671997 -0.9549763 -0.2354691 0.113249 -0.9652611 -0.2258991 -0.05296313 -0.97271 -0.2258991 -0.05296307 -0.97271 -0.2258991 -0.05296313 -0.97271 -0.1918053 0.09226328 -0.9770867 -0.1470751 0.1024973 -0.9838004 -0.1370144 0.1131975 -0.98408 -0.1434912 0.1046794 -0.9840999 0.04418092 -0.498413 -0.8658133 0.01603025 -0.4950429 -0.8687208 0.01367139 -0.4221835 -0.9064074 -0.03657996 -0.4207744 -0.9064276 -0.02969962 -0.3416096 -0.9393727 -0.06957995 -0.3356898 -0.9393993 0.08802849 -0.4909092 -0.866752 0.07644891 -0.4886806 -0.869107 0.06535249 -0.4177091 -0.9062274 0.01281058 -0.4226114 -0.9062204 0.01039689 -0.3429061 -0.9393122 -0.03008854 -0.3418195 -0.9392839 0.1692163 -0.4710369 -0.865731 0.1705004 -0.4705278 -0.8657559 0.1274586 -0.4773466 -0.869422 0.1342581 -0.4790739 -0.8674463 0.1140415 -0.4069302 -0.9063125 0.06580108 -0.4174391 -0.9063194 0.05348628 -0.3393185 -0.9391497 0.009424507 -0.3433966 -0.9391433 0.2057588 -0.4549899 -0.8663992 0.1902009 -0.4562418 -0.8692911 0.1627085 -0.3902893 -0.906201 0.1135371 -0.4074055 -0.9061623 0.09230172 -0.3311781 -0.9390429 0.05274045 -0.3397136 -0.9390491 0.2805847 -0.4142865 -0.8658169 0.2794117 -0.4148771 -0.8659135 0.2419708 -0.4323101 -0.8686531 0.2448309 -0.432228 -0.8678922 0.2083992 -0.3679041 -0.9062099 0.162789 -0.3902003 -0.9062249 0.1320617 -0.3165501 -0.9393379 0.09387916 -0.3298626 -0.9393495 0.07612919 -0.267479 -0.9605516 0.04261833 -0.2744939 -0.960644 0.02935874 -0.2650429 -0.9637897 0.007325947 -0.2668774 -0.9637026 0.02885478 -0.2837207 -0.9584727 -0.02485525 -0.2823236 -0.9589973 -0.04412674 -0.2639985 -0.9635133 -0.05439692 -0.2624394 -0.9634141 -0.04435288 -0.2751514 -0.9603773 -0.04435658 -0.2751153 -0.9603875 0.3117907 -0.3905118 -0.8661912 0.2946478 -0.3968287 -0.8693156 0.2519971 -0.3393921 -0.9062618 0.2084978 -0.3676419 -0.9062936 0.1693115 -0.2985435 -0.9392579 0.1317336 -0.3169289 -0.9392563 0.1003705 -0.2414599 -0.9652062 0.1099461 -0.2380471 -0.9650106 -0.06082653 -0.2235006 -0.972804 0.3714505 -0.3345386 -0.866088 0.3725241 -0.3336213 -0.8659809 0.3411746 -0.3604235 -0.868156 0.3409157 -0.3605589 -0.8682015 0.2904192 -0.3071591 -0.9062616 0.252034 -0.3393898 -0.9062524 0.2046472 -0.2755792 -0.9392421 0.169307 -0.298568 -0.939251 0.1289238 -0.2273619 -0.9652385 0.1005639 -0.2411653 -0.9652597 0.0692594 -0.1661163 -0.983671 -0.06108582 -0.2224861 -0.9730203 0.0943256 -0.1532673 -0.9836726 0.08830726 -0.1565678 -0.9837116 0.1285184 -0.2278681 -0.9651732 0.1550285 -0.2106195 -0.9651973 0.2038674 -0.2769775 -0.9390003 0.235584 -0.2503623 -0.9390522 0.2901131 -0.3083141 -0.9059674 0.3256825 -0.2701564 -0.9060609 0.379939 -0.3151581 -0.8696675 0.4180157 -0.2660741 -0.868601 0.4005769 -0.2988326 -0.8661625 0.398547 -0.3016911 -0.8661078 0.4416095 -0.2323237 -0.8666065 0.4178316 -0.2685627 -0.8679233 0.3558725 -0.228739 -0.9061089 0.3257544 -0.270019 -0.906076 0.2641423 -0.2189475 -0.9393033 0.2363324 -0.2486531 -0.9393183 0.1799845 -0.1893591 -0.9652713 0.1555634 -0.209762 -0.9652979 0.105812 -0.1426718 -0.9840978 0.09168928 -0.151921 -0.9841306 0.09957647 -0.152604 -0.9832581 0.1050842 -0.1435375 -0.98405 0.1221805 -0.1292288 -0.9840589 0.1796445 -0.190021 -0.9652046 0.2010181 -0.1672487 -0.9652045 0.2639573 -0.219617 -0.9391992 0.2890481 -0.1853065 -0.9392086 0.3559204 -0.2281771 -0.9062317 0.3804906 -0.184358 -0.9062225 0.4445575 -0.2153984 -0.8694666 0.4696808 -0.1541664 -0.8692714 0.461318 -0.1933071 -0.8659204 0.4606079 -0.1951048 -0.8658952 0.4843332 -0.1195397 -0.8666786 0.4843332 -0.1195396 -0.8666785 0.4843335 -0.1195398 -0.8666784 0.4711729 -0.1613773 -0.8671526 0.3998821 -0.1369605 -0.9062761 0.3804852 -0.1841597 -0.906265 0.3090571 -0.1495882 -0.9392057 0.2890965 -0.1853013 -0.9391947 0.2201121 -0.1410806 -0.9652187 0.2011545 -0.1668034 -0.9652531 0.1368373 -0.113467 -0.9840736 0.1222608 -0.1293098 -0.9840384 0.4945137 -0.07607454 -0.8658342 0.4836106 -0.1026116 -0.8692477 0.4135804 -0.08775109 -0.906229 0.3999903 -0.1373711 -0.9061661 0.3247961 -0.1115455 -0.9391833 0.3090816 -0.1498082 -0.9391624 0.2354313 -0.1141099 -0.965169 0.2198195 -0.1419345 -0.9651601 0.1505085 -0.09718257 -0.9838205 0.1479086 -0.09886473 -0.9840472 0.4973161 -0.034361 -0.8668887 0.4926747 -0.04357326 -0.869122 0.4210616 -0.03724032 -0.9062672 0.4135309 -0.0873872 -0.9062868 0.3358519 -0.07097107 -0.9392373 0.3247287 -0.1109512 -0.9392769 0.275315 -0.09406983 -0.9567406 0.220171 -0.129852 -0.9667798 0.4980756 0.04833191 -0.8657857 0.4943506 0.01611071 -0.8691133 0.4224969 0.01376891 -0.9062598 0.4211416 -0.03729826 -0.9062277 0.3420754 -0.03029614 -0.939184 0.3359804 -0.07150185 -0.9391511 0.4912137 0.08916109 -0.8664638 0.4884608 0.07547068 -0.869316 0.4177718 0.06454986 -0.9062561 0.4224976 0.01377314 -0.9062594 0.3432404 0.01118874 -0.939181 0.3420054 -0.03021651 -0.939212 0.4706706 0.1687777 -0.8660158 0.4708712 0.1688607 -0.8658905 0.4774131 0.1274989 -0.8693796 0.4792876 0.1351879 -0.8671838 0.4067375 0.1147253 -0.9063128 0.4176533 0.06469869 -0.9063001 0.3392744 0.05255746 -0.9392181 0.3431575 0.01121854 -0.939211 0.4544803 0.2070227 -0.8663656 0.4559544 0.1898674 -0.8695149 0.3904786 0.1626046 -0.9061382 0.4071671 0.1143004 -0.9061736 0.3306691 0.09282654 -0.9391705 0.3394436 0.05230289 -0.9391712 0.41523 0.2793084 -0.8657777 0.4144725 0.2809628 -0.8656054 0.4324336 0.2415809 -0.8687001 0.432322 0.2450699 -0.867778 0.367774 0.2084814 -0.9062439 0.3900896 0.162902 -0.9062522 0.3167099 0.1322631 -0.9392557 0.3302966 0.09327703 -0.939257 0.2673509 0.07549947 -0.960637 0.2743558 0.04227375 -0.9606987 0.2654507 0.02973133 -0.9636659 0.2671427 0.00873351 -0.9636174 0.2830627 0.02917617 -0.9586576 0.2818427 -0.02490103 -0.9591375 0.2632509 -0.04441446 -0.9637045 0.2616667 -0.05568671 -0.9635506 0.2751421 -0.04482829 -0.9603579 0.2752314 -0.04525542 -0.9603123 0.2752313 -0.04525536 -0.9603124 0.2752314 -0.04525536 -0.9603123 0.2378827 0.1104081 -0.9649984 0.2414427 0.1003366 -0.965214 0.3171158 0.1317846 -0.9391861 0.298753 0.1694704 -0.9391626 0.3676475 0.2085502 -0.9062793 0.3395184 0.2516878 -0.9063005 0.3969282 0.2942451 -0.8694067 0.3595924 0.3413819 -0.8684192 0.3909024 0.3113725 -0.8661655 0.3904233 0.3118877 -0.8661962 0.3382908 0.367069 -0.8664985 0.3605577 0.3410689 -0.8681418 0.3073363 0.2907285 -0.9061022 0.3402895 0.2514025 -0.9060904 0.2760106 0.2039089 -0.939276 0.2981595 0.1698765 -0.9392779 0.2272562 0.129479 -0.965189 0.2416758 0.1001896 -0.965171 0.1653409 0.06854617 -0.9838516 0.2235473 -0.06662827 -0.9724131 0.2235472 -0.06662833 -0.9724131 0.2235472 -0.06662833 -0.9724133 0.1524837 0.09428077 -0.9837987 0.1557543 0.0885207 -0.9838215 0.227457 0.1292688 -0.9651699 0.2105485 0.1553924 -0.9651542 0.2761386 0.2037963 -0.9392628 0.249392 0.2357521 -0.9392681 0.3075058 0.2906816 -0.9060599 0.2706118 0.3253714 -0.9060369 0.3157798 0.379683 -0.8695539 0.2665255 0.4180834 -0.8684299 0.3019609 0.399235 -0.8656969 0.301295 0.3996458 -0.8657395 0.2340903 0.4403114 -0.8667917 0.2340903 0.4403114 -0.8667917 0.2340903 0.4403115 -0.8667916 0.2680625 0.4179431 -0.8680243 0.2280897 0.3556292 -0.9063681 0.2691075 0.3256544 -0.9063832 0.2187382 0.2647012 -0.9391948 0.2498832 0.2355695 -0.9391834 0.1901831 0.1792861 -0.9652393 0.2098087 0.1559345 -0.9652279 0.1426066 0.1059879 -0.9840884 0.152489 0.09088689 -0.9841173 0.1530978 0.09537965 -0.9835974 0.1423835 0.1061958 -0.9840983 0.1295344 0.1215692 -0.9840944 0.1907796 0.1790574 -0.965164 0.1665275 0.2016522 -0.9651969 0.2186134 0.2647204 -0.9392185 0.185724 0.2888329 -0.9391924 0.2286632 0.3556066 -0.9062324 0.1840096 0.3806366 -0.9062319 0.2150146 0.4447639 -0.869456 0.1542869 0.4695597 -0.8693154 0.1941946 0.4609465 -0.8659197 0.1948766 0.4606842 -0.865906 0.1173483 0.4856767 -0.8662261 0.1630079 0.4711984 -0.8668336 0.1383233 0.3998568 -0.9060802 0.1848085 0.3806628 -0.9060584 0.1500499 0.3090727 -0.9391268 0.1862635 0.2887334 -0.9391161 0.1417592 0.2197459 -0.9652026 0.1662182 0.2018122 -0.9652168 0.112982 0.1371718 -0.9840828 0.1298969 0.1213079 -0.9840788 0.07560783 0.494132 -0.866093 0.1013119 0.4834862 -0.8694694 0.08665502 0.413542 -0.9063521 0.1370823 0.3996709 -0.9063507 0.1112968 0.3244616 -0.9393283 0.1486858 0.3091014 -0.9393343 0.113369 0.2356778 -0.9651961 0.1419525 0.2196867 -0.9651877 0.09735727 0.1506654 -0.9837793 0.09956413 0.1472078 -0.9840818 0.0338822 0.497931 -0.8665546 0.04447275 0.4926643 -0.8690825 0.03803849 0.4213716 -0.90609 0.087897 0.4138961 -0.9060708 0.07137608 0.336084 -0.9391236 0.1127981 0.3246031 -0.9391003 0.0956332 0.2752078 -0.9566164 0.1318656 0.2193154 -0.9667018 -0.04418092 0.498413 -0.8658133 -0.01603275 0.4951213 -0.868676 -0.01366817 0.4220843 -0.9064536 0.0365476 0.4207187 -0.9064547 0.02968591 0.3416628 -0.9393537 0.06957143 0.3357047 -0.9393947 -0.08801817 0.4909097 -0.8667529 -0.07646697 0.4886023 -0.8691493 -0.06538075 0.4177432 -0.9062098 -0.01281231 0.4226678 -0.9061942 -0.01039767 0.3429312 -0.9393031 0.03008323 0.3417598 -0.9393058 -0.1692071 0.4710114 -0.8657466 -0.1705753 0.4704797 -0.8657674 -0.1273837 0.4773513 -0.8694305 -0.1342357 0.4790754 -0.867449 -0.1140252 0.4069538 -0.906304 -0.06579649 0.4174392 -0.9063197 -0.053478 0.3392658 -0.9391692 -0.009424507 0.3433966 -0.9391433 -0.2057872 0.4550527 -0.8663594 -0.1901909 0.4562178 -0.869306 -0.1627356 0.3903541 -0.9061682 -0.1135371 0.4074055 -0.9061623 -0.09229534 0.3311553 -0.9390516 -0.05275434 0.3398028 -0.939016 -0.2805691 0.4142019 -0.8658624 -0.2794876 0.4149896 -0.8658351 -0.2419239 0.4322773 -0.8686825 -0.2448438 0.4322509 -0.8678772 -0.2083761 0.3678634 -0.9062318 -0.1627673 0.3901484 -0.9062511 -0.1320571 0.3165392 -0.9393423 -0.09387916 0.3298626 -0.9393495 -0.07613557 0.2675015 -0.9605448 -0.04262787 0.2745554 -0.960626 -0.02936685 0.2649888 -0.9638043 -0.007325947 0.2668774 -0.9637026 -0.02882492 0.2836967 -0.9584808 0.02485984 0.2823759 -0.9589816 0.04408353 0.263955 -0.9635272 0.05440324 0.2624393 -0.9634138 0.04436081 0.2750455 -0.9604073 0.04423803 0.2751051 -0.9603959 -0.3117455 0.3905178 -0.8662047 -0.2946478 0.3968287 -0.8693156 -0.2519971 0.3393921 -0.9062618 -0.2085534 0.3677399 -0.9062411 -0.1692882 0.2985023 -0.9392753 -0.1317336 0.3169289 -0.9392563 -0.1003479 0.2414056 -0.9652221 -0.1099461 0.2380471 -0.9650106 0.06107795 0.2234972 -0.9727891 -0.371483 0.3345339 -0.8660759 -0.3726184 0.3337057 -0.8659077 -0.3411493 0.3604271 -0.8681645 -0.3408797 0.3605208 -0.8682314 -0.2904675 0.3072102 -0.9062288 -0.252034 0.3393898 -0.9062524 -0.2046472 0.2755792 -0.9392421 -0.1692731 0.2985697 -0.9392565 -0.1289125 0.227383 -0.9652349 -0.1005888 0.241225 -0.9652422 -0.06926995 0.1661415 -0.983666 0.06104308 0.2225025 -0.9730193 0.06104302 0.2225025 -0.9730193 0.06104302 0.2225025 -0.9730193 -0.09429001 0.1532095 -0.9836851 -0.08834922 0.156598 -0.983703 -0.1284943 0.2277826 -0.9651965 -0.1559958 0.2099669 -0.9651835 -0.204697 0.2755158 -0.9392499 -0.2352254 0.2499811 -0.9392436 -0.2900355 0.3082316 -0.9060202 -0.3257409 0.2701842 -0.9060317 -0.3799217 0.3151218 -0.8696883 -0.4179857 0.2660353 -0.8686273 -0.4005984 0.2988486 -0.8661469 -0.3985031 0.3016974 -0.8661259 -0.4416243 0.2321866 -0.8666356 -0.4178083 0.2685659 -0.8679336 -0.355892 0.2287662 -0.9060943 -0.3257565 0.2700188 -0.9060754 -0.2641059 0.2189174 -0.9393208 -0.235386 0.249634 -0.9392957 -0.1795039 0.1903632 -0.9651634 -0.155848 0.2101782 -0.9651615 -0.1058362 0.142726 -0.9840874 -0.09168511 0.1518988 -0.9841344 -0.09956711 0.1525897 -0.9832613 -0.1050625 0.143508 -0.9840566 -0.1222114 0.1292615 -0.9840508 -0.1796001 0.1899739 -0.9652221 -0.2010181 0.1672487 -0.9652045 -0.2639573 0.219617 -0.9391992 -0.2890658 0.1853333 -0.9391978 -0.3559457 0.2282096 -0.9062137 -0.3805327 0.1843784 -0.9062006 -0.4445575 0.2153984 -0.8694666 -0.469743 0.1541868 -0.8692342 -0.4611591 0.1932405 -0.86602 -0.4605954 0.1950995 -0.865903 -0.4843332 0.1195397 -0.8666786 -0.4843332 0.1195396 -0.8666785 -0.4843335 0.1195398 -0.8666784 -0.471123 0.1613602 -0.8671828 -0.3998821 0.1369605 -0.9062761 -0.3804562 0.1841334 -0.9062826 -0.3091206 0.1496078 -0.9391816 -0.2890473 0.1852689 -0.9392163 -0.2200332 0.14103 -0.965244 -0.2011545 0.1668034 -0.9652531 -0.1368719 0.1134957 -0.9840655 -0.1221604 0.1292036 -0.9840648 -0.4945894 0.07609587 -0.8657891 -0.4836106 0.1026116 -0.8692477 -0.4136263 0.0877608 -0.9062072 -0.3999369 0.1373527 -0.9061926 -0.3248411 0.1115609 -0.9391659 -0.3090816 0.1498082 -0.9391624 -0.2354313 0.1141099 -0.965169 -0.2199288 0.142005 -0.9651249 -0.1505085 0.09718257 -0.9838205 -0.1478812 0.09883272 -0.9840545 -0.4972873 0.03436166 -0.8669053 -0.4926575 0.04357373 -0.8691318 -0.4210894 0.03724479 -0.9062541 -0.4134761 0.08737564 -0.906313 -0.3358519 0.07097107 -0.9392373 -0.3247287 0.1109512 -0.9392769 -0.2752155 0.0940358 -0.9567726 -0.2203665 0.1299673 -0.9667198 -0.4980736 -0.04833197 -0.8657868 -0.4943706 -0.01611053 -0.869102 -0.4225611 -0.01377028 -0.9062299 -0.4210255 0.03728842 -0.9062821 -0.3420754 0.03029614 -0.939184 -0.3359804 0.07150185 -0.9391511 -0.4911722 -0.08914643 -0.8664888 -0.4884608 -0.07547068 -0.869316 -0.417818 -0.06455695 -0.9062343 -0.4224976 -0.01377314 -0.9062594 -0.3431929 -0.01118719 -0.9391984 -0.3420652 0.03022176 -0.9391902 -0.4709771 -0.1688876 -0.8658277 -0.4705955 -0.1687619 -0.8660597 -0.47735 -0.1274821 -0.8694167 -0.4793385 -0.1352022 -0.8671535 -0.4067375 -0.1147253 -0.9063128 -0.4176533 -0.06469869 -0.9063001 -0.3392744 -0.05255746 -0.9392181 -0.3431575 -0.01121854 -0.939211 -0.4545899 -0.2070921 -0.8662915 -0.4559065 -0.1898474 -0.8695443 -0.3904353 -0.1625866 -0.90616 -0.4071671 -0.1143004 -0.9061736 -0.3307137 -0.09283936 -0.9391536 -0.3393639 -0.05229419 -0.9392005 -0.41523 -0.2793084 -0.8657777 -0.4141109 -0.2807177 -0.8658579 -0.4324336 -0.2415809 -0.8687001 -0.4323676 -0.2450958 -0.8677479 -0.3677332 -0.2084583 -0.9062656 -0.3900637 -0.1628911 -0.9062653 -0.316712 -0.132263 -0.9392551 -0.3303018 -0.09327685 -0.9392551 -0.2674059 -0.07551658 -0.9606204 -0.2744122 -0.04228579 -0.960682 -0.265393 -0.02972483 -0.9636821 -0.2671347 -0.008733272 -0.9636197 -0.2830223 -0.02916991 -0.9586697 -0.2818785 0.02490419 -0.959127 -0.2632892 0.04442453 -0.9636936 -0.2615777 0.05566781 -0.9635758 -0.2752541 0.04485166 -0.9603248 -0.2751713 0.04525011 -0.9603297 -0.2751713 0.04524999 -0.9603297 -0.237941 -0.1104394 -0.9649804 -0.2414591 -0.1003361 -0.9652099 -0.3171367 -0.1317836 -0.9391792 -0.298753 -0.1694704 -0.9391626 -0.3675985 -0.2085224 -0.9063056 -0.3395735 -0.2517457 -0.9062638 -0.3969059 -0.2942482 -0.8694158 -0.3595727 -0.3413586 -0.8684365 -0.390927 -0.3114086 -0.8661414 -0.3903895 -0.3118607 -0.8662212 -0.3382892 -0.3670625 -0.866502 -0.3382893 -0.3670626 -0.8665018 -0.360547 -0.3410083 -0.86817 -0.3073779 -0.2907245 -0.9060896 -0.3402442 -0.251369 -0.9061167 -0.2759725 -0.2038808 -0.9392933 -0.2981595 -0.1698765 -0.9392779 -0.2272562 -0.129479 -0.965189 -0.2415862 -0.1001657 -0.9651958 -0.1652774 -0.06852573 -0.9838637 -0.2234988 0.0667169 -0.9724182 -0.1525142 -0.09430456 -0.9837918 -0.1557726 -0.0885393 -0.983817 -0.2274829 -0.1293042 -0.965159 -0.2105674 -0.1554058 -0.9651479 -0.2761386 -0.2037963 -0.9392628 -0.249392 -0.2357694 -0.9392638 -0.3074972 -0.2907038 -0.9060557 -0.2705531 -0.3253284 -0.9060699 -0.3157926 -0.3797256 -0.8695307 -0.2665078 -0.4180557 -0.8684486 -0.3019117 -0.3991699 -0.865744 -0.301295 -0.3996458 -0.8657395 -0.2338339 -0.4403612 -0.8668355 -0.2680714 -0.4179569 -0.8680149 -0.2280969 -0.3556285 -0.9063665 -0.2690985 -0.3256435 -0.9063897 -0.2187382 -0.2647012 -0.9391948 -0.2498287 -0.235551 -0.9392026 -0.1901948 -0.179319 -0.9652309 -0.2097613 -0.1558736 -0.965248 -0.1426302 -0.105986 -0.9840852 -0.152489 -0.09088772 -0.9841172 -0.1528846 -0.09534412 -0.983634 -0.1528845 -0.09534406 -0.9836341 -0.1528846 -0.09534412 -0.9836341 -0.1424092 -0.1061954 -0.9840946 -0.1295344 -0.1215692 -0.9840944 -0.1907326 -0.1790133 -0.9651815 -0.1665651 -0.2016696 -0.9651868 -0.2186412 -0.2647187 -0.9392126 -0.1857385 -0.2888269 -0.9391913 -0.2286849 -0.3556047 -0.9062277 -0.184007 -0.3806313 -0.9062346 -0.2150146 -0.4447639 -0.869456 -0.1542493 -0.4695466 -0.8693292 -0.1943004 -0.4609782 -0.865879 -0.1948307 -0.4607145 -0.8659003 -0.1178312 -0.4858622 -0.8660565 -0.1630166 -0.4712233 -0.8668184 -0.1383233 -0.3998568 -0.9060802 -0.1848116 -0.3806691 -0.906055 -0.1500396 -0.3090514 -0.9391354 -0.1862838 -0.2887649 -0.9391023 -0.1417465 -0.2197262 -0.9652091 -0.1661975 -0.2017871 -0.9652256 -0.112982 -0.1371718 -0.9840828 -0.1298969 -0.1213079 -0.9840788 -0.07560783 -0.494132 -0.866093 -0.1013172 -0.4835117 -0.8694546 -0.08665257 -0.4135305 -0.9063575 -0.1370686 -0.399631 -0.9063704 -0.1112878 -0.3244619 -0.9393293 -0.148667 -0.3091108 -0.9393342 -0.1133562 -0.2356997 -0.9651923 -0.1419525 -0.2196867 -0.9651877 -0.09735727 -0.1506654 -0.9837793 -0.09953212 -0.1471605 -0.9840921 -0.03385567 -0.4979647 -0.8665363 -0.04446864 -0.492619 -0.8691083 -0.03803849 -0.4213717 -0.90609 -0.08787548 -0.4139247 -0.9060598 -0.07134366 -0.3360614 -0.9391341 -0.1128351 -0.3246089 -0.9390939 -0.09565669 -0.2752072 -0.9566143 -0.1318656 -0.2193154 -0.9667018 0.9996169 -0.02768105 7.59709e-5 0.9996149 -0.02775353 3.55239e-5 0.9996131 -0.02781921 -7.22984e-6 0.9996128 -0.02782571 -7.79497e-5 0.9996144 -0.02776956 -3.90983e-5 0.9996114 -0.02787852 -1.57714e-4 0.9996147 -0.0277599 1.58245e-4 0.9996146 -0.02776265 1.72649e-4 -0.02300071 -0.8945442 -0.4463875 -0.02591937 -0.8943033 -0.4467099 -0.02338033 -0.8945516 -0.4463528 -0.02754479 -0.8927436 -0.4497225 -0.02754473 -0.8927435 -0.4497225 -0.02754479 -0.8927435 -0.4497224 -0.02676773 -0.8946765 -0.4459121 -0.01513051 -0.8939087 -0.4479935 -0.02605164 -0.8944785 -0.4463513 -0.02629685 -0.8944835 -0.4463272 -0.02491879 -0.8945593 -0.4462541 -0.02491879 -0.8945593 -0.4462542 -0.02391964 -0.894557 -0.4463133 -0.02332615 -0.8946077 -0.4462431 0.9895846 -0.1439527 0 0.9960865 0.08838379 0 0.9489951 0.3152908 0 0.9489951 0.3152909 0 0.850286 0.5263211 0 0.850286 0.5263211 0 0.7062811 0.7079315 0 0.7062813 0.7079313 0 0.5229084 0.852389 0 0.5229085 0.8523888 0 0.3130487 0.9497371 0 0.3130486 0.9497371 0 0.08612471 0.9962844 0 0.08612471 0.9962844 0 -0.146448 0.9892184 0 -0.1464479 0.9892184 0 -0.3703899 0.9288764 0 -0.3703898 0.9288764 0 -0.5743783 0.8185901 0 -0.7472655 0.6645257 0 -0.7472653 0.6645259 0 -0.8809549 0.4732005 0 -0.9661505 0.2579795 0 -0.9661502 0.2579801 0 -0.9996149 0.02775406 0 -0.9996148 0.02775537 0 -0.9790843 -0.2034554 0 -0.9790841 -0.2034559 0 -0.9055302 -0.4242821 0 -0.9055298 -0.4242826 0 -0.7837216 -0.6211124 0 -0.7837224 -0.6211115 0 -0.6198344 -0.7847328 0 -0.4195725 -0.9077219 0 -0.4195726 -0.9077218 0 -0.2010038 -0.9795905 0 -0.2010038 -0.9795905 0 0.02871024 -0.9995878 0 0.02871024 -0.9995878 0 0.2612041 -0.9652836 0 0.2612041 -0.9652836 0 0.4742 -0.8804172 0 0.6659524 -0.7459943 0 0.6659527 -0.745994 0 0.8203064 -0.5719244 0 0.8203071 -0.5719235 0 0.9298798 -0.3678637 0 0.9298796 -0.3678642 0 0.9895846 -0.1439533 0 -0.9897597 0.1235386 -0.07151252 -0.9897596 0.1235392 -0.0715124 -0.9897596 0.1235389 -0.07151234 -0.984611 0.1601532 -0.06994551 -0.9658876 0.2493294 -0.06997203 -0.9658875 0.24933 -0.06997191 -0.9658873 0.2493305 -0.06997215 -0.9534334 0.2936279 -0.06890261 -0.9534331 0.2936286 -0.06890243 -0.9534333 0.2936282 -0.06890243 -0.9556279 0.2863994 -0.06892567 -0.9464731 0.3151876 -0.06961005 -0.9464731 0.3151877 -0.06961011 -0.9464731 0.3151877 -0.06961011 -0.9157647 0.3956329 -0.06964057 -0.8799337 0.4694512 -0.07302373 -0.8799338 0.4694508 -0.07302385 -0.8799333 0.4694517 -0.07302367 0.7861481 0.4275831 -0.4462556 0.7879572 0.4237659 -0.4467058 0.7892103 0.4209914 -0.4471168 0.7884443 0.4267154 -0.4430233 0.7884442 0.4267154 -0.4430233 0.7884443 0.4267154 -0.4430233 0.7874079 0.4252324 -0.4462804 0.7877764 0.4246975 -0.4461392 0.7868168 0.4261754 -0.4464235 0.7868169 0.4261754 -0.4464235 0.789143 0.4221876 -0.4461066 0.789143 0.4221876 -0.4461064 0.789143 0.4221876 -0.4461065 0.7875333 0.4252095 -0.4460809 0.7865094 0.4270981 -0.4460832 0.7856494 0.4287475 -0.4460164 0.5471692 -0.8369958 0.00664252 0.5803668 -0.8143553 0 0.6440599 -0.7649751 0 0.6762117 -0.7366732 0.007096767 0.7070787 -0.7071349 0 0.764995 -0.6440362 0 0.7892009 -0.6141021 0.006376206 0.8123466 -0.5831749 0 0.86015 -0.5100413 0 0.8796955 -0.4754922 0.006570875 0.897798 -0.4404076 0 0.9314493 -0.3638712 0 0.9458301 -0.3245887 0.006908357 0.9585111 -0.2850551 0 0.9781661 -0.2078254 0 0.986373 -0.164363 0.007300853 0.9926662 -0.1208885 0 0.9990636 -0.04326492 0 0.9999746 -0.002165198 0.006802201 0.9992414 0.03894531 0 0.9921392 0.1251395 0 0.9864368 0.1640118 0.00653392 0.9792535 0.2026397 0 0.9581561 0.2862465 0 0.9457762 0.3247506 0.006678223 0.9320835 0.3622434 0 0.8978691 0.4402626 0 0.8796954 0.4754922 0.006579339 0.8600709 0.5101746 0 0.8122614 0.5832937 0 0.7892447 0.6140459 0.006382226 0.764995 0.6440362 0 0.7070787 0.7071349 0 0.6762114 0.7366733 0.007113695 0.6440599 0.7649751 0 0.5832232 0.812312 0 0.5472081 0.8369652 0.007257163 0.509995 0.8601774 0 0.4420203 0.897005 0 0.4025203 0.9153828 0.007199347 0.3623895 0.9320267 0 0.2849962 0.9585286 0 0.2466088 0.9690927 0.006587624 0.2077456 0.978183 0 0.1208242 0.9926739 0 0.08214592 0.9965995 0.00645399 0.04324442 0.9990646 0 -0.04324442 0.9990646 0 -0.08215326 0.9965988 0.006454586 -0.1208242 0.9926739 0 -0.2027452 0.9792315 0 -0.2445564 0.9696089 0.007131755 -0.2861809 0.9581757 0 -0.3662448 0.9305185 0 -0.4016929 0.9157521 0.006391227 -0.4368237 0.8995472 0 -0.5131766 0.8582831 0 -0.5471805 0.8369882 0.006659388 -0.5804736 0.8142791 0 -0.644041 0.7649911 0 -0.6772252 0.7357391 0.007350146 -0.7093125 0.7048943 0 -0.7628798 0.6465404 0 -0.7882012 0.6153817 0.006654918 -0.8122614 0.5832937 0 -0.86015 0.5100413 0 -0.8796917 0.4754989 0.006576597 -0.8977918 0.4404204 0 -0.9314582 0.3638487 0 -0.9458318 0.3245839 0.006906867 -0.9585085 0.285064 0 -0.9781661 0.2078254 0 -0.986373 0.164363 0.007303714 -0.9926662 0.1208885 0 -0.9990559 0.04344487 0 -0.9999744 0 0.007159829 -0.9990559 -0.04344344 0 -0.9926662 -0.1208885 0 -0.9864315 -0.1640136 0.007245302 -0.9783514 -0.2069509 0 -0.9581561 -0.2862465 0 -0.9458315 -0.3245891 0.006675779 -0.9320228 -0.3623997 0 -0.8995664 -0.4367843 0 -0.879654 -0.4755598 0.00719273 -0.8582594 -0.5132161 0 -0.8143945 -0.5803117 0 -0.789198 -0.6140998 0.00693947 -0.7628666 -0.646556 0 -0.7092385 -0.7049688 0 -0.6772791 -0.7356896 0.007339298 -0.644041 -0.7649911 0 -0.5833303 -0.8122351 0 -0.5471666 -0.8369923 0.007256627 -0.509971 -0.8601916 0 -0.4403334 -0.8978344 0 -0.4025012 -0.9153935 0.006899893 -0.3639138 -0.9314326 0 -0.2849669 -0.9585375 0 -0.2466086 -0.9690927 0.006604552 -0.2077766 -0.9781764 0 -0.1208242 -0.9926739 0 -0.08215326 -0.9965988 0.006448924 -0.04323667 -0.9990649 0 0.03876572 -0.9992484 0 0.08214545 -0.9965941 0.007225513 0.1256264 -0.9920777 0 0.2027452 -0.9792315 0 0.2440655 -0.9697333 0.00703305 0.2849962 -0.9585286 0 0.3676576 -0.9299612 0 0.4024894 -0.9154033 0.006251692 0.4368237 -0.8995472 0 0.5132558 -0.8582358 0 0.4344906 -0.5113729 -0.7414282 0.4336788 -0.5124008 -0.7411937 0.4746745 -0.4746056 -0.7412379 0.4704739 -0.4733669 -0.7447 0.5091727 -0.4306412 -0.7451787 0.5091727 -0.4306412 -0.7451788 0.5091727 -0.4306413 -0.7451787 0.5102447 -0.4306038 -0.7444668 0.5104245 -0.431837 -0.7436287 0.5433164 -0.3896801 -0.7436107 0.5430471 -0.389621 -0.7438382 0.543549 -0.3881901 -0.7442197 0.543549 -0.3881902 -0.7442197 0.543549 -0.38819 -0.7442197 0.5733445 -0.3428288 -0.7441402 0.5765736 -0.3429786 -0.7415717 0.6035663 -0.2917736 -0.742008 0.6015762 -0.2934125 -0.7429773 0.6021403 -0.2944298 -0.7421174 0.623746 -0.2454565 -0.7420863 0.6230447 -0.2445053 -0.7429888 0.622372 -0.2331316 -0.7471966 0.6365377 -0.192152 -0.7469253 0.6453417 -0.1903204 -0.7398055 0.6603595 -0.1321118 -0.7392374 0.6554346 -0.138721 -0.7424029 0.6547991 -0.1381378 -0.743072 0.6640547 -0.08257764 -0.7431099 0.6646897 -0.08311098 -0.7424824 0.6629886 -0.07924175 -0.7444239 0.6667918 -0.0300849 -0.7446366 0.6680412 -0.02965199 -0.7435333 0.6677756 0.03924173 -0.7433275 0.6677756 0.03924179 -0.7433276 0.6677756 0.03924149 -0.7433276 0.6652562 0.02939867 -0.7460362 0.6666802 0.02854812 -0.7447971 0.6620466 0.08232516 -0.7449274 0.6696369 0.07958531 -0.7384123 0.6626225 0.08652663 -0.7439386 0.6541213 0.1356196 -0.7441322 0.6548887 0.13637 -0.7433196 0.6389924 0.1993874 -0.7429223 0.6389922 0.1993876 -0.7429223 0.6389923 0.1993871 -0.7429224 0.6399926 0.1915945 -0.7441109 0.6441782 0.190669 -0.7407292 0.6268117 0.2423716 -0.7405155 0.6262307 0.2424295 -0.740988 0.6262305 0.2424296 -0.740988 0.6262306 0.2424296 -0.740988 0.6246623 0.2433617 -0.7420055 0.6246623 0.2433617 -0.7420055 0.6246623 0.2433617 -0.7420055 0.6019213 0.2949442 -0.7420909 0.6036882 0.2973192 -0.739704 0.5769227 0.3461857 -0.739808 0.571493 0.3369488 -0.7482389 0.5407158 0.3844434 -0.7482178 0.5410652 0.388195 -0.7460249 0.5447679 0.387432 -0.7437235 0.5104194 0.4319446 -0.7435697 0.5098346 0.4302623 -0.7449451 0.5092564 0.4307528 -0.7450571 0.5092565 0.4307528 -0.7450571 0.5092564 0.4307527 -0.7450571 0.4719021 0.4718336 -0.7447695 0.4731712 0.4761702 -0.7411956 0.4335668 0.5125867 -0.7411308 0.4345151 0.5084675 -0.7434093 0.4296498 0.5076465 -0.7467905 0.3877196 0.5407117 -0.7465282 0.3878775 0.5435857 -0.7443559 0.3881709 0.5436121 -0.7441837 0.388171 0.543612 -0.7441837 0.3428609 0.5734404 -0.7440515 0.3428567 0.5734149 -0.744073 0.2947575 0.5991835 -0.7443771 0.2925099 0.6028978 -0.7422616 0.2927448 0.6028177 -0.7422341 0.2453963 0.6238372 -0.7420295 0.2444461 0.6231037 -0.7429589 0.2334908 0.6223156 -0.7471314 0.1894103 0.6373634 -0.7469215 0.188816 0.6403141 -0.7445445 0.1434476 0.6518478 -0.7446592 0.1387658 0.6554242 -0.7424037 0.1380816 0.6549081 -0.7429865 0.1380816 0.6549081 -0.7429865 0.08263605 0.6641206 -0.7430446 0.08308392 0.6646054 -0.7425611 0.07917618 0.6631593 -0.7442789 0.02716422 0.6670232 -0.7445417 0.02660942 0.6681058 -0.7435904 -0.01960772 0.6684261 -0.7435202 -0.02656757 0.669999 -0.7418865 -0.02853232 0.6667973 -0.7446927 -0.08274537 0.6620302 -0.7448955 -0.0794388 0.6701587 -0.7379545 -0.08688861 0.6633611 -0.7432378 -0.1358846 0.6552344 -0.7431039 -0.1357339 0.6549997 -0.7433382 -0.199575 0.638988 -0.7428757 -0.199575 0.638988 -0.7428756 -0.1995749 0.638988 -0.7428756 -0.1917096 0.6399451 -0.7441222 -0.1906101 0.6441507 -0.7407683 -0.2434523 0.6264997 -0.740425 -0.2431896 0.6278976 -0.7393264 -0.2477799 0.6194989 -0.7448667 -0.2937838 0.5996251 -0.7444064 -0.2940483 0.5998475 -0.7441228 -0.3414018 0.5741229 -0.7441961 -0.3416267 0.5741068 -0.7441053 -0.386938 0.5445693 -0.7441259 -0.3875035 0.5442236 -0.7440845 -0.3875034 0.5442237 -0.7440845 -0.3875034 0.5442237 -0.7440845 -0.3875534 0.5449159 -0.7435516 -0.3875535 0.544916 -0.7435516 -0.3875534 0.5449159 -0.7435517 -0.4318525 0.510287 -0.743714 -0.4318526 0.5102871 -0.743714 -0.4318526 0.5102871 -0.743714 -0.4344938 0.5112906 -0.741483 -0.4338769 0.5122384 -0.7411901 -0.4338768 0.5122384 -0.7411901 -0.4746538 0.4746769 -0.7412056 -0.4747215 0.4746823 -0.7411587 -0.51239 0.4335299 -0.7412884 -0.5107259 0.4340426 -0.7421362 -0.510509 0.4319085 -0.7435293 -0.5433164 0.3896801 -0.7436107 -0.5431021 0.3895713 -0.7438243 -0.5487996 0.3723327 -0.7484567 -0.5487996 0.3723328 -0.7484567 -0.5679591 0.342696 -0.7483195 -0.5765163 0.3429445 -0.7416321 -0.6035343 0.2921297 -0.7418939 -0.6035343 0.2921296 -0.7418939 -0.6035343 0.2921297 -0.741894 -0.6015548 0.2934184 -0.7429924 -0.6021192 0.2944357 -0.7421322 -0.623746 0.2454565 -0.7420863 -0.6229709 0.2443455 -0.7431035 -0.6222203 0.2334688 -0.7472177 -0.6373201 0.1893974 -0.7469617 -0.6402563 0.188812 -0.7445951 -0.652041 0.1434313 -0.7444931 -0.6555133 0.1388269 -0.7423136 -0.6548304 0.1380284 -0.7430648 -0.6640672 0.08257645 -0.7430989 -0.6646715 0.0829786 -0.7425135 -0.6630147 0.07953494 -0.7443693 -0.667023 0.02717703 -0.7445414 -0.6681221 0.02652925 -0.7435786 -0.6682485 -0.01966744 -0.7436782 -0.6682485 -0.01966756 -0.7436781 -0.6682485 -0.01966726 -0.7436781 -0.6701021 -0.02658015 -0.7417929 -0.6666817 -0.02854704 -0.7447957 -0.6620122 -0.08232367 -0.7449582 -0.6600681 -0.08332568 -0.7465702 -0.6638334 -0.0792638 -0.7436683 -0.6638334 -0.07926368 -0.7436683 -0.6638334 -0.07926374 -0.7436683 -0.6541435 -0.1356242 -0.7441118 -0.6549323 -0.1363791 -0.7432796 -0.6389839 -0.1993684 -0.7429347 -0.638984 -0.1993683 -0.7429347 -0.6389841 -0.1993681 -0.7429346 -0.640051 -0.191612 -0.7440562 -0.6442853 -0.1907715 -0.7406098 -0.6442852 -0.1907715 -0.7406098 -0.6442853 -0.1907714 -0.7406097 -0.6266601 -0.2424916 -0.7406044 -0.6153721 -0.2438792 -0.7495601 -0.6199237 -0.2415559 -0.7465557 -0.5974701 -0.292683 -0.7465697 -0.5992522 -0.2951509 -0.7441658 -0.5741505 -0.3414818 -0.7441381 -0.5742222 -0.3415699 -0.7440423 -0.5443139 -0.3870016 -0.7442796 -0.5444186 -0.3876507 -0.7438652 -0.5449069 -0.3873611 -0.7436586 -0.5103819 -0.4319129 -0.7436138 -0.5113722 -0.4345214 -0.7414106 -0.5124647 -0.433582 -0.7412062 -0.5124648 -0.4335814 -0.7412065 -0.512465 -0.4335812 -0.7412065 -0.4746745 -0.4746056 -0.7412379 -0.4746654 -0.4747214 -0.7411696 -0.4335694 -0.5123691 -0.7412797 -0.4340646 -0.5107824 -0.7420843 -0.4319604 -0.5105357 -0.7434806 -0.3896427 -0.5434124 -0.7435601 -0.3896072 -0.5430199 -0.7438654 -0.388409 -0.5434572 -0.7441725 -0.3414845 -0.5742811 -0.744036 -0.341556 -0.5742321 -0.744041 -0.341556 -0.5742321 -0.744041 -0.2947204 -0.5995508 -0.744096 -0.2934094 -0.6014821 -0.7430547 -0.2944173 -0.6020128 -0.7422258 -0.2453176 -0.6237264 -0.7421487 -0.2422394 -0.6212568 -0.7452248 -0.2376606 -0.6211447 -0.746791 -0.2376606 -0.6211447 -0.746791 -0.2376606 -0.6211446 -0.746791 -0.189425 -0.6375038 -0.7467979 -0.1888328 -0.6401929 -0.7446444 -0.1433897 -0.6519787 -0.7445557 -0.1387658 -0.6554242 -0.7424037 -0.1380732 -0.654843 -0.7430454 -0.08262997 -0.6639827 -0.7431684 -0.08309292 -0.6648095 -0.7423772 -0.07795929 -0.6623876 -0.745094 -0.02727824 -0.666801 -0.7447364 -0.02660781 -0.6681552 -0.743546 0.01977086 -0.6680954 -0.7438129 0.02656251 -0.6699595 -0.7419224 0.02850002 -0.6666909 -0.7447893 0.0823813 -0.6619622 -0.7449963 0.07938528 -0.669557 -0.7385063 0.08586829 -0.6635922 -0.7431501 0.136487 -0.6551148 -0.7430989 0.1363183 -0.6549549 -0.7432708 0.199601 -0.6388278 -0.7430064 0.199601 -0.638828 -0.7430063 0.199601 -0.638828 -0.7430062 0.1908333 -0.640036 -0.7442692 0.1901842 -0.6424675 -0.7423378 0.1901842 -0.6424676 -0.7423378 0.1901842 -0.6424676 -0.7423378 0.2427517 -0.6246179 -0.7422426 0.2424985 -0.6259896 -0.741169 0.2469813 -0.6175025 -0.7467871 0.2927122 -0.5975955 -0.7464578 0.2927122 -0.5975955 -0.7464578 0.2927122 -0.5975955 -0.7464578 0.2952111 -0.5993197 -0.7440876 0.3414096 -0.5740638 -0.744238 0.3415556 -0.5741137 -0.7441325 0.386938 -0.5445693 -0.7441259 0.3876271 -0.5444114 -0.7438828 0.3875819 -0.5448382 -0.7435938 0.4319307 -0.5104861 -0.743532 0.3826091 -0.7841402 -0.4886048 0.4460403 -0.7499117 -0.4885494 0.447035 -0.7501511 -0.4872711 0.5065364 -0.7113812 -0.4871937 0.510623 -0.7126216 -0.4810767 0.5675876 -0.6678364 -0.4814965 0.5650551 -0.6674796 -0.4849575 0.6163873 -0.6202015 -0.4851977 0.6164027 -0.6202492 -0.4851171 0.6683807 -0.5639705 -0.484979 0.6707937 -0.5641145 -0.4814674 0.7122392 -0.5110484 -0.4811912 0.7130334 -0.5109636 -0.4801038 0.7539978 -0.448548 -0.4798876 0.7529392 -0.4488047 -0.4813078 0.7529392 -0.4488047 -0.4813077 0.7529391 -0.4488047 -0.4813078 0.7878907 -0.3842607 -0.4812194 0.7876377 -0.3841664 -0.4817085 0.7876377 -0.3841665 -0.4817085 0.7876377 -0.3841665 -0.4817085 0.8154679 -0.3205277 -0.4819483 0.8162894 -0.3205606 -0.4805336 0.8411491 -0.2479401 -0.4806184 0.836757 -0.2500302 -0.4871578 0.8540022 -0.1810292 -0.4877589 0.8540022 -0.1810293 -0.4877588 0.8573704 -0.1791597 -0.4825118 0.8690736 -0.108145 -0.4827173 0.8709864 -0.1069613 -0.4795226 0.8768043 -0.03876954 -0.4792822 0.8777141 -0.03831046 -0.4776508 0.8777066 0.03881525 -0.4776241 0.8725731 0.03406733 -0.4872943 0.8667883 0.1078634 -0.4868713 0.8688424 0.1100713 -0.4826979 0.8574468 0.1784886 -0.4826251 0.8580981 0.1793102 -0.4811608 0.8396229 0.2514102 -0.4814835 0.8390134 0.2505273 -0.4830037 0.81624 0.315778 -0.4837733 0.8169295 0.316949 -0.4818398 0.7862703 0.3872268 -0.4814919 0.7840031 0.3824859 -0.4889209 0.7514309 0.4431038 -0.488887 0.7536446 0.4492464 -0.4797892 0.7127927 0.5112672 -0.4801381 0.7125687 0.5106286 -0.481149 0.6698779 0.5652338 -0.4814295 0.6693704 0.562913 -0.4848425 0.6162665 0.6202573 -0.4852799 0.6164632 0.6201348 -0.4851866 0.568153 0.6649421 -0.4848239 0.568242 0.6712473 -0.4759498 0.510779 0.7158168 -0.476142 0.5109259 0.7130521 -0.4801162 0.4502026 0.753178 -0.4796255 0.4502025 0.7531781 -0.4796255 0.4502025 0.753178 -0.4796255 0.4499043 0.7549707 -0.47708 0.3836274 0.7905429 -0.4773594 0.3843088 0.787691 -0.4815078 0.3207472 0.8154039 -0.4819105 0.3205001 0.8164394 -0.4803192 0.2480749 0.8410697 -0.4806877 0.2498909 0.8369385 -0.4869173 0.1808432 0.854102 -0.4876532 0.1791081 0.8573458 -0.482575 0.1081439 0.8690642 -0.4827343 0.1069623 0.8709595 -0.4795714 0.03492772 0.8770662 -0.4790983 0.03794831 0.8730078 -0.4862278 -0.03461986 0.8730562 -0.4863892 -0.03414124 0.8725842 -0.4872692 -0.108337 0.866674 -0.4869695 -0.1099427 0.8682805 -0.4837372 -0.1775433 0.8566825 -0.4843278 -0.1792644 0.858094 -0.4811851 -0.2514656 0.8396627 -0.4813852 -0.2519963 0.8400246 -0.4804756 -0.3176599 0.817391 -0.4805873 -0.3149912 0.8158953 -0.4848665 -0.3848098 0.7850594 -0.48539 -0.3826049 0.7840389 -0.4887705 -0.4460284 0.7498357 -0.4886769 -0.4470778 0.7502229 -0.4871214 -0.5065043 0.7114252 -0.4871629 -0.5106172 0.7125258 -0.4812247 -0.5675539 0.6678857 -0.4814679 -0.5650941 0.6674382 -0.484969 -0.6182394 0.6183283 -0.485232 -0.6182728 0.6182646 -0.4852709 -0.6664131 0.5663015 -0.4849705 -0.668964 0.5663391 -0.4814014 -0.7123346 0.5109386 -0.4811665 -0.7129883 0.5109313 -0.4802051 -0.7539978 0.448548 -0.4798876 -0.7529116 0.4486335 -0.4815105 -0.7878823 0.3842674 -0.4812279 -0.787613 0.3844269 -0.4815411 -0.8153907 0.320773 -0.4819158 -0.8164068 0.3204483 -0.480409 -0.8412278 0.2479568 -0.480472 -0.8420475 0.2477511 -0.4791405 -0.8585358 0.1816489 -0.4794996 -0.8566223 0.1827729 -0.4824856 -0.8690921 0.1081473 -0.4826832 -0.8709705 0.1070418 -0.4795336 -0.877025 0.03484773 -0.4791795 -0.8729848 0.03801661 -0.4862636 -0.8730864 -0.03462588 -0.4863345 -0.8770594 -0.03810572 -0.4788684 -0.8713875 -0.1085249 -0.4784416 -0.8693321 -0.1062874 -0.4826641 -0.8574975 -0.1784098 -0.4825642 -0.8580799 -0.1793064 -0.4811945 -0.8396229 -0.2514102 -0.4814835 -0.8390311 -0.2505326 -0.4829702 -0.81638 -0.3158321 -0.4835016 -0.8168949 -0.3169355 -0.4819073 -0.786228 -0.387217 -0.4815688 -0.7839937 -0.3825685 -0.4888714 -0.7498112 -0.4459426 -0.4887927 -0.7501322 -0.4471526 -0.4871923 -0.7115435 -0.5064535 -0.487043 -0.7125443 -0.5106988 -0.4811106 -0.667989 -0.567677 -0.4811795 -0.667989 -0.567677 -0.4811794 -0.667989 -0.567677 -0.4811794 -0.6674382 -0.5651301 -0.4849273 -0.6183074 -0.6182184 -0.4852855 -0.6182261 -0.6182508 -0.4853479 -0.5662707 -0.666553 -0.4848141 -0.5663099 -0.6688485 -0.4815963 -0.5110166 -0.7122857 -0.4811561 -0.5108883 -0.7129995 -0.4802344 -0.4485918 -0.7539343 -0.4799464 -0.4486963 -0.7529434 -0.4814022 -0.3842609 -0.7879365 -0.4811443 -0.3842899 -0.7876727 -0.4815526 -0.3207472 -0.8154039 -0.4819105 -0.320463 -0.8163268 -0.4805352 -0.2480776 -0.8411679 -0.4805144 -0.2499055 -0.836809 -0.4871324 -0.1808276 -0.8540281 -0.4877882 -0.1790508 -0.8573337 -0.4826176 -0.1081364 -0.8691822 -0.4825233 -0.1070082 -0.8709328 -0.4796096 -0.03492224 -0.8771073 -0.4790232 -0.03795409 -0.8729661 -0.4863019 0.03462284 -0.8731314 -0.4862539 0.03812485 -0.8770704 -0.4788467 0.1084405 -0.8714477 -0.4783509 0.1063382 -0.8693264 -0.4826635 0.1784977 -0.8575354 -0.4824641 0.1791905 -0.8580028 -0.4813753 0.2504211 -0.8399006 -0.4815146 0.2509666 -0.8402651 -0.4805939 0.3176872 -0.817461 -0.4804502 0.3168027 -0.8169841 -0.4818435 0.3872758 -0.7861214 -0.4816955 0.4308935 -0.8874437 -0.1636295 0.5050522 -0.8473568 -0.1640391 0.5050522 -0.8473569 -0.1640391 0.5050522 -0.8473569 -0.1640391 0.5066 -0.8471992 -0.1600312 0.5749989 -0.802327 -0.1601493 0.57233 -0.8029747 -0.1663432 0.6371455 -0.7526401 -0.1660673 0.6343143 -0.7534592 -0.1730452 0.6943767 -0.6986082 -0.1725911 0.6974174 -0.6974902 -0.1646707 0.754945 -0.6347361 -0.1648277 0.7542992 -0.6351649 -0.1661269 0.8014782 -0.5743949 -0.1664429 0.8006768 -0.5747909 -0.1689145 0.8466817 -0.5045047 -0.1691307 0.848517 -0.5032405 -0.1636098 0.8866086 -0.4325796 -0.1637071 0.8849673 -0.4340573 -0.1686041 0.9175707 -0.3600449 -0.1686175 0.9186635 -0.3589907 -0.1648725 0.9451003 -0.2822788 -0.1646335 0.9458581 -0.281311 -0.1619158 0.945858 -0.281311 -0.1619158 0.945858 -0.281311 -0.1619158 0.9660932 -0.2017142 -0.1611692 0.963968 -0.2049248 -0.1696216 0.9782629 -0.1199234 -0.1691746 0.9788116 -0.119122 -0.1665466 0.9850629 -0.04294025 -0.166755 0.9851657 -0.04242354 -0.1662794 0.9851657 -0.04242354 -0.1662795 0.9851657 -0.04242354 -0.1662795 0.9853198 0.03856861 -0.1663054 0.9852526 0.03839927 -0.1667424 0.9782527 0.1236358 -0.1665412 0.9782526 0.1236358 -0.1665412 0.9782527 0.1236358 -0.1665412 0.9780967 0.1230385 -0.1678945 0.9650694 0.2015086 -0.1674382 0.9650694 0.2015086 -0.1674383 0.9650694 0.2015085 -0.1674383 0.9647235 0.1994786 -0.1718046 0.9438979 0.2819197 -0.1719832 0.9438725 0.282092 -0.1718397 0.9186277 0.3562438 -0.1709197 0.9186169 0.3573032 -0.1687531 0.8859406 0.4320785 -0.1685754 0.8857094 0.4344233 -0.1636928 0.8474776 0.504966 -0.1636804 0.8476973 0.50276 -0.1692391 0.8011348 0.5741611 -0.168885 0.8011348 0.5741611 -0.168885 0.8011349 0.5741611 -0.168885 0.8009405 0.5751541 -0.1664094 0.7546635 0.6346749 -0.1663455 0.7545676 0.635217 -0.1647032 0.6952319 0.6996552 -0.1647281 0.6965729 0.6964683 -0.1723898 0.6363649 0.751731 -0.1730327 0.6350873 0.7543677 -0.1661134 0.574316 0.8015343 -0.1664455 0.574899 0.8006229 -0.1688024 0.5045987 0.8466085 -0.1692167 0.5031604 0.8485645 -0.1636099 0.432596 0.8865988 -0.1637175 0.4353291 0.8834275 -0.1733331 0.3598877 0.9168683 -0.1727235 0.3598877 0.9168683 -0.1727235 0.3598877 0.9168683 -0.1727235 0.3574386 0.9192814 -0.1648011 0.2822132 0.9451146 -0.1646645 0.2812299 0.9459105 -0.1617501 0.2018343 0.9660461 -0.1613005 0.2047503 0.9640084 -0.1696032 0.1201339 0.9782275 -0.1692305 0.1201339 0.9782275 -0.1692304 0.1201339 0.9782275 -0.1692304 0.1191618 0.9787987 -0.1665941 0.04282194 0.9851124 -0.1664929 0.04263949 0.9851503 -0.166315 -0.03855979 0.9853075 -0.1663802 -0.04271233 0.9868651 -0.1557983 -0.1240956 0.9799811 -0.1556832 -0.1191385 0.9785958 -0.1677989 -0.2015964 0.9650831 -0.167253 -0.1997327 0.9647119 -0.1715754 -0.1997334 0.9647116 -0.1715753 -0.1997327 0.9647118 -0.1715754 -0.2830488 0.9435254 -0.1721723 -0.281778 0.9433911 -0.1749696 -0.3545695 0.9185099 -0.1749866 -0.3545695 0.9185098 -0.1749866 -0.3545695 0.9185099 -0.1749866 -0.3615391 0.9187203 -0.1588787 -0.4329775 0.8873134 -0.158762 -0.4308773 0.8874104 -0.1638525 -0.5050028 0.8474432 -0.1637444 -0.5066057 0.8472088 -0.1599622 -0.575015 0.8023496 -0.1599782 -0.5723484 0.8029621 -0.1663407 -0.6371641 0.7526621 -0.1658971 -0.6342942 0.7534611 -0.1731109 -0.6966127 0.6964588 -0.1722671 -0.6994653 0.6953772 -0.1649208 -0.7527785 0.6372904 -0.1648798 -0.7523387 0.6374871 -0.1661227 -0.8015016 0.5744116 -0.1662724 -0.8006231 0.5749266 -0.1687071 -0.8466691 0.5044973 -0.1692157 -0.8485079 0.5032351 -0.1636735 -0.8866086 0.4325796 -0.1637071 -0.8849677 0.4340712 -0.168566 -0.91754 0.3600415 -0.1687914 -0.9186921 0.3589801 -0.1647365 -0.9462553 0.2784186 -0.1645718 -0.9443156 0.280609 -0.1718338 -0.9634704 0.2055473 -0.1716837 -0.9639685 0.2049236 -0.1696206 -0.9782639 0.1199209 -0.1691709 -0.9788099 0.1191218 -0.1665572 -0.9850648 0.04294031 -0.1667444 -0.9851657 0.04242354 -0.1662794 -0.9851657 0.04242354 -0.1662795 -0.9851657 0.04242354 -0.1662795 -0.9851438 -0.04294377 -0.1662757 -0.9850717 -0.04275375 -0.1667507 -0.9787453 -0.1196322 -0.1665712 -0.9786075 -0.1189231 -0.1678832 -0.9649993 -0.2018414 -0.1674406 -0.9656103 -0.2040184 -0.1611627 -0.9455928 -0.2824259 -0.1615238 -0.9455893 -0.2824301 -0.1615371 -0.9201968 -0.3568522 -0.1609178 -0.92018 -0.3579112 -0.1586455 -0.8873111 -0.4329224 -0.1589253 -0.8874427 -0.430922 -0.16356 -0.8474835 -0.5049825 -0.1635982 -0.8471372 -0.506744 -0.1599035 -0.8024207 -0.5748947 -0.1600539 -0.8029981 -0.5722618 -0.1664654 -0.7525203 -0.6372467 -0.166223 -0.7525042 -0.6376556 -0.1647204 -0.6974403 -0.6974954 -0.1645518 -0.6986741 -0.6943905 -0.1722683 -0.6363909 -0.7517101 -0.1730279 -0.6350711 -0.7543808 -0.1661164 -0.5743086 -0.8015393 -0.1664465 -0.5749267 -0.8006159 -0.168741 -0.5045987 -0.8466085 -0.1692167 -0.5031359 -0.8485693 -0.1636599 -0.4326261 -0.8866158 -0.1635454 -0.4339916 -0.8849886 -0.1686612 -0.3601007 -0.9175211 -0.1687677 -0.3589128 -0.9187015 -0.1648305 -0.2822901 -0.9450871 -0.1646901 -0.2812048 -0.9459404 -0.161619 -0.2017825 -0.9661138 -0.1609603 -0.2047379 -0.9640375 -0.1694527 -0.2047379 -0.9640375 -0.1694527 -0.2047379 -0.9640375 -0.1694528 -0.120152 -0.9782236 -0.1692404 -0.1191675 -0.9788457 -0.1663143 -0.04281944 -0.9850549 -0.1668336 -0.04264193 -0.9852074 -0.1659756 0.04282921 -0.985136 -0.1663512 0.03815007 -0.9833383 -0.177737 0.1194486 -0.9766859 -0.1783726 0.1238363 -0.9779877 -0.1679428 0.2016182 -0.965017 -0.1676084 0.2016181 -0.965017 -0.1676084 0.2016182 -0.965017 -0.1676084 0.1996893 -0.9646816 -0.1717953 0.2819328 -0.9438912 -0.1719979 0.2805839 -0.9437423 -0.1749946 0.3560464 -0.917932 -0.1750197 0.3629833 -0.9181959 -0.1586177 0.4329534 -0.887264 -0.1591041 -0.4668216 -0.1819579 -0.8654299 -0.4787563 -0.1417019 -0.866437 -0.49869 -0.02143806 -0.8665154 -0.4886589 0.1029824 -0.866376 -0.4125459 0.2800707 -0.8668138 -0.3221451 0.3805468 -0.8668372 -0.3221451 0.3805466 -0.8668372 -0.3221451 0.3805469 -0.8668373 -0.2901523 0.4080933 -0.8656047 -0.2547858 0.4283329 -0.8669575 -0.1857 0.4644582 -0.8659065 -0.1416956 0.4788235 -0.866401 -0.02133488 0.4986848 -0.8665209 0.1030403 0.4887177 -0.8663358 0.2900251 0.4060881 -0.86659 0.2900251 0.4060881 -0.8665899 0.2900251 0.4060882 -0.8665899 0.3806288 0.321865 -0.8669053 0.3806288 0.3218653 -0.8669051 0.3806288 0.3218659 -0.8669049 0.4084798 0.2906212 -0.865265 0.4267174 0.2559822 -0.8674015 0.4660536 0.1811572 -0.8660116 0.4788075 0.1416296 -0.8664206 0.4996961 0.02139121 -0.8659366 0.4678345 -0.1753095 -0.8662549 0.4062651 -0.2901408 -0.8664682 0.3220576 -0.3805754 -0.8668572 0.3220576 -0.3805752 -0.8668573 0.3220576 -0.3805754 -0.8668572 0.2905727 -0.4083851 -0.865326 0.254768 -0.4284119 -0.8669236 0.185721 -0.4643443 -0.8659631 0.1416568 -0.4788458 -0.8663948 0.02132505 -0.4987201 -0.8665007 -0.1030476 -0.488652 -0.8663721 -0.2901033 -0.4062003 -0.8665112 -0.3806464 -0.3219009 -0.8668842 -0.3806464 -0.3219012 -0.8668841 -0.3806464 -0.3219013 -0.8668841 -0.4084798 -0.2906212 -0.865265 -0.4284111 -0.2548404 -0.8669028 0.162978 -0.07047408 -0.9841096 -0.05723637 0.2248376 -0.9727138 -0.224771 -0.05693447 -0.972747 0.2245591 0.0572313 -0.9727784 0.1595858 0.1759011 -0.9713863 0.2881782 0.1976649 -0.9369536 0.1662492 0.1610391 -0.9728451 0.1662492 0.1610389 -0.9728451 0.1662492 0.161039 -0.9728452 0.2363246 0.1811131 -0.9546459 0.2363245 0.181113 -0.9546459 0.2363244 0.181113 -0.954646 0.2610871 0.01780647 -0.9651511 0.1659384 0.1640792 -0.9723901 0.2102774 0.01439058 -0.9775359 0.1791467 -0.01467275 -0.983713 0.1751207 -0.02847707 -0.9841351 0.1759178 -0.02205848 -0.9841578 0.1759178 -0.02205848 -0.9841578 0.1759178 -0.02205854 -0.9841578 0.1757872 -0.1594614 -0.9714273 0.1967168 -0.2865929 -0.9376391 0.1534367 -0.1704728 -0.9733428 0.1534368 -0.1704728 -0.9733428 0.1534368 -0.1704727 -0.9733428 0.1693851 -0.2376127 -0.9564774 0.01972234 -0.2603159 -0.9653221 0.1570526 -0.1701602 -0.9728206 0.01606571 -0.2121064 -0.9771146 -0.01465821 -0.1791526 -0.9837121 -0.02844953 -0.1750944 -0.9841405 -0.02201551 -0.1758459 -0.9841716 -0.02201551 -0.175846 -0.9841716 -0.02201551 -0.175846 -0.9841716 -0.1595672 -0.1758145 -0.971405 -0.2881669 -0.1976572 -0.9369586 -0.1703804 -0.1533161 -0.973378 -0.2378134 -0.1695852 -0.956392 -0.2603095 -0.01973968 -0.9653235 -0.1702455 -0.1568929 -0.9728316 -0.212101 -0.01604586 -0.9771161 -0.1791319 0.01467084 -0.9837157 -0.1748763 0.03053146 -0.984117 -0.1757763 0.02175301 -0.9841898 -0.1757763 0.02175301 -0.9841898 -0.1757763 0.02175301 -0.9841898 -0.1766123 0.1630625 -0.9706795 -0.1975569 0.2881495 -0.9369851 -0.1616447 0.169739 -0.9721419 -0.1782166 0.2364144 -0.9551687 -0.01972234 0.2603159 -0.9653221 -0.1569236 0.1706262 -0.9727599 -0.0160681 0.2121382 -0.9771076 0.01467472 0.1791595 -0.9837107 0.02847468 0.1751405 -0.9841316 0.02190482 0.1761026 -0.9841281 0.02190482 0.1761028 -0.9841281 0.02190488 0.1761028 -0.9841281 -0.4085062 -0.2905492 -0.8652767 -0.4216588 -0.2596921 -0.8687716 -0.3597776 -0.2216398 -0.9063311 -0.3826084 -0.1794103 -0.9063239 -0.3106894 -0.145682 -0.9392811 -0.3264733 -0.1056876 -0.9392792 -0.3805266 -0.3220571 -0.8668788 -0.3842408 -0.3112767 -0.8691753 -0.3279789 -0.2657585 -0.9065331 -0.3587955 -0.2221376 -0.9065985 -0.2922968 -0.1810712 -0.9390293 -0.3118765 -0.1446511 -0.9390469 -0.3229076 -0.3816081 -0.8660867 -0.3229023 -0.3815695 -0.8661057 -0.3491587 -0.3491075 -0.8696047 -0.3471615 -0.35616 -0.867542 -0.2956169 -0.3031968 -0.9059153 -0.3307033 -0.2646144 -0.9058778 -0.2683658 -0.2147 -0.9390867 -0.2922481 -0.1809541 -0.9390669 -0.290825 -0.4055271 -0.8665846 -0.2999473 -0.3922564 -0.8695784 -0.2568778 -0.3359504 -0.906174 -0.2944076 -0.3035133 -0.906203 -0.238736 -0.2461625 -0.9393664 -0.2663649 -0.2157288 -0.9394206 -0.2197409 -0.4493271 -0.865921 -0.2207078 -0.4487683 -0.865965 -0.25331 -0.4259561 -0.8685595 -0.2522782 -0.4275969 -0.8680534 -0.2149981 -0.3643957 -0.9060859 -0.2573656 -0.3359144 -0.9060488 -0.2088634 -0.2725334 -0.9392027 -0.2400171 -0.2457001 -0.939161 -0.1944595 -0.1990773 -0.9604967 -0.2161568 -0.1749949 -0.9605484 -0.2145162 -0.1583591 -0.9637973 -0.2269615 -0.1405574 -0.9637075 -0.230386 -0.1654516 -0.9589307 -0.2559266 -0.1187226 -0.9593783 -0.24985 -0.09343624 -0.9637659 -0.254212 -0.08232176 -0.9636387 -0.2613056 -0.1004051 -0.9600199 -0.2621094 -0.09724295 -0.9601263 -0.1507596 -0.2146199 -0.9649922 -0.1589277 -0.2075762 -0.9652223 -0.208667 -0.2725855 -0.9392313 -0.1739438 -0.2958452 -0.9392653 -0.2142799 -0.3644263 -0.9062438 -0.168771 -0.3877356 -0.9061884 -0.1971476 -0.4528962 -0.869493 -0.1414589 -0.4760425 -0.8679707 -0.178842 -0.4666682 -0.8661619 -0.1816169 -0.4658254 -0.8660382 -0.1072624 -0.4876852 -0.8664053 -0.1408183 -0.4759363 -0.868133 -0.1199513 -0.4054246 -0.9062244 -0.1682391 -0.3876234 -0.9063354 -0.1366612 -0.3149367 -0.9392223 -0.1741477 -0.2958379 -0.9392297 -0.1327688 -0.2255787 -0.9651356 -0.1599174 -0.2072991 -0.9651185 -0.1105202 -0.1432082 -0.9835023 -0.2240297 -0.05651897 -0.9729422 -0.2240297 -0.05651891 -0.9729422 -0.2240297 -0.05651903 -0.9729422 -0.08516168 -0.157708 -0.9838068 -0.09072142 -0.1544036 -0.983834 -0.1325742 -0.2255979 -0.9651579 -0.1035984 -0.2403035 -0.9651538 -0.1357467 -0.3149381 -0.9393545 -0.09813338 -0.3285772 -0.9393651 -0.1211267 -0.4055631 -0.9060061 -0.0715593 -0.4172075 -0.9059897 -0.08342695 -0.4864047 -0.8697416 -0.0202431 -0.4949557 -0.8686825 -0.05842345 -0.4965495 -0.8660401 -0.06199377 -0.4959505 -0.8661351 0.01474171 -0.4987197 -0.866638 -0.02321165 -0.4963786 -0.8677958 -0.01977312 -0.4227237 -0.9060429 -0.07134741 -0.4170712 -0.906069 -0.05792415 -0.338577 -0.9391542 -0.0996012 -0.3287875 -0.9391371 -0.07592761 -0.2506868 -0.9650861 -0.1043674 -0.2401907 -0.965099 -0.07078385 -0.1629506 -0.9840919 -0.08672839 -0.1547406 -0.9841411 -0.08480262 -0.1591765 -0.9836012 -0.06960487 -0.1631397 -0.9841447 -0.04964119 -0.170423 -0.9841198 -0.07296299 -0.2505068 -0.9653615 -0.04290944 -0.2575035 -0.9653242 -0.05635124 -0.3382006 -0.9393854 -0.01631206 -0.3425726 -0.9393498 -0.02013581 -0.4228438 -0.905979 0.03049242 -0.4222527 -0.9059652 0.03559023 -0.492839 -0.8693925 0.1007788 -0.4837306 -0.8693954 0.06411975 -0.4955243 -0.8662242 0.05882775 -0.4962368 -0.8661919 0.1489799 -0.4767074 -0.8663459 0.14898 -0.4767073 -0.866346 0.1489799 -0.4767076 -0.8663457 0.09488761 -0.4888279 -0.8672046 0.08058631 -0.4151644 -0.9061702 0.03118586 -0.4217836 -0.9061601 0.02530282 -0.3422697 -0.9392611 -0.01694464 -0.3428092 -0.9392523 -0.01293307 -0.261417 -0.9651394 -0.04564493 -0.2579721 -0.9650737 -0.03100478 -0.1752909 -0.9840284 -0.05242097 -0.1702638 -0.9840032 0.180671 -0.4662387 -0.8660137 0.1530892 -0.4699245 -0.8693301 0.1307262 -0.4012638 -0.9065861 0.08204883 -0.4139646 -0.9065877 0.06683158 -0.3370894 -0.9390977 0.02446734 -0.342823 -0.9390814 0.01862496 -0.2607035 -0.9652393 -0.01177233 -0.2612252 -0.9652062 -0.008096516 -0.1794573 -0.9837325 -0.01222681 -0.1772786 -0.9840848 0.2193033 -0.4475585 -0.8669472 0.2098469 -0.44815 -0.8689798 0.1792663 -0.382838 -0.9062554 0.1298 -0.4021912 -0.9063081 0.10566 -0.3273658 -0.9389716 0.06603688 -0.3377073 -0.9389318 0.05565667 -0.2846599 -0.9570116 -0.002287328 -0.2554122 -0.9668296 0.2904167 -0.4085996 -0.8652772 0.2597559 -0.4216758 -0.8687442 0.2218871 -0.3601939 -0.9061052 0.1788666 -0.3832942 -0.9061415 0.1450941 -0.3109461 -0.9392872 0.1073603 -0.3258859 -0.9392935 0.3220236 -0.3805988 -0.8668595 0.311278 -0.3842626 -0.8691654 0.2657212 -0.3279524 -0.9065536 0.2229945 -0.3582608 -0.9065996 0.1815007 -0.2915573 -0.9391762 0.1445487 -0.3115823 -0.9391604 0.3822415 -0.3231232 -0.8657268 0.3822416 -0.3231232 -0.8657268 0.3822076 -0.3232875 -0.8656805 0.3496558 -0.3496749 -0.8691768 0.3552211 -0.3480499 -0.8675709 0.3024107 -0.2963401 -0.9059417 0.2645556 -0.330717 -0.9058899 0.2146813 -0.268384 -0.9390857 0.1810131 -0.2922528 -0.9390541 0.4055293 -0.290816 -0.8665864 0.3934803 -0.2990566 -0.8693322 0.3361559 -0.2555831 -0.9064638 0.3030789 -0.2939459 -0.9064983 0.2461425 -0.238707 -0.939379 0.2157009 -0.266353 -0.9394302 0.4492745 -0.2197274 -0.8659517 0.4501408 -0.2181508 -0.8659005 0.4501408 -0.2181508 -0.8659005 0.4501408 -0.2181508 -0.8659005 0.4248002 -0.254036 -0.8689135 0.4275954 -0.252241 -0.868065 0.3648123 -0.215251 -0.9058582 0.3356848 -0.2585952 -0.9057838 0.2724429 -0.2098634 -0.939006 0.2451733 -0.2414976 -0.9389191 0.1982719 -0.1951982 -0.9605134 0.1750446 -0.216148 -0.9605413 0.158354 -0.2145873 -0.9637824 0.1405697 -0.2269611 -0.9637058 0.1672513 -0.2306631 -0.9585518 0.1192187 -0.2570096 -0.9590271 0.09196436 -0.2504758 -0.963745 0.08358985 -0.253672 -0.9636718 0.09966015 -0.2599427 -0.9604675 0.09681648 -0.2608454 -0.9605136 0.4650918 -0.1824946 -0.866248 0.452915 -0.1971765 -0.8694766 0.3877208 -0.1687583 -0.9061972 0.3648927 -0.2134186 -0.9062592 0.295932 -0.1730927 -0.9393952 0.2730788 -0.2072144 -0.9394094 0.2079864 -0.1578398 -0.9653125 0.2134679 -0.1512805 -0.9651662 0.0601412 -0.2233036 -0.9728919 0.06014108 -0.2233036 -0.9728919 0.06014114 -0.2233036 -0.9728919 0.4886717 -0.1030804 -0.866357 0.4896728 -0.09775626 -0.8664088 0.4740608 -0.1431213 -0.8687824 0.4761564 -0.1409298 -0.8679942 0.4053564 -0.1199191 -0.9062592 0.3877037 -0.168276 -0.9062941 0.3152319 -0.1367452 -0.9391111 0.2957364 -0.1751895 -0.939068 0.2251768 -0.1333569 -0.9651484 0.2072579 -0.1598721 -0.9651348 0.1432897 -0.1105532 -0.9834868 0.05843859 -0.2216684 -0.9733695 0.1577091 -0.08508241 -0.9838134 0.1544336 -0.09077715 -0.9838241 0.2253338 -0.1324581 -0.9652355 0.2397319 -0.1041568 -0.9652358 0.3151598 -0.1369566 -0.9391045 0.3293246 -0.09839206 -0.9390764 0.4056317 -0.1211504 -0.9059721 0.4171687 -0.07160872 -0.9060036 0.4864047 -0.08338862 -0.8697453 0.4950493 -0.02243351 -0.8685752 0.4963302 -0.05905139 -0.8661233 0.4960188 -0.06202709 -0.8660936 0.4995725 0.02952617 -0.8657688 0.4962529 -0.02505183 -0.8678165 0.4225438 -0.02132338 -0.9060916 0.4171029 -0.0712583 -0.9060616 0.3385886 -0.05788385 -0.9391524 0.3292231 -0.09781873 -0.9391717 0.2505774 -0.07440972 -0.9652327 0.2397143 -0.1041485 -0.9652411 0.1629557 -0.07078504 -0.984091 0.1547857 -0.0867033 -0.9841362 0.1589627 -0.08487367 -0.9836297 0.1589627 -0.08487355 -0.9836297 0.1589627 -0.08487361 -0.9836297 0.1700477 -0.05093419 -0.9841187 0.1700872 -0.05092883 -0.9841122 0.2506327 -0.07504308 -0.9651694 0.2580474 -0.04300326 -0.9651747 0.3381693 -0.05639892 -0.9393939 0.3425757 -0.01629561 -0.9393489 0.4220056 -0.02004855 -0.9063715 0.421305 0.03191566 -0.9063573 0.4931202 0.03735446 -0.869159 0.4840487 0.1003758 -0.869265 0.4954828 0.06470054 -0.8662048 0.4962624 0.05897623 -0.8661671 0.4769138 0.1488196 -0.8662598 0.4769138 0.1488198 -0.8662598 0.4769138 0.1488198 -0.8662597 0.4888387 0.09490489 -0.8671965 0.4151524 0.08056807 -0.9061774 0.4217933 0.03118318 -0.9061557 0.3422909 0.02530258 -0.9392533 0.3428291 -0.01696866 -0.9392445 0.2614645 -0.01293241 -0.9651265 0.2581991 -0.04369813 -0.965103 0.1751664 -0.02967739 -0.9840915 0.1699129 -0.05220472 -0.9840753 0.4663474 0.1803936 -0.8660129 0.4663474 0.1803937 -0.8660129 0.4663473 0.1803937 -0.8660129 0.4699323 0.1531032 -0.8693234 0.4020796 0.1310201 -0.906182 0.4152334 0.0804454 -0.9061511 0.3373211 0.06535142 -0.9391186 0.34273 0.02451479 -0.9391141 0.2607705 0.01862639 -0.9652212 0.2611124 -0.0118038 -0.9652363 0.1794269 -0.008146762 -0.9837376 0.1772536 -0.01220685 -0.9840896 0.4467796 0.2188996 -0.867451 0.4473206 0.2095115 -0.8694879 0.3828309 0.1792963 -0.9062524 0.401603 0.1314262 -0.9063345 0.3263367 0.1068271 -0.9391978 0.3369333 0.06591576 -0.9392184 0.2846416 0.05567264 -0.9570161 0.2553788 -0.002305984 -0.9668384 0.4085349 0.2903945 -0.8653152 0.4216837 0.259761 -0.8687389 0.3604436 0.2220442 -0.9059674 0.3841229 0.1782777 -0.9059067 0.311195 0.1444516 -0.9393038 0.3258383 0.1072999 -0.9393169 0.3805894 0.3220294 -0.8668615 0.3842335 0.3113315 -0.8691591 0.3285477 0.2661582 -0.9062099 0.3594418 0.2225884 -0.9062318 0.2917341 0.1806732 -0.9392809 0.3113108 0.1443861 -0.9392755 0.322923 0.3815013 -0.866128 0.3229196 0.3817899 -0.8660021 0.3491355 0.3490843 -0.8696233 0.347179 0.3561897 -0.8675228 0.2955681 0.3032198 -0.9059235 0.3297598 0.2656416 -0.9059212 0.2672147 0.215223 -0.9392952 0.2917116 0.1807115 -0.9392805 0.290825 0.4055271 -0.8665846 0.2999541 0.3922556 -0.8695765 0.2568921 0.3359491 -0.9061704 0.2944174 0.3035234 -0.9061965 0.2390822 0.2465195 -0.9391848 0.2678059 0.2149822 -0.939182 0.2182617 0.4495203 -0.8661949 0.2204863 0.4484333 -0.8661949 0.253988 0.4246906 -0.8689811 0.2522676 0.4276592 -0.8680257 0.2152154 0.3648449 -0.9058536 0.258625 0.3356291 -0.9057959 0.2095692 0.271971 -0.9392085 0.2390066 0.2465753 -0.9391893 0.1929985 0.1990947 -0.9607877 0.215972 0.1733309 -0.9608916 0.2145414 0.1583213 -0.9637979 0.2269505 0.1405506 -0.963711 0.2306594 0.1673443 -0.9585365 0.2570046 0.1191744 -0.959034 0.2508666 0.09399205 -0.9634478 0.2548815 0.08395379 -0.963321 0.2604291 0.09813696 -0.9604925 0.2608057 0.09675925 -0.9605302 0.150749 0.2146049 -0.9649972 0.1589319 0.2075664 -0.9652238 0.2084069 0.2722154 -0.9393963 0.1731221 0.2959437 -0.939386 0.2134585 0.3648785 -0.9062556 0.1687871 0.387694 -0.9062033 0.1971531 0.4529433 -0.8694671 0.1414613 0.4760342 -0.8679748 0.1753723 0.4679567 -0.8661762 0.1825088 0.4649884 -0.8663004 0.1072779 0.4877554 -0.8663638 0.1408131 0.4759092 -0.8681487 0.119935 0.4054083 -0.9062339 0.168232 0.3876595 -0.9063213 0.1367746 0.3151979 -0.9391182 0.1751707 0.2956843 -0.9390879 0.1333737 0.2251715 -0.9651473 0.1599017 0.2072997 -0.9651209 0.1104927 0.1431976 -0.983507 0.2240751 0.05664908 -0.9729242 0.08516168 0.157708 -0.9838068 0.09074229 0.1543474 -0.9838408 0.1324419 0.2253457 -0.965235 0.1029949 0.2402981 -0.9652197 0.1350668 0.3152235 -0.9393568 0.09813511 0.328583 -0.9393631 0.1211287 0.4055699 -0.9060027 0.07156127 0.4172191 -0.9059841 0.0834316 0.4863713 -0.8697598 0.02014839 0.4950048 -0.8686567 0.05928778 0.4963256 -0.8661097 0.06199377 0.4959505 -0.8661351 -0.01464509 0.4987199 -0.8666396 -0.01464504 0.4987199 -0.8666396 -0.01464509 0.4987201 -0.8666394 0.02321225 0.4963917 -0.8677883 0.01977384 0.4227384 -0.9060361 0.07134044 0.4171042 -0.9060544 0.05791968 0.3386245 -0.9391373 0.0995751 0.3287863 -0.9391403 0.07591259 0.2506758 -0.9650902 0.1043492 0.2402495 -0.9650862 0.07077592 0.1629508 -0.9840924 0.08674019 0.154782 -0.9841336 0.08477145 0.1589465 -0.9836411 0.07048153 0.1629821 -0.9841083 0.04967361 0.1705022 -0.9841045 0.07296299 0.2505068 -0.9653615 0.04315447 0.2574081 -0.9653387 0.0567097 0.3382472 -0.939347 0.0163061 0.3425669 -0.939352 0.02013665 0.4227868 -0.9060055 -0.03049242 0.4222527 -0.9059652 -0.0355916 0.4928585 -0.8693813 -0.1003851 0.4840444 -0.8692663 -0.06486439 0.4956234 -0.8661122 -0.06486439 0.4956233 -0.8661122 -0.06486439 0.4956233 -0.8661122 -0.05882728 0.4963581 -0.8661224 -0.1489799 0.4767074 -0.8663459 -0.14898 0.4767073 -0.866346 -0.1489799 0.4767076 -0.8663457 -0.09488761 0.4888279 -0.8672046 -0.08059167 0.415131 -0.906185 -0.03116899 0.4218162 -0.9061455 -0.02529412 0.3422769 -0.9392587 0.01686328 0.3428295 -0.9392463 0.01286172 0.2614598 -0.9651287 0.04561036 0.2578679 -0.965103 0.03100579 0.1752965 -0.9840273 0.05180412 0.1704273 -0.9840075 -0.1806141 0.4661839 -0.866055 -0.1530805 0.4699466 -0.8693195 -0.1307175 0.4012984 -0.906572 -0.08206707 0.413964 -0.9065864 -0.06683903 0.3370804 -0.9391003 -0.02448374 0.3428078 -0.9390865 -0.01862478 0.2607005 -0.9652401 0.01177161 0.2612091 -0.9652105 0.00809741 0.179427 -0.983738 0.01222652 0.177275 -0.9840855 -0.219285 0.4475604 -0.866951 -0.2098471 0.4481747 -0.8689671 -0.1792502 0.3828281 -0.9062627 -0.1298211 0.4021832 -0.9063086 -0.1056674 0.3273885 -0.9389629 -0.06603109 0.3376777 -0.9389429 -0.05565428 0.2845849 -0.9570341 0.002278804 0.2553824 -0.9668375 -0.2901101 0.4078478 -0.8657345 -0.260336 0.4209229 -0.8689356 -0.2223331 0.3594549 -0.9062892 -0.1793982 0.3825935 -0.9063324 -0.1456835 0.3107009 -0.939277 -0.1073415 0.3258288 -0.9393154 -0.3220155 0.380577 -0.8668721 -0.3102006 0.3845629 -0.8694176 -0.2653111 0.3289136 -0.9063255 -0.2224686 0.3591749 -0.906367 -0.1810079 0.2922711 -0.9390494 -0.144675 0.3118544 -0.9390506 -0.3816339 0.3228627 -0.866092 -0.3816533 0.3228186 -0.8661 -0.3491337 0.349229 -0.8695659 -0.3561162 0.347148 -0.8675653 -0.3031819 0.2956147 -0.905921 -0.2645578 0.3307168 -0.9058894 -0.2146888 0.2683933 -0.9390814 -0.181029 0.2922784 -0.9390431 -0.4055346 0.2909107 -0.8665522 -0.392253 0.2999376 -0.8695833 -0.3359498 0.256954 -0.9061526 -0.3035635 0.2944159 -0.9061835 -0.246151 0.2387152 -0.9393747 -0.2157198 0.2663761 -0.9394193 -0.44924 0.2199697 -0.8659082 -0.44924 0.2199697 -0.8659081 -0.44924 0.2199698 -0.8659082 -0.4501808 0.2178891 -0.8659455 -0.4236726 0.2555761 -0.8690123 -0.428395 0.2526516 -0.8675512 -0.3641442 0.2148568 -0.9062206 -0.3359118 0.2569254 -0.9061747 -0.2727325 0.208648 -0.9391928 -0.2456741 0.2400734 -0.9391533 -0.1990432 0.1944917 -0.9604972 -0.175025 0.2161238 -0.9605503 -0.1583454 0.2145757 -0.9637864 -0.1405697 0.2269611 -0.9637058 -0.1672359 0.2305871 -0.9585728 -0.1192077 0.2569859 -0.9590349 -0.09195929 0.2504619 -0.9637491 -0.08358985 0.253672 -0.9636718 -0.09968745 0.2599923 -0.9604513 -0.09678727 0.2608461 -0.9605163 -0.2146072 0.1508242 -0.9649849 -0.207587 0.158886 -0.9652268 -0.2727634 0.2087885 -0.9391526 -0.2957628 0.1744657 -0.9391945 -0.364157 0.2148262 -0.9062227 -0.3877329 0.1687573 -0.9061921 -0.4528743 0.1972125 -0.8694896 -0.4760265 0.1415006 -0.8679726 -0.4676514 0.175599 -0.8662951 -0.4676514 0.175599 -0.8662951 -0.4676514 0.1755989 -0.8662951 -0.4651217 0.1824989 -0.8662309 -0.4876513 0.1073057 -0.8664189 -0.4759243 0.1408044 -0.8681418 -0.4053947 0.1198728 -0.9062482 -0.387657 0.1683243 -0.9063051 -0.3151971 0.1367619 -0.9391204 -0.2957088 0.1752193 -0.9390711 -0.2251551 0.1333907 -0.9651487 -0.2072733 0.1598715 -0.9651315 -0.1407933 0.1086345 -0.9840609 -0.05568236 0.2231164 -0.9732003 -0.1577004 0.08514595 -0.9838094 -0.1544343 0.09072798 -0.9838285 -0.2253636 0.1324114 -0.9652349 -0.2403043 0.103011 -0.9652164 -0.3151884 0.135019 -0.9393754 -0.3285962 0.09817439 -0.9393543 -0.4056046 0.1211423 -0.9059854 -0.4171919 0.07161271 -0.9059926 -0.4864047 0.08338862 -0.8697453 -0.4949422 0.02014005 -0.8686925 -0.4962881 0.05929213 -0.8661308 -0.4959979 0.06202447 -0.8661058 -0.4987881 -0.01463997 -0.8666005 -0.4987881 -0.01464027 -0.8666003 -0.4987881 -0.01464021 -0.8666004 -0.4964058 0.02323484 -0.8677797 -0.4227232 0.01980417 -0.9060424 -0.4170896 0.07125878 -0.9060676 -0.3378574 0.05776041 -0.9394234 -0.3285335 0.09761381 -0.9394345 -0.251117 0.07466322 -0.9650729 -0.240249 0.1043167 -0.9650899 -0.1629147 0.07076722 -0.984099 -0.1547937 0.08677631 -0.9841285 -0.159051 0.08486509 -0.9836162 -0.159051 0.08486497 -0.9836162 -0.159051 0.08486503 -0.9836162 -0.162978 0.07047408 -0.9841096 -0.1705287 0.04971224 -0.9840978 -0.2510438 0.07311034 -0.9652108 -0.2577535 0.04435044 -0.9651923 -0.3379885 0.05818074 -0.9393503 -0.3425598 0.01636785 -0.9393535 -0.4228605 0.0201621 -0.9059705 -0.4222366 -0.03051561 -0.9059719 -0.4928653 -0.03557753 -0.869378 -0.4840806 -0.1003824 -0.8692464 -0.4972079 -0.05928003 -0.865604 -0.496792 -0.06255191 -0.8656125 -0.4769152 -0.1488234 -0.8662583 -0.4769153 -0.1488236 -0.8662583 -0.4888012 -0.09484028 -0.8672248 -0.4151428 -0.08056849 -0.9061816 -0.4217933 -0.03118318 -0.9061557 -0.3423143 -0.02534115 -0.9392437 -0.3428291 0.01696866 -0.9392445 -0.2614861 0.01293361 -0.9651206 -0.2579719 0.04566097 -0.9650729 -0.1748815 0.03095024 -0.984103 -0.1704823 0.04964929 -0.9841091 -0.4657792 -0.1845241 -0.8654482 -0.4699659 -0.1531105 -0.869304 -0.4012701 -0.1306909 -0.9065882 -0.4139277 -0.0820983 -0.9066001 -0.337102 -0.06677907 -0.9390968 -0.3427304 -0.02446824 -0.9391151 -0.260748 -0.01857817 -0.9652281 -0.261084 0.01180237 -0.965244 -0.1794444 0.008098185 -0.9837349 -0.17723 0.01220488 -0.9840938 -0.4475791 -0.2192226 -0.8669571 -0.4481744 -0.2098507 -0.8689664 -0.3828098 -0.1792864 -0.9062634 -0.4022076 -0.1297867 -0.9063027 -0.3267043 -0.1054406 -0.9392266 -0.3365086 -0.06769365 -0.9392442 -0.2855108 -0.05742192 -0.9566538 -0.2554614 0.002383589 -0.9668164 -0.7880899 -0.4239838 -0.4462648 -0.785377 -0.4296588 -0.4456191 -0.7890737 -0.4212481 -0.4471162 -0.7890737 -0.4212481 -0.4471163 -0.7890737 -0.4212481 -0.4471162 -0.7884369 -0.4264903 -0.4432532 -0.7874079 -0.4252324 -0.4462804 -0.7876314 -0.4249867 -0.44612 -0.7869633 -0.4258813 -0.4464459 -0.7865232 -0.4268046 -0.4463397 -0.787328 -0.4251289 -0.44652 -0.7864249 -0.4268094 -0.4465082 -0.7875509 -0.4245703 -0.4466583 -0.5236635 -0.8519252 1.03349e-5 -0.5208325 -0.8536573 0.001717567 -0.5236118 -0.8519569 -3.58825e-4 -0.5235675 -0.8519842 3.3991e-4 -0.522386 -0.8527073 0.001780033 -0.523383 -0.8520974 5.39872e-4 -0.5216187 -0.8531589 0.005825161 -0.5216187 -0.853159 0.005825281 -0.5216186 -0.853159 0.005825281 -0.5258216 -0.8505257 -0.01084727 -0.4218845 0.9037219 -0.07280325 -0.4218842 0.9037221 -0.07280325 -0.4218844 0.9037219 -0.07280325 -0.3448819 0.9360797 -0.06936454 -0.2490147 0.9660205 -0.06925314 -0.241949 0.9678219 -0.06914764 -0.2242965 0.9720648 -0.06914627 -0.1898394 0.9793204 -0.06994664 -0.1101437 0.9914579 -0.06985557 -0.05899512 0.9956497 -0.07211947 -0.4514963 -0.8922465 0.006882727 -0.4141471 -0.91021 0 -0.3368949 -0.9415423 0 -0.2986201 -0.9543488 0.006680011 -0.2598679 -0.9656442 0 -0.1769912 -0.9842125 0 -0.1383938 -0.9903562 0.006483733 -0.099487 -0.9950389 0 -0.01294124 -0.9999163 0 0.02811378 -0.9995815 0.00681436 0.06938296 -0.9975902 0 0.1510984 -0.9885188 0 0.1902865 -0.9817065 0.006601452 0.2292996 -0.973356 0 0.3149455 -0.9491099 0 0.3504135 -0.9365743 0.006237864 0.3854783 -0.922717 0 0.466185 -0.8846873 0 0.5007118 -0.8655892 0.006567001 0.5346718 -0.8450598 0 0.6007464 -0.7994397 0 0.6343594 -0.7730058 0.00710082 0.6670898 -0.7449774 0 0.7283005 -0.6852579 0 0.7540524 -0.6567834 0.006365835 0.7787336 -0.6273548 0 0.8300455 -0.5576958 0 0.8520845 -0.5233607 0.006754934 0.872732 -0.4881998 0 0.9102327 -0.414097 0 0.9263365 -0.3766363 0.006771504 0.9410725 -0.3382052 0 0.9659711 -0.2586501 0 0.9758932 -0.2181381 0.006944715 0.9842345 -0.176869 0 0.9950338 -0.09953814 0 0.9983867 -0.05632799 0.007163345 0.9999157 -0.01299053 0 0.9976083 0.06912302 0 0.9938924 0.1101409 0.006840169 0.9885132 0.1511346 0 0.9733428 0.2293556 0 0.9627145 0.2704284 0.007027804 0.9504189 0.3109729 0 0.9211608 0.3891825 0 0.9036929 0.4281233 0.007051229 0.884741 0.4660831 0 0.845079 0.5346415 0 0.8222865 0.5690323 0.006865978 0.7978121 0.6029062 0 0.7469872 0.6648385 0 0.7178294 0.6961831 0.007080078 0.6873556 0.7263211 0 0.6251849 0.7804768 0 0.5920037 0.8059052 0.006962358 0.5577216 0.8300281 0 0.4881412 0.8727647 0 0.4515326 0.8922281 0.006888866 0.4141471 0.91021 0 0.3382706 0.9410489 0 0.2986196 0.9543473 0.006899833 0.2587401 0.965947 0 0.1770226 0.9842068 0 0.1383814 0.9903578 0.006477534 0.09950488 0.9950371 0 0.01299726 0.9999155 0 -0.02812987 0.9995812 0.006797492 -0.06911599 0.9976087 0 -0.151067 0.9885236 0 -0.190271 0.9817095 0.006590187 -0.2292996 0.973356 0 -0.3149455 0.9491099 0 -0.3503838 0.9365854 0.006254255 -0.3855425 0.9226902 0 -0.4661361 0.884713 0 -0.5007629 0.8655596 0.006573081 -0.5346718 0.8450598 0 -0.6027202 0.7979526 0 -0.6343955 0.7729801 0.006644546 -0.6649404 0.7468965 0 -0.7283005 0.6852579 0 -0.7540525 0.6567835 0.006360232 -0.7787336 0.6273548 0 -0.8300455 0.5576958 0 -0.8520845 0.5233607 0.006754934 -0.872732 0.4881998 0 -0.9102327 0.414097 0 -0.9263365 0.3766363 0.006774365 -0.9410725 0.3382052 0 -0.9659262 0.2588179 0 -0.9759124 0.2180524 0.006946265 -0.9842032 0.1770433 0 -0.9950516 0.09935963 0 -0.9983867 0.05632799 0.007163226 -0.9999157 0.01299053 0 -0.9976083 -0.06912302 0 -0.9938924 -0.1101409 0.006838738 -0.9885132 -0.1511346 0 -0.9723691 -0.2334493 0 -0.9621515 -0.2724332 0.006688594 -0.9504189 -0.3109729 0 -0.9211657 -0.3891708 0 -0.9045655 -0.4262818 0.006731092 -0.8864375 -0.4628484 0 -0.845079 -0.5346415 0 -0.8222444 -0.5690934 0.006859958 -0.797899 -0.6027911 0 -0.7448586 -0.6672223 0 -0.7167055 -0.6973426 0.006827175 -0.6874285 -0.7262521 0 -0.6273823 -0.7787114 0 -0.5930355 -0.8051446 0.007160544 -0.5576382 -0.8300842 0 -0.488218 -0.8727217 0 -0.2258464 -0.6329041 -0.7405579 -0.1992076 -0.637946 -0.7438691 -0.1748269 -0.6450036 -0.7439126 -0.1743456 -0.6471375 -0.7421702 -0.1191971 -0.659672 -0.742041 -0.1184837 -0.6604614 -0.7414529 -0.1182342 -0.6602581 -0.7416738 -0.06462258 -0.6676145 -0.7416974 -0.06517308 -0.6664773 -0.7426711 -0.05872851 -0.6654426 -0.7441352 -0.00908041 -0.6680586 -0.7440533 -0.00881946 -0.6684553 -0.7437001 0.03925126 -0.6671213 -0.7439144 0.04445803 -0.6698653 -0.7411504 0.04781651 -0.6647685 -0.7455176 0.1000362 -0.6589375 -0.7455161 0.1000362 -0.6589375 -0.7455161 0.1000362 -0.6589375 -0.7455161 0.09865021 -0.6628903 -0.7421891 0.1054102 -0.6587827 -0.7449121 0.1539666 -0.6491401 -0.7449238 0.1572793 -0.6528332 -0.740994 0.2083895 -0.6380909 -0.7412247 0.2068226 -0.6382409 -0.7415343 0.2083926 -0.6329742 -0.745598 0.2596186 -0.6136097 -0.7457087 0.2599185 -0.6107607 -0.7479397 0.2548014 -0.6173415 -0.7442888 0.3108361 -0.5915565 -0.7439367 0.3079457 -0.5895047 -0.7467622 0.3600236 -0.5600229 -0.7461618 0.3600234 -0.5600231 -0.7461617 0.3600234 -0.5600231 -0.7461616 0.3565198 -0.5609399 -0.7471547 0.3564057 -0.5632489 -0.7454701 0.4016568 -0.5316083 -0.7456973 0.4019884 -0.5342934 -0.7435966 0.4016542 -0.5354398 -0.7429524 0.4486754 -0.497317 -0.7425404 0.4422225 -0.4948353 -0.748049 0.4693282 -0.4689753 -0.7481933 0.4693282 -0.4689756 -0.7481932 0.4693279 -0.468976 -0.748193 0.4842265 -0.457902 -0.7455539 0.4844515 -0.4582526 -0.7451921 0.5199515 -0.4171683 -0.7453999 0.5211892 -0.4203214 -0.7427597 0.5213043 -0.4170138 -0.7445411 0.5540553 -0.3724427 -0.7445194 0.5559722 -0.3725283 -0.7430462 0.5841064 -0.3268508 -0.7429592 0.5799671 -0.3268986 -0.7461739 0.6069575 -0.2742342 -0.745921 0.6069575 -0.2742342 -0.745921 0.6069575 -0.2742343 -0.745921 0.6052476 -0.2748546 -0.7470813 0.6076442 -0.2813699 -0.7426975 0.6299735 -0.2264405 -0.7428716 0.6329204 -0.2258116 -0.7405545 0.6376043 -0.1996008 -0.7440566 0.6376044 -0.1996009 -0.7440565 0.6376041 -0.1996006 -0.7440569 0.6448076 -0.1756258 -0.7438944 0.6485622 -0.1745803 -0.7408704 0.6608503 -0.1181527 -0.7411591 0.6605174 -0.1184953 -0.7414011 0.6602978 -0.1182217 -0.7416404 0.6675645 -0.0646336 -0.7417414 0.6665216 -0.06516045 -0.7426326 0.6653538 -0.05854481 -0.744229 0.6679121 -0.01214551 -0.7441412 0.6685231 -0.01174592 -0.7435987 0.6668459 0.04889112 -0.7435902 0.6658347 0.04718047 -0.7446061 0.6647734 0.04778856 -0.7455151 0.659123 0.1001109 -0.745342 0.6630908 0.09851169 -0.7420284 0.6586897 0.1054878 -0.7449833 0.6491561 0.1539983 -0.7449033 0.6528083 0.1572594 -0.7410202 0.6372108 0.2121365 -0.7409187 0.6372109 0.2121366 -0.7409185 0.637211 0.2121363 -0.7409186 0.6365108 0.2062121 -0.7431895 0.6334498 0.2071229 -0.7455478 0.6135904 0.2596533 -0.7457123 0.6107562 0.2597988 -0.747985 0.6174288 0.2549632 -0.7441608 0.5927015 0.3084926 -0.7440009 0.5938724 0.3101303 -0.7423845 0.5552277 0.3767911 -0.7414517 0.5609416 0.3564813 -0.7471718 0.5631855 0.3566087 -0.745421 0.5315497 0.4015063 -0.7458202 0.534431 0.4019159 -0.7435369 0.5355401 0.4014363 -0.7429978 0.5355401 0.4014362 -0.7429979 0.5355433 0.4014351 -0.7429962 0.4985395 0.4469229 -0.7427774 0.4985395 0.4469229 -0.7427774 0.4985395 0.446923 -0.7427774 0.4979684 0.444904 -0.7443707 0.4527913 0.4912214 -0.7440979 0.45789 0.4843187 -0.7455013 0.4582018 0.4843841 -0.7452672 0.4172061 0.5199652 -0.7453693 0.4205271 0.5214159 -0.742484 0.4224272 0.5215365 -0.7413198 0.3727142 0.5576464 -0.7416971 0.3726618 0.5559293 -0.7430114 0.3268094 0.5840829 -0.7429959 0.3267741 0.5798842 -0.7462929 0.2740843 0.6069566 -0.7459769 0.2748411 0.6052268 -0.747103 0.2813408 0.607822 -0.742563 0.226447 0.6301049 -0.7427582 0.2258171 0.6328849 -0.7405832 0.1992268 0.6375982 -0.7441622 0.1992269 0.6375981 -0.7441622 0.1992269 0.637598 -0.7441623 0.1756091 0.6449618 -0.7437645 0.1747245 0.6484543 -0.7409308 0.1180121 0.6609601 -0.7410836 0.1184845 0.6605557 -0.7413688 0.1182589 0.660247 -0.7416797 0.0646075 0.6675671 -0.7417412 0.06516814 0.6666556 -0.7425116 0.05873012 0.6654609 -0.7441187 0.009055316 0.667968 -0.744135 0.008837461 0.6684682 -0.7436884 -0.03941124 0.6669748 -0.7440373 -0.03941118 0.6669748 -0.7440373 -0.03941124 0.6669749 -0.7440372 -0.04445481 0.669727 -0.7412756 -0.04807835 0.6643164 -0.7459037 -0.09994786 0.6583704 -0.7460287 -0.09812998 0.6633339 -0.7418617 -0.1054141 0.6588072 -0.74489 -0.1539493 0.6489996 -0.7450498 -0.1572194 0.65267 -0.7411504 -0.1572194 0.65267 -0.7411504 -0.1572193 0.65267 -0.7411504 -0.2124806 0.6370533 -0.7409555 -0.2072929 0.6367439 -0.7426889 -0.2077376 0.6349832 -0.744071 -0.25939 0.61615 -0.7436908 -0.2598884 0.6105591 -0.7481148 -0.2548155 0.6173755 -0.7442558 -0.3107772 0.5915355 -0.743978 -0.3080522 0.5896342 -0.746616 -0.3600051 0.5602052 -0.7460338 -0.3580548 0.5605608 -0.746705 -0.3580343 0.5657145 -0.7428181 -0.4021557 0.5352621 -0.7428091 -0.4020249 0.5343543 -0.7435331 -0.4016897 0.5354871 -0.7428991 -0.4486867 0.4972506 -0.742578 -0.4422516 0.4949501 -0.747956 -0.4693222 0.4690645 -0.7481412 -0.4693221 0.4690647 -0.7481412 -0.4693219 0.4690651 -0.7481409 -0.4843573 0.4579579 -0.7454345 -0.4843087 0.4581176 -0.745368 -0.521346 0.4153503 -0.7454411 -0.5248757 0.4232944 -0.7384629 -0.5243322 0.4129009 -0.744707 -0.5526201 0.3744736 -0.7445675 -0.5546392 0.3746697 -0.7429658 -0.5840421 0.326802 -0.7430312 -0.57994 0.326799 -0.7462387 -0.6069681 0.2741242 -0.745953 -0.6052076 0.2748364 -0.7471203 -0.6051726 0.2749145 -0.7471199 -0.6051726 0.2749145 -0.7471199 -0.6051726 0.2749145 -0.7471199 -0.6252024 0.2248239 -0.7473797 -0.6281026 0.2240927 -0.7451642 -0.6257581 0.2351138 -0.7437396 -0.6456626 0.1727445 -0.7438275 -0.6433645 0.1733587 -0.7456735 -0.6540763 0.1247233 -0.7460753 -0.6540763 0.1247233 -0.7460753 -0.6540763 0.1247234 -0.7460753 -0.6604855 0.118573 -0.7414172 -0.6602939 0.1182222 -0.7416438 -0.6675645 0.0646336 -0.7417414 -0.6665605 0.06507641 -0.7426051 -0.665255 0.0589143 -0.7442882 -0.665255 0.0589143 -0.7442882 -0.665255 0.05891436 -0.7442883 -0.668027 0.009133219 -0.7440811 -0.6685055 0.008720576 -0.7436561 -0.6672298 -0.03913974 -0.7438229 -0.669848 -0.04441994 -0.7411684 -0.66475 -0.04778569 -0.7455361 -0.6591448 -0.1001142 -0.7453222 -0.6630746 -0.09863078 -0.742027 -0.6588151 -0.1051098 -0.744926 -0.6490808 -0.1540717 -0.7449538 -0.6528392 -0.1571772 -0.7410104 -0.6370609 -0.2126142 -0.7409107 -0.6370609 -0.2126142 -0.7409107 -0.6370609 -0.212614 -0.7409107 -0.6365634 -0.2062292 -0.7431397 -0.6333962 -0.2072138 -0.7455681 -0.61267 -0.2621024 -0.7456125 -0.6153593 -0.2619097 -0.7434623 -0.6221725 -0.2569019 -0.7395288 -0.6221724 -0.2569018 -0.7395288 -0.6221725 -0.2569018 -0.7395288 -0.5958479 -0.3131376 -0.7395338 -0.5939791 -0.3103632 -0.7422019 -0.5639183 -0.3625535 -0.7419914 -0.5639182 -0.3625536 -0.7419913 -0.5639183 -0.3625535 -0.7419914 -0.5656162 -0.3564864 -0.7436369 -0.5631198 -0.3563688 -0.7455852 -0.5314633 -0.4015639 -0.7458507 -0.5343992 -0.4020401 -0.7434927 -0.535562 -0.4017514 -0.7428117 -0.4972813 -0.4487671 -0.742509 -0.4963943 -0.4464953 -0.7444694 -0.4717596 -0.4720537 -0.7447203 -0.4717595 -0.472056 -0.7447189 -0.4717597 -0.4720547 -0.7447196 -0.4616451 -0.4854528 -0.7424415 -0.4582214 -0.4843786 -0.7452588 -0.4171978 -0.519866 -0.7454431 -0.4203848 -0.5214875 -0.7425143 -0.4169291 -0.5212291 -0.7446411 -0.3724155 -0.5540546 -0.7445337 -0.3725451 -0.5558861 -0.7431023 -0.3267722 -0.5839455 -0.7431202 -0.3268492 -0.5830425 -0.7437951 -0.2750467 -0.6088898 -0.7440447 -0.2764058 -0.6058782 -0.745997 -0.2812927 -0.607948 -0.7424781 -0.2812927 -0.6079481 -0.742478 -0.2812927 -0.607948 -0.742478 -0.2263995 -0.6300718 -0.7428006 -0.4874974 -0.7274904 -0.4828086 -0.4282971 -0.7639737 -0.4826033 -0.4286388 -0.7623789 -0.4848167 -0.3630768 -0.7957494 -0.4847249 -0.362496 -0.7976279 -0.4820649 -0.2945877 -0.8255195 -0.4813894 -0.2956473 -0.8225532 -0.4857973 -0.2273324 -0.8438785 -0.4859931 -0.2254095 -0.8481657 -0.4793803 -0.1550127 -0.8640451 -0.4789543 -0.1558132 -0.8625917 -0.4813085 -0.08530348 -0.8723654 -0.4813543 -0.0873205 -0.8694408 -0.4862591 -0.01152485 -0.8735219 -0.4866486 -0.01140272 -0.8735275 -0.4866415 0.05785238 -0.8718373 -0.4863672 0.06088709 -0.8751192 -0.4800618 0.131621 -0.8671739 -0.4802973 0.1340229 -0.8692805 -0.4758039 0.2060711 -0.8552348 -0.4755084 0.2015653 -0.8518047 -0.4835292 0.2698079 -0.8326256 -0.4836719 0.2747911 -0.8358602 -0.4752132 0.3428355 -0.8103283 -0.4752179 0.3393844 -0.8084927 -0.4807889 0.4059208 -0.7769467 -0.4812298 0.4079583 -0.7779968 -0.4777982 0.4709467 -0.7410894 -0.478535 0.4696769 -0.7408183 -0.4801999 0.5288946 -0.7000588 -0.4797794 0.528935 -0.7000228 -0.4797872 0.5843911 -0.6540635 -0.4803 0.5814347 -0.6536465 -0.4844378 0.6354262 -0.6008231 -0.4850209 0.6348981 -0.6006975 -0.4858673 0.6818768 -0.5469206 -0.485718 0.6837508 -0.547005 -0.4829807 0.7275292 -0.4875737 -0.4826731 0.7275654 -0.4874646 -0.4827286 0.7630297 -0.4300291 -0.4825565 0.764274 -0.429702 -0.4808757 0.7980304 -0.3625212 -0.4813792 0.7977428 -0.3624382 -0.481918 0.8255234 -0.2946577 -0.4813396 0.8225781 -0.2955417 -0.4858195 0.8438573 -0.2274773 -0.485962 0.8480854 -0.22535 -0.4795504 0.8640044 -0.155048 -0.4790162 0.8574743 -0.1586446 -0.4894587 0.8677964 -0.08471935 -0.4896451 0.869658 -0.08359426 -0.4865255 0.8733522 -0.01541364 -0.4868453 0.8783058 -0.01143026 -0.4779627 0.8762708 0.06195783 -0.4778187 0.8751209 0.06097507 -0.4800474 0.8672237 0.1315711 -0.4802211 0.8653168 0.1295512 -0.4841935 0.8507844 0.2051552 -0.4838156 0.850932 0.2052968 -0.4834958 0.850932 0.2052968 -0.4834958 0.850932 0.2052968 -0.4834958 0.8326447 0.269819 -0.4836328 0.8357882 0.2748629 -0.4752984 0.8103159 0.3428381 -0.475237 0.8084629 0.3394604 -0.4807851 0.7770225 0.4057126 -0.4812831 0.777948 0.4079484 -0.4778861 0.7411612 0.4710865 -0.4782861 0.7407605 0.4696418 -0.4803234 0.6999977 0.5289996 -0.4797528 0.700006 0.5289018 -0.4798483 0.6540544 0.5842334 -0.4805043 0.6541779 0.5854137 -0.4788968 0.6031774 0.6377865 -0.478963 0.6027542 0.6329473 -0.4858655 0.6027542 0.6329473 -0.4858654 0.5469818 0.6818591 -0.4856739 0.5470829 0.6837395 -0.4829085 0.4875131 0.7274614 -0.4828363 0.487518 0.7275212 -0.4827413 0.4299197 0.7630335 -0.482648 0.42978 0.7643647 -0.4806618 0.3624467 0.7980886 -0.4813388 0.3625179 0.7977793 -0.4817976 0.294631 0.8255404 -0.4813271 0.2955948 0.8224942 -0.4859291 0.2273468 0.8437545 -0.4862014 0.2253699 0.8481928 -0.4793512 0.1549994 0.8639712 -0.4790918 0.1558148 0.8626008 -0.4812917 0.08527439 0.8723676 -0.4813555 0.08730792 0.8693155 -0.4864853 0.01155441 0.8735342 -0.4866258 0.01155441 0.8735342 -0.4866257 0.01155441 0.8735342 -0.4866257 0.01140671 0.8736609 -0.4864019 -0.05784845 0.8719551 -0.4861563 -0.06089514 0.8750597 -0.4801691 -0.1316307 0.8672145 -0.4802212 -0.1340337 0.8693687 -0.4756397 -0.1340337 0.8693688 -0.4756396 -0.2059953 0.855215 -0.4755769 -0.201522 0.8517372 -0.483666 -0.2709646 0.8321843 -0.4837846 -0.2743187 0.8345109 -0.4778503 -0.3407263 0.8092423 -0.4785736 -0.3394262 0.8085858 -0.4806027 -0.4059299 0.776968 -0.4811878 -0.4079263 0.777848 -0.4780679 -0.4727813 0.7400851 -0.4782802 -0.4682862 0.7386246 -0.4849142 -0.5253298 0.6992243 -0.4848856 -0.5288437 0.7000366 -0.479868 -0.584375 0.6539565 -0.4804651 -0.5853144 0.6541833 -0.4790107 -0.637894 0.603099 -0.4789184 -0.6330205 0.6027613 -0.4857614 -0.6838305 0.5446627 -0.4855085 -0.6856255 0.5446458 -0.4829894 -0.7256077 0.4901962 -0.482909 -0.7258582 0.4901708 -0.4825583 -0.7630297 0.4300291 -0.4825565 -0.7695572 0.4287812 -0.4732108 -0.8020926 0.3641881 -0.4733018 -0.7962005 0.3656948 -0.4820083 -0.8254526 0.2946324 -0.4814768 -0.8225045 0.2956025 -0.485907 -0.8438925 0.227398 -0.485938 -0.848098 0.2254473 -0.4794824 -0.8639852 0.1549513 -0.4790824 -0.86263 0.1558322 -0.4812337 -0.8724441 0.08526235 -0.4812191 -0.869323 0.08732062 -0.4864696 -0.8734553 0.01151758 -0.4867683 -0.873621 0.01128184 -0.4864765 -0.8718742 -0.05764967 -0.486325 -0.8750978 -0.06106102 -0.4800785 -0.8672245 -0.131482 -0.4802438 -0.8692749 -0.13402 -0.4758151 -0.8551652 -0.2061221 -0.4756114 -0.8518161 -0.2015643 -0.4835091 -0.8326288 -0.2697252 -0.4837124 -0.8358083 -0.2747817 -0.4753099 -0.8088964 -0.3460878 -0.4752999 -0.8044849 -0.3378774 -0.4885112 -0.7732945 -0.4039433 -0.4887182 -0.7741911 -0.4059661 -0.4856128 -0.7395794 -0.4660758 -0.485588 -0.7407883 -0.4697751 -0.4801501 -0.700091 -0.5287994 -0.4798373 -0.700091 -0.5287994 -0.4798374 -0.7000562 -0.5287646 -0.4799265 -0.6521735 -0.5866107 -0.4801642 -0.6515411 -0.5829663 -0.4854324 -0.6029379 -0.6337066 -0.4846463 -0.6031788 -0.6369529 -0.4800692 -0.6031789 -0.6369528 -0.4800692 -0.6031788 -0.6369528 -0.4800693 -0.5489294 -0.684109 -0.4802826 -0.5489103 -0.6822083 -0.4830005 -0.4875801 -0.7275945 -0.4825682 -0.549552 -0.8181669 -0.1691021 -0.4830631 -0.8590899 -0.169159 -0.4816084 -0.8609384 -0.1638242 -0.4082446 -0.8981338 -0.1633769 -0.4084332 -0.8978548 -0.1644359 -0.3336358 -0.9281649 -0.1649159 -0.3336358 -0.9281649 -0.1649159 -0.3336358 -0.9281649 -0.1649159 -0.3324798 -0.9292301 -0.1612105 -0.2534682 -0.9537267 -0.1617379 -0.256043 -0.9517538 -0.1691355 -0.1751782 -0.9698499 -0.1694221 -0.1744965 -0.9702855 -0.1676223 -0.09851545 -0.9808661 -0.1679181 -0.09810018 -0.981122 -0.1666612 -0.01287341 -0.985988 -0.1663196 -0.01276075 -0.9860106 -0.1661937 0.06844788 -0.9836131 -0.1667941 0.06840342 -0.9835801 -0.1670071 0.06840342 -0.9835801 -0.167007 0.06840342 -0.9835801 -0.167007 0.1502188 -0.9745575 -0.1663493 0.1489127 -0.9742467 -0.1693174 0.2269265 -0.9590625 -0.1694215 0.2258852 -0.9588472 -0.1720122 0.3076723 -0.9358693 -0.1717159 0.3106197 -0.9361075 -0.16498 0.3817576 -0.9094774 -0.1646574 0.3800464 -0.9094103 -0.1689307 0.4578564 -0.8729206 -0.1684553 0.4598296 -0.8727798 -0.1637442 0.5282711 -0.83323 -0.1632716 0.5271829 -0.8333691 -0.166054 0.594417 -0.7867853 -0.1662452 0.594417 -0.7867852 -0.1662452 0.594417 -0.7867853 -0.1662452 0.5917156 -0.7873882 -0.1728944 0.6546168 -0.7359021 -0.1729886 0.657899 -0.7348098 -0.1649956 0.7165128 -0.6778972 -0.1645143 0.7191995 -0.6767528 -0.1573458 0.7710762 -0.6168872 -0.1577717 0.7679156 -0.6185596 -0.1664026 0.8191409 -0.5489604 -0.1662851 0.8181086 -0.549611 -0.1691924 0.8590276 -0.4831125 -0.1693344 0.8590276 -0.4831124 -0.1693344 0.8590276 -0.4831125 -0.1693344 0.8608933 -0.481722 -0.1637279 0.8981837 -0.4081714 -0.1632861 0.8979083 -0.4083719 -0.1642956 0.9282925 -0.333332 -0.1648123 0.9282924 -0.3333319 -0.1648122 0.9282925 -0.333332 -0.1648123 0.9281534 -0.3336231 -0.1650064 0.9532938 -0.2533916 -0.1643882 0.9520345 -0.2549772 -0.1691659 0.9691053 -0.1792504 -0.1694231 0.971988 -0.1748039 -0.1571077 0.9830613 -0.09451156 -0.1570289 0.9811401 -0.09810793 -0.16655 0.9859744 -0.01280623 -0.1664049 0.985973 -0.01275092 -0.1664175 0.9837516 0.06826287 -0.1660517 0.9836229 0.06830739 -0.1667933 0.9752347 0.1459215 -0.1662054 0.9760009 0.1491243 -0.1586953 0.9597893 0.2314488 -0.158858 0.9588808 0.2258487 -0.1718718 0.9358388 0.3077641 -0.1717183 0.9357212 0.3061674 -0.1751781 0.9078691 0.3811538 -0.1746298 0.9079196 0.3835887 -0.168943 0.8729115 0.4579064 -0.168366 0.8727839 0.4597914 -0.1638301 0.8331968 0.5282969 -0.1633573 0.8333632 0.5272052 -0.1660131 0.7867652 0.5943992 -0.1664037 0.7867794 0.5944243 -0.1662467 0.7349222 0.6576024 -0.1656757 0.7358734 0.6548622 -0.1721798 0.6792119 0.7133752 -0.1725316 0.6779317 0.7164248 -0.164755 0.6162062 0.7701537 -0.1647828 0.6165153 0.7695741 -0.1663271 0.5490002 0.8191289 -0.1662127 0.5495647 0.8181858 -0.1689698 0.4830296 0.859108 -0.1691625 0.4816096 0.8609308 -0.1638609 0.4082604 0.8980959 -0.1635459 0.4084383 0.8978661 -0.1643617 0.3336753 0.9281529 -0.1649038 0.3336077 0.9281817 -0.1648778 0.2533593 0.9533169 -0.1643044 0.254989 0.9520098 -0.169287 0.1751731 0.9698212 -0.1695919 0.174452 0.9703543 -0.1672693 0.174452 0.9703543 -0.1672692 0.174452 0.9703543 -0.1672693 0.09852129 0.9809238 -0.1675774 0.09810203 0.9811404 -0.1665518 0.01287269 0.9859303 -0.1666608 0.01281481 0.9859948 -0.1662829 -0.06845784 0.9837563 -0.1659432 -0.0681557 0.983636 -0.1667784 -0.1502554 0.9745811 -0.1661776 -0.1488789 0.9742255 -0.1694693 -0.1488789 0.9742255 -0.1694692 -0.1488789 0.9742255 -0.1694694 -0.2269299 0.9590036 -0.1697499 -0.2269299 0.9590036 -0.1697499 -0.2269299 0.9590035 -0.1697499 -0.2258868 0.9588539 -0.1719725 -0.307663 0.9358413 -0.1718856 -0.3106247 0.9361225 -0.1648847 -0.3817465 0.9094511 -0.1648281 -0.3800457 0.9094086 -0.1689413 -0.45787 0.8729463 -0.1682851 -0.4597517 0.8727485 -0.1641292 -0.4597518 0.8727485 -0.1641292 -0.4597518 0.8727485 -0.1641293 -0.5282631 0.8332347 -0.1632725 -0.5272569 0.8334165 -0.1655819 -0.5272569 0.8334164 -0.1655818 -0.5272569 0.8334165 -0.165582 -0.5943945 0.7867658 -0.1664177 -0.5943152 0.7868595 -0.1662583 -0.6576493 0.7348769 -0.1656903 -0.655001 0.7357504 -0.1721777 -0.7133542 0.6792789 -0.1723543 -0.7191933 0.676747 -0.1573989 -0.7732048 0.6141955 -0.1578556 -0.7667157 0.6177674 -0.1746731 -0.815906 0.5509878 -0.1752427 -0.8180021 0.5497671 -0.1692001 -0.8180021 0.5497672 -0.1692001 -0.8180021 0.5497672 -0.1692001 -0.8609338 0.4797427 -0.1692333 -0.859475 0.4809196 -0.1732603 -0.894947 0.4111013 -0.173395 -0.8977672 0.4086593 -0.1643526 -0.8977672 0.4086593 -0.1643526 -0.8977672 0.4086593 -0.1643525 -0.9282647 0.3333448 -0.1649426 -0.9282647 0.3333448 -0.1649426 -0.9282647 0.3333449 -0.1649425 -0.92816 0.3336254 -0.1649639 -0.953283 0.2534005 -0.1644379 -0.9520385 0.2549766 -0.1691437 -0.969843 0.1751828 -0.169457 -0.9702769 0.1744962 -0.1676717 -0.9808921 0.09850984 -0.1677691 -0.9811401 0.09810793 -0.16655 -0.9859744 0.01280623 -0.1664049 -0.9859712 0.01275092 -0.1664282 -0.9837516 -0.06826287 -0.1660517 -0.9836229 -0.06830739 -0.1667933 -0.9745909 -0.1502141 -0.1661579 -0.97426 -0.1488559 -0.169291 -0.9590798 -0.2269078 -0.1693485 -0.9596257 -0.2303876 -0.1613695 -0.9375416 -0.3081488 -0.1614321 -0.9374253 -0.3067249 -0.164784 -0.9093899 -0.3819679 -0.1646534 -0.9095199 -0.3840783 -0.1589259 -0.8743245 -0.4586246 -0.1588086 -0.8744979 -0.4565193 -0.1638406 -0.833202 -0.5283141 -0.1632747 -0.8333109 -0.5273461 -0.1658287 -0.78687 -0.5943033 -0.1662509 -0.7867565 -0.594407 -0.1664169 -0.7349222 -0.6576024 -0.1656757 -0.7347583 -0.6581907 -0.1640588 -0.6780794 -0.7162737 -0.1648041 -0.6780794 -0.7162737 -0.164804 -0.6778553 -0.716485 -0.1648072 -0.6778554 -0.716485 -0.1648072 -0.6778554 -0.716485 -0.1648072 -0.6182723 -0.7684918 -0.1648023 -0.6185727 -0.7679524 -0.1661838 -0.5490162 -0.8191528 -0.1660421 -0.3932873 0.3096148 -0.8657157 -0.3629732 0.3433665 -0.8662275 -0.2674784 0.4226627 -0.8659166 -0.1555299 0.4754431 -0.8658893 0.04384231 0.4975585 -0.8663218 0.04384237 0.4975585 -0.8663218 0.04384237 0.4975586 -0.8663218 0.1486064 0.4759457 -0.8668287 0.2102162 0.454123 -0.8657838 0.2432417 0.4346715 -0.8671184 0.3151282 0.3891145 -0.865612 0.3433722 0.3629384 -0.8662397 0.4226397 0.2675281 -0.8659125 0.4932506 0.07896798 -0.8662956 0.4972332 -0.04399633 -0.8665008 0.4972332 -0.04399627 -0.8665008 0.4972332 -0.04399639 -0.8665007 0.4756094 -0.1488831 -0.8669657 0.4549314 -0.2106457 -0.8652548 0.4346612 -0.2432653 -0.8671169 0.3909399 -0.3125938 -0.8657084 0.3629732 -0.3433665 -0.8662275 0.2674995 -0.4226961 -0.8658938 0.07890141 -0.4931445 -0.8663621 -0.04385048 -0.4975596 -0.8663207 -0.0438506 -0.4975597 -0.8663207 -0.0438506 -0.4975597 -0.8663207 -0.1485738 -0.4758412 -0.8668916 -0.2102429 -0.4540374 -0.8658221 -0.2432353 -0.4346263 -0.8671427 -0.3127414 -0.3909944 -0.8656306 -0.3433724 -0.3629946 -0.8662162 -0.4226397 -0.2675281 -0.8659125 -0.4931201 -0.07861113 -0.8664023 -0.4972883 0.04384696 -0.8664767 -0.4678894 0.1756627 -0.8661538 -0.4678894 0.1756625 -0.8661538 -0.4678893 0.1756626 -0.8661537 -0.4556899 0.2069653 -0.8657437 -0.4556899 0.2069653 -0.8657438 -0.4556899 0.2069653 -0.8657438 -0.4346323 0.2432491 -0.867136 0.01962274 -0.1764746 -0.9841096 0.1676224 0.1609505 -0.9726241 0.231493 -0.05025422 -0.9715377 0.316394 -0.1526662 -0.9362628 0.2173805 -0.06998467 -0.9735748 0.2173805 -0.06998467 -0.9735748 0.2173805 -0.06998467 -0.9735749 0.266029 -0.1210389 -0.9563359 0.1459015 -0.2168338 -0.965244 0.221481 -0.06722241 -0.972845 0.221481 -0.06722235 -0.972845 0.221481 -0.06722247 -0.972845 0.1186203 -0.1763211 -0.9771593 0.07598811 -0.1631355 -0.9836731 0.06142008 -0.1667417 -0.9840857 0.07501196 -0.1607864 -0.9841347 0.0750119 -0.1607865 -0.9841347 0.07501196 -0.1607865 -0.9841347 -0.05020874 -0.2314028 -0.9715616 -0.1530168 -0.3167555 -0.9360833 -0.06352645 -0.2270056 -0.9718194 -0.1121858 -0.276799 -0.9543567 -0.2169085 -0.1458553 -0.9652342 -0.06731671 -0.2214938 -0.9728356 -0.176348 -0.1186099 -0.9771556 -0.1628645 -0.07520377 -0.9837782 -0.1666677 -0.06136214 -0.984102 -0.1607679 -0.07511073 -0.9841302 -0.2314344 0.05017548 -0.9715558 -0.3100405 0.1413545 -0.9401563 -0.226601 0.0632956 -0.9719288 -0.2766164 0.1125144 -0.954371 -0.1459015 0.2168338 -0.965244 -0.2214769 0.06726557 -0.972843 -0.2214769 0.06726533 -0.972843 -0.2214769 0.06726568 -0.9728429 -0.1186196 0.1763581 -0.9771527 -0.07597774 0.1631771 -0.9836669 -0.06142008 0.1667417 -0.9840857 -0.07504373 0.1602087 -0.9842264 0.04949128 0.2308293 -0.9717348 0.1530745 0.3164495 -0.9361774 0.06346398 0.2266861 -0.9718981 0.112185 0.2766268 -0.9544068 0.2168816 0.1458373 -0.9652429 0.06729769 0.2215093 -0.9728334 0.06729775 0.2215092 -0.9728333 0.06729769 0.2215096 -0.9728332 0.1763489 0.1185722 -0.9771601 0.1631357 0.07597219 -0.9836743 0.1667021 0.06137478 -0.9840953 0.1606134 0.07503855 -0.9841609 -0.4560604 0.2059648 -0.8657872 -0.4357922 0.2330322 -0.8693567 -0.3731242 0.1995199 -0.9060741 -0.3460758 0.2435683 -0.9060387 -0.2808333 0.1976198 -0.9391907 -0.2555872 0.2293332 -0.9391919 -0.470144 0.1688212 -0.8662933 -0.4607521 0.1797301 -0.8691402 -0.3940834 0.1537028 -0.9061313 -0.3731061 0.1993112 -0.9061274 -0.3029287 0.1618804 -0.9391641 -0.2807991 0.1978936 -0.9391433 -0.4924275 0.08825165 -0.8658677 -0.4914662 0.09347379 -0.865866 -0.4780482 0.1279815 -0.8689596 -0.4826019 0.1232913 -0.8671187 -0.4096617 0.1046616 -0.9062137 -0.3940097 0.1532519 -0.9062397 -0.320074 0.1244302 -0.9391857 -0.3029446 0.1618213 -0.9391691 -0.4969303 0.04814136 -0.8664543 -0.4901868 0.06235903 -0.8693839 -0.4192525 0.05338019 -0.906299 -0.4095256 0.1041418 -0.9063352 -0.3326674 0.08464676 -0.9392377 -0.3200805 0.1243193 -0.9391981 -0.4981384 -0.03582096 -0.8663573 -0.4985098 -0.0292201 -0.8663915 -0.4952764 0.006641268 -0.8687102 -0.4970098 0.003592967 -0.8677376 -0.4225928 0.00299412 -0.9063147 -0.4191371 0.05312097 -0.9063677 -0.3404858 0.04305171 -0.9392636 -0.3326271 0.08459633 -0.9392564 -0.2696189 0.06854224 -0.9605247 -0.2589936 0.1005783 -0.9606282 -0.2453206 0.1066737 -0.9635552 -0.2361892 0.1261789 -0.96348 -0.2597256 0.1166777 -0.9586078 -0.2313182 0.1630035 -0.9591255 -0.2065958 0.1702861 -0.9634941 -0.1996356 0.1790766 -0.9633677 -0.215011 0.1768795 -0.9604604 -0.2178868 0.1739168 -0.9603533 -0.4940909 -0.07353538 -0.8662949 -0.4908789 -0.05493193 -0.8694944 -0.420287 -0.0470255 -0.9061719 -0.4229164 0.003679692 -0.9061613 -0.3432634 0.002978742 -0.9392345 -0.3405593 0.04330587 -0.9392252 -0.2597369 0.03301924 -0.9651148 -0.2611196 0.0254569 -0.9649708 -0.1562229 0.1750533 -0.9720858 -0.1562229 0.1750532 -0.9720858 -0.1562229 0.1750532 -0.9720858 -0.4745661 -0.1552628 -0.8664182 -0.4737684 -0.1583693 -0.8662925 -0.4819442 -0.1143065 -0.868714 -0.4824016 -0.1161196 -0.8682194 -0.4109804 -0.09900188 -0.9062527 -0.4200029 -0.04742091 -0.9062831 -0.3413866 -0.03857028 -0.9391313 -0.3435788 0.003717064 -0.9391165 -0.2620169 0.002931416 -0.9650589 -0.2599091 0.03365987 -0.9650463 -0.1768165 0.02296143 -0.983976 -0.1572481 0.1759896 -0.9717514 -0.1791634 -0.004924118 -0.983807 -0.1790847 0.001330554 -0.9838328 -0.2616776 0.001918256 -0.9651535 -0.2599985 -0.03020423 -0.9651366 -0.3408226 -0.03956443 -0.9392948 -0.333617 -0.08042889 -0.9392715 -0.4108747 -0.09902834 -0.9062978 -0.3966368 -0.1458795 -0.9063104 -0.4632709 -0.1703816 -0.8696841 -0.4382966 -0.230272 -0.8688331 -0.4628198 -0.1908581 -0.8656623 -0.4628198 -0.1908581 -0.8656623 -0.460633 -0.1959758 -0.8656852 -0.4208338 -0.2708389 -0.8657628 -0.442456 -0.2274746 -0.8674608 -0.3756786 -0.1931413 -0.9064006 -0.3964123 -0.1461292 -0.9063684 -0.3224615 -0.1188935 -0.9390862 -0.3344225 -0.07930099 -0.9390809 -0.2547695 -0.06048297 -0.9651085 -0.2601552 -0.02968776 -0.9651104 -0.1763293 -0.02018332 -0.9841244 -0.1772451 -0.002699673 -0.9841631 -0.1825765 -0.01075065 -0.9831329 -0.1765103 -0.01959449 -0.9841038 -0.1727476 -0.04150551 -0.9840913 -0.2543157 -0.06112509 -0.9651878 -0.2456071 -0.08993816 -0.9651882 -0.3229697 -0.1182684 -0.9389905 -0.3058159 -0.1573925 -0.9389911 -0.3755173 -0.1932339 -0.9064478 -0.3489457 -0.2382159 -0.906361 -0.4082579 -0.2786781 -0.8692894 -0.3662543 -0.330449 -0.8698629 -0.4000482 -0.3000221 -0.8659956 -0.3994832 -0.300495 -0.8660924 -0.353047 -0.3531833 -0.8663829 -0.353047 -0.3531835 -0.8663828 -0.3530471 -0.3531836 -0.8663828 -0.3770486 -0.3268498 -0.8666047 -0.3199831 -0.2772935 -0.9059355 -0.3510348 -0.2370831 -0.9058511 -0.2845823 -0.192189 -0.9391892 -0.3048707 -0.1580677 -0.9391851 -0.2320882 -0.1203041 -0.9652264 -0.2452792 -0.09029972 -0.9652379 -0.1667397 -0.06137794 -0.9840888 -0.1727615 -0.04157882 -0.9840858 -0.3142558 -0.3896639 -0.865682 -0.3307718 -0.3681164 -0.8689536 -0.2824381 -0.3143542 -0.9063168 -0.3182107 -0.2780346 -0.9063326 -0.2585721 -0.225919 -0.9392024 -0.2845711 -0.1922482 -0.9391804 -0.2164539 -0.146236 -0.9652787 -0.2316067 -0.1207572 -0.9652855 -0.1589342 -0.08287858 -0.9838044 -0.1590558 -0.0790342 -0.9841011 -0.2778338 -0.4133412 -0.8671548 -0.2829097 -0.4057087 -0.869116 -0.2415173 -0.3463299 -0.9064905 -0.2816312 -0.3144816 -0.9065237 -0.2289578 -0.2557108 -0.9392499 -0.2581488 -0.2260872 -0.9392784 -0.2181276 -0.191139 -0.9570195 -0.2217402 -0.1264419 -0.9668732 -0.2059271 -0.4561359 -0.8657563 -0.2330482 -0.4358273 -0.8693349 -0.1994991 -0.373079 -0.9060972 -0.24352 -0.3461009 -0.906042 -0.1976083 -0.2808281 -0.9391946 -0.2292795 -0.2555689 -0.93921 -0.1686326 -0.4691807 -0.8668521 -0.1793318 -0.4598927 -0.8696774 -0.1536735 -0.3940771 -0.9061388 -0.1993666 -0.3731289 -0.9061058 -0.1618639 -0.3029361 -0.9391645 -0.1978617 -0.2807909 -0.9391524 -0.08819305 -0.492479 -0.8658443 -0.08897382 -0.492255 -0.8658919 -0.1292365 -0.4768717 -0.8694201 -0.123329 -0.4825699 -0.8671311 -0.1046924 -0.409682 -0.906201 -0.1532484 -0.3940203 -0.9062357 -0.1244894 -0.3200765 -0.9391771 -0.1618252 -0.3029057 -0.9391809 -0.04809302 -0.4970049 -0.8664141 -0.06239467 -0.4901717 -0.8693898 -0.05335897 -0.4192732 -0.9062908 -0.1042025 -0.4094977 -0.9063408 -0.08464294 -0.3326733 -0.939236 -0.1242455 -0.3200777 -0.939209 0.03583079 -0.4982073 -0.8663173 0.02933681 -0.4985593 -0.8663592 -0.006731927 -0.4952725 -0.8687117 -0.003566443 -0.4970037 -0.8677411 -0.003032386 -0.4225494 -0.9063349 -0.05307292 -0.4191393 -0.9063695 -0.04311835 -0.3404943 -0.9392575 -0.08457064 -0.3326081 -0.9392655 -0.06855249 -0.2695722 -0.9605371 -0.1005526 -0.2590576 -0.9606136 -0.1066944 -0.2452971 -0.9635589 -0.1261723 -0.2362129 -0.9634751 -0.1166793 -0.2596799 -0.95862 -0.163028 -0.2313455 -0.9591149 -0.1702932 -0.2066379 -0.9634838 -0.1790701 -0.1996521 -0.9633655 -0.1767967 -0.2149682 -0.9604851 -0.1766577 -0.215133 -0.9604738 0.07351946 -0.4939869 -0.8663555 0.05493259 -0.4908587 -0.8695058 0.04703491 -0.4203183 -0.9061569 -0.003661215 -0.4229391 -0.9061508 -0.002985358 -0.3440177 -0.9389585 -0.04521954 -0.3411875 -0.938907 -0.03439563 -0.2595105 -0.9651277 -0.02329361 -0.2615427 -0.9649108 -0.1750559 -0.1556426 -0.9721784 0.1563333 -0.4748463 -0.8660721 0.1550958 -0.4755547 -0.865906 0.1145506 -0.4828781 -0.8681629 0.1144617 -0.4828997 -0.8681626 0.09746736 -0.4112365 -0.9063028 0.04749041 -0.4199675 -0.9062958 0.03859835 -0.3413704 -0.9391361 -0.00188142 -0.343536 -0.9391376 -0.001428067 -0.2615149 -0.9651984 -0.03366482 -0.2593462 -0.9651976 -0.02293717 -0.1767639 -0.983986 -0.1755411 -0.1571479 -0.9718487 -0.1755429 -0.1571475 -0.9718485 -0.1755429 -0.1571475 -0.9718485 0.004892647 -0.1792066 -0.9837994 -0.00135529 -0.1791021 -0.9838296 -0.001966595 -0.2616385 -0.965164 0.03015875 -0.2600377 -0.9651275 0.03953164 -0.3408135 -0.9392995 0.07900923 -0.3338918 -0.9392944 0.09735447 -0.4113825 -0.9062486 0.1472507 -0.3961775 -0.9062895 0.1721303 -0.4630842 -0.869439 0.230344 -0.4382627 -0.8688311 0.1910182 -0.4629228 -0.8655718 0.1960195 -0.4607193 -0.8656293 0.2705427 -0.4207692 -0.8658869 0.2705426 -0.420769 -0.8658869 0.2705426 -0.4207693 -0.8658869 0.2274919 -0.4424296 -0.8674696 0.1931658 -0.3756474 -0.9064083 0.1476972 -0.3957653 -0.906397 0.1200411 -0.321589 -0.9392395 0.07881629 -0.3340014 -0.9392716 0.0601567 -0.2549155 -0.9650903 0.02957016 -0.2602688 -0.9650833 0.02002924 -0.1763344 -0.9841266 0.002727091 -0.1771989 -0.9841713 0.01075261 -0.1827095 -0.9831082 0.01075255 -0.1827095 -0.9831082 0.01075261 -0.1827095 -0.9831082 0.03991222 -0.1728999 -0.9841304 0.04183167 -0.1727493 -0.9840772 0.06152176 -0.2540858 -0.965223 0.09035199 -0.2452269 -0.9652462 0.1189016 -0.3227854 -0.938974 0.1573627 -0.3057883 -0.9390051 0.1932291 -0.375558 -0.906432 0.2381601 -0.3489399 -0.9063779 0.2786497 -0.4081723 -0.8693387 0.3304969 -0.366268 -0.8698389 0.3000195 -0.3999758 -0.8660299 0.3005517 -0.3995209 -0.8660553 0.3532918 -0.3532318 -0.8662635 0.3532917 -0.3532317 -0.8662634 0.3532918 -0.3532319 -0.8662635 0.3267794 -0.3770487 -0.8666311 0.2773403 -0.3200013 -0.9059149 0.2371056 -0.3510336 -0.9058456 0.192206 -0.2845939 -0.9391822 0.1580988 -0.3048912 -0.9391731 0.1203348 -0.2320222 -0.9652385 0.09029859 -0.2453252 -0.9652264 0.06138008 -0.1667217 -0.9840916 0.04306429 -0.1723603 -0.9840922 0.3896486 -0.3144235 -0.8656281 0.3681169 -0.3307453 -0.8689635 0.3143468 -0.2823936 -0.9063333 0.277967 -0.3182384 -0.9063436 0.2258929 -0.2585626 -0.9392113 0.192216 -0.2845814 -0.939184 0.1462178 -0.2164878 -0.9652737 0.1207475 -0.2316678 -0.9652721 0.0831049 -0.1594039 -0.9837094 0.07763135 -0.1596378 -0.9841185 0.4133756 -0.2778602 -0.8671299 0.4056809 -0.2829204 -0.8691255 0.346924 -0.2419075 -0.9061592 0.3141364 -0.2831631 -0.9061661 0.2549108 -0.2297048 -0.9392849 0.226109 -0.2581572 -0.9392708 0.1919563 -0.2191342 -0.9566258 0.1253355 -0.2228784 -0.9667555 0.4569652 -0.2061675 -0.8652617 0.4569652 -0.2061675 -0.8652617 0.4569652 -0.2061675 -0.8652617 0.4356448 -0.2346477 -0.8689961 0.3724156 -0.2006075 -0.9061255 0.3468555 -0.2422726 -0.9060879 0.2810721 -0.1962789 -0.9394005 0.255186 -0.2289731 -0.9393889 0.4691813 -0.168642 -0.86685 0.4610527 -0.1779677 -0.8693434 0.3939098 -0.1521679 -0.9064658 0.3724262 -0.1989542 -0.9064856 0.3029186 -0.1619167 -0.939161 0.2807771 -0.1978314 -0.939163 0.4924275 -0.08825165 -0.8658677 0.492457 -0.08787018 -0.8658897 0.4764071 -0.1297465 -0.8695989 0.4826142 -0.1232988 -0.8671107 0.4096301 -0.1047165 -0.9062217 0.3940383 -0.1531906 -0.9062376 0.3200946 -0.1244748 -0.9391728 0.3029212 -0.1617618 -0.9391869 0.4969324 -0.04805058 -0.8664579 0.4901732 -0.06235527 -0.8693918 0.4192364 -0.05337703 -0.9063067 0.4095624 -0.1041482 -0.9063177 0.3326556 -0.08467704 -0.9392392 0.3200804 -0.1242735 -0.9392043 0.499175 0.03589725 -0.8657574 0.499141 0.0367549 -0.865741 0.4950562 -0.008927702 -0.8688152 0.4970058 -0.005358994 -0.8677306 0.4233639 -0.004530012 -0.9059484 0.4198511 -0.05505394 -0.9059218 0.3402516 -0.04452973 -0.9392795 0.3326562 -0.08460372 -0.9392455 0.2695921 -0.06853449 -0.9605328 0.2589775 -0.1006304 -0.960627 0.2453687 -0.1066413 -0.9635465 0.2362236 -0.1261973 -0.9634691 0.2596711 -0.1166532 -0.9586256 0.2313523 -0.1629791 -0.9591215 0.2066187 -0.170305 -0.9634858 0.1996144 -0.1791079 -0.9633662 0.2149758 -0.1768044 -0.960482 0.2179555 -0.173914 -0.9603381 0.4940646 0.07352817 -0.8663105 0.4911903 0.0567187 -0.8692037 0.4193516 0.04844242 -0.9065306 0.4219464 -0.001835703 -0.9066189 0.3433316 -0.001434504 -0.9392132 0.3403824 -0.04514497 -0.9392027 0.2594907 -0.03443235 -0.9651317 0.261573 -0.02328521 -0.9649028 0.1556206 -0.1750207 -0.9721882 0.4754607 0.1554626 -0.8658918 0.4745364 0.1582893 -0.8658867 0.4829047 0.1145343 -0.8681503 0.4829081 0.1144748 -0.8681563 0.4112467 0.09753555 -0.9062909 0.4199749 0.04741775 -0.9062961 0.3413891 0.03857022 -0.9391304 0.3435155 -0.001904666 -0.9391451 0.261501 -0.001486063 -0.965202 0.2593281 -0.03358465 -0.9652052 0.1767632 -0.02295452 -0.9839857 0.1572183 -0.1755555 -0.9718348 0.1791634 0.004924118 -0.983807 0.1791195 -0.001380085 -0.9838263 0.2617099 -0.001918494 -0.9651447 0.2599985 0.03020423 -0.9651366 0.34082 0.03956449 -0.9392957 0.3338766 0.07901269 -0.9392994 0.411373 0.09729951 -0.906259 0.3961936 0.1473031 -0.906274 0.463152 0.172151 -0.8693988 0.4393763 0.2287061 -0.8687014 0.4628011 0.1911712 -0.8656032 0.4606105 0.1959574 -0.8657012 0.4144517 0.281279 -0.8655126 0.4416664 0.2270156 -0.8679832 0.3756896 0.1931528 -0.9063937 0.3957188 0.147638 -0.9064269 0.3213549 0.1199182 -0.9393353 0.333747 0.07918745 -0.9393308 0.2547464 0.06047749 -0.9651149 0.2601552 0.02968776 -0.9651104 0.1763517 0.02018588 -0.9841203 0.1771935 0.002772808 -0.9841722 0.1831104 0.01078212 -0.9830333 0.1765463 0.01965063 -0.9840962 0.1727258 0.04150027 -0.9840953 0.2543157 0.06112509 -0.9651878 0.2455741 0.08992183 -0.9651982 0.3230057 0.1182783 -0.9389769 0.3063557 0.1561958 -0.9390149 0.377022 0.1922425 -0.9060338 0.3502168 0.237487 -0.9060619 0.4094385 0.2777152 -0.8690423 0.3680385 0.3299399 -0.8693029 0.4006331 0.3002248 -0.8656548 0.4002403 0.3010646 -0.8655449 0.3389316 0.367299 -0.8661506 0.3389316 0.367299 -0.8661506 0.3389316 0.367299 -0.8661506 0.3755613 0.3273273 -0.8670701 0.3187861 0.2777817 -0.9062079 0.3494976 0.2378776 -0.9062371 0.2834304 0.1928738 -0.9393971 0.3042587 0.1577655 -0.9394344 0.2320662 0.1203047 -0.9652316 0.2453019 0.09031099 -0.9652311 0.1667606 0.06138563 -0.9840847 0.1727259 0.0415703 -0.9840923 0.3142799 0.3896607 -0.8656747 0.3307718 0.3681164 -0.8689536 0.2824381 0.3143542 -0.9063168 0.3182543 0.2779992 -0.9063282 0.2585878 0.2259 -0.9392026 0.2845711 0.1922482 -0.9391804 0.2164539 0.146236 -0.9652787 0.2316144 0.1207569 -0.9652838 0.1593829 0.08310604 -0.9837127 0.1596691 0.07761323 -0.9841148 0.2767438 0.4140403 -0.8671699 0.2825826 0.4052008 -0.8694593 0.2415096 0.3463408 -0.9064884 0.2815937 0.3145337 -0.9065173 0.2289131 0.2556763 -0.9392703 0.2581561 0.2261095 -0.939271 0.2191653 0.1919572 -0.9566186 0.2228792 0.1247985 -0.9668249 0.2059131 0.4559377 -0.8658641 0.2330456 0.4358083 -0.869345 0.1995194 0.3730883 -0.906089 0.243543 0.3460942 -0.9060385 0.1976192 0.2808173 -0.9391956 0.2292785 0.2555808 -0.9392071 0.1686326 0.4691807 -0.8668521 0.1793354 0.4599018 -0.869672 0.1536778 0.394088 -0.9061334 0.1993556 0.3731427 -0.9061026 0.1618449 0.3029263 -0.9391708 0.1978682 0.2808001 -0.9391484 0.08822172 0.4926393 -0.8657503 0.08797615 0.4927297 -0.8657238 0.1297933 0.476563 -0.8695065 0.1237578 0.4824762 -0.8671222 0.1050469 0.4095391 -0.9062246 0.1532248 0.3940566 -0.9062238 0.1244704 0.3200877 -0.9391757 0.1618116 0.3029238 -0.9391774 0.04809325 0.4969168 -0.8664646 0.06218081 0.4903066 -0.8693292 0.05317258 0.4192745 -0.9063011 0.1046598 0.4094133 -0.9063261 0.0850082 0.3325226 -0.9392563 0.1242647 0.3201435 -0.939184 -0.0360682 0.4981588 -0.8663353 -0.0292775 0.4985331 -0.8663761 0.006713032 0.495289 -0.8687024 0.003566205 0.4970365 -0.8677225 0.003032445 0.4225611 -0.9063294 0.0528419 0.4191461 -0.9063798 0.04292476 0.3404308 -0.9392893 0.0845111 0.3324196 -0.9393377 0.06854182 0.2695876 -0.9605336 0.1005296 0.2589702 -0.9606395 0.106706 0.2453238 -0.9635509 0.1261783 0.236236 -0.9634685 0.1166671 0.2596526 -0.9586289 0.1630129 0.231324 -0.9591226 0.1702837 0.2066264 -0.963488 0.1791118 0.1996623 -0.9633556 0.1767708 0.2149266 -0.9604992 0.1739113 0.2180242 -0.960323 0.02328616 0.261561 -0.964906 0.03440648 0.2595046 -0.9651288 0.04524332 0.3411909 -0.9389046 0.002976059 0.3440073 -0.9389623 0.003652036 0.4229391 -0.9061508 -0.04704046 0.4202992 -0.9061654 -0.05495148 0.4909939 -0.8694282 -0.1145477 0.4828458 -0.8681814 -0.07891553 0.4930885 -0.8663927 -0.07891559 0.4930884 -0.8663926 -0.07891553 0.4930884 -0.8663926 -0.0731005 0.4940605 -0.866349 -0.1582584 0.4746279 -0.8658422 -0.1144618 0.4829321 -0.8681447 -0.09742814 0.4110711 -0.906382 -0.04766422 0.4198248 -0.9063528 -0.03875708 0.3413797 -0.9391261 0.00188148 0.3435509 -0.9391322 0.001428067 0.2615178 -0.9651976 0.03366482 0.2593462 -0.9651976 0.02299225 0.1772263 -0.9839016 0.1680113 0.162145 -0.9723586 -0.004876494 0.1791355 -0.9838124 0.001342952 0.1790934 -0.9838312 0.001966476 0.2616245 -0.9651678 -0.03016906 0.2600259 -0.9651303 -0.03956592 0.3408616 -0.9392806 -0.0787031 0.3341242 -0.9392375 -0.09694033 0.4114704 -0.9062532 -0.1472507 0.3961775 -0.9062895 -0.1721284 0.4631397 -0.8694099 -0.2303287 0.4383097 -0.8688114 -0.1910455 0.4627387 -0.8656643 -0.1960101 0.4606972 -0.8656433 -0.2705102 0.4207866 -0.8658886 -0.227481 0.4424308 -0.8674719 -0.1931396 0.3756799 -0.9064004 -0.1476972 0.3957653 -0.906397 -0.1199482 0.3213399 -0.9393365 -0.07918542 0.3337488 -0.9393303 -0.06045788 0.2547886 -0.9651051 -0.02977824 0.2601706 -0.9651034 -0.02017629 0.1762772 -0.9841338 -0.002724051 0.1772056 -0.9841701 -0.01135885 0.1833224 -0.9829872 -0.01938736 0.176572 -0.9840968 -0.04151087 0.1727366 -0.984093 -0.06111961 0.2542808 -0.9651973 -0.09042757 0.2454479 -0.965183 -0.1188148 0.3225031 -0.9390819 -0.1578347 0.3052685 -0.939095 -0.193784 0.3747167 -0.9066616 -0.2379037 0.3485335 -0.9066014 -0.2786744 0.4082246 -0.8693062 -0.3305062 0.3662021 -0.8698631 -0.299932 0.4000762 -0.8660138 -0.3005748 0.3994268 -0.8660907 -0.3531208 0.35302 -0.8664195 -0.3531208 0.35302 -0.8664194 -0.3531209 0.35302 -0.8664194 -0.3267582 0.3771031 -0.8666155 -0.2773297 0.3200023 -0.9059177 -0.2362717 0.3516158 -0.9058377 -0.1917293 0.2853457 -0.9390515 -0.1574995 0.3055914 -0.9390463 -0.1198583 0.232541 -0.965173 -0.0903384 0.2454766 -0.9651841 -0.06136387 0.1667528 -0.9840874 -0.04153549 0.1727313 -0.9840928 -0.3896245 0.3144041 -0.865646 -0.3681243 0.3306913 -0.868981 -0.314312 0.2823624 -0.9063552 -0.2780041 0.3182808 -0.9063174 -0.2258973 0.2585623 -0.9392104 -0.1922104 0.2845817 -0.939185 -0.1462112 0.2164781 -0.965277 -0.1207475 0.2316678 -0.9652721 -0.08311712 0.1594273 -0.9837045 -0.07763713 0.1596907 -0.9841094 -0.4123786 0.279403 -0.867109 -0.4063657 0.2833979 -0.8686498 -0.3463288 0.2414925 -0.9064976 -0.3145372 0.2817 -0.9064831 -0.2557085 0.2289276 -0.939258 -0.2261316 0.2581797 -0.9392592 -0.1919392 0.2191148 -0.9566338 -0.1247993 0.2228442 -0.9668328 0.5178724 0.8554558 -0.001880943 0.525018 0.851091 5.14236e-4 0.5261484 0.8503928 2.92365e-4 0.5236377 0.8519411 -2.98272e-4 0.5233654 0.8521083 -3.6056e-4 0.5207464 0.8537108 -0.001043617 0.99961 -0.02792704 -2.22523e-5 0.9996129 -0.02782469 1.30231e-5 0.9996131 -0.02781784 6.86222e-6 0.9996135 -0.02779966 -2.40727e-4 0.9996139 -0.02778387 -3.34403e-4 0.9996039 -0.02813065 9.10047e-4 0.9996142 -0.02777689 -1.17871e-4 0.9996138 -0.02779048 -1.04341e-4 -0.02663177 -0.9996454 2.89904e-4 -0.03211784 -0.9994792 -0.003132998 -0.02768778 -0.9996166 5.48981e-5 -0.02709937 -0.9996021 0.007829844 -0.02709937 -0.9996021 0.007829844 -0.02709937 -0.9996021 0.007829844 -0.02936309 -0.999566 0.002379953 -0.02936309 -0.9995661 0.002380013 -0.02936309 -0.999566 0.002379953 -0.02585268 -0.9996449 0.00647515 -0.03644496 -0.9990695 -0.02306509 -0.02595585 -0.9995859 0.01241993 -0.02595573 -0.9995859 0.01242029 -0.02595579 -0.999586 0.01242011 -0.9758026 -0.2185443 0.006910026 -0.9658347 -0.2591591 0 -0.9414177 -0.3372428 0 -0.9267284 -0.37567 0.006820678 -0.8520171 -0.5234693 0.006850183 -0.7796101 -0.6262653 0 -0.7535049 -0.6574081 0.006712257 -0.726242 -0.6874392 0 -0.6370927 -0.7707564 0.006908714 -0.5326451 -0.8463388 0 -0.4996806 -0.8661865 0.006356418 -0.4661141 -0.8847246 0 -0.3503867 -0.93658 0.006873786 -0.1924429 -0.9812838 0.006916821 -0.151252 -0.9884952 0 -0.06909066 -0.9976104 0 -0.02809727 -0.9995821 0.006804764 0.09504908 -0.9954726 0 0.1383675 -0.9903546 0.007220327 0.1813983 -0.9834097 0 0.2551586 -0.9668992 0 0.2983917 -0.9544147 0.007424056 0.3409413 -0.9400846 0 0.4110933 -0.9115933 0 0.450091 -0.8929541 0.007147669 0.4882063 -0.8727282 0 0.5922964 -0.8056894 0.007039427 0.6258425 -0.7799495 0 0.6871496 -0.726516 0 0.716188 -0.6978747 0.006752312 0.8216404 -0.5699673 0.006674826 0.9045491 -0.4263126 0.00696814 0.9216559 -0.3880083 0 0.9620199 -0.2728917 0.006928384 0.9726147 -0.2324237 0 0.9938868 -0.1101923 0.006840109 0.975801 0.2185512 0.006918728 0.9658303 0.2591754 0 0.9414251 0.3372222 0 0.926733 0.3756587 0.00682044 0.8520172 0.5234694 0.006838917 0.7795849 0.6262966 0 0.7535047 0.6574082 0.006712257 0.7262729 0.6874065 0 0.6370926 0.7707563 0.00691998 0.5357308 0.8443888 0 0.4996786 0.8661829 0.006964981 0.4627318 0.8864984 0 0.3503867 0.9365798 0.006885051 0.1924118 0.9812899 0.006916821 0.1511892 0.988505 0 0.06915473 0.9976059 0 0.02812945 0.9995812 0.006793498 -0.09511291 0.9954665 0 -0.1383677 0.9903546 0.007220327 -0.1813361 0.9834212 0 -0.2552188 0.9668834 0 -0.2983918 0.9544144 0.007446587 -0.3408845 0.9401052 0 -0.4111466 0.9115692 0 -0.4500913 0.8929539 0.007147669 -0.4881566 0.8727561 0 -0.5923176 0.8056743 0.006994247 -0.6258814 0.7799183 0 -0.6871158 0.726548 0 -0.7161721 0.6978908 0.006786286 -0.8216405 0.5699673 0.00666356 -0.9045549 0.4263002 0.006973564 -0.9216656 0.3879852 0 -0.9620174 0.2729002 0.006928563 -0.9726112 0.2324383 0 -0.9938868 0.1101923 0.006838023 -0.6571268 -0.1187816 -0.7443624 -0.6575747 -0.1171927 -0.7442187 -0.6575747 -0.1171926 -0.7442187 -0.6575741 -0.1171926 -0.7442193 -0.6457052 -0.1727445 -0.7437904 -0.6292685 -0.2257279 -0.7436855 -0.6292686 -0.2257279 -0.7436854 -0.6292685 -0.225728 -0.7436854 -0.6291862 -0.2258615 -0.7437146 -0.6086522 -0.2772573 -0.7434185 -0.6086294 -0.2771643 -0.7434718 -0.6090013 -0.2766695 -0.7433515 -0.5839675 -0.3262531 -0.743331 -0.5839222 -0.3259494 -0.7434998 -0.5536022 -0.3752775 -0.7434322 -0.5536023 -0.3752776 -0.7434322 -0.5536022 -0.3752776 -0.7434322 -0.5536883 -0.3725034 -0.7447621 -0.5537742 -0.3725199 -0.7446899 -0.5211315 -0.4168057 -0.7447786 -0.5219775 -0.4169927 -0.7440811 -0.5229384 -0.4165476 -0.7436556 -0.4846466 -0.4600956 -0.7439286 -0.4846467 -0.4600955 -0.7439286 -0.4834815 -0.4561795 -0.7470916 -0.450225 -0.4885424 -0.7474114 -0.4457428 -0.4982016 -0.7437127 -0.4457428 -0.4982016 -0.7437127 -0.4457428 -0.4982015 -0.7437127 -0.4443087 -0.4979965 -0.7447076 -0.4013711 -0.5331668 -0.7447379 -0.4021498 -0.5334185 -0.7441373 -0.3595588 -0.5640035 -0.7433825 -0.3595588 -0.5640034 -0.7433825 -0.3595588 -0.5640034 -0.7433825 -0.3595902 -0.5640119 -0.7433609 -0.3135611 -0.5904767 -0.743651 -0.310518 -0.593604 -0.7424372 -0.3071446 -0.5916749 -0.7453745 -0.258848 -0.6140244 -0.7456353 -0.258848 -0.6140244 -0.7456352 -0.258848 -0.6140243 -0.7456352 -0.2602254 -0.6151741 -0.7442067 -0.2602254 -0.6151741 -0.7442067 -0.2590556 -0.614865 -0.7448701 -0.20833 -0.6340247 -0.7447223 -0.208595 -0.6324462 -0.7459893 -0.208595 -0.6324462 -0.7459893 -0.208595 -0.6324462 -0.7459893 -0.1563291 -0.6470969 -0.7462083 -0.1563292 -0.6470971 -0.7462081 -0.1563292 -0.6470971 -0.7462081 -0.1530544 -0.6487812 -0.7454242 -0.1581358 -0.65388 -0.7398879 -0.1038805 -0.6647072 -0.7398468 -0.1038804 -0.6647072 -0.7398468 -0.1011532 -0.6611701 -0.7433856 -0.09809315 -0.6592051 -0.7455377 -0.04525667 -0.665045 -0.7454308 -0.04427289 -0.6669003 -0.7438306 0.00910443 -0.6685476 -0.7436136 0.008826792 -0.6681098 -0.7440104 0.05897378 -0.6652427 -0.7442945 0.06218558 -0.6675573 -0.7419571 0.06701093 -0.6618248 -0.7466576 0.1212291 -0.6593778 -0.7419734 0.1182241 -0.6602614 -0.7416725 0.118224 -0.6602614 -0.7416725 0.1182238 -0.6602614 -0.7416725 0.1728915 -0.6478651 -0.7418755 0.1712214 -0.6461942 -0.7437179 0.227769 -0.6282497 -0.7439245 0.2268011 -0.6281605 -0.7442954 0.2261642 -0.6295946 -0.7432768 0.2756188 -0.609503 -0.7433305 0.2786816 -0.6114702 -0.7405679 0.3283717 -0.5867573 -0.7401945 0.3251509 -0.5846648 -0.7432658 0.3737221 -0.554902 -0.7432466 0.3747494 -0.5547093 -0.7428732 0.3749374 -0.5534945 -0.743684 0.4167187 -0.5228868 -0.7435961 0.4167187 -0.5228868 -0.743596 0.4167187 -0.5228868 -0.743596 0.4165138 -0.5217536 -0.7445062 0.4174756 -0.5193629 -0.7456382 0.4583035 -0.4842182 -0.7453125 0.4590386 -0.4843487 -0.7447751 0.4972507 -0.4453384 -0.7445909 0.497664 -0.4452254 -0.7443823 0.497664 -0.4452254 -0.7443823 0.4983962 -0.4488048 -0.7417382 0.4983963 -0.4488048 -0.7417382 0.4983963 -0.4488048 -0.7417381 0.5330684 -0.4035828 -0.7436122 0.5335354 -0.398015 -0.7462735 0.5619702 -0.3576801 -0.7458248 0.5926783 -0.3116011 -0.7427229 0.5928041 -0.3116269 -0.7426116 0.5914026 -0.3092417 -0.7447232 0.6161212 -0.2609803 -0.7431581 0.6154906 -0.2579111 -0.7447504 0.6154906 -0.2579112 -0.7447504 0.6154905 -0.2579111 -0.7447505 0.6337603 -0.2082868 -0.7449595 0.6478424 -0.1598964 -0.7448043 0.6478434 -0.1598967 -0.7448033 0.6478434 -0.1598968 -0.7448033 0.6499826 -0.1548516 -0.7440052 0.6614473 -0.1017702 -0.7430547 0.6614474 -0.1017701 -0.7430547 0.6614474 -0.1017701 -0.7430547 0.6608118 -0.1009545 -0.7437312 0.6670135 -0.04608714 -0.7436189 0.666711 -0.04620015 -0.7438831 0.6682577 0.00901103 -0.7438753 0.668441 0.009049773 -0.7437102 0.6655145 0.06457352 -0.7435864 0.665306 0.06406074 -0.7438173 0.6653899 0.06391376 -0.7437549 0.6578025 0.1193922 -0.7436676 0.657141 0.1187796 -0.7443501 0.6577 0.1172141 -0.7441046 0.6577 0.1172142 -0.7441046 0.6576998 0.117214 -0.7441048 0.6456841 0.1727486 -0.7438078 0.6292446 0.2256507 -0.7437291 0.6292447 0.2256507 -0.7437291 0.6292446 0.2256507 -0.7437291 0.6293102 0.225882 -0.7436035 0.6087245 0.2773087 -0.74334 0.6085416 0.2771294 -0.7435567 0.6091997 0.2766163 -0.7432088 0.5841262 0.3263418 -0.7431674 0.5838062 0.3258846 -0.7436193 0.5534324 0.3751781 -0.7436088 0.5537433 0.3725405 -0.7447027 0.5538829 0.3725931 -0.7445725 0.5212168 0.4168561 -0.7446907 0.5218873 0.4169154 -0.7441877 0.5218873 0.4169154 -0.7441876 0.5227759 0.416428 -0.7438368 0.4847613 0.4602215 -0.743776 0.4835694 0.4563512 -0.74693 0.4501039 0.4883978 -0.7475788 0.4459459 0.4983709 -0.7434775 0.4441515 0.4978202 -0.7449191 0.4011579 0.5328837 -0.7450553 0.4022375 0.5335333 -0.7440077 0.4022375 0.5335333 -0.7440076 0.4022375 0.5335333 -0.7440076 0.3595004 0.563961 -0.743443 0.359495 0.5638625 -0.7435203 0.3137459 0.5904673 -0.7435804 0.3137459 0.5904675 -0.7435804 0.3137459 0.5904675 -0.7435804 0.3105592 0.5936828 -0.742357 0.3070458 0.5914846 -0.7455662 0.2589693 0.6141665 -0.745476 0.2601301 0.6150903 -0.7443094 0.2591524 0.6148484 -0.74485 0.2082243 0.6338593 -0.7448927 0.2085755 0.6323757 -0.7460545 0.1568651 0.6469548 -0.7462191 0.153068 0.6486037 -0.745576 0.1581764 0.6540733 -0.7397084 0.1038206 0.664642 -0.7399137 0.1011276 0.6610032 -0.7435375 0.09807145 0.6590595 -0.7456693 0.04519748 0.6648657 -0.7455943 0.04429596 0.6671642 -0.7435926 -0.009057521 0.6683594 -0.7437834 -0.009057462 0.6683596 -0.7437832 -0.009057462 0.6683596 -0.7437832 -0.00887686 0.6681067 -0.7440126 -0.05897885 0.6654393 -0.7441183 -0.06215488 0.6676475 -0.7418785 -0.06700676 0.661783 -0.7466949 -0.1211729 0.6590718 -0.7422543 -0.1188275 0.6600733 -0.7417435 -0.1188272 0.6600733 -0.7417435 -0.1729749 0.6478555 -0.7418646 -0.1712193 0.6460178 -0.7438716 -0.2277299 0.6284896 -0.7437339 -0.2268101 0.6283406 -0.7441407 -0.2268101 0.6283406 -0.7441407 -0.2268101 0.6283405 -0.7441407 -0.2261392 0.6295251 -0.7433433 -0.2756135 0.609468 -0.7433613 -0.2756147 0.6094675 -0.7433612 -0.2756147 0.6094675 -0.7433612 -0.278737 0.6115919 -0.7404465 -0.3284025 0.5867507 -0.7401862 -0.3251891 0.5847435 -0.7431872 -0.3736237 0.5547834 -0.7433848 -0.3747566 0.5547075 -0.7428708 -0.3748003 0.5534014 -0.7438223 -0.4166904 0.5228178 -0.7436603 -0.4164156 0.5215563 -0.7446994 -0.4175583 0.5197111 -0.7453493 -0.4583484 0.4842056 -0.7452931 -0.4591775 0.4845128 -0.7445827 -0.4973425 0.4453985 -0.7444936 -0.4974766 0.4450567 -0.7446084 -0.4985219 0.449 -0.7415356 -0.5328018 0.403331 -0.7439398 -0.5335289 0.3980169 -0.7462772 -0.561786 0.3575918 -0.7460058 -0.5914974 0.3092913 -0.7446273 -0.6163259 0.2610669 -0.7429579 -0.6153945 0.2578783 -0.7448413 -0.6337182 0.208273 -0.7449991 -0.6479063 0.1599103 -0.7447457 -0.647907 0.1599106 -0.7447451 -0.647907 0.1599105 -0.7447451 -0.6498966 0.1548311 -0.7440845 -0.6615199 0.1017708 -0.74299 -0.6611449 0.1010205 -0.7434261 -0.6669583 0.04608178 -0.7436687 -0.6666274 0.04619377 -0.7439585 -0.6683685 -0.00901252 -0.7437758 -0.6684012 -0.009049117 -0.7437459 -0.6654899 -0.06457114 -0.7436086 -0.6653246 -0.06405937 -0.7438008 -0.6653422 -0.06391024 -0.7437979 -0.6578229 -0.1194049 -0.7436475 -0.8742781 0.06047886 -0.4816432 -0.8761392 -0.01186162 -0.4819123 -0.8719581 -0.08395302 -0.4823286 -0.8722196 -0.08421427 -0.4818102 -0.8622452 -0.1558604 -0.4819136 -0.8627017 -0.1563181 -0.4809476 -0.8470763 -0.2266167 -0.4807357 -0.8465887 -0.2259309 -0.481916 -0.824755 -0.2960603 -0.4817962 -0.8249816 -0.2966404 -0.481051 -0.8249816 -0.2966404 -0.4810509 -0.8249816 -0.2966404 -0.481051 -0.7972465 -0.3618653 -0.4831683 -0.7643953 -0.4266877 -0.4833607 -0.7264976 -0.4887146 -0.4830728 -0.6837311 -0.546881 -0.4831491 -0.6843401 -0.5498165 -0.4789368 -0.6385802 -0.6025806 -0.4786566 -0.6385802 -0.6025806 -0.4786565 -0.6385802 -0.6025806 -0.4786565 -0.6384027 -0.6010618 -0.480798 -0.5846804 -0.6534788 -0.4807436 -0.5846806 -0.6550841 -0.4785535 -0.5282822 -0.7017853 -0.4779282 -0.5282822 -0.7017853 -0.4779282 -0.5282822 -0.7017853 -0.4779282 -0.4705306 -0.7380408 -0.4836288 -0.4705307 -0.7380408 -0.4836287 -0.4705306 -0.7380408 -0.4836287 -0.4699502 -0.7427049 -0.4770076 -0.407834 -0.777095 -0.4793692 -0.3419502 -0.8055511 -0.4838983 -0.2737989 -0.8317814 -0.4828809 -0.2009812 -0.8519548 -0.4835077 -0.2015427 -0.8512722 -0.4844753 -0.1350557 -0.8641858 -0.484709 -0.1333679 -0.8669382 -0.4802408 -0.0581156 -0.8754659 -0.479773 -0.06075447 -0.8716736 -0.4863066 0.01154708 -0.8735919 -0.4865223 0.01142621 -0.8735358 -0.486626 0.08101963 -0.8696044 -0.4870566 0.08101427 -0.8696049 -0.4870566 0.08101433 -0.8696049 -0.4870566 0.08376228 -0.8725546 -0.4812819 0.1585023 -0.8621215 -0.4812729 0.1585023 -0.8621215 -0.4812728 0.1585023 -0.8621216 -0.4812729 0.1555917 -0.859706 -0.486515 0.2237716 -0.8445375 -0.4865005 0.2288861 -0.8480975 -0.4778512 0.2983307 -0.8262903 -0.4777483 0.2923507 -0.8227075 -0.487528 0.3646745 -0.7958174 -0.4834122 0.4255315 -0.7651868 -0.4831277 0.4267412 -0.7655879 -0.4814221 0.4907472 -0.7264037 -0.4811496 0.4905012 -0.7261762 -0.4817435 0.5461938 -0.685329 -0.4816603 0.5451324 -0.6850852 -0.4832071 0.5451323 -0.6850852 -0.483207 0.5451323 -0.6850852 -0.4832071 0.602231 -0.6354677 -0.4832169 0.6022311 -0.6354678 -0.4832169 0.602231 -0.6354677 -0.4832169 0.6045544 -0.6358358 -0.4798197 0.6539502 -0.5850383 -0.4796659 0.6511631 -0.5848455 -0.4836759 0.6511656 -0.5848427 -0.4836759 0.6511631 -0.5848455 -0.483676 0.6969694 -0.5294948 -0.4836 0.7011996 -0.5293615 -0.4775936 0.7424385 -0.4692437 -0.4781166 0.739078 -0.4696601 -0.4828905 0.775089 -0.4074599 -0.482922 0.7773936 -0.4069898 -0.4796025 0.8081869 -0.3411027 -0.4800863 0.8075489 -0.3413438 -0.4809879 0.8328369 -0.2737157 -0.4811055 0.8660494 -0.1322219 -0.4821577 0.8742413 -0.06047636 -0.4817104 0.8761817 0.01186215 -0.4818352 0.8719235 0.08395612 -0.4823907 0.8722199 0.08421415 -0.4818096 0.8622994 0.1558581 -0.4818176 0.8626652 0.1563115 -0.4810152 0.8470574 0.2266295 -0.4807628 0.8465065 0.2258993 -0.4820751 0.8465065 0.2258993 -0.4820751 0.8465064 0.2258992 -0.4820751 0.8246275 0.2959985 -0.4820522 0.8251124 0.2967101 -0.4807834 0.7974051 0.3619076 -0.4828749 0.7643296 0.4266511 -0.4834969 0.7264668 0.488694 -0.4831399 0.6837652 0.5469779 -0.482991 0.6837652 0.5469779 -0.482991 0.6843527 0.5498731 -0.478854 0.6385313 0.6024795 -0.4788488 0.6385313 0.6024795 -0.4788488 0.638368 0.6009777 -0.4809495 0.5845239 0.6532292 -0.4812729 0.5847183 0.6551952 -0.4783554 0.5847183 0.6551952 -0.4783553 0.5847183 0.6551952 -0.4783554 0.5283675 0.7018963 -0.4776708 0.4705006 0.7379634 -0.483776 0.4699437 0.7426078 -0.4771651 0.4077706 0.777158 -0.4793209 0.4077706 0.777158 -0.4793209 0.3418766 0.8055064 -0.4840245 0.2737916 0.831593 -0.4832093 0.2010746 0.8520909 -0.4832289 0.2015336 0.851222 -0.4845671 0.1349984 0.8641927 -0.4847128 0.1334016 0.8671573 -0.4798356 0.05809569 0.8751661 -0.4803219 0.06069856 0.8717336 -0.4862062 -0.01161146 0.87373 -0.4862728 -0.0116077 0.87373 -0.4862728 -0.0116077 0.87373 -0.4862728 -0.0113663 0.8733389 -0.4869804 -0.08096313 0.8696911 -0.4869111 -0.08375966 0.8725271 -0.4813324 -0.1585431 0.8623376 -0.4808721 -0.1556318 0.8596256 -0.4866443 -0.2238278 0.8445135 -0.4865163 -0.2238272 0.8445137 -0.4865163 -0.2238271 0.8445137 -0.4865163 -0.2288613 0.8482427 -0.4776056 -0.2288613 0.8482427 -0.4776055 -0.2288613 0.8482426 -0.4776055 -0.2982748 0.8263053 -0.477757 -0.2924162 0.8227382 -0.4874368 -0.3646348 0.79585 -0.4833883 -0.4254581 0.765055 -0.4834008 -0.4267683 0.7656365 -0.481321 -0.4906632 0.7262793 -0.481423 -0.4905737 0.7262833 -0.4815081 -0.5462353 0.6852851 -0.4816756 -0.5462353 0.6852852 -0.4816756 -0.5462353 0.6852851 -0.4816756 -0.5450424 0.6849606 -0.4834851 -0.6022467 0.6354852 -0.4831745 -0.6022467 0.6354852 -0.4831743 -0.6022467 0.6354853 -0.4831744 -0.6046051 0.6358892 -0.4796849 -0.6538384 0.5849383 -0.4799402 -0.6512204 0.5848999 -0.4835331 -0.6968492 0.5294035 -0.4838732 -0.7011114 0.5292949 -0.4777967 -0.7423753 0.4692038 -0.478254 -0.7390154 0.4696204 -0.483025 -0.7751557 0.4074949 -0.4827851 -0.7774263 0.4070069 -0.4795349 -0.8082561 0.3411319 -0.4799493 -0.8075829 0.3413582 -0.4809204 -0.8327654 0.2736922 -0.4812425 -0.8660859 0.1322275 -0.4820905 -0.9835504 0.06812608 -0.1672946 -0.9859099 -0.0133289 -0.1667449 -0.9858943 -0.01330369 -0.1668401 -0.9814016 -0.09474998 -0.1669538 -0.9814305 -0.09486073 -0.1667205 -0.9702245 -0.1757878 -0.1666228 -0.9700596 -0.1751614 -0.168235 -0.9525423 -0.2555945 -0.1653319 -0.9281327 -0.3337197 -0.1649271 -0.9280335 -0.3324536 -0.1680132 -0.8976122 -0.4074015 -0.1682749 -0.8976119 -0.4075884 -0.1678228 -0.8606098 -0.480686 -0.1682016 -0.860593 -0.4809404 -0.1675596 -0.8605929 -0.4809404 -0.1675596 -0.860593 -0.4809404 -0.1675596 -0.8180267 -0.5502895 -0.1673734 -0.8180469 -0.5503849 -0.1669602 -0.8180469 -0.5503849 -0.1669601 -0.818047 -0.550385 -0.1669602 -0.7685295 -0.6174733 -0.1675982 -0.7685295 -0.6174733 -0.1675982 -0.7685295 -0.6174733 -0.1675982 -0.7686004 -0.6174281 -0.1674396 -0.7177942 -0.6758061 -0.1675042 -0.7167445 -0.6784597 -0.1611518 -0.6572294 -0.7363674 -0.1606627 -0.6589816 -0.7327863 -0.1696097 -0.5949482 -0.7855993 -0.1699135 -0.5949482 -0.7855993 -0.1699135 -0.5949481 -0.7855992 -0.1699135 -0.5953851 -0.7847819 -0.1721453 -0.5266939 -0.8323818 -0.1724358 -0.5253603 -0.8343492 -0.1669073 -0.5253603 -0.8343493 -0.1669073 -0.5253604 -0.8343492 -0.1669072 -0.4582292 -0.8731045 -0.1664774 -0.4592736 -0.8717637 -0.170575 -0.3850284 -0.9070166 -0.170511 -0.3836011 -0.9085094 -0.1657136 -0.3836011 -0.9085094 -0.1657135 -0.3836011 -0.9085094 -0.1657136 -0.3083374 -0.9367126 -0.1658245 -0.3083374 -0.9367126 -0.1658244 -0.3083374 -0.9367126 -0.1658244 -0.3070952 -0.9377893 -0.1619993 -0.3070954 -0.9377893 -0.1619993 -0.3070953 -0.9377893 -0.1619994 -0.229928 -0.9583835 -0.1692167 -0.1498533 -0.9740923 -0.1693763 -0.1498534 -0.9740923 -0.1693761 -0.1498534 -0.9740923 -0.1693761 -0.1491259 -0.9746025 -0.1670673 -0.06854796 -0.9835343 -0.1672166 -0.06813061 -0.9837449 -0.166145 -0.06812769 -0.9837452 -0.166145 -0.06813061 -0.9837449 -0.166145 0.01289457 -0.9859503 -0.1665406 0.01276129 -0.9859565 -0.1665142 0.09421819 -0.9814639 -0.1668879 0.09370291 -0.9813852 -0.1676393 0.1755592 -0.9700462 -0.1678971 0.1790789 -0.9708395 -0.1593788 0.2572329 -0.9531319 -0.1592822 0.2512863 -0.952215 -0.1736147 0.2512863 -0.952215 -0.1736147 0.2512862 -0.9522149 -0.1736147 0.3297765 -0.9280651 -0.1730394 0.3297765 -0.9280651 -0.1730393 0.3297766 -0.9280651 -0.1730393 0.3367093 -0.9284369 -0.1569452 0.4113835 -0.8977582 -0.1574606 0.4049382 -0.8979719 -0.172255 0.4812061 -0.8602426 -0.1685925 0.549099 -0.8173237 -0.1745632 0.6173477 -0.7693806 -0.16412 0.6797215 -0.7148776 -0.1640997 0.6770681 -0.7158582 -0.1706631 0.6770653 -0.7158609 -0.1706631 0.6770681 -0.7158582 -0.1706632 0.7331267 -0.6584569 -0.1701758 0.7332929 -0.6583755 -0.1697742 0.7865322 -0.5937817 -0.169678 0.786554 -0.5937943 -0.169532 0.8318216 -0.5285862 -0.1693208 0.831712 -0.5286429 -0.1696823 0.8731831 -0.457143 -0.1690314 0.8730042 -0.4572893 -0.1695588 0.8730043 -0.4572893 -0.1695588 0.8730043 -0.4572893 -0.1695589 0.9078291 -0.3837311 -0.1691063 0.9089333 -0.382653 -0.1655814 0.9366803 -0.3084475 -0.165802 0.9365323 -0.3086618 -0.1662389 0.9365323 -0.3086619 -0.1662388 0.9365323 -0.3086618 -0.1662389 0.9590904 -0.228991 -0.1664593 0.9589481 -0.2291646 -0.1670397 0.9745776 -0.148954 -0.1673657 0.983554 -0.06812632 -0.1672734 0.9859091 0.0133289 -0.1667503 0.9858978 0.01330375 -0.166819 0.9813944 0.09474927 -0.1669964 0.9814233 0.09486007 -0.166763 0.9702103 0.1757853 -0.1667082 0.9700701 0.1751633 -0.1681716 0.9525372 0.2556081 -0.1653407 0.9281236 0.3337402 -0.1649372 0.9280175 0.3324279 -0.1681526 0.8976653 0.4074121 -0.1679658 0.8976654 0.4074121 -0.1679658 0.8976653 0.4074119 -0.1679657 0.8976185 0.4075915 -0.1677805 0.8606605 0.4807143 -0.1678611 0.8605938 0.4809653 -0.1674836 0.8180028 0.5502734 -0.1675438 0.8179994 0.5503572 -0.1672845 0.7685573 0.617526 -0.1672763 0.768566 0.6174433 -0.1675419 0.7685659 0.6174433 -0.1675418 0.7685659 0.6174434 -0.1675419 0.7178213 0.6757767 -0.1675067 0.7178213 0.6757767 -0.1675066 0.7178213 0.6757767 -0.1675067 0.7168267 0.6784754 -0.160719 0.6571921 0.7363994 -0.1606696 0.6589459 0.7327451 -0.1699264 0.5949133 0.7855541 -0.1702442 0.595357 0.784743 -0.1724195 0.5267095 0.8323026 -0.1727699 0.5274081 0.8312809 -0.1755361 0.4574605 0.8716397 -0.1759951 0.4559507 0.8735084 -0.1705644 0.4559508 0.8735083 -0.1705643 0.4559507 0.8735083 -0.1705644 0.3850057 0.9070276 -0.1705042 0.3850057 0.9070276 -0.1705041 0.3850057 0.9070276 -0.1705041 0.3835687 0.9084374 -0.1661821 0.3083982 0.936695 -0.1658111 0.3070968 0.9378001 -0.1619337 0.2299342 0.9583917 -0.1691612 0.2299342 0.9583917 -0.1691612 0.2299342 0.9583917 -0.1691613 0.1498567 0.974113 -0.1692538 0.1498567 0.974113 -0.1692537 0.1498567 0.9741131 -0.1692537 0.1490665 0.9746318 -0.1669497 0.06848311 0.9835405 -0.1672074 0.06848424 0.9835404 -0.1672074 0.06848424 0.9835404 -0.1672074 0.06819063 0.9836964 -0.1664083 -0.01283085 0.9859511 -0.1665407 -0.01276177 0.9859011 -0.1668418 -0.01276177 0.9859012 -0.1668416 -0.01276171 0.9859011 -0.1668418 -0.09422391 0.9814829 -0.1667734 -0.09421938 0.9814833 -0.1667733 -0.09421944 0.9814833 -0.1667733 -0.09376168 0.9813303 -0.1679269 -0.1756332 0.9700921 -0.1675545 -0.1790045 0.9707829 -0.1598056 -0.2571571 0.9530948 -0.1596268 -0.2513688 0.9522942 -0.1730594 -0.3298378 0.9280194 -0.1731676 -0.3366351 0.9284165 -0.1572251 -0.4113155 0.897749 -0.1576911 -0.4113104 0.8977513 -0.1576908 -0.4113104 0.8977513 -0.1576909 -0.4049871 0.8979323 -0.1723456 -0.4811846 0.8603014 -0.1683535 -0.549124 0.817361 -0.1743099 -0.6174393 0.7694124 -0.1636258 -0.6797605 0.7149186 -0.1637592 -0.6769923 0.7158542 -0.1709802 -0.733083 0.6584175 -0.1705165 -0.7332767 0.6583608 -0.1699013 -0.7865788 0.5938168 -0.1693382 -0.786525 0.5937724 -0.1697432 -0.8318464 0.528602 -0.1691504 -0.8317458 0.5286644 -0.1694493 -0.8731573 0.4571294 -0.1692016 -0.8729993 0.4573017 -0.1695508 -0.9078022 0.3837197 -0.1692765 -0.9089592 0.3826405 -0.1654673 -0.9367032 0.3084618 -0.1656455 -0.9367032 0.3084618 -0.1656454 -0.9367033 0.3084619 -0.1656455 -0.9365051 0.3086584 -0.1663976 -0.9590764 0.2289877 -0.1665444 -0.958948 0.2291749 -0.1670255 -0.9745883 0.1489556 -0.1673023 0.07356983 0.4944361 -0.866095 0.1174607 0.4856967 -0.8661996 0.229834 0.4427732 -0.8666766 0.3323928 0.3725531 -0.8664406 0.4548246 0.2065032 -0.8663089 0.4982475 0.04785621 -0.8657132 0.4947754 -0.07558995 -0.8657271 0.4854097 -0.1156668 -0.8666018 0.4423485 -0.2313016 -0.8665031 0.371483 -0.3345339 -0.8660759 0.2058563 -0.454804 -0.8664736 0.08794575 -0.4909265 -0.8667508 0.08794575 -0.4909265 -0.8667508 0.08794564 -0.4909265 -0.8667508 0.05041283 -0.4978531 -0.865795 0.006796896 -0.4990278 -0.8665593 -0.07357513 -0.4944718 -0.8660741 -0.1174691 -0.4857317 -0.8661788 -0.2298159 -0.4427382 -0.8666992 -0.332335 -0.3724884 -0.8664905 -0.4546514 -0.2065398 -0.8663911 -0.4546514 -0.2065398 -0.866391 -0.4982467 -0.04785621 -0.8657137 -0.4947242 0.07559251 -0.8657562 -0.4854796 0.1156834 -0.8665604 -0.4424181 0.231338 -0.8664578 -0.3714505 0.3345386 -0.866088 -0.2059456 0.4550014 -0.8663488 -0.08830553 0.490863 -0.8667501 -0.08830553 0.4908629 -0.8667501 -0.08830547 0.490863 -0.8667501 -0.05041515 0.4978762 -0.8657816 -0.006764769 0.4991422 -0.8664937 0.2230219 -0.06666874 -0.9725311 0.0608412 0.2234821 -0.9728074 -0.2231861 0.06677168 -0.9724863 -0.06104761 -0.223516 -0.9727866 0.07334232 -0.2261162 -0.9713354 0.0317052 -0.3419892 -0.9391689 0.06110286 -0.2258821 -0.9722365 0.04383641 -0.2975322 -0.9537048 -0.1145674 -0.2355909 -0.9650759 0.07096111 -0.2304173 -0.9705012 -0.09300965 -0.1912854 -0.9771178 -0.1030474 -0.1469609 -0.98376 -0.1134723 -0.1369192 -0.9840616 -0.09960168 -0.1470575 -0.9841005 -0.2275591 -0.07253414 -0.9710592 -0.3472435 -0.02752548 -0.937371 -0.2273793 -0.05599021 -0.9721954 -0.2273792 -0.05599015 -0.9721955 -0.2273792 -0.05599015 -0.9721955 -0.2943354 -0.03675276 -0.9549953 -0.2355271 0.1132769 -0.9652436 -0.2260392 -0.05312871 -0.9726684 -0.1918624 0.09229075 -0.9770728 -0.1471431 0.1025226 -0.9837877 -0.1370705 0.1132438 -0.9840669 -0.1431796 0.1043381 -0.9841815 -0.07326734 0.225885 -0.9713948 -0.03168541 0.3418794 -0.9392096 -0.03168535 0.3418794 -0.9392096 -0.03168535 0.3418793 -0.9392096 -0.0612508 0.2258801 -0.9722276 -0.04392951 0.2975027 -0.9537099 -0.04392945 0.2975027 -0.9537099 -0.04392945 0.2975027 -0.9537099 0.1145568 0.235569 -0.9650825 -0.07117176 0.2303853 -0.9704933 -0.07117176 0.2303853 -0.9704933 -0.0711717 0.2303854 -0.9704933 0.09307473 0.1913997 -0.9770892 0.1030417 0.1469981 -0.9837551 0.1134956 0.1369473 -0.984055 0.09962761 0.1470958 -0.9840921 0.227501 0.07251566 -0.9710741 0.3475065 0.02758902 -0.9372717 0.3475065 0.02758896 -0.9372717 0.3475064 0.02758902 -0.9372717 0.2274959 0.05607223 -0.9721633 0.294401 0.03671997 -0.9549763 0.294401 0.03671991 -0.9549764 0.2944008 0.03671997 -0.9549763 0.2354691 -0.113249 -0.9652611 0.2258991 0.05296313 -0.97271 0.2258991 0.05296307 -0.97271 0.2258991 0.05296313 -0.97271 0.1918053 -0.09226328 -0.9770867 0.1470751 -0.1024973 -0.9838004 0.1370144 -0.1131975 -0.98408 0.1434912 -0.1046794 -0.9840999 -0.01602935 0.4950169 -0.8687356 -0.01367151 0.422188 -0.9064052 0.03658241 0.4208023 -0.9064145 0.02969962 0.3416096 -0.9393727 0.06957995 0.3356898 -0.9393993 -0.08802849 0.4909092 -0.866752 -0.07644891 0.4886806 -0.869107 -0.06535249 0.4177091 -0.9062274 -0.01281058 0.4226114 -0.9062204 -0.01039689 0.3429061 -0.9393122 0.03008854 0.3418195 -0.9392839 -0.1692163 0.4710369 -0.865731 -0.1705004 0.4705278 -0.8657559 -0.1274586 0.4773466 -0.869422 -0.1342581 0.4790739 -0.8674463 -0.1140415 0.4069302 -0.9063125 -0.06580108 0.4174391 -0.9063194 -0.05348628 0.3393185 -0.9391497 -0.2057588 0.4549899 -0.8663992 -0.1902009 0.4562418 -0.8692911 -0.1627085 0.3902893 -0.906201 -0.09230172 0.3311781 -0.9390429 -0.05274045 0.3397136 -0.9390491 -0.2805847 0.4142865 -0.8658169 -0.2794117 0.4148771 -0.8659135 -0.2419708 0.4323101 -0.8686531 -0.2448309 0.432228 -0.8678922 -0.2083992 0.3679041 -0.9062099 -0.162789 0.3902003 -0.9062249 -0.1320617 0.3165501 -0.9393379 -0.07612919 0.267479 -0.9605516 -0.04261833 0.2744939 -0.960644 -0.02935874 0.2650429 -0.9637897 -0.02885478 0.2837207 -0.9584727 0.02485525 0.2823236 -0.9589973 0.04412674 0.2639985 -0.9635133 0.05439692 0.2624394 -0.9634141 0.04435288 0.2751514 -0.9603773 0.04435658 0.2751153 -0.9603875 -0.1099385 0.2380304 -0.9650156 -0.1003602 0.2414492 -0.96521 -0.1317393 0.3169287 -0.9392556 -0.1693071 0.2985437 -0.9392587 -0.2084978 0.3676419 -0.9062936 -0.2519831 0.3393734 -0.9062728 -0.2946444 0.3968292 -0.8693166 -0.3410614 0.3603039 -0.8682501 -0.312875 0.3894183 -0.8662925 -0.3117907 0.3905118 -0.8661912 -0.3725376 0.3336333 -0.8659703 -0.3409878 0.360635 -0.8681416 -0.2904192 0.3071591 -0.9062616 -0.169307 0.298568 -0.939251 -0.1289238 0.2273619 -0.9652385 -0.1005639 0.2411653 -0.9652597 -0.0692594 0.1661163 -0.983671 0.06108582 0.2224861 -0.9730203 -0.0943256 0.1532673 -0.9836726 -0.08830726 0.1565678 -0.9837116 -0.1285184 0.2278681 -0.9651732 -0.1550285 0.2106195 -0.9651973 -0.2038674 0.2769775 -0.9390003 -0.235584 0.2503623 -0.9390522 -0.2901131 0.3083141 -0.9059674 -0.3256825 0.2701564 -0.9060609 -0.379939 0.3151581 -0.8696675 -0.4180157 0.2660741 -0.868601 -0.4005769 0.2988326 -0.8661625 -0.398547 0.3016911 -0.8661078 -0.4178316 0.2685627 -0.8679233 -0.3558725 0.228739 -0.9061089 -0.3257544 0.270019 -0.906076 -0.2641423 0.2189475 -0.9393033 -0.2363324 0.2486531 -0.9393183 -0.1799845 0.1893591 -0.9652713 -0.1555634 0.209762 -0.9652979 -0.105812 0.1426718 -0.9840978 -0.09168928 0.151921 -0.9841306 -0.09957647 0.152604 -0.9832581 -0.1050842 0.1435375 -0.98405 -0.1221805 0.1292288 -0.9840589 -0.1796445 0.190021 -0.9652046 -0.2890481 0.1853065 -0.9392086 -0.3559204 0.2281771 -0.9062317 -0.3804906 0.184358 -0.9062225 -0.4696808 0.1541664 -0.8692714 -0.461318 0.1933071 -0.8659204 -0.4606079 0.1951048 -0.8658952 -0.4711729 0.1613773 -0.8671526 -0.3804852 0.1841597 -0.906265 -0.3090571 0.1495882 -0.9392057 -0.2890965 0.1853013 -0.9391947 -0.2201121 0.1410806 -0.9652187 -0.1368373 0.113467 -0.9840736 -0.1222608 0.1293098 -0.9840384 -0.4945137 0.07607454 -0.8658342 -0.4135804 0.08775109 -0.906229 -0.3999903 0.1373711 -0.9061661 -0.3247961 0.1115455 -0.9391833 -0.2198195 0.1419345 -0.9651601 -0.1479086 0.09886473 -0.9840472 -0.4973161 0.034361 -0.8668887 -0.4926747 0.04357326 -0.869122 -0.4210616 0.03724032 -0.9062672 -0.4135309 0.0873872 -0.9062868 -0.275315 0.09406983 -0.9567406 -0.220171 0.129852 -0.9667798 -0.4980756 -0.04833191 -0.8657857 -0.4943506 -0.01611071 -0.8691133 -0.4224969 -0.01376891 -0.9062598 -0.4211416 0.03729826 -0.9062277 -0.4912137 -0.08916109 -0.8664638 -0.4177718 -0.06454986 -0.9062561 -0.3432404 -0.01118874 -0.939181 -0.3420054 0.03021651 -0.939212 -0.4706706 -0.1687777 -0.8660158 -0.4708712 -0.1688607 -0.8658905 -0.4774131 -0.1274989 -0.8693796 -0.4792876 -0.1351879 -0.8671838 -0.4544803 -0.2070227 -0.8663656 -0.4559544 -0.1898674 -0.8695149 -0.3904786 -0.1626046 -0.9061382 -0.3306691 -0.09282654 -0.9391705 -0.3394436 -0.05230289 -0.9391712 -0.4144725 -0.2809628 -0.8656054 -0.432322 -0.2450699 -0.867778 -0.367774 -0.2084814 -0.9062439 -0.3900896 -0.162902 -0.9062522 -0.3167099 -0.1322631 -0.9392557 -0.3302966 -0.09327703 -0.939257 -0.2673509 -0.07549947 -0.960637 -0.2743558 -0.04227375 -0.9606987 -0.2654507 -0.02973133 -0.9636659 -0.2671427 -0.00873351 -0.9636174 -0.2830627 -0.02917617 -0.9586576 -0.2818427 0.02490103 -0.9591375 -0.2632509 0.04441446 -0.9637045 -0.2616667 0.05568671 -0.9635506 -0.2751421 0.04482829 -0.9603579 -0.2752314 0.04525542 -0.9603123 -0.2752313 0.04525536 -0.9603124 -0.2752314 0.04525536 -0.9603123 -0.2378827 -0.1104081 -0.9649984 -0.2414427 -0.1003366 -0.965214 -0.3171158 -0.1317846 -0.9391861 -0.3676475 -0.2085502 -0.9062793 -0.3395184 -0.2516878 -0.9063005 -0.3969282 -0.2942451 -0.8694067 -0.3595924 -0.3413819 -0.8684192 -0.3909024 -0.3113725 -0.8661655 -0.3904233 -0.3118877 -0.8661962 -0.3382908 -0.367069 -0.8664985 -0.3605577 -0.3410689 -0.8681418 -0.3073363 -0.2907285 -0.9061022 -0.3402895 -0.2514025 -0.9060904 -0.2760106 -0.2039089 -0.939276 -0.2416758 -0.1001896 -0.965171 -0.1653409 -0.06854617 -0.9838516 -0.2235473 0.06662827 -0.9724131 -0.2235472 0.06662833 -0.9724131 -0.2235472 0.06662833 -0.9724133 -0.1524837 -0.09428077 -0.9837987 -0.1557543 -0.08852183 -0.9838215 -0.2274569 -0.1292712 -0.9651696 -0.249392 -0.2357521 -0.9392681 -0.3075058 -0.2906816 -0.9060599 -0.2706118 -0.3253714 -0.9060369 -0.3157798 -0.379683 -0.8695539 -0.2665255 -0.4180834 -0.8684299 -0.3019609 -0.399235 -0.8656969 -0.2340903 -0.4403114 -0.8667917 -0.2340903 -0.4403114 -0.8667917 -0.2340903 -0.4403115 -0.8667916 -0.2680625 -0.4179431 -0.8680243 -0.2280897 -0.3556292 -0.9063681 -0.2691075 -0.3256544 -0.9063832 -0.2498832 -0.2355695 -0.9391834 -0.1901831 -0.1792861 -0.9652393 -0.2098087 -0.1559327 -0.9652281 -0.1426066 -0.1059864 -0.9840885 -0.1525112 -0.09090095 -0.9841125 -0.1530978 -0.09537965 -0.9835974 -0.1423835 -0.1061958 -0.9840983 -0.1907796 -0.1790574 -0.965164 -0.1665275 -0.2016522 -0.9651969 -0.2186134 -0.2647204 -0.9392185 -0.185724 -0.2888329 -0.9391924 -0.2286632 -0.3556066 -0.9062324 -0.1840096 -0.3806366 -0.9062319 -0.1542869 -0.4695597 -0.8693154 -0.1941946 -0.4609465 -0.8659197 -0.1948766 -0.4606842 -0.865906 -0.1173483 -0.4856767 -0.8662261 -0.1630079 -0.4711984 -0.8668336 -0.1848085 -0.3806628 -0.9060584 -0.1500499 -0.3090727 -0.9391268 -0.1862635 -0.2887334 -0.9391161 -0.1417592 -0.2197459 -0.9652026 -0.1662182 -0.2018122 -0.9652168 -0.1013119 -0.4834862 -0.8694694 -0.08665502 -0.413542 -0.9063521 -0.1370823 -0.3996709 -0.9063507 -0.1112968 -0.3244616 -0.9393283 -0.1486858 -0.3091014 -0.9393343 -0.113369 -0.2356778 -0.9651961 -0.09956413 -0.1472078 -0.9840818 -0.0338822 -0.497931 -0.8665546 -0.04447275 -0.4926643 -0.8690825 -0.03803849 -0.4213716 -0.90609 -0.087897 -0.4138961 -0.9060708 -0.07137608 -0.336084 -0.9391236 -0.1127981 -0.3246031 -0.9391003 -0.0956332 -0.2752078 -0.9566164 0.01603275 -0.4951213 -0.868676 0.01366817 -0.4220843 -0.9064536 -0.0365476 -0.4207187 -0.9064547 -0.02968591 -0.3416628 -0.9393537 -0.06957143 -0.3357047 -0.9393947 0.08801817 -0.4909097 -0.8667529 0.07646697 -0.4886023 -0.8691493 0.06538075 -0.4177432 -0.9062098 0.01281231 -0.4226678 -0.9061942 0.01039767 -0.3429312 -0.9393031 -0.03008323 -0.3417598 -0.9393058 0.1692071 -0.4710114 -0.8657466 0.1705753 -0.4704797 -0.8657674 0.1273837 -0.4773513 -0.8694305 0.1342357 -0.4790754 -0.867449 0.1140252 -0.4069538 -0.906304 0.06579649 -0.4174392 -0.9063197 0.053478 -0.3392658 -0.9391692 0.2057872 -0.4550527 -0.8663594 0.1901909 -0.4562178 -0.869306 0.1627356 -0.3903541 -0.9061682 0.09229534 -0.3311553 -0.9390516 0.05275434 -0.3398028 -0.939016 0.2805691 -0.4142019 -0.8658624 0.2794876 -0.4149896 -0.8658351 0.2419239 -0.4322773 -0.8686825 0.2448438 -0.4322509 -0.8678772 0.2083761 -0.3678634 -0.9062318 0.1627673 -0.3901484 -0.9062511 0.1320571 -0.3165392 -0.9393423 0.07613557 -0.2675015 -0.9605448 0.04262787 -0.2745554 -0.960626 0.02936685 -0.2649888 -0.9638043 0.02882492 -0.2836967 -0.9584808 -0.02485984 -0.2823759 -0.9589816 -0.04408353 -0.263955 -0.9635272 -0.05440324 -0.2624393 -0.9634138 -0.04436081 -0.2750455 -0.9604073 -0.04423803 -0.2751051 -0.9603959 0.1099615 -0.2380803 -0.9650008 0.1003422 -0.2414057 -0.9652227 0.1317508 -0.3169564 -0.9392446 0.1692837 -0.2985025 -0.939276 0.2085396 -0.3677154 -0.9062542 0.2519831 -0.3393734 -0.9062728 0.2946521 -0.3968396 -0.8693092 0.3410813 -0.3603553 -0.8682209 0.3131038 -0.389512 -0.8661677 0.3117483 -0.3905175 -0.8662039 0.3726453 -0.3337298 -0.8658868 0.3409174 -0.3605586 -0.868201 0.2904675 -0.3072102 -0.9062288 0.1692731 -0.2985697 -0.9392565 0.1289125 -0.227383 -0.9652349 0.1005888 -0.241225 -0.9652422 0.06926995 -0.1661415 -0.983666 -0.06104308 -0.2225025 -0.9730193 -0.06104302 -0.2225025 -0.9730193 -0.06104302 -0.2225025 -0.9730193 0.09429001 -0.1532095 -0.9836851 0.08834922 -0.156598 -0.983703 0.1284943 -0.2277826 -0.9651965 0.1559958 -0.2099669 -0.9651835 0.204697 -0.2755158 -0.9392499 0.2352254 -0.2499811 -0.9392436 0.2900355 -0.3082316 -0.9060202 0.3257409 -0.2701842 -0.9060317 0.3799217 -0.3151218 -0.8696883 0.4179857 -0.2660353 -0.8686273 0.4005984 -0.2988486 -0.8661469 0.3985031 -0.3016974 -0.8661259 0.4416243 -0.2321866 -0.8666356 0.4178083 -0.2685659 -0.8679336 0.355892 -0.2287662 -0.9060943 0.3257565 -0.2700188 -0.9060754 0.2641059 -0.2189174 -0.9393208 0.235386 -0.249634 -0.9392957 0.1795039 -0.1903632 -0.9651634 0.155848 -0.2101782 -0.9651615 0.1058362 -0.142726 -0.9840874 0.09168511 -0.1518988 -0.9841344 0.09956711 -0.1525897 -0.9832613 0.1050625 -0.143508 -0.9840566 0.1222114 -0.1292615 -0.9840508 0.1796001 -0.1899739 -0.9652221 0.2890658 -0.1853333 -0.9391978 0.3559457 -0.2282096 -0.9062137 0.3805327 -0.1843784 -0.9062006 0.469743 -0.1541868 -0.8692342 0.4611591 -0.1932405 -0.86602 0.4605954 -0.1950995 -0.865903 0.471123 -0.1613602 -0.8671828 0.3804562 -0.1841334 -0.9062826 0.3091206 -0.1496078 -0.9391816 0.2890473 -0.1852689 -0.9392163 0.2200332 -0.14103 -0.965244 0.1368719 -0.1134957 -0.9840655 0.1221604 -0.1292036 -0.9840648 0.4945894 -0.07609587 -0.8657891 0.4136263 -0.0877608 -0.9062072 0.3999369 -0.1373527 -0.9061926 0.3248411 -0.1115609 -0.9391659 0.2199288 -0.142005 -0.9651249 0.1478812 -0.09883272 -0.9840545 0.4972873 -0.03436166 -0.8669053 0.4926575 -0.04357373 -0.8691318 0.4210894 -0.03724479 -0.9062541 0.4134761 -0.08737564 -0.906313 0.2752155 -0.0940358 -0.9567726 0.2203665 -0.1299673 -0.9667198 0.4980736 0.04833197 -0.8657868 0.4943706 0.01611053 -0.869102 0.4225611 0.01377028 -0.9062299 0.4210255 -0.03728842 -0.9062821 0.4911722 0.08914643 -0.8664888 0.417818 0.06455695 -0.9062343 0.3431929 0.01118719 -0.9391984 0.3420652 -0.03022176 -0.9391902 0.4709771 0.1688876 -0.8658277 0.4705955 0.1687619 -0.8660597 0.47735 0.1274821 -0.8694167 0.4793385 0.1352022 -0.8671535 0.4545899 0.2070921 -0.8662915 0.4559065 0.1898474 -0.8695443 0.3904353 0.1625866 -0.90616 0.3307137 0.09283936 -0.9391536 0.3393639 0.05229419 -0.9392005 0.4141109 0.2807177 -0.8658579 0.4323676 0.2450958 -0.8677479 0.3677332 0.2084583 -0.9062656 0.3900637 0.1628911 -0.9062653 0.316712 0.132263 -0.9392551 0.3303018 0.09327685 -0.9392551 0.2674059 0.07551658 -0.9606204 0.2744122 0.04228579 -0.960682 0.265393 0.02972483 -0.9636821 0.2671347 0.008733272 -0.9636197 0.2830223 0.02916991 -0.9586697 0.2818785 -0.02490419 -0.959127 0.2632892 -0.04442453 -0.9636936 0.2615777 -0.05566781 -0.9635758 0.2752541 -0.04485166 -0.9603248 0.2751713 -0.04525011 -0.9603297 0.2751713 -0.04524999 -0.9603297 0.237941 0.1104394 -0.9649804 0.2414591 0.1003361 -0.9652099 0.3171367 0.1317836 -0.9391792 0.3675985 0.2085224 -0.9063056 0.3395735 0.2517457 -0.9062638 0.3969059 0.2942482 -0.8694158 0.3595727 0.3413586 -0.8684365 0.390927 0.3114086 -0.8661414 0.3903895 0.3118607 -0.8662212 0.3382892 0.3670625 -0.866502 0.3382893 0.3670626 -0.8665018 0.360547 0.3410083 -0.86817 0.3073779 0.2907245 -0.9060896 0.3402442 0.251369 -0.9061167 0.2759725 0.2038808 -0.9392933 0.2415862 0.1001657 -0.9651958 0.1652774 0.06852573 -0.9838637 0.2234988 -0.0667169 -0.9724182 0.1525142 0.09430456 -0.9837918 0.1557726 0.0885393 -0.983817 0.2274829 0.1293042 -0.965159 0.2105674 0.1554058 -0.9651479 0.249392 0.2357694 -0.9392638 0.3074972 0.2907038 -0.9060557 0.2705531 0.3253284 -0.9060699 0.3157926 0.3797256 -0.8695307 0.2665078 0.4180557 -0.8684486 0.3019117 0.3991699 -0.865744 0.2338339 0.4403612 -0.8668355 0.2680714 0.4179569 -0.8680149 0.2280969 0.3556285 -0.9063665 0.2690985 0.3256435 -0.9063897 0.2498287 0.235551 -0.9392026 0.1901948 0.179319 -0.9652309 0.2097613 0.1558736 -0.965248 0.1426302 0.105986 -0.9840852 0.152489 0.09088772 -0.9841172 0.1528846 0.09534412 -0.983634 0.1528845 0.09534406 -0.9836341 0.1528846 0.09534412 -0.9836341 0.1424092 0.1061954 -0.9840946 0.1907326 0.1790133 -0.9651815 0.1665651 0.2016696 -0.9651868 0.2186412 0.2647187 -0.9392126 0.1857385 0.2888269 -0.9391913 0.2286849 0.3556047 -0.9062277 0.184007 0.3806313 -0.9062346 0.1542493 0.4695466 -0.8693292 0.1943004 0.4609782 -0.865879 0.1948307 0.4607145 -0.8659003 0.1178312 0.4858622 -0.8660565 0.1630166 0.4712233 -0.8668184 0.1848116 0.3806691 -0.906055 0.1500396 0.3090514 -0.9391354 0.1862838 0.2887649 -0.9391023 0.1417465 0.2197262 -0.9652091 0.1661975 0.2017871 -0.9652256 0.1013172 0.4835117 -0.8694546 0.08665257 0.4135305 -0.9063575 0.1370686 0.399631 -0.9063704 0.1112878 0.3244619 -0.9393293 0.148667 0.3091108 -0.9393342 0.1133562 0.2356997 -0.9651923 0.09953212 0.1471605 -0.9840921 0.03385567 0.4979647 -0.8665363 0.04446631 0.4925929 -0.8691231 0.03804057 0.421395 -0.9060791 0.08787548 0.4139247 -0.9060598 0.07134366 0.3360614 -0.9391341 0.1128351 0.3246089 -0.9390939 0.09565669 0.2752072 -0.9566143 -0.9996169 0.02768105 7.59709e-5 -0.9996149 0.02775353 3.55239e-5 -0.9996131 0.02781921 -7.22984e-6 -0.9996128 0.02782571 -7.79497e-5 -0.9996144 0.02776956 -3.90983e-5 -0.9996114 0.02787852 -1.57714e-4 -0.9996147 0.0277599 1.58245e-4 -0.9996146 0.02776265 1.72649e-4 0.02300071 0.8945442 -0.4463875 0.02591937 0.8943033 -0.4467099 0.02338033 0.8945516 -0.4463528 0.02754479 0.8927436 -0.4497225 0.02754473 0.8927435 -0.4497225 0.02754479 0.8927435 -0.4497224 0.02676773 0.8946765 -0.4459121 0.01513051 0.8939087 -0.4479935 0.02605164 0.8944785 -0.4463513 0.02629685 0.8944835 -0.4463272 0.02491879 0.8945593 -0.4462541 0.02491879 0.8945593 -0.4462542 0.02391964 0.894557 -0.4463133 0.02332615 0.8946077 -0.4462431 -0.9895846 0.1439527 0 -0.9960865 -0.08838379 0 -0.9489951 -0.3152908 0 -0.9489951 -0.3152909 0 -0.850286 -0.5263211 0 -0.850286 -0.5263211 0 -0.7062811 -0.7079315 0 -0.7062813 -0.7079313 0 -0.5229084 -0.852389 0 -0.5229085 -0.8523888 0 -0.3130487 -0.9497371 0 -0.3130486 -0.9497371 0 -0.08612471 -0.9962844 0 -0.08612471 -0.9962844 0 0.146448 -0.9892184 0 0.1464479 -0.9892184 0 0.3703899 -0.9288764 0 0.3703898 -0.9288764 0 0.5743783 -0.8185901 0 0.7472655 -0.6645257 0 0.7472653 -0.6645259 0 0.8809549 -0.4732005 0 0.9661505 -0.2579795 0 0.9661502 -0.2579801 0 0.9996149 -0.02775406 0 0.9996148 -0.02775537 0 0.9790843 0.2034554 0 0.9790841 0.2034559 0 0.9055302 0.4242821 0 0.9055298 0.4242826 0 0.7837216 0.6211124 0 0.7837224 0.6211115 0 0.6198344 0.7847328 0 0.4195725 0.9077219 0 0.4195726 0.9077218 0 0.2010038 0.9795905 0 0.2010038 0.9795905 0 -0.02871024 0.9995878 0 -0.02871024 0.9995878 0 -0.2612041 0.9652836 0 -0.2612041 0.9652836 0 -0.4742 0.8804172 0 -0.6659524 0.7459943 0 -0.6659527 0.745994 0 -0.8203064 0.5719244 0 -0.8203071 0.5719235 0 -0.9298798 0.3678637 0 -0.9298796 0.3678642 0 -0.9895846 0.1439533 0 -0.4719793 0.8816065 -0.00237447 -0.4750519 0.8799577 -4.26474e-4 -0.4760404 0.8794234 2.96022e-4 -0.4763062 0.8792648 0.005099475 -0.4746661 0.8801658 4.17846e-4 -0.4782033 0.8782368 0.00467956 -0.4787737 0.8779115 0.00687015 -0.4648176 0.8842798 -0.04465228 -0.4648176 0.8842798 -0.04465234 -0.4648176 0.8842799 -0.04465234 0.4719188 -0.8816419 6.51226e-4 0.473756 -0.8806551 0.001374185 0.4760282 -0.8794301 -2.97974e-4 0.4756411 -0.8796219 0.005555331 0.4754323 -0.8797305 0.006190121 0.4754323 -0.8797305 0.00619018 0.4754323 -0.8797305 0.00619018 0.4788759 -0.877857 -0.006721019 0.4788759 -0.877857 -0.006721019 0.4788759 -0.877857 -0.006721079 0.478281 -0.8781945 -0.004680335 0.4747207 -0.8801364 -4.17894e-4 -0.5471692 0.8369958 0.00664252 -0.5803668 0.8143553 0 -0.6440599 0.7649751 0 -0.6762117 0.7366732 0.007096767 -0.7070787 0.7071349 0 -0.764995 0.6440362 0 -0.7892009 0.6141021 0.006376206 -0.8123466 0.5831749 0 -0.8796955 0.4754922 0.006570875 -0.897798 0.4404076 0 -0.9314493 0.3638712 0 -0.9458301 0.3245887 0.006908357 -0.9585111 0.2850551 0 -0.986373 0.164363 0.007300853 -0.9990636 0.04326492 0 -0.9999746 0.002165198 0.006802201 -0.9992414 -0.03894531 0 -0.9921392 -0.1251395 0 -0.9864368 -0.1640118 0.00653392 -0.9792535 -0.2026397 0 -0.9457762 -0.3247506 0.006678223 -0.9320835 -0.3622434 0 -0.8978691 -0.4402626 0 -0.8796954 -0.4754922 0.006579339 -0.8600709 -0.5101746 0 -0.8122614 -0.5832937 0 -0.7892447 -0.6140459 0.006382226 -0.764995 -0.6440362 0 -0.7070787 -0.7071349 0 -0.6762114 -0.7366733 0.007113695 -0.6440599 -0.7649751 0 -0.5832232 -0.812312 0 -0.5472081 -0.8369652 0.007257163 -0.509995 -0.8601774 0 -0.4420203 -0.897005 0 -0.4025203 -0.9153828 0.007199347 -0.3623895 -0.9320267 0 -0.2849962 -0.9585286 0 -0.2466088 -0.9690927 0.006587624 -0.2077456 -0.978183 0 -0.08214592 -0.9965995 0.00645399 -0.04324442 -0.9990646 0 0.04324442 -0.9990646 0 0.08215326 -0.9965988 0.006454586 0.1208242 -0.9926739 0 0.2445564 -0.9696089 0.007131755 0.2861809 -0.9581757 0 0.3662448 -0.9305185 0 0.4016929 -0.9157521 0.006391227 0.5131766 -0.8582831 0 0.5471805 -0.8369882 0.006659388 0.5804736 -0.8142791 0 0.644041 -0.7649911 0 0.6772252 -0.7357391 0.007350146 0.7093125 -0.7048943 0 0.7628798 -0.6465404 0 0.7882012 -0.6153817 0.006654918 0.8122614 -0.5832937 0 0.8796917 -0.4754989 0.006576597 0.8977918 -0.4404204 0 0.9314582 -0.3638487 0 0.9458318 -0.3245839 0.006906867 0.9585085 -0.285064 0 0.986373 -0.164363 0.007303714 0.9990559 -0.04344487 0 0.9999744 0 0.007159829 0.9990559 0.04344344 0 0.9926662 0.1208885 0 0.9864315 0.1640136 0.007245302 0.9783514 0.2069509 0 0.9458315 0.3245891 0.006675779 0.9320228 0.3623997 0 0.8995664 0.4367843 0 0.879654 0.4755598 0.00719273 0.8582594 0.5132161 0 0.8143945 0.5803117 0 0.789198 0.6140998 0.00693947 0.7628666 0.646556 0 0.7092385 0.7049688 0 0.6772791 0.7356896 0.007339298 0.644041 0.7649911 0 0.5833303 0.8122351 0 0.5471666 0.8369923 0.007256627 0.509971 0.8601916 0 0.4403334 0.8978344 0 0.4025012 0.9153935 0.006899893 0.3639138 0.9314326 0 0.2849669 0.9585375 0 0.2466086 0.9690927 0.006604552 0.2077766 0.9781764 0 0.08215326 0.9965988 0.006448924 0.04323667 0.9990649 0 -0.03876572 0.9992484 0 -0.08214545 0.9965941 0.007225513 -0.1256264 0.9920777 0 -0.2440655 0.9697333 0.00703305 -0.2849962 0.9585286 0 -0.3676576 0.9299612 0 -0.4024894 0.9154033 0.006251692 -0.5132558 0.8582358 0 -0.4344906 0.5113729 -0.7414282 -0.4336788 0.5124008 -0.7411937 -0.4746745 0.4746056 -0.7412379 -0.4704739 0.4733669 -0.7447 -0.5091727 0.4306412 -0.7451787 -0.5091727 0.4306412 -0.7451788 -0.5091727 0.4306413 -0.7451787 -0.5102447 0.4306038 -0.7444668 -0.5104245 0.431837 -0.7436287 -0.5430471 0.389621 -0.7438382 -0.543549 0.3881901 -0.7442197 -0.543549 0.3881902 -0.7442197 -0.543549 0.38819 -0.7442197 -0.5733445 0.3428288 -0.7441402 -0.5765736 0.3429786 -0.7415717 -0.6035663 0.2917736 -0.742008 -0.6015762 0.2934125 -0.7429773 -0.6021403 0.2944298 -0.7421174 -0.6230447 0.2445053 -0.7429888 -0.622372 0.2331316 -0.7471966 -0.6365377 0.192152 -0.7469253 -0.6453417 0.1903204 -0.7398055 -0.6603595 0.1321118 -0.7392374 -0.6554346 0.138721 -0.7424029 -0.6547991 0.1381378 -0.743072 -0.6640547 0.08257764 -0.7431099 -0.6646897 0.08311098 -0.7424824 -0.6629886 0.07924175 -0.7444239 -0.6667918 0.0300849 -0.7446366 -0.6680412 0.02965199 -0.7435333 -0.6677756 -0.03924173 -0.7433275 -0.6677756 -0.03924179 -0.7433276 -0.6677756 -0.03924149 -0.7433276 -0.6652562 -0.02939867 -0.7460362 -0.6666802 -0.02854812 -0.7447971 -0.6620466 -0.08232516 -0.7449274 -0.6696369 -0.07958531 -0.7384123 -0.6626225 -0.08652663 -0.7439386 -0.6541213 -0.1356196 -0.7441322 -0.6548887 -0.13637 -0.7433196 -0.6389924 -0.1993874 -0.7429223 -0.6389922 -0.1993876 -0.7429223 -0.6389923 -0.1993871 -0.7429224 -0.6399926 -0.1915945 -0.7441109 -0.6441782 -0.190669 -0.7407292 -0.6268117 -0.2423716 -0.7405155 -0.6262307 -0.2424295 -0.740988 -0.6262305 -0.2424296 -0.740988 -0.6262306 -0.2424296 -0.740988 -0.6246623 -0.2433617 -0.7420055 -0.6246623 -0.2433617 -0.7420055 -0.6246623 -0.2433617 -0.7420055 -0.6019213 -0.2949442 -0.7420909 -0.6036882 -0.2973192 -0.739704 -0.5769227 -0.3461857 -0.739808 -0.571493 -0.3369488 -0.7482389 -0.5407158 -0.3844434 -0.7482178 -0.5410652 -0.388195 -0.7460249 -0.5447679 -0.387432 -0.7437235 -0.5104194 -0.4319446 -0.7435697 -0.5098346 -0.4302623 -0.7449451 -0.5092564 -0.4307528 -0.7450571 -0.5092565 -0.4307528 -0.7450571 -0.5092564 -0.4307527 -0.7450571 -0.4719021 -0.4718336 -0.7447695 -0.4731712 -0.4761702 -0.7411956 -0.4335668 -0.5125867 -0.7411308 -0.4345151 -0.5084675 -0.7434093 -0.4296498 -0.5076465 -0.7467905 -0.3877196 -0.5407117 -0.7465282 -0.3878775 -0.5435857 -0.7443559 -0.3881709 -0.5436121 -0.7441837 -0.388171 -0.543612 -0.7441837 -0.3428609 -0.5734404 -0.7440515 -0.3428567 -0.5734149 -0.744073 -0.2947575 -0.5991835 -0.7443771 -0.2925099 -0.6028978 -0.7422616 -0.2927448 -0.6028177 -0.7422341 -0.2453963 -0.6238372 -0.7420295 -0.2444461 -0.6231037 -0.7429589 -0.2334908 -0.6223156 -0.7471314 -0.1894103 -0.6373634 -0.7469215 -0.188816 -0.6403141 -0.7445445 -0.1434476 -0.6518478 -0.7446592 -0.1380816 -0.6549081 -0.7429865 -0.1380816 -0.6549081 -0.7429865 -0.08263605 -0.6641206 -0.7430446 -0.08308392 -0.6646054 -0.7425611 -0.07917618 -0.6631593 -0.7442789 -0.02716422 -0.6670232 -0.7445417 -0.02660942 -0.6681058 -0.7435904 0.01960772 -0.6684261 -0.7435202 0.02656757 -0.669999 -0.7418865 0.02853232 -0.6667973 -0.7446927 0.08274537 -0.6620302 -0.7448955 0.0794388 -0.6701587 -0.7379545 0.08688861 -0.6633611 -0.7432378 0.1358846 -0.6552344 -0.7431039 0.1357339 -0.6549997 -0.7433382 0.199575 -0.638988 -0.7428757 0.199575 -0.638988 -0.7428756 0.1995749 -0.638988 -0.7428756 0.1917096 -0.6399451 -0.7441222 0.1906101 -0.6441507 -0.7407683 0.2434523 -0.6264997 -0.740425 0.2431896 -0.6278976 -0.7393264 0.2477799 -0.6194989 -0.7448667 0.2937838 -0.5996251 -0.7444064 0.2940483 -0.5998475 -0.7441228 0.3414018 -0.5741229 -0.7441961 0.3416267 -0.5741068 -0.7441053 0.3875035 -0.5442236 -0.7440845 0.3875034 -0.5442237 -0.7440845 0.3875034 -0.5442237 -0.7440845 0.3875534 -0.5449159 -0.7435516 0.3875535 -0.544916 -0.7435516 0.3875534 -0.5449159 -0.7435517 0.4318525 -0.510287 -0.743714 0.4318526 -0.5102871 -0.743714 0.4318526 -0.5102871 -0.743714 0.4344938 -0.5112906 -0.741483 0.4338769 -0.5122384 -0.7411901 0.4338768 -0.5122384 -0.7411901 0.4746538 -0.4746769 -0.7412056 0.4747215 -0.4746823 -0.7411587 0.51239 -0.4335299 -0.7412884 0.5107259 -0.4340426 -0.7421362 0.510509 -0.4319085 -0.7435293 0.5431021 -0.3895713 -0.7438243 0.5487996 -0.3723327 -0.7484567 0.5487996 -0.3723328 -0.7484567 0.5679591 -0.342696 -0.7483195 0.5765163 -0.3429445 -0.7416321 0.6035343 -0.2921297 -0.7418939 0.6035343 -0.2921296 -0.7418939 0.6035343 -0.2921297 -0.741894 0.6015548 -0.2934184 -0.7429924 0.6021192 -0.2944357 -0.7421322 0.6229709 -0.2443455 -0.7431035 0.6222203 -0.2334688 -0.7472177 0.6373201 -0.1893974 -0.7469617 0.6402563 -0.188812 -0.7445951 0.652041 -0.1434313 -0.7444931 0.6555133 -0.1388269 -0.7423136 0.6548304 -0.1380284 -0.7430648 0.6640672 -0.08257645 -0.7430989 0.6646715 -0.0829786 -0.7425135 0.6630147 -0.07953494 -0.7443693 0.667023 -0.02717703 -0.7445414 0.6681221 -0.02652925 -0.7435786 0.6682485 0.01966744 -0.7436782 0.6682485 0.01966756 -0.7436781 0.6682485 0.01966726 -0.7436781 0.6701021 0.02658015 -0.7417929 0.6666817 0.02854704 -0.7447957 0.6620122 0.08232367 -0.7449582 0.6600681 0.08332568 -0.7465702 0.6638334 0.0792638 -0.7436683 0.6638334 0.07926368 -0.7436683 0.6638334 0.07926374 -0.7436683 0.6541435 0.1356242 -0.7441118 0.6549323 0.1363791 -0.7432796 0.6389839 0.1993684 -0.7429347 0.638984 0.1993683 -0.7429347 0.6389841 0.1993681 -0.7429346 0.640051 0.191612 -0.7440562 0.6442853 0.1907715 -0.7406098 0.6442852 0.1907715 -0.7406098 0.6442853 0.1907714 -0.7406097 0.6266601 0.2424916 -0.7406044 0.6153721 0.2438792 -0.7495601 0.6199237 0.2415559 -0.7465557 0.5974701 0.292683 -0.7465697 0.5992522 0.2951509 -0.7441658 0.5741505 0.3414818 -0.7441381 0.5742222 0.3415699 -0.7440423 0.5443139 0.3870016 -0.7442796 0.5444186 0.3876507 -0.7438652 0.5449069 0.3873611 -0.7436586 0.5103819 0.4319129 -0.7436138 0.5113722 0.4345214 -0.7414106 0.5124647 0.433582 -0.7412062 0.5124648 0.4335814 -0.7412065 0.512465 0.4335812 -0.7412065 0.4746745 0.4746056 -0.7412379 0.4746654 0.4747214 -0.7411696 0.4335694 0.5123691 -0.7412797 0.4340646 0.5107824 -0.7420843 0.4319604 0.5105357 -0.7434806 0.3896427 0.5434124 -0.7435601 0.3896072 0.5430199 -0.7438654 0.388409 0.5434572 -0.7441725 0.3414845 0.5742811 -0.744036 0.341556 0.5742321 -0.744041 0.341556 0.5742321 -0.744041 0.2947204 0.5995508 -0.744096 0.2934094 0.6014821 -0.7430547 0.2944173 0.6020128 -0.7422258 0.2453176 0.6237264 -0.7421487 0.2422394 0.6212568 -0.7452248 0.2376606 0.6211447 -0.746791 0.2376606 0.6211447 -0.746791 0.2376606 0.6211446 -0.746791 0.189425 0.6375038 -0.7467979 0.1888328 0.6401929 -0.7446444 0.1433897 0.6519787 -0.7445557 0.1380732 0.654843 -0.7430454 0.08262997 0.6639827 -0.7431684 0.08309292 0.6648095 -0.7423772 0.07795929 0.6623876 -0.745094 0.02727824 0.666801 -0.7447364 0.02660781 0.6681552 -0.743546 -0.01977086 0.6680954 -0.7438129 -0.02656251 0.6699595 -0.7419224 -0.02850002 0.6666909 -0.7447893 -0.0823813 0.6619622 -0.7449963 -0.07938528 0.669557 -0.7385063 -0.08586829 0.6635922 -0.7431501 -0.136487 0.6551148 -0.7430989 -0.1363183 0.6549549 -0.7432708 -0.199601 0.6388278 -0.7430064 -0.199601 0.638828 -0.7430063 -0.199601 0.638828 -0.7430062 -0.1908333 0.640036 -0.7442692 -0.1901842 0.6424675 -0.7423378 -0.1901842 0.6424676 -0.7423378 -0.1901842 0.6424676 -0.7423378 -0.2427517 0.6246179 -0.7422426 -0.2424985 0.6259896 -0.741169 -0.2469813 0.6175025 -0.7467871 -0.2927122 0.5975955 -0.7464578 -0.2927122 0.5975955 -0.7464578 -0.2927122 0.5975955 -0.7464578 -0.2952111 0.5993197 -0.7440876 -0.3414096 0.5740638 -0.744238 -0.3415556 0.5741137 -0.7441325 -0.3876271 0.5444114 -0.7438828 -0.3875819 0.5448382 -0.7435938 -0.4319307 0.5104861 -0.743532 -0.3826091 0.7841402 -0.4886048 -0.4460403 0.7499117 -0.4885494 -0.447035 0.7501511 -0.4872711 -0.5065364 0.7113812 -0.4871937 -0.510623 0.7126216 -0.4810767 -0.5675876 0.6678364 -0.4814965 -0.5650551 0.6674796 -0.4849575 -0.6163873 0.6202015 -0.4851977 -0.6164027 0.6202492 -0.4851171 -0.6683807 0.5639705 -0.484979 -0.6707937 0.5641145 -0.4814674 -0.7122392 0.5110484 -0.4811912 -0.7130334 0.5109636 -0.4801038 -0.7529392 0.4488047 -0.4813078 -0.7529392 0.4488047 -0.4813077 -0.7529391 0.4488047 -0.4813078 -0.7878907 0.3842607 -0.4812194 -0.7876377 0.3841664 -0.4817085 -0.7876377 0.3841665 -0.4817085 -0.7876377 0.3841665 -0.4817085 -0.8154679 0.3205277 -0.4819483 -0.8162894 0.3205606 -0.4805336 -0.8411491 0.2479401 -0.4806184 -0.836757 0.2500302 -0.4871578 -0.8540022 0.1810292 -0.4877589 -0.8540022 0.1810293 -0.4877588 -0.8573704 0.1791597 -0.4825118 -0.8690736 0.108145 -0.4827173 -0.8709864 0.1069613 -0.4795226 -0.8768043 0.03876954 -0.4792822 -0.8777141 0.03831046 -0.4776508 -0.8777066 -0.03881525 -0.4776241 -0.8725731 -0.03406733 -0.4872943 -0.8667883 -0.1078634 -0.4868713 -0.8688424 -0.1100713 -0.4826979 -0.8574468 -0.1784886 -0.4826251 -0.8580981 -0.1793102 -0.4811608 -0.8390134 -0.2505273 -0.4830037 -0.81624 -0.315778 -0.4837733 -0.8169295 -0.316949 -0.4818398 -0.7862703 -0.3872268 -0.4814919 -0.7840031 -0.3824859 -0.4889209 -0.7514309 -0.4431038 -0.488887 -0.7536446 -0.4492464 -0.4797892 -0.7127927 -0.5112672 -0.4801381 -0.7125687 -0.5106286 -0.481149 -0.6698779 -0.5652338 -0.4814295 -0.6693704 -0.562913 -0.4848425 -0.6162665 -0.6202573 -0.4852799 -0.6164632 -0.6201348 -0.4851866 -0.568153 -0.6649421 -0.4848239 -0.568242 -0.6712473 -0.4759498 -0.510779 -0.7158168 -0.476142 -0.5109259 -0.7130521 -0.4801162 -0.4502026 -0.753178 -0.4796255 -0.4502025 -0.7531781 -0.4796255 -0.4502025 -0.753178 -0.4796255 -0.4499043 -0.7549707 -0.47708 -0.3836274 -0.7905429 -0.4773594 -0.3843088 -0.787691 -0.4815078 -0.3205001 -0.8164394 -0.4803192 -0.2480749 -0.8410697 -0.4806877 -0.2498909 -0.8369385 -0.4869173 -0.1808432 -0.854102 -0.4876532 -0.1791081 -0.8573458 -0.482575 -0.1081439 -0.8690642 -0.4827343 -0.1069623 -0.8709595 -0.4795714 -0.03492772 -0.8770662 -0.4790983 -0.03794831 -0.8730078 -0.4862278 0.03461986 -0.8730562 -0.4863892 0.03414124 -0.8725842 -0.4872692 0.108337 -0.866674 -0.4869695 0.1099427 -0.8682805 -0.4837372 0.1775433 -0.8566825 -0.4843278 0.1792644 -0.858094 -0.4811851 0.2514656 -0.8396627 -0.4813852 0.2519963 -0.8400246 -0.4804756 0.3176599 -0.817391 -0.4805873 0.3149912 -0.8158953 -0.4848665 0.3848098 -0.7850594 -0.48539 0.3826049 -0.7840389 -0.4887705 0.4460284 -0.7498357 -0.4886769 0.4470778 -0.7502229 -0.4871214 0.5065043 -0.7114252 -0.4871629 0.5106172 -0.7125258 -0.4812247 0.5675539 -0.6678857 -0.4814679 0.5650941 -0.6674382 -0.484969 0.6182394 -0.6183283 -0.485232 0.6182728 -0.6182646 -0.4852709 0.6664131 -0.5663015 -0.4849705 0.668964 -0.5663391 -0.4814014 0.7123346 -0.5109386 -0.4811665 0.7129883 -0.5109313 -0.4802051 0.7529116 -0.4486335 -0.4815105 0.7878823 -0.3842674 -0.4812279 0.787613 -0.3844269 -0.4815411 0.8153907 -0.320773 -0.4819158 0.8164068 -0.3204483 -0.480409 0.8412278 -0.2479568 -0.480472 0.8420475 -0.2477511 -0.4791405 0.8585358 -0.1816489 -0.4794996 0.8566223 -0.1827729 -0.4824856 0.8690921 -0.1081473 -0.4826832 0.8709705 -0.1070418 -0.4795336 0.877025 -0.03484773 -0.4791795 0.8729848 -0.03801661 -0.4862636 0.8730864 0.03462588 -0.4863345 0.8770594 0.03810572 -0.4788684 0.8713875 0.1085249 -0.4784416 0.8693321 0.1062874 -0.4826641 0.8574975 0.1784098 -0.4825642 0.8580799 0.1793064 -0.4811945 0.8390311 0.2505326 -0.4829702 0.81638 0.3158321 -0.4835016 0.8168949 0.3169355 -0.4819073 0.786228 0.387217 -0.4815688 0.7839937 0.3825685 -0.4888714 0.7498112 0.4459426 -0.4887927 0.7501322 0.4471526 -0.4871923 0.7115435 0.5064535 -0.487043 0.7125443 0.5106988 -0.4811106 0.667989 0.567677 -0.4811795 0.667989 0.567677 -0.4811794 0.667989 0.567677 -0.4811794 0.6674382 0.5651301 -0.4849273 0.6183074 0.6182184 -0.4852855 0.6182261 0.6182508 -0.4853479 0.5662707 0.666553 -0.4848141 0.5663099 0.6688485 -0.4815963 0.5110166 0.7122857 -0.4811561 0.5108883 0.7129995 -0.4802344 0.4485918 0.7539343 -0.4799464 0.4486963 0.7529434 -0.4814022 0.3842609 0.7879365 -0.4811443 0.3842899 0.7876727 -0.4815526 0.320463 0.8163268 -0.4805352 0.2480776 0.8411679 -0.4805144 0.2499055 0.836809 -0.4871324 0.1808276 0.8540281 -0.4877882 0.1790508 0.8573337 -0.4826176 0.1081364 0.8691822 -0.4825233 0.1070082 0.8709328 -0.4796096 0.03492224 0.8771073 -0.4790232 0.03795409 0.8729661 -0.4863019 -0.03462284 0.8731314 -0.4862539 -0.03812485 0.8770704 -0.4788467 -0.1084405 0.8714477 -0.4783509 -0.1063382 0.8693264 -0.4826635 -0.1784977 0.8575354 -0.4824641 -0.1791905 0.8580028 -0.4813753 -0.2504211 0.8399006 -0.4815146 -0.2509666 0.8402651 -0.4805939 -0.3176872 0.817461 -0.4804502 -0.3168027 0.8169841 -0.4818435 -0.3872758 0.7861214 -0.4816955 -0.4308935 0.8874437 -0.1636295 -0.5050522 0.8473568 -0.1640391 -0.5050522 0.8473569 -0.1640391 -0.5050522 0.8473569 -0.1640391 -0.5066 0.8471992 -0.1600312 -0.5749989 0.802327 -0.1601493 -0.57233 0.8029747 -0.1663432 -0.6371455 0.7526401 -0.1660673 -0.6343143 0.7534592 -0.1730452 -0.6943767 0.6986082 -0.1725911 -0.6974174 0.6974902 -0.1646707 -0.754945 0.6347361 -0.1648277 -0.7542992 0.6351649 -0.1661269 -0.8014782 0.5743949 -0.1664429 -0.8006768 0.5747909 -0.1689145 -0.8466817 0.5045047 -0.1691307 -0.848517 0.5032405 -0.1636098 -0.8849673 0.4340573 -0.1686041 -0.9175707 0.3600449 -0.1686175 -0.9186635 0.3589907 -0.1648725 -0.9451003 0.2822788 -0.1646335 -0.9458581 0.281311 -0.1619158 -0.945858 0.281311 -0.1619158 -0.945858 0.281311 -0.1619158 -0.9660932 0.2017142 -0.1611692 -0.963968 0.2049248 -0.1696216 -0.9782629 0.1199234 -0.1691746 -0.9788116 0.119122 -0.1665466 -0.9850629 0.04294025 -0.166755 -0.9853198 -0.03856861 -0.1663054 -0.9852526 -0.03839927 -0.1667424 -0.9782527 -0.1236358 -0.1665412 -0.9782526 -0.1236358 -0.1665412 -0.9782527 -0.1236358 -0.1665412 -0.9780967 -0.1230385 -0.1678945 -0.9650694 -0.2015086 -0.1674382 -0.9650694 -0.2015086 -0.1674383 -0.9650694 -0.2015085 -0.1674383 -0.9647235 -0.1994786 -0.1718046 -0.9438979 -0.2819197 -0.1719832 -0.9438725 -0.282092 -0.1718397 -0.9186277 -0.3562438 -0.1709197 -0.9186169 -0.3573032 -0.1687531 -0.8859406 -0.4320785 -0.1685754 -0.8857094 -0.4344233 -0.1636928 -0.8474776 -0.504966 -0.1636804 -0.8476973 -0.50276 -0.1692391 -0.8011348 -0.5741611 -0.168885 -0.8011348 -0.5741611 -0.168885 -0.8011349 -0.5741611 -0.168885 -0.8009405 -0.5751541 -0.1664094 -0.7546635 -0.6346749 -0.1663455 -0.7545676 -0.635217 -0.1647032 -0.6952319 -0.6996552 -0.1647281 -0.6965729 -0.6964683 -0.1723898 -0.6363649 -0.751731 -0.1730327 -0.6350873 -0.7543677 -0.1661134 -0.574316 -0.8015343 -0.1664455 -0.574899 -0.8006229 -0.1688024 -0.5031604 -0.8485645 -0.1636099 -0.432596 -0.8865988 -0.1637175 -0.4353291 -0.8834275 -0.1733331 -0.3598877 -0.9168683 -0.1727235 -0.3598877 -0.9168683 -0.1727235 -0.3598877 -0.9168683 -0.1727235 -0.3574386 -0.9192814 -0.1648011 -0.2822132 -0.9451146 -0.1646645 -0.2812299 -0.9459105 -0.1617501 -0.2018343 -0.9660461 -0.1613005 -0.2047503 -0.9640084 -0.1696032 -0.1201339 -0.9782275 -0.1692305 -0.1201339 -0.9782275 -0.1692304 -0.1201339 -0.9782275 -0.1692304 -0.1191618 -0.9787987 -0.1665941 -0.04282194 -0.9851124 -0.1664929 -0.04263949 -0.9851503 -0.166315 0.03855979 -0.9853075 -0.1663802 0.04271233 -0.9868651 -0.1557983 0.1240956 -0.9799811 -0.1556832 0.1191385 -0.9785958 -0.1677989 0.2015964 -0.9650831 -0.167253 0.1997327 -0.9647119 -0.1715754 0.1997334 -0.9647116 -0.1715753 0.1997327 -0.9647118 -0.1715754 0.2830488 -0.9435254 -0.1721723 0.281778 -0.9433911 -0.1749696 0.3545695 -0.9185099 -0.1749866 0.3545695 -0.9185098 -0.1749866 0.3545695 -0.9185099 -0.1749866 0.3615391 -0.9187203 -0.1588787 0.4329775 -0.8873134 -0.158762 0.4308773 -0.8874104 -0.1638525 0.5050028 -0.8474432 -0.1637444 0.5066057 -0.8472088 -0.1599622 0.575015 -0.8023496 -0.1599782 0.5723484 -0.8029621 -0.1663407 0.6371641 -0.7526621 -0.1658971 0.6342942 -0.7534611 -0.1731109 0.6966127 -0.6964588 -0.1722671 0.6994653 -0.6953772 -0.1649208 0.7527785 -0.6372904 -0.1648798 0.7523387 -0.6374871 -0.1661227 0.8015016 -0.5744116 -0.1662724 0.8006231 -0.5749266 -0.1687071 0.8466691 -0.5044973 -0.1692157 0.8485079 -0.5032351 -0.1636735 0.8849677 -0.4340712 -0.168566 0.91754 -0.3600415 -0.1687914 0.9186921 -0.3589801 -0.1647365 0.9462553 -0.2784186 -0.1645718 0.9443156 -0.280609 -0.1718338 0.9634704 -0.2055473 -0.1716837 0.9639685 -0.2049236 -0.1696206 0.9782639 -0.1199209 -0.1691709 0.9788099 -0.1191218 -0.1665572 0.9850648 -0.04294031 -0.1667444 0.9851438 0.04294377 -0.1662757 0.9850717 0.04275375 -0.1667507 0.9787453 0.1196322 -0.1665712 0.9786075 0.1189231 -0.1678832 0.9649993 0.2018414 -0.1674406 0.9656103 0.2040184 -0.1611627 0.9455928 0.2824259 -0.1615238 0.9455893 0.2824301 -0.1615371 0.9201968 0.3568522 -0.1609178 0.92018 0.3579112 -0.1586455 0.8873111 0.4329224 -0.1589253 0.8874427 0.430922 -0.16356 0.8474835 0.5049825 -0.1635982 0.8471372 0.506744 -0.1599035 0.8024207 0.5748947 -0.1600539 0.8029981 0.5722618 -0.1664654 0.7525203 0.6372467 -0.166223 0.7525042 0.6376556 -0.1647204 0.6974403 0.6974954 -0.1645518 0.6986741 0.6943905 -0.1722683 0.6363909 0.7517101 -0.1730279 0.6350711 0.7543808 -0.1661164 0.5743086 0.8015393 -0.1664465 0.5749267 0.8006159 -0.168741 0.5031359 0.8485693 -0.1636599 0.4326261 0.8866158 -0.1635454 0.4339916 0.8849886 -0.1686612 0.3601007 0.9175211 -0.1687677 0.3589128 0.9187015 -0.1648305 0.2822901 0.9450871 -0.1646901 0.2812048 0.9459404 -0.161619 0.2017825 0.9661138 -0.1609603 0.2047379 0.9640375 -0.1694527 0.2047379 0.9640375 -0.1694527 0.2047379 0.9640375 -0.1694528 0.120152 0.9782236 -0.1692404 0.1191675 0.9788457 -0.1663143 0.04281944 0.9850549 -0.1668336 0.04264193 0.9852074 -0.1659756 -0.04282921 0.985136 -0.1663512 -0.03815007 0.9833383 -0.177737 -0.1194486 0.9766859 -0.1783726 -0.1238363 0.9779877 -0.1679428 -0.2016182 0.965017 -0.1676084 -0.2016181 0.965017 -0.1676084 -0.2016182 0.965017 -0.1676084 -0.1996893 0.9646816 -0.1717953 -0.2819328 0.9438912 -0.1719979 -0.2805839 0.9437423 -0.1749946 -0.3560464 0.917932 -0.1750197 -0.3629833 0.9181959 -0.1586177 -0.4329534 0.887264 -0.1591041 0.4668216 0.1819579 -0.8654299 0.4787563 0.1417019 -0.866437 0.49869 0.02143806 -0.8665154 0.4677 -0.1752591 -0.8663378 0.4125459 -0.2800707 -0.8668138 0.3221451 -0.3805468 -0.8668372 0.3221451 -0.3805466 -0.8668372 0.3221451 -0.3805469 -0.8668373 0.2901523 -0.4080933 -0.8656047 0.2547858 -0.4283329 -0.8669575 0.1857 -0.4644582 -0.8659065 0.1416956 -0.4788235 -0.866401 0.02133488 -0.4986848 -0.8665209 -0.1753734 -0.4679392 -0.8661854 -0.2900251 -0.4060881 -0.86659 -0.2900251 -0.4060881 -0.8665899 -0.2900251 -0.4060882 -0.8665899 -0.3806288 -0.321865 -0.8669053 -0.3806288 -0.3218653 -0.8669051 -0.3806288 -0.3218659 -0.8669049 -0.4267174 -0.2559822 -0.8674015 -0.4660536 -0.1811572 -0.8660116 -0.4788075 -0.1416296 -0.8664206 -0.4996961 -0.02139121 -0.8659366 -0.4678345 0.1753095 -0.8662549 -0.4062651 0.2901408 -0.8664682 -0.3220576 0.3805754 -0.8668572 -0.3220576 0.3805752 -0.8668573 -0.3220576 0.3805754 -0.8668572 -0.2905727 0.4083851 -0.865326 -0.254768 0.4284119 -0.8669236 -0.185721 0.4643443 -0.8659631 -0.1416568 0.4788458 -0.8663948 -0.02132505 0.4987201 -0.8665007 0.1788497 0.4666675 -0.8661606 0.2901033 0.4062003 -0.8665112 0.3806464 0.3219009 -0.8668842 0.3806464 0.3219012 -0.8668841 0.3806464 0.3219013 -0.8668841 0.4284111 0.2548404 -0.8669028 -0.1595858 -0.1759011 -0.9713863 -0.2881782 -0.1976649 -0.9369536 -0.1662492 -0.1610391 -0.9728451 -0.1662492 -0.1610389 -0.9728451 -0.1662492 -0.161039 -0.9728452 -0.2363246 -0.1811131 -0.9546459 -0.2363245 -0.181113 -0.9546459 -0.2363244 -0.181113 -0.954646 -0.2610871 -0.01780647 -0.9651511 -0.1659384 -0.1640792 -0.9723901 -0.2102774 -0.01439058 -0.9775359 -0.1791467 0.01467275 -0.983713 -0.1751207 0.02847707 -0.9841351 -0.1759178 0.02205848 -0.9841578 -0.1759178 0.02205848 -0.9841578 -0.1759178 0.02205854 -0.9841578 -0.1757872 0.1594614 -0.9714273 -0.1967168 0.2865929 -0.9376391 -0.1534367 0.1704728 -0.9733428 -0.1534368 0.1704728 -0.9733428 -0.1534368 0.1704727 -0.9733428 -0.1693851 0.2376127 -0.9564774 -0.1570526 0.1701602 -0.9728206 -0.01606571 0.2121064 -0.9771146 0.01465821 0.1791526 -0.9837121 0.02844953 0.1750944 -0.9841405 0.02201551 0.1758459 -0.9841716 0.02201551 0.175846 -0.9841716 0.02201551 0.175846 -0.9841716 0.1595672 0.1758145 -0.971405 0.2881669 0.1976572 -0.9369586 0.1703804 0.1533161 -0.973378 0.2378134 0.1695852 -0.956392 0.2603095 0.01973968 -0.9653235 0.1702455 0.1568929 -0.9728316 0.212101 0.01604586 -0.9771161 0.1791319 -0.01467084 -0.9837157 0.1748763 -0.03053146 -0.984117 0.1757763 -0.02175301 -0.9841898 0.1757763 -0.02175301 -0.9841898 0.1757763 -0.02175301 -0.9841898 0.1766123 -0.1630625 -0.9706795 0.1975569 -0.2881495 -0.9369851 0.1616447 -0.169739 -0.9721419 0.1782166 -0.2364144 -0.9551687 0.1569236 -0.1706262 -0.9727599 0.0160681 -0.2121382 -0.9771076 -0.01467472 -0.1791595 -0.9837107 -0.02847468 -0.1751405 -0.9841316 -0.02190482 -0.1761026 -0.9841281 -0.02190482 -0.1761028 -0.9841281 -0.02190488 -0.1761028 -0.9841281 0.4085062 0.2905492 -0.8652767 0.4216588 0.2596921 -0.8687716 0.3597776 0.2216398 -0.9063311 0.3826084 0.1794103 -0.9063239 0.3106894 0.145682 -0.9392811 0.3264733 0.1056876 -0.9392792 0.3805266 0.3220571 -0.8668788 0.3842408 0.3112767 -0.8691753 0.3279789 0.2657585 -0.9065331 0.3587955 0.2221376 -0.9065985 0.2922968 0.1810712 -0.9390293 0.3118765 0.1446511 -0.9390469 0.3229076 0.3816081 -0.8660867 0.3229023 0.3815695 -0.8661057 0.3491587 0.3491075 -0.8696047 0.3471615 0.35616 -0.867542 0.2956169 0.3031968 -0.9059153 0.3307033 0.2646144 -0.9058778 0.2683658 0.2147 -0.9390867 0.2922481 0.1809541 -0.9390669 0.2999473 0.3922564 -0.8695784 0.2568778 0.3359504 -0.906174 0.2944076 0.3035133 -0.906203 0.238736 0.2461625 -0.9393664 0.2663649 0.2157288 -0.9394206 0.2197409 0.4493271 -0.865921 0.2207078 0.4487683 -0.865965 0.25331 0.4259561 -0.8685595 0.2522782 0.4275969 -0.8680534 0.2149981 0.3643957 -0.9060859 0.2573656 0.3359144 -0.9060488 0.2088634 0.2725334 -0.9392027 0.2400171 0.2457001 -0.939161 0.1944595 0.1990773 -0.9604967 0.2161568 0.1749949 -0.9605484 0.2145162 0.1583591 -0.9637973 0.2269615 0.1405574 -0.9637075 0.230386 0.1654516 -0.9589307 0.2559266 0.1187226 -0.9593783 0.24985 0.09343624 -0.9637659 0.254212 0.08232176 -0.9636387 0.2613056 0.1004051 -0.9600199 0.2621094 0.09724295 -0.9601263 0.1816217 0.4658458 -0.8660262 0.1971427 0.4528936 -0.8694955 0.168765 0.3877305 -0.9061918 0.2142843 0.364426 -0.9062428 0.1739482 0.2958449 -0.9392645 0.2086725 0.2725852 -0.9392301 0.1589313 0.2075809 -0.9652208 0.1507499 0.2146126 -0.9649953 0.2247407 0.05679398 -0.9727621 0.1030476 0.488652 -0.8663721 0.1072535 0.4876856 -0.8664061 0.1413721 0.4757342 -0.8681538 0.1408888 0.4761876 -0.8679838 0.1199513 0.4054246 -0.9062244 0.1682391 0.3876234 -0.9063354 0.1366612 0.3149367 -0.9392223 0.1741477 0.2958379 -0.9392297 0.1327688 0.2255787 -0.9651356 0.1599174 0.2072991 -0.9651185 0.1105202 0.1432082 -0.9835023 0.2240297 0.05651897 -0.9729422 0.2240297 0.05651891 -0.9729422 0.2240297 0.05651903 -0.9729422 0.09072142 0.1544036 -0.983834 0.1325742 0.2255979 -0.9651579 0.1035984 0.2403035 -0.9651538 0.1357467 0.3149381 -0.9393545 0.09813338 0.3285772 -0.9393651 0.1211267 0.4055631 -0.9060061 0.0715593 0.4172075 -0.9059897 0.08342695 0.4864047 -0.8697416 0.0202431 0.4949557 -0.8686825 0.05842345 0.4965495 -0.8660401 -0.01474171 0.4987197 -0.866638 0.02321165 0.4963786 -0.8677958 0.01977312 0.4227237 -0.9060429 0.07134741 0.4170712 -0.906069 0.05792415 0.338577 -0.9391542 0.0996012 0.3287875 -0.9391371 0.07592761 0.2506868 -0.9650861 0.1043674 0.2401907 -0.965099 0.07078385 0.1629506 -0.9840919 0.08672839 0.1547406 -0.9841411 0.08480262 0.1591765 -0.9836012 0.06960487 0.1631397 -0.9841447 0.04964119 0.170423 -0.9841198 0.04290944 0.2575035 -0.9653242 0.05635124 0.3382006 -0.9393854 0.01631206 0.3425726 -0.9393498 0.02013581 0.4228438 -0.905979 -0.03559023 0.492839 -0.8693925 -0.1007788 0.4837306 -0.8693954 -0.06411975 0.4955243 -0.8662242 -0.05882775 0.4962368 -0.8661919 -0.08058631 0.4151644 -0.9061702 -0.03118586 0.4217836 -0.9061601 -0.02530282 0.3422697 -0.9392611 0.01694464 0.3428092 -0.9392523 0.01293307 0.261417 -0.9651394 0.04564493 0.2579721 -0.9650737 0.03100478 0.1752909 -0.9840284 0.05242097 0.1702638 -0.9840032 -0.180671 0.4662387 -0.8660137 -0.1530892 0.4699245 -0.8693301 -0.1307262 0.4012638 -0.9065861 -0.08204883 0.4139646 -0.9065877 -0.06683158 0.3370894 -0.9390977 -0.02446734 0.342823 -0.9390814 -0.01862496 0.2607035 -0.9652393 0.01177233 0.2612252 -0.9652062 0.008096516 0.1794573 -0.9837325 0.01222681 0.1772786 -0.9840848 -0.2193033 0.4475585 -0.8669472 -0.2098469 0.44815 -0.8689798 -0.1792663 0.382838 -0.9062554 -0.1298 0.4021912 -0.9063081 -0.10566 0.3273658 -0.9389716 -0.06603688 0.3377073 -0.9389318 -0.05565667 0.2846599 -0.9570116 0.002287328 0.2554122 -0.9668296 -0.2904167 0.4085996 -0.8652772 -0.2597559 0.4216758 -0.8687442 -0.2218871 0.3601939 -0.9061052 -0.1788666 0.3832942 -0.9061415 -0.1450941 0.3109461 -0.9392872 -0.1073603 0.3258859 -0.9392935 -0.3220236 0.3805988 -0.8668595 -0.311278 0.3842626 -0.8691654 -0.2657212 0.3279524 -0.9065536 -0.2229945 0.3582608 -0.9065996 -0.1815007 0.2915573 -0.9391762 -0.1445487 0.3115823 -0.9391604 -0.3822415 0.3231232 -0.8657268 -0.3822416 0.3231232 -0.8657268 -0.3822076 0.3232875 -0.8656805 -0.3496558 0.3496749 -0.8691768 -0.3552211 0.3480499 -0.8675709 -0.3024107 0.2963401 -0.9059417 -0.2645556 0.330717 -0.9058899 -0.2146813 0.268384 -0.9390857 -0.1810131 0.2922528 -0.9390541 -0.4055293 0.290816 -0.8665864 -0.3934803 0.2990566 -0.8693322 -0.3361559 0.2555831 -0.9064638 -0.3030789 0.2939459 -0.9064983 -0.2461425 0.238707 -0.939379 -0.2157009 0.266353 -0.9394302 -0.4492745 0.2197274 -0.8659517 -0.4501408 0.2181508 -0.8659005 -0.4501408 0.2181508 -0.8659005 -0.4501408 0.2181508 -0.8659005 -0.4248002 0.254036 -0.8689135 -0.4275954 0.252241 -0.868065 -0.3648123 0.215251 -0.9058582 -0.3356848 0.2585952 -0.9057838 -0.2724429 0.2098634 -0.939006 -0.2451733 0.2414976 -0.9389191 -0.1982719 0.1951982 -0.9605134 -0.1750446 0.216148 -0.9605413 -0.158354 0.2145873 -0.9637824 -0.1672513 0.2306631 -0.9585518 -0.1192187 0.2570096 -0.9590271 -0.09196436 0.2504758 -0.963745 -0.09966015 0.2599427 -0.9604675 -0.09681648 0.2608454 -0.9605136 -0.4650918 0.1824946 -0.866248 -0.452915 0.1971765 -0.8694766 -0.3877208 0.1687583 -0.9061972 -0.3648927 0.2134186 -0.9062592 -0.295932 0.1730927 -0.9393952 -0.2730788 0.2072144 -0.9394094 -0.2079864 0.1578398 -0.9653125 -0.2134679 0.1512805 -0.9651662 -0.0601412 0.2233036 -0.9728919 -0.06014108 0.2233036 -0.9728919 -0.06014114 0.2233036 -0.9728919 -0.4886717 0.1030804 -0.866357 -0.4896728 0.09775626 -0.8664088 -0.4740608 0.1431213 -0.8687824 -0.4761564 0.1409298 -0.8679942 -0.4053564 0.1199191 -0.9062592 -0.3877037 0.168276 -0.9062941 -0.3152319 0.1367452 -0.9391111 -0.2957364 0.1751895 -0.939068 -0.2251768 0.1333569 -0.9651484 -0.2072579 0.1598721 -0.9651348 -0.1432897 0.1105532 -0.9834868 -0.05843859 0.2216684 -0.9733695 -0.1577091 0.08508241 -0.9838134 -0.1544336 0.09077715 -0.9838241 -0.2253338 0.1324581 -0.9652355 -0.2397319 0.1041568 -0.9652358 -0.3151598 0.1369566 -0.9391045 -0.3293246 0.09839206 -0.9390764 -0.4056317 0.1211504 -0.9059721 -0.4171687 0.07160872 -0.9060036 -0.4950493 0.02243351 -0.8685752 -0.4963302 0.05905139 -0.8661233 -0.4960188 0.06202709 -0.8660936 -0.4995725 -0.02952617 -0.8657688 -0.4962529 0.02505183 -0.8678165 -0.4225438 0.02132338 -0.9060916 -0.4171029 0.0712583 -0.9060616 -0.3385886 0.05788385 -0.9391524 -0.3292231 0.09781873 -0.9391717 -0.2505774 0.07440972 -0.9652327 -0.2397143 0.1041485 -0.9652411 -0.1629557 0.07078504 -0.984091 -0.1547857 0.0867033 -0.9841362 -0.1589627 0.08487367 -0.9836297 -0.1589627 0.08487355 -0.9836297 -0.1589627 0.08487361 -0.9836297 -0.170066 0.05089044 -0.9841178 -0.2506327 0.07504308 -0.9651694 -0.2580474 0.04300326 -0.9651747 -0.3381693 0.05639892 -0.9393939 -0.3425757 0.01629561 -0.9393489 -0.4220056 0.02004855 -0.9063715 -0.421305 -0.03191566 -0.9063573 -0.4931202 -0.03735446 -0.869159 -0.4840487 -0.1003758 -0.869265 -0.4954828 -0.06470054 -0.8662048 -0.4962624 -0.05897623 -0.8661671 -0.4769138 -0.1488196 -0.8662598 -0.4769138 -0.1488198 -0.8662598 -0.4769138 -0.1488198 -0.8662597 -0.4888387 -0.09490489 -0.8671965 -0.4151524 -0.08056807 -0.9061774 -0.3422909 -0.02530258 -0.9392533 -0.2614645 0.01293241 -0.9651265 -0.2581991 0.04369813 -0.965103 -0.1751664 0.02967739 -0.9840915 -0.1700841 0.05164438 -0.9840753 -0.4663474 -0.1803936 -0.8660129 -0.4663474 -0.1803937 -0.8660129 -0.4663473 -0.1803937 -0.8660129 -0.4699323 -0.1531032 -0.8693234 -0.4020796 -0.1310201 -0.906182 -0.4152334 -0.0804454 -0.9061511 -0.3373211 -0.06535142 -0.9391186 -0.34273 -0.02451479 -0.9391141 -0.2607705 -0.01862639 -0.9652212 -0.2611124 0.0118038 -0.9652363 -0.1794269 0.008146762 -0.9837376 -0.1772536 0.01220685 -0.9840896 -0.4467796 -0.2188996 -0.867451 -0.4473206 -0.2095115 -0.8694879 -0.3828309 -0.1792963 -0.9062524 -0.401603 -0.1314262 -0.9063345 -0.3263367 -0.1068271 -0.9391978 -0.3369333 -0.06591576 -0.9392184 -0.2846416 -0.05567264 -0.9570161 -0.2553788 0.002305984 -0.9668384 -0.4085349 -0.2903945 -0.8653152 -0.4216837 -0.259761 -0.8687389 -0.3604436 -0.2220442 -0.9059674 -0.3841229 -0.1782777 -0.9059067 -0.311195 -0.1444516 -0.9393038 -0.3258383 -0.1072999 -0.9393169 -0.3805894 -0.3220294 -0.8668615 -0.3842335 -0.3113315 -0.8691591 -0.3285477 -0.2661582 -0.9062099 -0.3594418 -0.2225884 -0.9062318 -0.2917341 -0.1806732 -0.9392809 -0.3113108 -0.1443861 -0.9392755 -0.322923 -0.3815013 -0.866128 -0.3229196 -0.3817899 -0.8660021 -0.3491355 -0.3490843 -0.8696233 -0.347179 -0.3561897 -0.8675228 -0.2955681 -0.3032198 -0.9059235 -0.3297598 -0.2656416 -0.9059212 -0.2672147 -0.215223 -0.9392952 -0.2917116 -0.1807115 -0.9392805 -0.2999541 -0.3922556 -0.8695765 -0.2568921 -0.3359491 -0.9061704 -0.2944174 -0.3035234 -0.9061965 -0.2390822 -0.2465195 -0.9391848 -0.2678059 -0.2149822 -0.939182 -0.2182617 -0.4495203 -0.8661949 -0.2204863 -0.4484333 -0.8661949 -0.253988 -0.4246906 -0.8689811 -0.2522676 -0.4276592 -0.8680257 -0.2152154 -0.3648449 -0.9058536 -0.258625 -0.3356291 -0.9057959 -0.2095692 -0.271971 -0.9392085 -0.2390066 -0.2465753 -0.9391893 -0.1929985 -0.1990947 -0.9607877 -0.215972 -0.1733309 -0.9608916 -0.2145414 -0.1583213 -0.9637979 -0.2269505 -0.1405506 -0.963711 -0.2306594 -0.1673443 -0.9585365 -0.2570046 -0.1191744 -0.959034 -0.2508666 -0.09399205 -0.9634478 -0.2548815 -0.08395379 -0.963321 -0.2604291 -0.09813696 -0.9604925 -0.2608057 -0.09675925 -0.9605302 -0.1825058 -0.4649887 -0.8663009 -0.1971576 -0.4529536 -0.8694607 -0.1687811 -0.3876888 -0.9062066 -0.2134523 -0.3648759 -0.9062581 -0.173125 -0.2959409 -0.9393864 -0.2084013 -0.2722157 -0.9393975 -0.1589354 -0.2075712 -0.9652222 -0.1507512 -0.2146144 -0.9649947 -0.2245922 -0.0570864 -0.9727793 -0.1030403 -0.4887177 -0.8663358 -0.1072728 -0.4877734 -0.8663543 -0.1413627 -0.4757026 -0.8681726 -0.1408873 -0.4761602 -0.867999 -0.119935 -0.4054083 -0.9062339 -0.168232 -0.3876595 -0.9063213 -0.1367746 -0.3151979 -0.9391182 -0.1751707 -0.2956843 -0.9390879 -0.1333737 -0.2251715 -0.9651473 -0.1599017 -0.2072997 -0.9651209 -0.1104927 -0.1431976 -0.983507 -0.2240751 -0.05664908 -0.9729242 -0.09074229 -0.1543474 -0.9838408 -0.1324419 -0.2253457 -0.965235 -0.1029949 -0.2402981 -0.9652197 -0.1350668 -0.3152235 -0.9393568 -0.09813511 -0.328583 -0.9393631 -0.1211287 -0.4055699 -0.9060027 -0.07156127 -0.4172191 -0.9059841 -0.0834316 -0.4863713 -0.8697598 -0.02014839 -0.4950048 -0.8686567 -0.05928778 -0.4963256 -0.8661097 0.01464509 -0.4987199 -0.8666396 0.01464504 -0.4987199 -0.8666396 0.01464509 -0.4987201 -0.8666394 -0.02321225 -0.4963917 -0.8677883 -0.01977384 -0.4227384 -0.9060361 -0.07134044 -0.4171042 -0.9060544 -0.05791968 -0.3386245 -0.9391373 -0.0995751 -0.3287863 -0.9391403 -0.07591259 -0.2506758 -0.9650902 -0.1043492 -0.2402495 -0.9650862 -0.07077592 -0.1629508 -0.9840924 -0.08674019 -0.154782 -0.9841336 -0.08477145 -0.1589465 -0.9836411 -0.07048153 -0.1629821 -0.9841083 -0.04967361 -0.1705022 -0.9841045 -0.04315447 -0.2574081 -0.9653387 -0.0567097 -0.3382472 -0.939347 -0.0163061 -0.3425669 -0.939352 -0.02013665 -0.4227868 -0.9060055 0.0355916 -0.4928585 -0.8693813 0.1003851 -0.4840444 -0.8692663 0.06486439 -0.4956234 -0.8661122 0.06486439 -0.4956233 -0.8661122 0.06486439 -0.4956233 -0.8661122 0.05882728 -0.4963581 -0.8661224 0.08059167 -0.415131 -0.906185 0.03116899 -0.4218162 -0.9061455 0.02529412 -0.3422769 -0.9392587 -0.01686328 -0.3428295 -0.9392463 -0.01286172 -0.2614598 -0.9651287 -0.04561036 -0.2578679 -0.965103 -0.03100579 -0.1752965 -0.9840273 -0.05180412 -0.1704273 -0.9840075 0.1806141 -0.4661839 -0.866055 0.1530805 -0.4699466 -0.8693195 0.1307175 -0.4012984 -0.906572 0.08206707 -0.413964 -0.9065864 0.06683903 -0.3370804 -0.9391003 0.02448374 -0.3428078 -0.9390865 0.01862478 -0.2607005 -0.9652401 -0.01177161 -0.2612091 -0.9652105 -0.00809741 -0.179427 -0.983738 -0.01222652 -0.177275 -0.9840855 0.219285 -0.4475604 -0.866951 0.2098471 -0.4481747 -0.8689671 0.1792502 -0.3828281 -0.9062627 0.1298211 -0.4021832 -0.9063086 0.1056674 -0.3273885 -0.9389629 0.06603109 -0.3376777 -0.9389429 0.05565428 -0.2845849 -0.9570341 -0.002278804 -0.2553824 -0.9668375 0.2901101 -0.4078478 -0.8657345 0.260336 -0.4209229 -0.8689356 0.2223331 -0.3594549 -0.9062892 0.1793982 -0.3825935 -0.9063324 0.1456835 -0.3107009 -0.939277 0.1073415 -0.3258288 -0.9393154 0.3220155 -0.380577 -0.8668721 0.3102006 -0.3845629 -0.8694176 0.2653111 -0.3289136 -0.9063255 0.2224686 -0.3591749 -0.906367 0.1810079 -0.2922711 -0.9390494 0.144675 -0.3118544 -0.9390506 0.3816339 -0.3228627 -0.866092 0.3816533 -0.3228186 -0.8661 0.3491337 -0.349229 -0.8695659 0.3561162 -0.347148 -0.8675653 0.3031819 -0.2956147 -0.905921 0.2645578 -0.3307168 -0.9058894 0.2146888 -0.2683933 -0.9390814 0.181029 -0.2922784 -0.9390431 0.4055346 -0.2909107 -0.8665522 0.392253 -0.2999376 -0.8695833 0.3359498 -0.256954 -0.9061526 0.3035635 -0.2944159 -0.9061835 0.246151 -0.2387152 -0.9393747 0.2157198 -0.2663761 -0.9394193 0.44924 -0.2199697 -0.8659082 0.44924 -0.2199697 -0.8659081 0.44924 -0.2199698 -0.8659082 0.4501808 -0.2178891 -0.8659455 0.4236726 -0.2555761 -0.8690123 0.428395 -0.2526516 -0.8675512 0.3641442 -0.2148568 -0.9062206 0.3359118 -0.2569254 -0.9061747 0.2727325 -0.208648 -0.9391928 0.2456741 -0.2400734 -0.9391533 0.1990432 -0.1944917 -0.9604972 0.175025 -0.2161238 -0.9605503 0.1583454 -0.2145757 -0.9637864 0.1672359 -0.2305871 -0.9585728 0.1192077 -0.2569859 -0.9590349 0.09195929 -0.2504619 -0.9637491 0.09968745 -0.2599923 -0.9604513 0.09678727 -0.2608461 -0.9605163 0.4651066 -0.182493 -0.8662403 0.4528731 -0.1972126 -0.8694902 0.3877338 -0.1687573 -0.9061918 0.364157 -0.2148262 -0.9062227 0.2957628 -0.1744657 -0.9391945 0.2727608 -0.2087886 -0.9391533 0.207587 -0.158886 -0.9652268 0.2146068 -0.1507888 -0.9649906 0.05722212 -0.2249252 -0.9726943 0.4886589 -0.1029824 -0.866376 0.4875943 -0.1072931 -0.8664526 0.4757097 -0.1414068 -0.8681615 0.4761761 -0.1408785 -0.8679918 0.4053947 -0.1198728 -0.9062482 0.387657 -0.1683243 -0.9063051 0.3151971 -0.1367619 -0.9391204 0.2957088 -0.1752193 -0.9390711 0.2251551 -0.1333907 -0.9651487 0.2072733 -0.1598715 -0.9651315 0.1407933 -0.1086345 -0.9840609 0.05568236 -0.2231164 -0.9732003 0.1577004 -0.08514595 -0.9838094 0.1544343 -0.09072798 -0.9838285 0.2253636 -0.1324114 -0.9652349 0.2403043 -0.103011 -0.9652164 0.3151884 -0.135019 -0.9393754 0.3285962 -0.09817439 -0.9393543 0.4056046 -0.1211423 -0.9059854 0.4171919 -0.07161271 -0.9059926 0.4949422 -0.02014005 -0.8686925 0.4962881 -0.05929213 -0.8661308 0.4959979 -0.06202447 -0.8661058 0.4987881 0.01463997 -0.8666005 0.4987881 0.01464027 -0.8666003 0.4987881 0.01464021 -0.8666004 0.4964058 -0.02323484 -0.8677797 0.4227232 -0.01980417 -0.9060424 0.4170896 -0.07125878 -0.9060676 0.3378574 -0.05776041 -0.9394234 0.3285335 -0.09761381 -0.9394345 0.251117 -0.07466322 -0.9650729 0.240249 -0.1043167 -0.9650899 0.1629147 -0.07076722 -0.984099 0.1547937 -0.08677631 -0.9841285 0.159051 -0.08486509 -0.9836162 0.159051 -0.08486497 -0.9836162 0.159051 -0.08486503 -0.9836162 0.1705287 -0.04971224 -0.9840978 0.2510438 -0.07311034 -0.9652108 0.2577535 -0.04435044 -0.9651923 0.3379885 -0.05818074 -0.9393503 0.3425598 -0.01636785 -0.9393535 0.4228605 -0.0201621 -0.9059705 0.4222366 0.03051561 -0.9059719 0.4928653 0.03557753 -0.869378 0.4840806 0.1003824 -0.8692464 0.4972079 0.05928003 -0.865604 0.496792 0.06255191 -0.8656125 0.4769152 0.1488234 -0.8662583 0.4769153 0.1488236 -0.8662583 0.4888012 0.09484028 -0.8672248 0.4151428 0.08056849 -0.9061816 0.3423143 0.02534115 -0.9392437 0.2614861 -0.01293361 -0.9651206 0.2579719 -0.04566097 -0.9650729 0.1748815 -0.03095024 -0.984103 0.1704823 -0.04964929 -0.9841091 0.4657792 0.1845241 -0.8654482 0.4699659 0.1531105 -0.869304 0.4012701 0.1306909 -0.9065882 0.4139277 0.0820983 -0.9066001 0.337102 0.06677907 -0.9390968 0.3427304 0.02446824 -0.9391151 0.260748 0.01857817 -0.9652281 0.261084 -0.01180237 -0.965244 0.1794444 -0.008098185 -0.9837349 0.17723 -0.01220488 -0.9840938 0.4475791 0.2192226 -0.8669571 0.4481744 0.2098507 -0.8689664 0.3828098 0.1792864 -0.9062634 0.4022076 0.1297867 -0.9063027 0.3267043 0.1054406 -0.9392266 0.3365086 0.06769365 -0.9392442 0.2855108 0.05742192 -0.9566538 0.2554614 -0.002383589 -0.9668164 -0.7861481 -0.4275831 -0.4462556 -0.7879572 -0.4237659 -0.4467058 -0.7892103 -0.4209914 -0.4471168 -0.7884443 -0.4267154 -0.4430233 -0.7884442 -0.4267154 -0.4430233 -0.7884443 -0.4267154 -0.4430233 -0.7877764 -0.4246975 -0.4461392 -0.7868168 -0.4261754 -0.4464235 -0.7868169 -0.4261754 -0.4464235 -0.789143 -0.4221876 -0.4461066 -0.789143 -0.4221876 -0.4461064 -0.789143 -0.4221876 -0.4461065 -0.7875333 -0.4252095 -0.4460809 -0.7865094 -0.4270981 -0.4460832 -0.7856494 -0.4287475 -0.4460164 -0.8045751 0.3916915 -0.4463595 -0.8043524 0.3922875 -0.4462376 -0.8065042 0.3886575 -0.4455294 -0.8026028 0.3929794 -0.4487715 -0.8040181 0.3929952 -0.446217 -0.8036819 0.3935725 -0.446314 -0.8034695 0.3942732 -0.4460779 -0.8049192 0.3910116 -0.4463352 -0.8040095 0.3929851 -0.4462416 -0.8042434 0.3924269 -0.4463114 -0.8037582 0.3933008 -0.446416 -0.9318112 0.3628786 0.006860077 -0.9460405 0.3240486 0 -0.9694588 0.2452543 0 -0.978758 0.2049047 0.006850779 -0.986422 0.1642306 0 -0.9966452 0.08184421 0 -0.9991471 0.04072481 0.00683695 -0.9999999 -6.06164e-4 0 -0.9965457 -0.08304697 0 -0.9922264 -0.1242555 0.006881535 -0.9862324 -0.1653653 0 -0.9694271 -0.2453796 0 -0.9582059 -0.2859938 0.007004022 -0.9452446 -0.3263632 0 -0.9156168 -0.4020523 0 -0.8983859 -0.4391549 0.006773591 -0.8797216 -0.4754893 0 -0.8359612 -0.5487888 0 -0.8133289 -0.5817669 0.006604254 -0.7895277 -0.6137151 0 -0.7349974 -0.67807 0 -0.7068921 -0.7072898 0.00670135 -0.6777032 -0.7353356 0 -0.6136717 -0.7895613 0 -0.5798687 -0.81468 0.006989359 -0.5450273 -0.8384184 0 -0.4753372 -0.8798038 0 -0.4388967 -0.8985119 0.006792545 -0.40175 -0.9157494 0 -0.3240789 -0.9460301 0 -0.2853953 -0.9583864 0.006713271 -0.2462685 -0.9692016 0 -0.1641899 -0.9864287 0 -0.1232464 -0.9923526 0.00683844 -0.08209663 -0.9966245 0 0.04323911 -0.9990392 0.007164895 0.08638787 -0.9962616 0 0.1642222 -0.9864234 0 0.2054616 -0.9786406 0.006940484 0.2463396 -0.9691836 0 0.3241956 -0.9459902 0 0.3633723 -0.9316185 0.006908118 0.4019247 -0.9156727 0 0.4789206 -0.8778584 0 0.5124663 -0.8586835 0.006398916 0.5453686 -0.8381963 0 0.6139882 -0.7893154 0 0.6466235 -0.7627776 0.006963491 0.6781117 -0.7349589 0 0.7374029 -0.6754532 0 0.7634008 -0.645892 0.006540596 0.7883598 -0.6152144 0 0.8377299 -0.5460848 0 0.8596736 -0.5107973 0.006881773 0.880155 -0.4746866 0 0.9160296 -0.4011107 0 0.9318156 -0.3628674 0.006859898 0.9460473 -0.3240287 0 0.969455 -0.2452698 0 0.9787567 -0.2049112 0.006853818 0.986422 -0.1642306 0 0.9966452 -0.08184421 0 0.9991472 -0.0407235 0.006836235 0.9999999 6.06125e-4 0 0.9965457 0.08304697 0 0.992226 0.1242595 0.006876111 0.9862307 0.1653758 0 0.9694309 0.2453643 0 0.9582086 0.2859849 0.007003784 0.9452446 0.3263632 0 0.9156168 0.4020523 0 0.8983859 0.4391549 0.006767928 0.8797216 0.4754893 0 0.8359612 0.5487888 0 0.8133289 0.5817669 0.006609857 0.7895277 0.6137151 0 0.7349676 0.6781023 0 0.706892 0.7072897 0.006712615 0.6777378 0.7353038 0 0.6136314 0.7895926 0 0.5798689 0.8146802 0.006966829 0.5450723 0.838389 0 0.4753372 0.8798038 0 0.4388967 0.8985119 0.00680381 0.40175 0.9157494 0 0.3240789 0.9460301 0 0.2853657 0.9583951 0.006735861 0.2462077 0.9692171 0 0.1641899 0.9864287 0 0.1232463 0.9923524 0.006860971 0.08209663 0.9966245 0 -0.04323911 0.999039 0.00717616 -0.08638787 0.9962616 0 -0.1642222 0.9864234 0 -0.2054308 0.9786472 0.006918013 -0.2462788 0.969199 0 -0.3241956 0.9459902 0 -0.3633723 0.9316185 0.006908118 -0.4019247 0.9156727 0 -0.4789698 0.8778314 0 -0.5124663 0.8586837 0.00638765 -0.5453236 0.8382257 0 -0.6140285 0.7892839 0 -0.6466424 0.7627617 0.006952106 -0.6781117 0.7349589 0 -0.7373731 0.6754857 0 -0.7633876 0.6459077 0.006546378 -0.7883598 0.6152144 0 -0.8377299 0.5460848 0 -0.8596816 0.510784 0.0068928 -0.8801695 0.4746596 0 -0.9160296 0.4011107 0 -0.6484081 0.163545 -0.7435187 -0.6484869 0.1586822 -0.744503 -0.6590468 0.1095956 -0.7440741 -0.6596481 0.1094229 -0.7435664 -0.6662534 0.05462688 -0.743722 -0.6659759 0.0549972 -0.7439432 -0.6659322 0.05500715 -0.7439815 -0.6684057 -3.93184e-4 -0.7437968 -0.6683719 -4.12848e-4 -0.7438272 -0.6683785 -3.93395e-4 -0.7438212 -0.6683785 -3.9335e-4 -0.7438212 -0.6683784 -3.93359e-4 -0.7438213 -0.6659794 -0.05567026 -0.74389 -0.6657824 -0.05553144 -0.7440767 -0.6587632 -0.1103963 -0.7442068 -0.6587633 -0.1103964 -0.7442067 -0.6587633 -0.1103963 -0.7442067 -0.6587057 -0.1105252 -0.7442387 -0.6590141 -0.1103371 -0.7439934 -0.6475625 -0.1641252 -0.7441276 -0.6473163 -0.1641851 -0.7443286 -0.6487305 -0.1627324 -0.7434157 -0.6323484 -0.2175354 -0.7435145 -0.6326195 -0.217875 -0.7431844 -0.6113624 -0.2726359 -0.7429036 -0.61129 -0.2678626 -0.7446975 -0.6109809 -0.2679218 -0.7449297 -0.5862664 -0.3180538 -0.7450729 -0.5889009 -0.3180825 -0.74298 -0.5843592 -0.3208538 -0.7453705 -0.5576333 -0.3647897 -0.7456364 -0.5587383 -0.3667044 -0.7438679 -0.5285857 -0.4089635 -0.7438724 -0.5278467 -0.4107394 -0.7434185 -0.5288885 -0.4108542 -0.7426141 -0.4929932 -0.453287 -0.7426228 -0.4912855 -0.4529017 -0.7439884 -0.4879977 -0.4535477 -0.7457565 -0.4515361 -0.4898835 -0.7457408 -0.4515361 -0.4898835 -0.7457408 -0.4515361 -0.4898834 -0.7457408 -0.4523755 -0.4931668 -0.7430632 -0.400408 -0.5366702 -0.7427372 -0.4004078 -0.5366704 -0.7427372 -0.4004079 -0.5366705 -0.7427372 -0.4093838 -0.5268667 -0.7448601 -0.4133432 -0.5285021 -0.7415072 -0.3670728 -0.5617163 -0.7414395 -0.3670752 -0.5617147 -0.7414395 -0.3670752 -0.5617147 -0.7414395 -0.365849 -0.56106 -0.7425403 -0.3607775 -0.5604668 -0.745464 -0.316622 -0.5863391 -0.7456253 -0.3166546 -0.5845184 -0.7470397 -0.2674252 -0.6084944 -0.7471402 -0.2673352 -0.6097112 -0.7461797 -0.2154109 -0.6298738 -0.7462286 -0.2148204 -0.6307634 -0.7456473 -0.2192751 -0.6331483 -0.7423219 -0.1641302 -0.6493096 -0.7426025 -0.1633322 -0.6523595 -0.7401012 -0.1581436 -0.6527353 -0.7408962 -0.1094414 -0.662848 -0.7407126 -0.1116378 -0.6566792 -0.7458616 -0.05486285 -0.6636467 -0.7460316 -0.05303186 -0.6652705 -0.7447167 -0.05402892 -0.6660858 -0.7439158 -0.05402892 -0.6660858 -0.7439157 -0.05402886 -0.6660857 -0.7439158 0 -0.6682193 -0.7439644 0 -0.6683664 -0.7438323 0 -0.6684381 -0.7437679 0.05442136 -0.6659725 -0.7439886 0.05623644 -0.6688446 -0.7412722 0.1182385 -0.6610452 -0.7409716 0.1088538 -0.6574954 -0.7455539 0.1088538 -0.6574956 -0.7455538 0.1088538 -0.6574955 -0.7455539 0.1089251 -0.6575077 -0.7455327 0.1646152 -0.6455746 -0.7457448 0.1646071 -0.6458454 -0.7455121 0.164607 -0.6458455 -0.7455121 0.1646071 -0.6458455 -0.7455121 0.1581194 -0.6508225 -0.7425823 0.2181358 -0.6332411 -0.7425783 0.2189744 -0.6340174 -0.7416685 0.2750433 -0.6116716 -0.7417609 0.2684231 -0.6118736 -0.7440161 0.2679896 -0.6135939 -0.7427545 0.2679896 -0.6135941 -0.7427543 0.2679896 -0.6135941 -0.7427543 0.3191192 -0.5885908 -0.7427812 0.3191121 -0.5881459 -0.7431366 0.3168399 -0.5918457 -0.7411688 0.36738 -0.5616732 -0.7413199 0.3671981 -0.5615118 -0.7415323 0.4136503 -0.5282091 -0.7415447 0.4136503 -0.5282091 -0.7415447 0.4136503 -0.5282092 -0.7415447 0.4113473 -0.5289048 -0.7423296 0.4113473 -0.5289048 -0.7423296 0.4113473 -0.5289047 -0.7423296 0.4111859 -0.5275778 -0.7433626 0.4541779 -0.4913462 -0.7431699 0.4548069 -0.4943729 -0.740774 0.4555862 -0.4910674 -0.7424918 0.4936491 -0.4530862 -0.7423096 0.4890305 -0.4518033 -0.7461388 0.5195708 -0.4170271 -0.7457444 0.5271294 -0.409516 -0.7446014 0.5274357 -0.4102499 -0.7439804 0.5597051 -0.3647384 -0.7441076 0.5592747 -0.3637577 -0.7449109 0.5596894 -0.3671085 -0.742953 0.5890386 -0.3174177 -0.7431552 0.5864811 -0.3174603 -0.745157 0.610807 -0.2681189 -0.7450014 0.6131848 -0.2679539 -0.7431051 0.633119 -0.2158321 -0.7433552 0.6316627 -0.2167599 -0.7443235 0.6321441 -0.217767 -0.7436205 0.6481891 -0.1635944 -0.7436987 0.6483781 -0.1635318 -0.7435477 0.6490436 -0.1588185 -0.7439887 0.6590502 -0.1095886 -0.744072 0.6595841 -0.1094183 -0.7436239 0.6663489 -0.0546444 -0.7436351 0.666007 -0.05499517 -0.7439156 0.6659103 -0.05499762 -0.7440019 0.6683967 3.9321e-4 -0.7438049 0.6683915 4.12888e-4 -0.7438095 0.6682017 3.98932e-4 -0.7439802 0.6660147 0.05567127 -0.7438582 0.6657507 0.05552697 -0.7441054 0.6585807 0.1103993 -0.7443679 0.6585929 0.1105138 -0.7443401 0.6590788 0.1103479 -0.7439345 0.6475731 0.1641279 -0.7441176 0.6473593 0.1641772 -0.7442928 0.6485343 0.1626863 -0.743597 0.6323055 0.2175207 -0.7435554 0.6327086 0.2179027 -0.7431005 0.6112833 0.2726882 -0.7429494 0.6112835 0.2726883 -0.7429493 0.6112835 0.2726882 -0.7429493 0.6114075 0.2678849 -0.744593 0.6110087 0.2679145 -0.7449095 0.5862275 0.3180327 -0.7451124 0.5888433 0.3180514 -0.743039 0.5842669 0.3208801 -0.7454316 0.5576646 0.3647805 -0.7456175 0.5587722 0.3667652 -0.7438125 0.528702 0.4090535 -0.7437403 0.5279138 0.410757 -0.7433611 0.5287746 0.4107972 -0.7427269 0.4930248 0.453357 -0.7425591 0.4912855 0.4529017 -0.7439884 0.4880018 0.453441 -0.7458187 0.4514929 0.4898056 -0.7458182 0.4522521 0.4929957 -0.7432519 0.3999875 0.5368497 -0.742834 0.3999878 0.5368502 -0.7428336 0.3999878 0.5368501 -0.7428336 0.4094381 0.5269365 -0.7447808 0.413374 0.528494 -0.7414959 0.3671796 0.5619274 -0.7412266 0.3659231 0.5612062 -0.7423934 0.3607616 0.560423 -0.7455047 0.316667 0.586507 -0.7454741 0.3167154 0.5845488 -0.74699 0.2674673 0.608487 -0.7471311 0.2673618 0.6097718 -0.7461207 0.2154743 0.6300593 -0.7460538 0.2148204 0.6307634 -0.7456473 0.2192198 0.6329886 -0.7424744 0.1641303 0.6495062 -0.7424305 0.1632876 0.6522088 -0.7402437 0.1632877 0.6522089 -0.7402437 0.1632876 0.6522088 -0.7402438 0.1587622 0.6528181 -0.740691 0.1094712 0.6630284 -0.7405467 0.1116214 0.6565796 -0.7459517 0.05505979 0.6635662 -0.7460888 0.05505979 0.6635662 -0.7460887 0.05505979 0.6635662 -0.7460887 0.0530107 0.6650076 -0.7449529 0.05412364 0.6663539 -0.7436687 0 0.668434 -0.7437715 0 0.6684328 -0.7437726 0 0.6681874 -0.7439931 -0.05443608 0.6661553 -0.7438239 -0.05630999 0.6691869 -0.7409576 -0.1183454 0.6608889 -0.7410941 -0.1088502 0.6574205 -0.7456205 -0.10886 0.6575124 -0.745538 -0.1646152 0.6455746 -0.7457448 -0.1646707 0.6460921 -0.7452843 -0.1579722 0.6510353 -0.7424271 -0.2181358 0.6332411 -0.7425783 -0.2189381 0.6339123 -0.7417691 -0.2749915 0.6118722 -0.7416145 -0.2749915 0.6118722 -0.7416145 -0.2684257 0.6118731 -0.7440155 -0.2679181 0.6133963 -0.7429435 -0.3191143 0.5885914 -0.7427828 -0.3190461 0.5880436 -0.7432458 -0.3190461 0.5880436 -0.7432458 -0.3190461 0.5880436 -0.7432458 -0.3167054 0.5918737 -0.7412039 -0.36728 0.5615205 -0.7414851 -0.3673147 0.5616132 -0.7413977 -0.4138224 0.5280627 -0.7415531 -0.4114784 0.5289797 -0.7422035 -0.4114785 0.5289797 -0.7422034 -0.411318 0.5277473 -0.7431691 -0.4541425 0.4913561 -0.7431849 -0.4549416 0.4946106 -0.7405326 -0.4556 0.4909543 -0.7425581 -0.4934804 0.4529734 -0.7424906 -0.4890954 0.4518634 -0.7460598 -0.5196192 0.416627 -0.7459342 -0.5271535 0.4095088 -0.7445883 -0.5273222 0.4102002 -0.7440881 -0.5598534 0.3648351 -0.7439486 -0.5593451 0.3638035 -0.7448357 -0.5596937 0.3671072 -0.7429504 -0.5891334 0.3174565 -0.7430635 -0.5863795 0.3174249 -0.745252 -0.610807 0.2681189 -0.7450014 -0.6130502 0.2678757 -0.7432443 -0.6331843 0.2158964 -0.7432808 -0.6317265 0.2167932 -0.7442597 -0.6321424 0.2177673 -0.7436218 -0.6481701 0.1635772 -0.7437191 -0.7705866 0.4174475 -0.4815953 -0.8031915 0.3509656 -0.4813592 -0.8024047 0.3511229 -0.4825551 -0.828504 0.2843212 -0.4824341 -0.8295635 0.2839171 -0.4808486 -0.8500691 0.214412 -0.4810511 -0.8493942 0.2147161 -0.4821066 -0.8643693 0.1433841 -0.4819821 -0.8638669 0.1436598 -0.4828 -0.8730087 0.07209181 -0.482347 -0.8736285 0.07167786 -0.4812853 -0.8762833 -5.43011e-4 -0.481796 -0.8762175 -5.31783e-4 -0.4819156 -0.8731836 -0.07283246 -0.4819191 -0.8733218 -0.0730319 -0.4816383 -0.8645306 -0.1450623 -0.4811899 -0.8641766 -0.1447377 -0.4819232 -0.8493697 -0.2152759 -0.4818999 -0.8498155 -0.2158527 -0.4808548 -0.8291837 -0.2855728 -0.4805232 -0.8285332 -0.2845447 -0.4822522 -0.8023532 -0.3515846 -0.4823045 -0.802634 -0.3522114 -0.4813792 -0.7704503 -0.4179651 -0.4813643 -0.7706791 -0.4184169 -0.480605 -0.7331746 -0.4812009 -0.4805213 -0.7321908 -0.4780477 -0.4851464 -0.6898445 -0.536794 -0.4857641 -0.6907036 -0.5399672 -0.4810033 -0.64543 -0.593454 -0.4808663 -0.6457147 -0.5959684 -0.4773619 -0.5941765 -0.6477721 -0.4768077 -0.5939488 -0.6451221 -0.4806688 -0.5380544 -0.692483 -0.480588 -0.5381569 -0.6887542 -0.4858034 -0.4780691 -0.7315573 -0.4860802 -0.4775643 -0.7364495 -0.4791393 -0.4181481 -0.7718601 -0.4789407 -0.4183859 -0.77022 -0.4813675 -0.351917 -0.802662 -0.4815478 -0.3513103 -0.805103 -0.477902 -0.2832126 -0.8316023 -0.4777324 -0.2848761 -0.8271389 -0.4844451 -0.2124493 -0.848577 -0.4845438 -0.2127906 -0.8480176 -0.4853724 -0.1464959 -0.8617337 -0.485751 -0.144738 -0.8648805 -0.4806585 -0.06968289 -0.8741775 -0.4805809 -0.06968283 -0.8741776 -0.4805809 -0.06968289 -0.8741775 -0.4805809 -0.07211011 -0.8706717 -0.4865502 0 -0.8736691 -0.4865207 0 -0.8735435 -0.4867463 0.07319742 -0.8706072 -0.4865033 0.07615506 -0.8735294 -0.4807775 0.07615506 -0.8735293 -0.4807775 0.07615506 -0.8735294 -0.4807775 0.1433256 -0.8652815 -0.48036 0.1450757 -0.8667394 -0.4771959 0.2170995 -0.8514328 -0.4774202 0.2170995 -0.8514329 -0.47742 0.2170994 -0.8514329 -0.4774201 0.212907 -0.8482336 -0.4849437 0.2855829 -0.8268856 -0.4844612 0.284722 -0.8263454 -0.4858877 0.3511314 -0.8004385 -0.4858036 0.35389 -0.8017632 -0.4815992 0.4177122 -0.7704505 -0.4815835 0.4141717 -0.7690497 -0.4868516 0.4780637 -0.7310546 -0.4868413 0.4783399 -0.7312344 -0.4862995 0.53645 -0.6897599 -0.4862641 0.5403305 -0.6907794 -0.480486 0.5951457 -0.6438758 -0.4808592 0.5932133 -0.6435949 -0.4836152 0.642893 -0.5939323 -0.4836662 0.6443204 -0.5940119 -0.481665 0.6443204 -0.5940119 -0.4816648 0.6921784 -0.5377627 -0.4813528 0.6927689 -0.5376891 -0.4805849 0.7345316 -0.4787578 -0.4808892 0.7345316 -0.4787578 -0.4808892 0.7345316 -0.4787579 -0.4808892 0.7346408 -0.4787651 -0.4807152 0.7710797 -0.4173782 -0.4808654 0.7705866 -0.4174475 -0.4815953 0.8031069 -0.3509481 -0.481513 0.802473 -0.3511522 -0.4824202 0.8285605 -0.2843177 -0.482339 0.8295495 -0.2839278 -0.4808667 0.8500691 -0.214412 -0.4810511 0.8494296 -0.2147255 -0.4820398 0.8643525 -0.1433923 -0.4820098 0.8638669 -0.1436598 -0.4828 0.8730193 -0.07208901 -0.4823281 0.8736281 -0.07167792 -0.4812859 0.8762217 5.43014e-4 -0.4819082 0.8762651 5.31784e-4 -0.4818293 0.873162 0.07282507 -0.4819593 0.8733849 0.07304096 -0.4815225 0.8645138 0.1450707 -0.4812178 0.8642131 0.1447438 -0.4818558 0.8494061 0.2152852 -0.4818317 0.8498155 0.2158527 -0.4808548 0.8290416 0.2855238 -0.4807977 0.8285332 0.2845447 -0.4822522 0.8023002 0.3515419 -0.4824237 0.8026674 0.3522266 -0.4813125 0.7705825 0.4180369 -0.4810903 0.7706504 0.4183962 -0.480669 0.7332169 0.481258 -0.4803997 0.7321288 0.4780073 -0.48528 0.6899389 0.5368156 -0.4856063 0.6906447 0.5398782 -0.4811876 0.6453521 0.5934248 -0.4810069 0.6453521 0.5934248 -0.4810069 0.6453522 0.5934248 -0.4810069 0.6456143 0.5959334 -0.4775412 0.6456143 0.5959334 -0.4775412 0.6456144 0.5959334 -0.4775412 0.5942199 0.6477463 -0.4767888 0.5939345 0.6451095 -0.4807032 0.5380623 0.6924788 -0.480585 0.538072 0.6934633 -0.4791526 0.4800834 0.7347247 -0.4792699 0.4801825 0.7347103 -0.4791925 0.4181135 0.7717139 -0.4792065 0.4184322 0.7703002 -0.4811986 0.3519822 0.802798 -0.4812732 0.3513374 0.8051714 -0.4777667 0.2832126 0.8316023 -0.4777324 0.2848782 0.8271378 -0.4844456 0.2848782 0.8271378 -0.4844455 0.2848782 0.8271378 -0.4844457 0.2124126 0.8484306 -0.4848159 0.2128238 0.8479213 -0.4855261 0.2128238 0.8479213 -0.485526 0.2128238 0.8479213 -0.4855262 0.1464964 0.8617326 -0.4857527 0.1447372 0.864876 -0.4806668 0.06968164 0.8741675 -0.4805995 0.07211166 0.8707107 -0.48648 0.0721116 0.8707108 -0.4864801 0 0.8736568 -0.4865428 0 0.8736569 -0.4865427 0 0.8736569 -0.4865427 -0.003809392 0.8782061 -0.4782675 -0.003809392 0.8782061 -0.4782674 -0.003809332 0.878206 -0.4782676 -0.07363343 0.8751115 -0.4782866 -0.07363343 0.8751115 -0.4782865 -0.07363337 0.8751115 -0.4782865 -0.07239961 0.8740795 -0.4803574 -0.1432656 0.8652891 -0.4803642 -0.1451251 0.8666946 -0.4772621 -0.1451252 0.8666947 -0.477262 -0.1451251 0.8666946 -0.4772621 -0.2171411 0.8515982 -0.4771063 -0.2171411 0.8515982 -0.4771062 -0.217141 0.8515982 -0.4771062 -0.2129725 0.8484947 -0.4844581 -0.2855829 0.8268856 -0.4844612 -0.2846918 0.8262576 -0.4860546 -0.3511314 0.8004385 -0.4858036 -0.3538719 0.8018464 -0.4814739 -0.4177122 0.7704505 -0.4815835 -0.4142611 0.7691141 -0.4866737 -0.4781064 0.7310352 -0.4868283 -0.4783806 0.7312966 -0.4861661 -0.53645 0.6897599 -0.4862641 -0.5402005 0.6905335 -0.4809855 -0.5402005 0.6905335 -0.4809854 -0.5402005 0.6905335 -0.4809854 -0.5951097 0.6438972 -0.4808751 -0.5932635 0.6436494 -0.4834809 -0.642893 0.5939323 -0.4836662 -0.644419 0.5941089 -0.4814135 -0.6921538 0.5376918 -0.4814674 -0.6927543 0.5376778 -0.4806186 -0.7345771 0.4787016 -0.4808756 -0.7346401 0.4787656 -0.4807156 -0.7711188 0.4174356 -0.480753 -0.8682808 0.4682486 -0.1638042 -0.9036661 0.3954265 -0.1643945 -0.9035249 0.3956368 -0.1646643 -0.9331287 0.3193548 -0.1651772 -0.9329506 0.3195646 -0.1657759 -0.9560431 0.241674 -0.1660585 -0.9559273 0.2418342 -0.1664909 -0.9726715 0.1617484 -0.1665759 -0.9725466 0.1619218 -0.1671367 -0.9826605 0.08061712 -0.1669712 -0.9826257 0.08069634 -0.1671373 -0.9859869 -5.97561e-4 -0.1668218 -0.9859884 -5.97711e-4 -0.1668132 -0.9826546 -0.08217322 -0.1662451 -0.9825592 -0.08187997 -0.166953 -0.9723887 -0.1628627 -0.1671409 -0.9724432 -0.1630522 -0.1666384 -0.9556919 -0.2427402 -0.1665237 -0.9555339 -0.2418644 -0.1686908 -0.9321444 -0.3201232 -0.1691984 -0.9322718 -0.3218899 -0.1650944 -0.9031934 -0.396324 -0.16483 -0.9032011 -0.3966071 -0.1641059 -0.8669782 -0.4706949 -0.1636918 -0.8671908 -0.4687244 -0.168159 -0.82538 -0.5388911 -0.1683574 -0.8248992 -0.5415282 -0.1621382 -0.7774811 -0.6078026 -0.1615522 -0.7782431 -0.6049395 -0.1684817 -0.7243107 -0.6685131 -0.1687135 -0.7243624 -0.6682685 -0.1694595 -0.6675258 -0.7250345 -0.1695119 -0.6675258 -0.7250345 -0.1695119 -0.6675258 -0.7250346 -0.1695119 -0.6677456 -0.7245472 -0.1707258 -0.606622 -0.7763859 -0.1709822 -0.6052607 -0.7788417 -0.164515 -0.6052607 -0.7788417 -0.164515 -0.6052607 -0.7788417 -0.164515 -0.5366903 -0.8276259 -0.1643137 -0.5366902 -0.8276259 -0.1643136 -0.5366903 -0.8276259 -0.1643136 -0.5373314 -0.8265911 -0.1673981 -0.470633 -0.8663752 -0.1670288 -0.4690747 -0.8682167 -0.1617675 -0.3947008 -0.9045633 -0.1611722 -0.3961509 -0.9029862 -0.1663748 -0.3961505 -0.9029864 -0.1663747 -0.3961508 -0.9029862 -0.1663748 -0.3211005 -0.9323036 -0.1664471 -0.3197795 -0.9334895 -0.1622917 -0.240166 -0.9570908 -0.1621655 -0.242695 -0.9551526 -0.169655 -0.1626527 -0.9719197 -0.1700478 -0.1626527 -0.9719197 -0.1700477 -0.1626526 -0.9719198 -0.1700477 -0.1618623 -0.9724579 -0.1677089 -0.08137482 -0.9825567 -0.1672137 -0.0809521 -0.9827363 -0.1663615 0 -0.9860923 -0.1661986 0 -0.9860197 -0.1666293 0.08564037 -0.9823173 -0.1664888 0.0851671 -0.982201 -0.167415 0.1627404 -0.9722775 -0.1679053 0.1618432 -0.9721471 -0.1695193 0.2399349 -0.9558972 -0.169387 0.2399349 -0.9558971 -0.169387 0.2430734 -0.9563426 -0.162247 0.3214374 -0.9328969 -0.1624238 0.3214374 -0.9328969 -0.1624237 0.3214373 -0.9328969 -0.1624237 0.3196677 -0.9327877 -0.1664921 0.3981189 -0.9020513 -0.166748 0.3981189 -0.9020513 -0.1667479 0.3981189 -0.9020513 -0.166748 0.3959631 -0.9020999 -0.1715495 0.4671415 -0.8673829 -0.1715399 0.472901 -0.8668313 -0.1580137 0.5405372 -0.8262854 -0.1583419 0.5379842 -0.8268342 -0.1640684 0.5379817 -0.8268358 -0.1640684 0.5379842 -0.8268342 -0.1640685 0.6077018 -0.7769154 -0.1646237 0.6077018 -0.7769154 -0.1646237 0.6077018 -0.7769154 -0.1646237 0.6049432 -0.7776838 -0.1710312 0.6677703 -0.7244684 -0.1709632 0.6682586 -0.7242941 -0.1697897 0.7245445 -0.6679754 -0.169836 0.7277049 -0.6665801 -0.1616064 0.7795266 -0.6050232 -0.1621275 0.7770503 -0.6063978 -0.1687446 0.7770503 -0.6063978 -0.1687445 0.7770503 -0.6063978 -0.1687446 0.8258416 -0.5382089 -0.1682764 0.8257298 -0.5382692 -0.1686314 0.8667114 -0.469529 -0.1683863 0.8682711 -0.4682852 -0.1637517 0.9036701 -0.3954187 -0.1643912 0.9034869 -0.3956256 -0.1648994 0.9331201 -0.3193744 -0.1651873 0.9329544 -0.3195469 -0.1657885 0.9560449 -0.2416689 -0.1660551 0.9559009 -0.2418441 -0.1666287 0.9726573 -0.161746 -0.1666611 0.9725643 -0.1619248 -0.1670306 0.9826605 -0.08061712 -0.1669712 0.9826221 -0.08069604 -0.1671584 0.9859905 5.9751e-4 -0.166801 0.9859896 5.97685e-4 -0.166806 0.9826589 0.08218091 -0.1662167 0.9825489 0.08187812 -0.1670145 0.9724029 0.1628651 -0.1670557 0.9724396 0.1630626 -0.166649 0.9556919 0.2427402 -0.1665237 0.9555528 0.2418551 -0.1685974 0.9321415 0.3201297 -0.1692019 0.9322532 0.3218793 -0.1652202 0.9031895 0.3963319 -0.1648333 0.9032227 0.3966112 -0.1639769 0.8670226 0.4707309 -0.163353 0.8671463 0.4686937 -0.1684741 0.8253558 0.5388752 -0.1685274 0.8248884 0.541513 -0.162243 0.777463 0.607737 -0.1618863 0.7782248 0.6049297 -0.1686011 0.7782248 0.6049297 -0.168601 0.7782248 0.6049298 -0.1686011 0.7242794 0.668545 -0.1687216 0.7243853 0.6683363 -0.1690931 0.7243854 0.6683363 -0.1690931 0.7243854 0.6683363 -0.1690931 0.6675356 0.7250277 -0.1695023 0.6677527 0.7244827 -0.1709716 0.6039962 0.7784094 -0.1710773 0.6043826 0.7776876 -0.1729851 0.5388243 0.8244085 -0.1732603 0.53737 0.8265479 -0.1674875 0.4705779 0.8662737 -0.1677095 0.4690666 0.8681992 -0.1618842 0.3946654 0.9044569 -0.1618555 0.3961282 0.902939 -0.1666847 0.3210867 0.9322475 -0.1667875 0.3197647 0.9334584 -0.1624989 0.2402228 0.9570769 -0.1621631 0.24265 0.9552124 -0.1693821 0.242644 0.955214 -0.1693819 0.2426501 0.9552124 -0.1693822 0.1626611 0.9720008 -0.1695753 0.1618708 0.9725012 -0.1674494 0.08137482 0.9825567 -0.1672137 0.08095073 0.9827193 -0.1664635 -0.004276931 0.9861407 -0.165856 0 0.9841661 -0.1772487 -0.08124053 0.9808366 -0.177087 -0.0851649 0.9821593 -0.1676611 -0.1628231 0.9723587 -0.167354 -0.1628191 0.9723593 -0.1673538 -0.1628191 0.9723593 -0.1673539 -0.1618326 0.9720834 -0.1698949 -0.2399203 0.9558421 -0.1697177 -0.2430191 0.9563704 -0.1621645 -0.3214395 0.9328979 -0.1624134 -0.3196572 0.9327611 -0.1666617 -0.3980888 0.9020634 -0.1667549 -0.3980887 0.9020634 -0.1667548 -0.3980887 0.9020634 -0.1667548 -0.3959453 0.9020594 -0.1718032 -0.467221 0.8674083 -0.1711941 -0.4729412 0.8667851 -0.1581469 -0.5405372 0.8262854 -0.1583419 -0.5378938 0.8268128 -0.1644718 -0.6077554 0.7769209 -0.1644008 -0.6077554 0.7769209 -0.1644008 -0.6077554 0.7769209 -0.1644008 -0.6049898 0.7776721 -0.1709197 -0.6677703 0.7244684 -0.1709632 -0.6682788 0.7243152 -0.1696205 -0.7245876 0.6680152 -0.1694952 -0.7276793 0.6666164 -0.1615716 -0.7795487 0.6050403 -0.1619568 -0.7770763 0.6064033 -0.168605 -0.8258173 0.538193 -0.1684466 -0.8257389 0.5382751 -0.1685679 -0.8667114 0.469529 -0.1683863 0.2704689 0.420163 -0.8662041 0.3073997 0.3929848 -0.8666421 0.3945748 0.3065518 -0.8662199 0.4848074 0.1216071 -0.8661255 0.4848074 0.1216071 -0.8661255 0.4848076 0.1216073 -0.8661255 0.4993579 3.04827e-4 -0.8663958 0.4844607 -0.118534 -0.8667454 0.4844607 -0.118534 -0.8667454 0.4844609 -0.118534 -0.8667454 0.473164 -0.162992 -0.8657652 0.4564636 -0.2003706 -0.8668867 0.4183708 -0.2744104 -0.8658319 0.3938386 -0.3063235 -0.8666356 0.3069691 -0.3938559 -0.8663992 0.2001203 -0.4582061 -0.8660249 0 -0.4999648 -0.8660458 -0.1174863 -0.4847192 -0.8667436 -0.1638231 -0.4730227 -0.8656857 -0.2005875 -0.4564076 -0.8668661 -0.2704689 -0.420163 -0.8662041 -0.3073842 -0.3930181 -0.8666324 -0.3946131 -0.3065463 -0.8662043 -0.4848023 -0.1216083 -0.8661283 -0.4991967 -3.04859e-4 -0.8664888 -0.4844713 0.118537 -0.8667392 -0.4844713 0.118537 -0.8667392 -0.4844714 0.118537 -0.866739 -0.473164 0.162992 -0.8657652 -0.4564636 0.2003706 -0.8668867 -0.4183622 0.2744116 -0.8658357 -0.3938363 0.30635 -0.8666273 -0.3069449 0.3938249 -0.8664219 -0.2001231 0.4581826 -0.8660367 0 0.4999538 -0.8660521 0.1179186 0.4846942 -0.8666989 0.1638332 0.473052 -0.8656677 0.2006377 0.4564344 -0.8668403 0.1551589 0.174686 -0.9723222 -0.1550926 -0.1748332 -0.9723064 -0.02857488 -0.2360706 -0.9713157 -0.1102407 -0.3220765 -0.9402733 -0.1102406 -0.3220765 -0.9402733 -0.1102406 -0.3220764 -0.9402732 -0.04573637 -0.2298831 -0.972143 -0.04573637 -0.229883 -0.9721431 -0.04573643 -0.2298831 -0.9721431 -0.08873742 -0.2821815 -0.9552483 -0.2009996 -0.1669536 -0.9652594 -0.04890722 -0.226179 -0.9728573 -0.1638745 -0.1361359 -0.9770426 -0.1546695 -0.09127271 -0.9837412 -0.1596488 -0.07789802 -0.9840957 -0.1531055 -0.08934354 -0.9841628 -0.2362442 0.02731198 -0.9713098 -0.2362443 0.02731198 -0.9713098 -0.2362442 0.02731204 -0.9713098 -0.3281573 0.1188553 -0.9371159 -0.3281573 0.1188553 -0.937116 -0.3281571 0.1188553 -0.937116 -0.2290333 0.04356217 -0.9724435 -0.2841699 0.08736371 -0.9547854 -0.1666477 0.2020879 -0.965085 -0.2284203 0.04401415 -0.9725672 -0.134874 0.1635619 -0.97727 -0.09156811 0.1546875 -0.9837108 -0.07824152 0.1593726 -0.9841132 -0.08737289 0.1542226 -0.9841653 0.02852737 0.2359498 -0.9713464 0.1101843 0.3221932 -0.9402399 0.04571181 0.2300043 -0.9721155 0.04571187 0.2300041 -0.9721156 0.04571193 0.2300042 -0.9721156 0.08868336 0.2821829 -0.9552529 0.2010303 0.1669526 -0.9652532 0.04890722 0.226179 -0.9728573 0.1639794 0.1361754 -0.9770195 0.154699 0.09167098 -0.9836995 0.1596488 0.07789802 -0.9840957 0.1534187 0.08961951 -0.984089 0.2363819 -0.0273531 -0.9712752 0.3280594 -0.1188226 -0.9371543 0.3280594 -0.1188226 -0.9371544 0.3280593 -0.1188226 -0.9371544 0.2292088 -0.04358333 -0.9724011 0.2844499 -0.08743345 -0.9546956 0.166567 -0.202039 -0.9651092 0.2285955 -0.04412907 -0.9725208 0.2285952 -0.04412907 -0.972521 0.228596 -0.04412925 -0.9725208 0.1348055 -0.1635136 -0.9772875 0.09156095 -0.1546484 -0.9837177 0.07825756 -0.1594052 -0.9841066 0.08726185 -0.154304 -0.9841624 0.1619907 0.4736672 -0.8656781 0.1902731 0.4565967 -0.869089 0.1627036 0.3904396 -0.9061372 0.20853 0.3680493 -0.9061209 0.1692652 0.2987474 -0.9392015 0.2034319 0.2766403 -0.9391942 0.1222129 0.4836255 -0.866701 0.1332495 0.4757692 -0.8694184 0.1140899 0.407358 -0.9061142 0.1628185 0.3904447 -0.9061143 0.1321631 0.3169236 -0.9391977 0.1692671 0.2987449 -0.9392019 0.04050999 0.498782 -0.8657803 0.04114103 0.4987489 -0.8657697 0.080531 0.4877536 -0.8692589 0.07519936 0.4922044 -0.8672255 0.06384545 0.4178588 -0.9062659 0.1134209 0.4072118 -0.906264 0.09205704 0.3305269 -0.9392964 0.1316109 0.316888 -0.9392874 0 0.4999541 -0.8660519 0.01600432 0.4941478 -0.8692306 0.01368457 0.42261 -0.9062084 0.06403839 0.4179536 -0.9062085 0.05197578 0.3392527 -0.9392583 0.09220415 0.3305683 -0.9392673 -0.08180296 0.4940813 -0.8655588 -0.0883035 0.4931046 -0.865477 -0.04032438 0.4935162 -0.8688014 -0.04470568 0.4953939 -0.8675173 -0.03795421 0.4206396 -0.9064337 0.01279973 0.4221202 -0.9064496 0.01040893 0.3433176 -0.9391617 0.05269545 0.3394202 -0.9391577 0.04276734 0.2755115 -0.960346 0.07483881 0.2683281 -0.9604162 0.08371275 0.2527733 -0.9638973 0.1022616 0.2462086 -0.963807 0.08924365 0.2710381 -0.9584227 0.1396632 0.246491 -0.9590289 0.1496819 0.2215623 -0.9635899 0.1586691 0.2157623 -0.9634681 0.1545934 0.2320381 -0.9603434 0.1540908 0.2324573 -0.9603227 -7.23133e-5 0.2621732 -0.9650208 0.007165968 0.2615634 -0.9651597 0.009376704 0.3429443 -0.939309 -0.03116434 0.3417227 -0.939284 -0.0383417 0.4204029 -0.9065272 -0.08808344 0.4128808 -0.9065157 -0.1031584 0.4835542 -0.8692145 -0.1616477 0.469263 -0.8681373 -0.1180639 0.4865398 -0.8656442 -0.1236093 0.4849891 -0.8657404 -0.205263 0.456173 -0.8658945 -0.1622191 0.4687156 -0.8683265 -0.1381464 0.3991542 -0.9064168 -0.08773368 0.4131329 -0.9064349 -0.07137042 0.3360646 -0.939131 -0.03013956 0.3422901 -0.9391108 -0.02297806 0.2609072 -0.9650904 0.007902622 0.2617986 -0.9650902 0.005293965 0.1753671 -0.984489 0.1545354 0.1723005 -0.9728471 -0.02160716 0.1779441 -0.9838033 -0.01620727 0.1784265 -0.9838198 -0.0236814 0.2605801 -0.9651618 -0.05449658 0.2559159 -0.9651618 -0.07153594 0.3359238 -0.9391687 -0.111493 0.324837 -0.9391754 -0.1373255 0.4000941 -0.9061272 -0.1841751 0.3807003 -0.9061716 -0.2151249 0.4446684 -0.8694777 -0.2710633 0.4143983 -0.8687915 -0.2361551 0.44134 -0.8657078 -0.2386341 0.4398495 -0.8657866 -0.3079676 0.3929728 -0.8664458 -0.3079676 0.3929729 -0.8664458 -0.3079677 0.3929729 -0.8664457 -0.2695994 0.4171994 -0.867906 -0.2293556 0.3549249 -0.9063247 -0.1846789 0.3801383 -0.906305 -0.1501471 0.3090539 -0.9391175 -0.1111727 0.3251711 -0.9390977 -0.08456265 0.2473353 -0.9652328 -0.05520159 0.2554568 -0.9652433 -0.03754884 0.1737967 -0.9840654 -0.01938581 0.1765806 -0.9840953 -0.02182477 0.1778011 -0.9838244 -0.03712058 0.1740603 -0.9840352 -0.05776816 0.1682905 -0.9840433 -0.08480602 0.2470878 -0.9652748 -0.1144896 0.2348757 -0.9652593 -0.1504358 0.3086489 -0.9392045 -0.1858406 0.2887557 -0.9391931 -0.2289136 0.355684 -0.9061388 -0.2706803 0.3250588 -0.9061287 -0.3159747 0.3794468 -0.8695862 -0.3639616 0.3340891 -0.8694347 -0.3400275 0.3664052 -0.8660997 -0.3384355 0.3679419 -0.8660718 -0.3893206 0.3121321 -0.8666043 -0.3893207 0.3121321 -0.8666043 -0.3893207 0.3121321 -0.8666043 -0.3620833 0.3419862 -0.8671455 -0.3074634 0.2904006 -0.9061644 -0.2707014 0.3250093 -0.90614 -0.2196541 0.2637186 -0.9392576 -0.186131 0.288266 -0.9392859 -0.1417781 0.2195758 -0.9652386 -0.1143733 0.2350322 -0.965235 -0.07776504 0.1598203 -0.9840784 -0.05872297 0.1676792 -0.9840911 -0.4194964 0.2728351 -0.8657851 -0.3977935 0.2930595 -0.8694117 -0.3404457 0.2508121 -0.9061954 -0.3074793 0.2902218 -0.9062162 -0.2495379 0.2355286 -0.9392855 -0.2197691 0.263539 -0.9392811 -0.1673423 0.2006734 -0.96526 -0.1419236 0.2194449 -0.9652469 -0.09751254 0.1507608 -0.9837492 -0.09295439 0.1514105 -0.9840907 -0.4388737 0.2364823 -0.8668714 -0.4303183 0.2432968 -0.8692714 -0.3681215 0.2081326 -0.906183 -0.340423 0.2510235 -0.9061455 -0.2764136 0.2038205 -0.9391766 -0.2492731 0.2364169 -0.9391326 -0.2113028 0.200405 -0.9566552 -0.1452659 0.2105439 -0.9667312 -0.4737049 0.1615113 -0.865747 -0.4566095 0.1895306 -0.8692446 -0.3905841 0.1621235 -0.9061788 -0.3681283 0.20831 -0.9061394 -0.298898 0.1691361 -0.9391767 -0.2763971 0.2036144 -0.9392262 -0.4836033 0.1220448 -0.866737 -0.4758645 0.1330469 -0.8693973 -0.4072225 0.1138558 -0.9062047 -0.3905734 0.1617988 -0.9062415 -0.3171463 0.1313812 -0.9392322 -0.2988449 0.1687868 -0.9392566 -0.4986981 0.04119175 -0.8657965 -0.4988246 0.04089957 -0.8657374 -0.4876298 0.08108985 -0.8692766 -0.4919989 0.07561212 -0.8673062 -0.4179241 0.06422889 -0.9062088 -0.4072422 0.11425 -0.9061462 -0.3305518 0.09273386 -0.939221 -0.3171872 0.1313833 -0.9392182 -0.4995649 -2.92892e-4 -0.8662765 -0.4938574 0.0154007 -0.8694066 -0.4224722 0.01317465 -0.9062802 -0.4178407 0.06386154 -0.9062731 -0.339425 0.05187726 -0.9392015 -0.330605 0.09289067 -0.9391867 -0.4932537 -0.08258479 -0.8659564 -0.4934982 -0.08270239 -0.8658061 -0.4936202 -0.04126238 -0.8686982 -0.4949866 -0.04447591 -0.8677616 -0.4210312 -0.03783178 -0.9062568 -0.4226136 0.01319026 -0.906214 -0.3431453 0.01071006 -0.9392213 -0.3395114 0.05182522 -0.9391732 -0.2748337 0.04195249 -0.9605761 -0.2672967 0.07510316 -0.9606831 -0.2537059 0.08301991 -0.9637122 -0.2468019 0.1022314 -0.9636585 -0.2701568 0.09008634 -0.9585926 -0.2463218 0.1391249 -0.9591506 -0.2214651 0.1492304 -0.9636824 -0.2153621 0.1586558 -0.9635598 -0.231225 0.1545988 -0.9605386 -0.2327112 0.1528829 -0.9604542 -0.4846362 -0.1229197 -0.8660361 -0.4830684 -0.1031705 -0.8694831 -0.4134212 -0.0882951 -0.9062488 -0.42102 -0.03787386 -0.9062604 -0.3420226 -0.03076761 -0.939188 -0.343222 0.01074945 -0.9391929 -0.2613821 0.008185982 -0.9652008 -0.2622311 -0.001372992 -0.9650042 -0.1756451 0.1518289 -0.9726751 -0.4579313 -0.2008043 -0.8660119 -0.4567439 -0.2036852 -0.8659662 -0.4690604 -0.1613632 -0.8682997 -0.4691849 -0.1613563 -0.8682337 -0.39972 -0.1374671 -0.9062709 -0.4134308 -0.0883181 -0.9062423 -0.3358217 -0.07173889 -0.9391897 -0.3420029 -0.03070431 -0.9391973 -0.2604748 -0.02338486 -0.9651974 -0.261373 0.008177042 -0.9652032 -0.1788995 0.005598366 -0.9838514 -0.1769277 0.1521472 -0.9723929 -0.1780946 -0.02271449 -0.9837512 -0.1786509 -0.01605188 -0.9837816 -0.2603744 -0.02339524 -0.9652243 -0.2557674 -0.05477595 -0.9651854 -0.3356776 -0.07188963 -0.9392298 -0.3247147 -0.1114693 -0.9392205 -0.3999499 -0.1372961 -0.9061954 -0.3804093 -0.1848523 -0.9061558 -0.4442632 -0.2158777 -0.8694982 -0.4145911 -0.2712141 -0.8686525 -0.4380593 -0.2405301 -0.8661694 -0.4398764 -0.2375903 -0.8660599 -0.3951064 -0.3056756 -0.8662872 -0.4180278 -0.2692797 -0.8676066 -0.3556364 -0.2290875 -0.9061136 -0.3804487 -0.1846895 -0.9061725 -0.3088232 -0.1499205 -0.9392296 -0.3248258 -0.1114345 -0.9391861 -0.2474888 -0.08490252 -0.9651637 -0.255815 -0.05447059 -0.9651899 -0.1738079 -0.03700911 -0.984084 -0.1763664 -0.02002382 -0.9841209 -0.1793264 -0.02514302 -0.9834683 -0.1737893 -0.03699731 -0.9840877 -0.1680102 -0.05791372 -0.9840827 -0.2472376 -0.08522468 -0.9651997 -0.2352585 -0.1143532 -0.9651823 -0.3086849 -0.1500479 -0.9392546 -0.2883182 -0.1861961 -0.939257 -0.3551852 -0.2293719 -0.9062186 -0.3251605 -0.2701606 -0.9062471 -0.3800373 -0.3157542 -0.8694084 -0.335419 -0.3638401 -0.8689733 -0.3665277 -0.3406339 -0.8658095 -0.3679531 -0.3392128 -0.8657628 -0.2986197 -0.4001345 -0.8664404 -0.2986196 -0.4001344 -0.8664403 -0.2986198 -0.4001343 -0.8664403 -0.3405795 -0.3625798 -0.8674916 -0.2890732 -0.3077509 -0.9064911 -0.3240986 -0.2706226 -0.9064898 -0.2633631 -0.2199022 -0.9392992 -0.2881394 -0.1863049 -0.9392902 -0.2196094 -0.1419941 -0.9651992 -0.235108 -0.1143665 -0.9652174 -0.1598129 -0.07773751 -0.9840818 -0.1679546 -0.05784934 -0.9840959 -0.2730016 -0.418661 -0.8661369 -0.2928735 -0.3972448 -0.8697251 -0.2510274 -0.3404901 -0.9061191 -0.2906572 -0.3073386 -0.9061244 -0.2361987 -0.2497553 -0.9390594 -0.2649211 -0.2192325 -0.9390176 -0.2014361 -0.1666988 -0.9652125 -0.2195625 -0.1420762 -0.9651978 -0.1505115 -0.09739083 -0.9837995 -0.1511332 -0.09345328 -0.984086 -0.2369023 -0.4387047 -0.8668423 -0.2435678 -0.430393 -0.8691585 -0.2082962 -0.368067 -0.9061675 -0.2507818 -0.3404972 -0.9061844 -0.2037071 -0.2765903 -0.9391493 -0.2354784 -0.2500444 -0.9391633 -0.1995561 -0.2119111 -0.9566981 -0.2096813 -0.1459931 -0.9668091 -0.1619907 -0.4736672 -0.8656781 -0.1902781 -0.4566087 -0.8690816 -0.1627126 -0.3904612 -0.9061263 -0.2085546 -0.3680441 -0.9061174 -0.1692875 -0.2987462 -0.9391978 -0.2034229 -0.2766598 -0.9391905 -0.1222576 -0.4836582 -0.8666763 -0.133246 -0.4757567 -0.8694257 -0.114093 -0.4073693 -0.9061087 -0.1627917 -0.3904464 -0.9061183 -0.1321314 -0.3169027 -0.9392092 -0.1692792 -0.2987661 -0.939193 -0.04045963 -0.4988372 -0.8657507 -0.04123371 -0.4987469 -0.8657663 -0.08055233 -0.4878829 -0.8691845 -0.07520604 -0.4920732 -0.8672993 -0.06387335 -0.4179161 -0.9062374 -0.1134557 -0.4072377 -0.906248 -0.09208619 -0.330549 -0.9392857 -0.1316395 -0.3168727 -0.9392885 0 -0.4999936 -0.8660292 -0.01600432 -0.494148 -0.8692306 -0.01368343 -0.422575 -0.9062247 -0.0640341 -0.4179258 -0.9062218 -0.05197578 -0.3392527 -0.9392583 -0.09216547 -0.3305549 -0.9392758 0.08185338 -0.4940912 -0.8655483 0.08820354 -0.493109 -0.8654846 0.04032707 -0.4935472 -0.8687835 0.04473173 -0.4953866 -0.8675202 0.03797829 -0.4206521 -0.9064267 -0.01277387 -0.4221765 -0.9064237 -0.01039057 -0.3433178 -0.939162 -0.05269777 -0.3394351 -0.9391523 -0.04276615 -0.2755037 -0.9603483 -0.074817 -0.2683286 -0.9604178 -0.08374518 -0.2527864 -0.963891 -0.1022802 -0.2462081 -0.9638052 -0.08920699 -0.2710102 -0.9584339 -0.1396632 -0.246491 -0.9590289 -0.1496915 -0.221587 -0.9635828 -0.1586815 -0.2158049 -0.9634566 -0.154534 -0.2319489 -0.9603744 -0.1542112 -0.2325065 -0.9602915 1.08477e-4 -0.2621915 -0.9650158 -0.007189571 -0.2615751 -0.9651564 -0.009410381 -0.3428993 -0.9393251 0.03116893 -0.3417227 -0.9392839 0.0383417 -0.4204029 -0.9065272 0.08805692 -0.4128819 -0.9065178 0.1031386 -0.483568 -0.8692091 0.1616477 -0.469263 -0.8681373 0.118209 -0.4864956 -0.8656493 0.1235745 -0.4850339 -0.8657202 0.205094 -0.4561209 -0.865962 0.1622057 -0.4686658 -0.8683558 0.1381693 -0.3992205 -0.9063842 0.08773827 -0.4131327 -0.9064345 0.07137113 -0.3361114 -0.9391142 0.03014272 -0.3422601 -0.9391217 0.0229783 -0.2609101 -0.9650896 -0.007918715 -0.2617988 -0.96509 -0.005301952 -0.1753214 -0.9844971 -0.1544009 -0.1723041 -0.9728677 0.0216031 -0.1779108 -0.9838095 0.01622569 -0.1783568 -0.9838321 0.02371126 -0.2605555 -0.9651677 0.05449658 -0.2559159 -0.9651618 0.071527 -0.3359093 -0.9391747 0.1114549 -0.324793 -0.9391951 0.1372893 -0.4000689 -0.9061437 0.1841955 -0.3807425 -0.9061496 0.2151334 -0.4446855 -0.8694667 0.2710993 -0.4144533 -0.8687542 0.2362003 -0.4412078 -0.8657627 0.2386605 -0.4398659 -0.8657709 0.3077667 -0.3930018 -0.8665041 0.3077667 -0.3930017 -0.866504 0.2695938 -0.4171526 -0.8679303 0.2293646 -0.3549034 -0.9063308 0.1846297 -0.380037 -0.9063574 0.1501575 -0.3090752 -0.9391087 0.1111958 -0.3251703 -0.9390953 0.08458197 -0.2473237 -0.9652341 0.05520159 -0.2554568 -0.9652433 0.03755474 -0.1738241 -0.9840604 0.01938581 -0.1765806 -0.9840953 0.0220474 -0.1780662 -0.9837715 0.03711295 -0.1740245 -0.9840417 0.05775147 -0.168312 -0.9840406 0.08478218 -0.2470884 -0.9652768 0.1144872 -0.2349185 -0.9652493 0.150413 -0.30865 -0.9392077 0.1858627 -0.2887544 -0.939189 0.228955 -0.3557054 -0.9061199 0.2706907 -0.3250966 -0.9061118 0.3159343 -0.37943 -0.8696082 0.3639424 -0.3340408 -0.8694612 0.3400614 -0.3665258 -0.8660353 0.3384789 -0.3679358 -0.8660574 0.3889496 -0.3122176 -0.8667401 0.3621192 -0.3420228 -0.867116 0.3074599 -0.2904009 -0.9061654 0.2706675 -0.3249658 -0.9061658 0.2196497 -0.2637188 -0.9392585 0.186158 -0.2883167 -0.939265 0.1417654 -0.2195561 -0.9652449 0.114397 -0.2350315 -0.9652324 0.0777595 -0.1597595 -0.9840887 0.05871093 -0.1676449 -0.9840977 0.4194964 -0.2728351 -0.8657851 0.3978369 -0.2930901 -0.8693815 0.340408 -0.2507843 -0.9062172 0.3074975 -0.2902628 -0.906197 0.2495465 -0.2355628 -0.9392747 0.2197584 -0.2634913 -0.9392969 0.1674099 -0.2007266 -0.9652372 0.1419236 -0.2194449 -0.9652469 0.09752678 -0.1507828 -0.9837445 0.09294426 -0.1514106 -0.9840916 0.4387884 -0.2364544 -0.8669222 0.4303622 -0.2433226 -0.8692426 0.3681623 -0.2081557 -0.906161 0.3403776 -0.25099 -0.9061717 0.2764136 -0.2038205 -0.9391766 0.2492484 -0.2364185 -0.9391388 0.2112737 -0.2003999 -0.9566627 0.1452376 -0.2105447 -0.9667353 0.4736088 -0.1614608 -0.865809 0.4566815 -0.189548 -0.8692029 0.3906453 -0.1621401 -0.9061496 0.3681283 -0.20831 -0.9061394 0.2988567 -0.1691127 -0.9391942 0.2764454 -0.20365 -0.9392043 0.4836452 -0.1220645 -0.8667109 0.4758645 -0.1330469 -0.8693973 0.4071774 -0.1138432 -0.9062264 0.3905419 -0.1617757 -0.9062592 0.3171232 -0.1313621 -0.9392427 0.2989236 -0.1688148 -0.9392264 0.4987372 -0.04119068 -0.8657739 0.4986646 -0.04089361 -0.86583 0.4876552 -0.08108854 -0.8692625 0.4919981 -0.07561218 -0.8673067 0.4179704 -0.06423604 -0.9061868 0.4072422 -0.11425 -0.9061462 0.3305976 -0.09274667 -0.9392036 0.3171872 -0.1313833 -0.9392182 0.4995371 2.92897e-4 -0.8662925 0.493784 -0.01539927 -0.8694483 0.422547 -0.01317769 -0.9062452 0.4177852 -0.06385308 -0.9062993 0.339425 -0.05187726 -0.9392015 0.330605 -0.09289067 -0.9391867 0.4933488 0.08260071 -0.8659008 0.4934247 0.08270782 -0.8658473 0.4935583 0.04125678 -0.8687337 0.4949852 0.04447597 -0.8677625 0.4210796 0.03783595 -0.9062343 0.422501 -0.01318675 -0.9062666 0.3431453 -0.01071006 -0.9392213 0.3394522 -0.05181616 -0.9391951 0.2747723 -0.04194313 -0.9605941 0.2673268 -0.07511162 -0.9606741 0.2536737 -0.08300125 -0.9637222 0.2468376 -0.1022462 -0.9636477 0.2701568 -0.09008634 -0.9585926 0.2463216 -0.1391112 -0.9591526 0.2213889 -0.1491983 -0.9637048 0.2153204 -0.158625 -0.9635742 0.2312467 -0.1546189 -0.9605301 0.2327933 -0.1528799 -0.9604349 0.4845833 0.122896 -0.866069 0.4831424 0.1031799 -0.8694409 0.4133929 0.08828455 -0.9062628 0.4210162 0.03787398 -0.9062621 0.3419753 0.03076338 -0.9392053 0.3432822 -0.01075136 -0.9391708 0.2613821 -0.008185982 -0.9652008 0.2621948 0.001372814 -0.9650141 0.1758739 -0.1520267 -0.9726029 0.4578841 0.2007658 -0.8660458 0.4567794 0.2037659 -0.8659285 0.4691227 0.1613847 -0.8682621 0.4691132 0.1613414 -0.8682752 0.3997451 0.1374836 -0.9062573 0.4134858 0.08832985 -0.906216 0.3357743 0.07172906 -0.9392075 0.342037 0.03070998 -0.9391846 0.2604543 0.02338498 -0.965203 0.2613431 -0.008177101 -0.9652114 0.1788995 -0.005598366 -0.9838514 0.1768369 -0.1520692 -0.9724217 0.1781023 0.02271443 -0.9837499 0.1786689 0.01605182 -0.9837783 0.2604669 0.02340084 -0.9651992 0.255697 0.05475586 -0.9652051 0.3357034 0.07188892 -0.9392206 0.3247389 0.1114855 -0.9392102 0.3999267 0.1372976 -0.9062053 0.3803867 0.1848303 -0.9061698 0.4442844 0.2158752 -0.869488 0.4145952 0.2711918 -0.8686575 0.4380954 0.2406151 -0.8661275 0.4398236 0.2375618 -0.8660945 0.3951064 0.3056756 -0.8662872 0.4180247 0.2692973 -0.8676026 0.355613 0.2290897 -0.9061222 0.380523 0.1847122 -0.9061367 0.3088439 0.1499194 -0.9392229 0.3247691 0.1114151 -0.939208 0.2474888 0.08490252 -0.9651637 0.2558782 0.054484 -0.9651725 0.1738079 0.03700911 -0.984084 0.1763664 0.02002382 -0.9841209 0.1793264 0.02514302 -0.9834683 0.1738163 0.03701275 -0.9840823 0.167952 0.05789917 -0.9840934 0.2472074 0.08522534 -0.9652074 0.2351942 0.1143333 -0.9652003 0.3086586 0.1500493 -0.9392631 0.2883014 0.1861971 -0.939262 0.3551651 0.2293737 -0.9062259 0.3251785 0.2701756 -0.9062363 0.3799973 0.315721 -0.8694379 0.3353492 0.3637954 -0.8690189 0.3666067 0.3406226 -0.8657805 0.3679531 0.3392128 -0.8657628 0.2982763 0.4003319 -0.8664674 0.2982763 0.4003319 -0.8664674 0.2982763 0.4003319 -0.8664674 0.3405343 0.3625317 -0.8675293 0.2890893 0.307768 -0.9064803 0.3240986 0.2706226 -0.9064898 0.2633631 0.2199022 -0.9392992 0.2881394 0.1863049 -0.9392902 0.2196094 0.1419941 -0.9651992 0.2352246 0.1144232 -0.9651822 0.1598129 0.07773751 -0.9840818 0.168049 0.05787283 -0.9840784 0.2730016 0.418661 -0.8661369 0.2928735 0.3972448 -0.8697251 0.2510171 0.3404709 -0.9061292 0.2906727 0.3073259 -0.9061238 0.236241 0.2497709 -0.9390446 0.2648749 0.2191942 -0.9390396 0.2014361 0.1666988 -0.9652125 0.2195081 0.1420409 -0.9652153 0.1508635 0.09761959 -0.9837229 0.1515341 0.09265142 -0.9841002 0.2368975 0.4387671 -0.8668119 0.2435736 0.4303563 -0.8691751 0.2083066 0.3680449 -0.906174 0.2507941 0.3405264 -0.9061701 0.2037026 0.2765905 -0.9391501 0.2354468 0.2500231 -0.939177 0.199558 0.211911 -0.9566977 0.2096996 0.1459925 -0.9668053 -0.06440871 0.8926257 -0.4461736 -0.06257653 0.8926619 -0.446362 -0.07189512 0.8926237 -0.4450325 -0.06016314 0.8931084 -0.4458002 -0.06018143 0.8931414 -0.4457316 -0.06243383 0.8926571 -0.4463916 -0.06736379 0.8920776 -0.446833 -0.05745065 0.8930695 -0.4462357 -0.06092619 0.8928254 -0.4462633 -0.06532144 0.8924636 -0.4463651 -0.05894964 0.8927866 -0.4466064 -0.1514019 0.9884458 0.007234811 -0.1944329 0.9809159 0 -0.2718852 0.9623297 0 -0.31169 0.9501588 0.006907165 -0.3510866 0.936343 0 -0.428116 0.9037238 0 -0.4644243 0.8855874 0.006724476 -0.4997882 0.8661476 0 -0.5705772 0.8212441 0 -0.6041248 0.7968602 0.006870627 -0.6367265 0.7710897 0 -0.6984097 0.7156983 0 -0.7262926 0.6873542 0.006588339 -0.7530767 0.6579327 0 -0.806756 0.5908849 0 -0.8299851 0.5577449 0.006742596 -0.8521041 0.5233724 0 -0.8935715 0.448921 0 -0.9106579 0.4131091 0.006578743 -0.9263917 0.3765617 0 -0.9545783 0.2979602 0 -0.9657813 0.2592713 0.006695091 -0.9755281 0.219875 0 -0.9755281 0.219875 0 -0.9755281 0.219875 0 -0.9909793 0.1340156 0 -0.9954239 0.09533792 0.006488859 -0.9984292 0.05602848 0 -0.9996673 -0.02579426 0 -0.9975723 -0.06926912 0.007172524 -0.9936672 -0.1123632 0 -0.9810606 -0.1937017 0 -0.9723671 -0.2333589 0.006767511 -0.9620373 -0.2729185 0 -0.9368196 -0.3498128 0 -0.9211402 -0.3891672 0.007055222 -0.9036835 -0.4282013 0 -0.865108 -0.5015859 0 -0.8443942 -0.5356824 0.006571114 -0.8227272 -0.5684366 0 -0.770949 -0.6368969 0 -0.7450637 -0.6669607 0.006601393 -0.7178022 -0.6962472 0 -0.6557977 -0.7549368 0 -0.6249458 -0.78064 0.006647288 -0.5930078 -0.8051968 0 -0.5214934 -0.8532553 0 -0.4865359 -0.8736347 0.006720304 -0.4506812 -0.8926851 0 -0.3751191 -0.9269766 0 -0.3368585 -0.9415309 0.006789624 -0.2980366 -0.9545544 0 -0.216939 -0.9761852 0 -0.1773641 -0.9841229 0.006660103 -0.1378063 -0.9904593 0 -0.0561943 -0.9984199 0 -0.01297962 -0.9998901 0.007171034 0.03030484 -0.9995408 0 0.1080468 -0.9941459 0 0.1514018 -0.9884458 0.007240474 0.194464 -0.9809098 0 0.2718556 -0.9623382 0 0.3110089 -0.9503827 0.00680238 0.3497256 -0.9368522 0 0.428116 -0.9037238 0 0.4652769 -0.8851385 0.006883382 0.5017381 -0.8650197 0 0.570599 -0.8212289 0 0.6030511 -0.7976748 0.006666779 0.6346921 -0.7727652 0 0.6984829 -0.7156268 0 0.7273268 -0.6862571 0.006862759 0.7552378 -0.655451 0 0.806756 -0.5908849 0 0.8299851 -0.5577449 0.006739795 0.8521041 -0.5233724 0 0.8918361 -0.452359 0 0.909838 -0.4149064 0.006896674 0.926387 -0.376573 0 0.9545271 -0.2981243 0 0.9663195 -0.2572493 0.007029533 0.9764134 -0.2159097 0 0.9903702 -0.1384443 0 0.9954361 -0.09515869 0.007196426 0.9986526 -0.05189484 0 0.9996627 0.02597451 0 0.9975785 0.06918048 0.007162094 0.9936669 0.1123668 0 0.9819051 0.1893745 0 0.9728331 0.2313982 0.007114291 0.9620348 0.2729269 0 0.9354583 0.3534372 0 0.921112 0.3892454 0.006387531 0.9054228 0.4245113 0 0.8650297 0.5017207 0 0.8444396 0.5356109 0.006554424 0.8226531 0.5685437 0 0.7710376 0.6367896 0 0.7439414 0.6682096 0.006867527 0.7156434 0.6984659 0 0.6557977 0.7549368 0 0.6249458 0.78064 0.006652891 0.5930078 0.8051968 0 0.5233939 0.8520908 0 0.4865348 0.8736327 0.007052659 0.4489688 0.8935475 0 0.3765615 0.9263916 0 0.3375732 0.941274 0.006905496 0.2980366 0.9545544 0 0.2201297 0.9754706 0 0.1773635 0.9841188 0.007234811 0.1341578 0.99096 0 0.05616223 0.9984217 0 0.01295161 0.9998906 0.0071612 -0.03014224 0.9995456 0 -0.1080785 0.9941424 0 -0.1830269 0.6435074 -0.7432358 -0.1632309 0.6528033 -0.7397322 -0.1632308 0.6528033 -0.7397322 -0.1632309 0.652803 -0.7397324 -0.2368817 0.6286718 -0.7407151 -0.2330731 0.6253767 -0.7447019 -0.2826855 0.6044082 -0.7448353 -0.2826856 0.6044083 -0.7448353 -0.2826855 0.6044083 -0.7448353 -0.2864105 0.6052024 -0.7427646 -0.2860511 0.606735 -0.7416519 -0.336511 0.5800207 -0.7418466 -0.3335233 0.5784479 -0.7444194 -0.3372029 0.5746381 -0.7457113 -0.379262 0.5478999 -0.7456314 -0.3817036 0.5490835 -0.7435118 -0.4259656 0.5151813 -0.7437349 -0.4262979 0.5150279 -0.7436509 -0.4264179 0.5180057 -0.7415106 -0.4669718 0.4816292 -0.7416 -0.4659798 0.4777781 -0.7447086 -0.4655044 0.478605 -0.744475 -0.504063 0.4376693 -0.7445577 -0.5061633 0.4381641 -0.7428398 -0.5404862 0.3951449 -0.7427888 -0.5385535 0.3964301 -0.7435076 -0.5387715 0.3970893 -0.7429977 -0.5387715 0.3970893 -0.7429976 -0.5387715 0.3970893 -0.7429975 -0.5709002 0.3500715 -0.7426459 -0.5718699 0.3519608 -0.7410051 -0.5719159 0.3453639 -0.7440671 -0.5962128 0.3009839 -0.7442708 -0.5962202 0.3011716 -0.744189 -0.6157243 0.2586522 -0.7443002 -0.6214541 0.2515279 -0.7419761 -0.6214126 0.2512567 -0.7421027 -0.6391189 0.2012459 -0.7423121 -0.6395611 0.201728 -0.7418001 -0.6380341 0.1970688 -0.7443631 -0.6516816 0.1448586 -0.7445315 -0.6523253 0.1445769 -0.7440223 -0.657855 0.1157953 -0.7441897 -0.6655631 0.09170317 -0.7406864 -0.6613807 0.08834564 -0.7448293 -0.6659839 0.03828644 -0.744983 -0.6675368 0.03949493 -0.7435286 -0.6621909 0.03236597 -0.7486359 -0.662841 -0.01794397 -0.7485452 -0.66755 -0.02070534 -0.7442771 -0.6641571 -0.07276171 -0.7440438 -0.6653643 -0.07374411 -0.7428675 -0.6562995 -0.1297824 -0.7432547 -0.6544814 -0.1267607 -0.7453764 -0.6510476 -0.1288804 -0.7480153 -0.6391296 -0.178519 -0.7480939 -0.6435878 -0.1829528 -0.7431844 -0.6360194 -0.1994295 -0.7454578 -0.6238721 -0.2351416 -0.7453134 -0.6243952 -0.2356464 -0.7447157 -0.6046804 -0.2826014 -0.7446464 -0.6053092 -0.2863996 -0.7426818 -0.6065428 -0.2860805 -0.7417978 -0.5800108 -0.3365658 -0.7418295 -0.5784491 -0.3335106 -0.7444242 -0.5747565 -0.3371805 -0.7456301 -0.5478498 -0.3792859 -0.745656 -0.548436 -0.3803219 -0.7446968 -0.5146303 -0.4252668 -0.7445158 -0.5149317 -0.4237346 -0.7451807 -0.5154642 -0.4236963 -0.7448344 -0.4761762 -0.4673392 -0.7448828 -0.4802935 -0.4687095 -0.7413701 -0.481211 -0.4682362 -0.7410741 -0.481211 -0.4682362 -0.7410742 -0.4812111 -0.468236 -0.7410742 -0.4418334 -0.5059391 -0.7408164 -0.441294 -0.5034731 -0.7428152 -0.3955637 -0.5401996 -0.7427744 -0.3955796 -0.5402539 -0.7427265 -0.3901029 -0.5383495 -0.7469937 -0.3490497 -0.5660841 -0.746802 -0.3548095 -0.5694314 -0.7415243 -0.3548095 -0.5694314 -0.7415242 -0.3548095 -0.5694314 -0.7415242 -0.3437048 -0.5696579 -0.7465634 -0.3011574 -0.5932374 -0.7465746 -0.3010759 -0.5961878 -0.7442537 -0.2514505 -0.6187547 -0.7442549 -0.2514505 -0.6187548 -0.7442548 -0.2514505 -0.6187547 -0.7442548 -0.2507468 -0.619513 -0.7438613 -0.2506291 -0.6194964 -0.7439149 -0.1972061 -0.6386188 -0.7438251 -0.1962015 -0.6377151 -0.7448654 -0.2057976 -0.6409035 -0.7395201 -0.1459736 -0.6570022 -0.7396215 -0.1474618 -0.6517574 -0.7439538 -0.07830178 -0.6638492 -0.7437561 -0.07830172 -0.6638495 -0.7437558 -0.07830172 -0.6638494 -0.7437559 -0.09131693 -0.6600283 -0.74567 -0.09151953 -0.6602321 -0.7454648 -0.03521364 -0.6659796 -0.7451384 -0.03957808 -0.6729706 -0.7386096 -0.03305077 -0.6680583 -0.7433747 0.01812863 -0.6681581 -0.7437986 0.01771938 -0.6674136 -0.7444765 0.07239341 -0.6636667 -0.7445172 0.07397532 -0.6657951 -0.7424585 0.1313961 -0.6571977 -0.7421767 0.1294435 -0.6559671 -0.7436072 0.1290618 -0.6565101 -0.7431942 0.1837823 -0.6432351 -0.7432851 0.1826374 -0.6421291 -0.7445226 0.1541665 -0.6553232 -0.7394486 0.1541665 -0.6553233 -0.7394486 0.1541665 -0.6553232 -0.7394487 0.2369462 -0.6288428 -0.7405493 0.2330105 -0.6252468 -0.7448306 0.2330105 -0.6252468 -0.7448306 0.2857381 -0.6032899 -0.7445772 0.2853674 -0.6030453 -0.7449174 0.2850211 -0.6044518 -0.7439093 0.3352267 -0.5777224 -0.7442177 0.3321431 -0.5761093 -0.7468461 0.3285836 -0.579788 -0.7455727 0.3285835 -0.579788 -0.7455727 0.3285837 -0.579788 -0.7455727 0.3807333 -0.5469795 -0.7455574 0.3830956 -0.5480586 -0.7435521 0.4210308 -0.5192729 -0.7436994 0.4263368 -0.5181571 -0.7414514 0.4262496 -0.5132212 -0.7449265 0.4658628 -0.4775111 -0.744953 0.4674407 -0.4833303 -0.7401967 0.4718971 -0.4721075 -0.7445991 0.5040032 -0.4376471 -0.7446112 0.5015795 -0.4371137 -0.7465586 0.5304607 -0.4010866 -0.7468207 0.5304607 -0.4010866 -0.7468206 0.5304606 -0.4010867 -0.7468207 0.5385106 -0.3965126 -0.7434946 0.5370581 -0.3919553 -0.7469537 0.5682416 -0.3455957 -0.7467699 0.5719038 -0.3520022 -0.7409592 0.5718395 -0.3547943 -0.739676 0.6018434 -0.3009791 -0.7397271 0.5907968 -0.3012599 -0.7484661 0.611368 -0.2562263 -0.7487172 0.6166796 -0.2496842 -0.7465682 0.6201846 -0.2544597 -0.7420387 0.6399616 -0.1984745 -0.7423322 0.6377854 -0.1962587 -0.7447901 0.6380309 -0.196847 -0.7444245 0.6509974 -0.1477118 -0.7445694 0.6517898 -0.1473974 -0.7439383 0.6640849 -0.07792651 -0.7435852 0.6640849 -0.07792639 -0.7435851 0.6640847 -0.07792729 -0.7435852 0.6601259 -0.090954 -0.7456281 0.6609249 -0.09164613 -0.744835 0.6661022 -0.03526538 -0.7450264 0.6630056 -0.03367108 -0.7478569 0.6675374 -0.03915476 -0.7435461 0.6683984 0.01809507 -0.7435833 0.6676754 0.01785278 -0.7442384 0.6639868 0.07576376 -0.7438961 0.6648712 0.07644581 -0.7430359 0.6573906 0.1235081 -0.7433595 0.6597635 0.1274704 -0.7405833 0.6597635 0.1274704 -0.7405832 0.6597635 0.1274703 -0.7405832 0.6563301 0.1299362 -0.7432008 0.6434217 0.182876 -0.7433472 0.6435495 0.1830343 -0.7431976 0.6359135 0.1993021 -0.7455822 0.6247909 0.232387 -0.7454078 0.6254103 0.2331792 -0.7446405 0.6017065 0.2888026 -0.7446761 0.6008443 0.2842714 -0.7471118 0.6020967 0.2837629 -0.7462963 0.6020967 0.2837629 -0.7462963 0.5773739 0.3313741 -0.7462109 0.5805672 0.3376853 -0.7408849 0.5788391 0.3394981 -0.7414085 0.5516214 0.3818213 -0.7415703 0.5521751 0.3830278 -0.7405353 0.5131974 0.4341437 -0.74037 0.5149148 0.4237206 -0.7452005 0.5154399 0.4237035 -0.744847 0.477573 0.465749 -0.7449846 0.4775679 0.4658882 -0.7449007 0.487998 0.4614958 -0.7408642 0.4403353 0.5071598 -0.7408736 0.4398061 0.5047187 -0.7428524 0.3953946 0.5405029 -0.7426438 0.3955178 0.5401847 -0.7428097 0.3938963 0.5395376 -0.7441405 0.3505516 0.5684838 -0.7442713 0.3520388 0.5694611 -0.7428209 0.3437274 0.5694296 -0.7467272 0.3011106 0.5932137 -0.7466123 0.3010857 0.5962402 -0.7442077 0.2582898 0.6159335 -0.7442529 0.2515506 0.6214438 -0.7419771 0.2493947 0.6199982 -0.7439117 0.1980274 0.6384034 -0.7437918 0.1957873 0.6362209 -0.7462508 0.2051596 0.6393408 -0.7410486 0.1463183 0.6555026 -0.7408828 0.1471309 0.6531396 -0.7428063 0.07808202 0.6648238 -0.7429082 0.0914604 0.660904 -0.7448765 0.0916078 0.6609135 -0.7448499 0.03538966 0.6661897 -0.7449423 0.03961294 0.6731564 -0.7384384 0.03271955 0.667692 -0.7437183 -0.01813352 0.6683396 -0.7436352 -0.01765942 0.6674611 -0.7444353 -0.07241892 0.6636655 -0.7445158 -0.07398444 0.6659664 -0.7423039 -0.1313961 0.6571977 -0.7421767 -0.1301141 0.6563282 -0.7431715 -0.1292611 0.6575244 -0.7422622 -0.1841534 0.6447203 -0.7419053 -0.02669572 0.8775441 -0.4787525 -0.09693312 0.8725851 -0.4787477 -0.09555345 0.8712057 -0.481529 -0.1704488 0.8599481 -0.4810786 -0.1668167 0.8569791 -0.4876055 -0.2388769 0.8398675 -0.4874017 -0.2381916 0.8394557 -0.4884456 -0.3046461 0.8174212 -0.4888899 -0.3089632 0.8201623 -0.4815347 -0.3748741 0.7921919 -0.4815616 -0.372754 0.7911098 -0.484974 -0.4368247 0.7577562 -0.4847574 -0.4402828 0.7590122 -0.4796371 -0.5006119 0.7202552 -0.4802292 -0.4987964 0.7196602 -0.4830026 -0.5584294 0.6746601 -0.4826909 -0.5562375 0.6743163 -0.4856928 -0.608459 0.6277006 -0.4855613 -0.6129778 0.6281135 -0.4793036 -0.6638248 0.5745729 -0.4787512 -0.6620379 0.5745977 -0.4811894 -0.7058197 0.5196958 -0.4813883 -0.7020521 0.5198137 -0.486741 -0.7444192 0.4564121 -0.4873685 -0.7444192 0.4564122 -0.4873685 -0.7444192 0.4564122 -0.4873685 -0.7455386 0.4563845 -0.4856804 -0.7805891 0.3940648 -0.485174 -0.780627 0.3941351 -0.4850557 -0.8105778 0.3281238 -0.4850758 -0.8116383 0.3276893 -0.483594 -0.8350054 0.2629293 -0.4833574 -0.8364769 0.2622894 -0.4811556 -0.8557827 0.189733 -0.4812872 -0.8539571 0.1906599 -0.484155 -0.866899 0.1194071 -0.4839712 -0.868999 0.1181197 -0.4805085 -0.8758272 0.05050486 -0.479975 -0.8769503 0.04951423 -0.4780234 -0.8781197 -0.02719587 -0.4776675 -0.8730219 -0.02272325 -0.4871516 -0.8680367 -0.09613406 -0.4871043 -0.8708196 -0.09885144 -0.4815617 -0.860668 -0.1665722 -0.4811492 -0.861517 -0.1678203 -0.4791919 -0.8442121 -0.2402099 -0.4791715 -0.8447616 -0.2408005 -0.4779046 -0.8220303 -0.3101614 -0.4775628 -0.8205277 -0.3077047 -0.481718 -0.7921248 -0.3747429 -0.4817742 -0.7911477 -0.3727156 -0.4849418 -0.757788 -0.4369131 -0.4846282 -0.7582031 -0.4382828 -0.4827383 -0.7198361 -0.4991825 -0.4823412 -0.7209779 -0.5034632 -0.4761468 -0.6791045 -0.5587238 -0.4760723 -0.6785527 -0.5567409 -0.479172 -0.6263831 -0.6147317 -0.4793215 -0.6259079 -0.610702 -0.4850592 -0.5762881 -0.6575081 -0.4853609 -0.5764257 -0.6604391 -0.4812002 -0.5178359 -0.7070863 -0.481534 -0.5177554 -0.7082012 -0.4799796 -0.4603599 -0.7466777 -0.4801471 -0.4605396 -0.7459246 -0.4811441 -0.3950999 -0.7823964 -0.4814061 -0.3944662 -0.7851846 -0.4773696 -0.3297076 -0.8146452 -0.4771226 -0.3303306 -0.812429 -0.4804591 -0.2586872 -0.8379332 -0.4805715 -0.2588399 -0.8374286 -0.4813681 -0.19344 -0.8547992 -0.4815595 -0.1942468 -0.8532075 -0.4840509 -0.1199339 -0.8669214 -0.4838009 -0.1182494 -0.8696324 -0.4793292 -0.04634392 -0.8762992 -0.4795331 -0.04930222 -0.8722645 -0.486543 0.02318412 -0.8735737 -0.4861395 0.02672404 -0.8775722 -0.4786992 0.09694892 -0.8726384 -0.4786473 0.09504103 -0.8708355 -0.4822995 0.1695547 -0.8592519 -0.482636 0.1668629 -0.8569014 -0.4877261 0.2388703 -0.840013 -0.4871543 0.2395653 -0.8402693 -0.4863703 0.3052315 -0.8190808 -0.485737 0.3076836 -0.820526 -0.4817343 0.3748286 -0.7922316 -0.4815316 0.3727871 -0.7911278 -0.4849194 0.4369366 -0.7578756 -0.48447 0.4369366 -0.7578756 -0.4844699 0.4369366 -0.7578757 -0.4844699 0.44311 -0.760104 -0.4752849 0.5039609 -0.7212352 -0.4752297 0.4987852 -0.7197642 -0.482859 0.4987852 -0.7197642 -0.482859 0.556472 -0.6763262 -0.4826198 0.5543799 -0.6758948 -0.4856225 0.5543799 -0.6758949 -0.4856225 0.6104047 -0.6258599 -0.4854951 0.6107444 -0.6258251 -0.4851127 0.6592112 -0.5744853 -0.485188 0.662117 -0.5744935 -0.4812051 0.7058717 -0.5196612 -0.4813497 0.7067637 -0.5196957 -0.4800016 0.7495089 -0.4558922 -0.4799988 0.745538 -0.456385 -0.4856808 0.7789852 -0.3972507 -0.4851537 0.7843081 -0.3959825 -0.4775547 0.8145381 -0.3296377 -0.4773539 0.8103706 -0.3311283 -0.4833773 0.8362216 -0.2593011 -0.4832146 0.8375276 -0.2588498 -0.4811906 0.8549312 -0.1932853 -0.4813873 0.8583937 -0.1916455 -0.4758492 0.8714518 -0.1202125 -0.4755218 0.8685691 -0.1218329 -0.4803586 0.8761761 -0.04650795 -0.4797422 0.877123 -0.04583603 -0.4780737 0.8781906 0.02344167 -0.4777361 0.8777081 0.0228452 -0.4786511 0.8722444 0.1003325 -0.478668 0.8708932 0.09885972 -0.4814269 0.8607348 0.1666701 -0.4809955 0.8614989 0.1678168 -0.4792257 0.8442715 0.2401503 -0.4790967 0.8446556 0.240682 -0.4781519 0.8231806 0.3067509 -0.477784 0.8218755 0.3044391 -0.4814953 0.8218754 0.3044391 -0.4814952 0.792038 0.3748797 -0.4818103 0.7934868 0.3776159 -0.4772682 0.7596325 0.4418138 -0.477241 0.7582948 0.4381477 -0.482717 0.7196994 0.4992814 -0.4824427 0.7196051 0.49883 -0.4830498 0.6762653 0.5563879 -0.482802 0.6767696 0.5589547 -0.4791165 0.6282674 0.6128088 -0.4793177 0.6278296 0.6087461 -0.4850342 0.5744164 0.6592657 -0.4851954 0.5745596 0.6619838 -0.4813094 0.5179002 0.7072197 -0.4812689 0.5177448 0.7082443 -0.4799275 0.4603862 0.7466662 -0.4801397 0.4605671 0.7459169 -0.48113 0.3951057 0.7824741 -0.4812755 0.3944943 0.7851693 -0.4773713 0.3297044 0.8145684 -0.4772562 0.3310037 0.8103175 -0.4835515 0.2593743 0.8362376 -0.4831476 0.258817 0.8374435 -0.4813547 0.1925671 0.8550213 -0.4815148 0.1934603 0.853388 -0.4840479 0.1199527 0.8667465 -0.4841094 0.1182183 0.8696056 -0.4793857 0.04654747 0.8763086 -0.4794963 0.04932391 0.872648 -0.4858527 -0.02310627 0.8734429 -0.4863781 -0.02971297 0.9855736 -0.1666188 -0.1075034 0.9801737 -0.1664412 -0.1065277 0.9798461 -0.1689777 -0.1883421 0.9673528 -0.1695758 -0.1918515 0.9681037 -0.161147 -0.2694693 0.9493615 -0.1615524 -0.2681415 0.9492168 -0.1645835 -0.3477281 0.9229709 -0.1649543 -0.3461121 0.9229111 -0.1686469 -0.4200638 0.8916339 -0.1689245 -0.4223487 0.8915517 -0.1635762 -0.4949643 0.853337 -0.1637876 -0.4926148 0.8536523 -0.1691402 -0.5615161 0.8100057 -0.1690874 -0.5625243 0.8099271 -0.166086 -0.6274015 0.7607595 -0.1661697 -0.6274015 0.7607595 -0.1661697 -0.6274015 0.7607596 -0.1661697 -0.6279678 0.7606287 -0.1646229 -0.6888396 0.7059432 -0.1647551 -0.6889612 0.7058827 -0.1645058 -0.7450107 0.6463556 -0.1648741 -0.7418857 0.6478391 -0.1729456 -0.7418856 0.6478391 -0.1729456 -0.7418856 0.6478391 -0.1729456 -0.7915146 0.5861839 -0.1728962 -0.7963674 0.583286 -0.1599265 -0.841827 0.5155056 -0.159942 -0.8405964 0.5163519 -0.1636409 -0.8806336 0.4445374 -0.1639242 -0.8822253 0.44318 -0.1589653 -0.9154772 0.3696997 -0.1588196 -0.9137125 0.3714643 -0.1647542 -0.9411495 0.2951527 -0.1646885 -0.942004 0.2940955 -0.1616675 -0.9631701 0.21503 -0.1614485 -0.9617721 0.2169947 -0.1670563 -0.976839 0.1328985 -0.167701 -0.9771302 0.1323568 -0.1664282 -0.984408 0.05585813 -0.1667959 -0.984408 0.05585813 -0.1667959 -0.984408 0.05585819 -0.1667959 -0.9845603 0.05546569 -0.1660265 -0.9857517 -0.02578216 -0.1662194 -0.9856844 -0.02549433 -0.1666627 -0.9797139 -0.1113445 -0.1666229 -0.979584 -0.1106733 -0.1678291 -0.9676996 -0.1883664 -0.1675584 -0.9682431 -0.1911669 -0.1611233 -0.9490527 -0.270455 -0.1617194 -0.9488626 -0.2693564 -0.1646419 -0.9235029 -0.3462535 -0.1650784 -0.923418 -0.3448048 -0.1685494 -0.8917142 -0.4199914 -0.1686807 -0.891514 -0.42243 -0.1635716 -0.854146 -0.493566 -0.1637901 -0.8539495 -0.4952052 -0.159819 -0.809287 -0.5651019 -0.1603581 -0.809287 -0.5651018 -0.160358 -0.8092868 -0.5651018 -0.1603581 -0.8102878 -0.5600802 -0.1724642 -0.7614856 -0.6247003 -0.1728854 -0.7614855 -0.6247003 -0.1728854 -0.7614856 -0.6247003 -0.1728854 -0.760549 -0.6280141 -0.1648142 -0.7605489 -0.6280141 -0.1648142 -0.760549 -0.6280141 -0.1648142 -0.7059549 -0.6887856 -0.1649304 -0.7071338 -0.6857987 -0.1721687 -0.6478465 -0.7421265 -0.1718812 -0.6466193 -0.7445815 -0.1657769 -0.5820275 -0.7960024 -0.166206 -0.583909 -0.7927222 -0.1750485 -0.5171908 -0.8378073 -0.1749076 -0.5144539 -0.8417316 -0.1637836 -0.4428306 -0.8814826 -0.1639804 -0.4442068 -0.8799333 -0.1685162 -0.3712413 -0.9130861 -0.1686825 -0.3700283 -0.9142898 -0.1647827 -0.2912427 -0.9423873 -0.1645716 -0.293608 -0.9403293 -0.1719747 -0.2186932 -0.960583 -0.1716204 -0.2141688 -0.9637263 -0.1592589 -0.1330206 -0.9783492 -0.1585515 -0.1358901 -0.9766605 -0.1663374 -0.05565178 -0.9844263 -0.1667569 -0.05541151 -0.9845608 -0.166041 0.03000909 -0.9856303 -0.1662297 0.02987968 -0.9855698 -0.1666116 0.1069934 -0.9801771 -0.1667492 0.1065189 -0.9800406 -0.1678518 0.1884089 -0.9677302 -0.1673334 0.192025 -0.9684374 -0.1589197 0.270663 -0.9495236 -0.1585762 0.2681093 -0.9492183 -0.1646273 0.3463058 -0.9234675 -0.1651673 0.3446915 -0.9234765 -0.1684609 0.4201781 -0.8916079 -0.1687774 0.4223333 -0.8915306 -0.1637306 0.4967224 -0.8523377 -0.1636685 0.4943117 -0.8526747 -0.1691212 0.4943117 -0.8526747 -0.1691211 0.4943116 -0.8526747 -0.1691212 0.5614379 -0.8100999 -0.168895 0.5625934 -0.8098128 -0.166409 0.6253569 -0.7624433 -0.16616 0.6259883 -0.7622457 -0.1646827 0.6888338 -0.7059485 -0.1647563 0.6889066 -0.705849 -0.1648786 0.744842 -0.6465596 -0.1648368 0.7449721 -0.6463477 -0.1650801 0.794732 -0.5843313 -0.1641893 0.7963728 -0.5833014 -0.1598436 0.8418151 -0.5154983 -0.1600277 0.8405998 -0.5163502 -0.1636295 0.8805875 -0.4446669 -0.16382 0.8791367 -0.4457997 -0.1684675 0.9124798 -0.3727055 -0.1687342 0.9136871 -0.3714717 -0.1648777 0.9423587 -0.2911498 -0.1649001 0.9403006 -0.2937378 -0.1719093 0.9614461 -0.2146353 -0.1719102 0.9626318 -0.2130004 -0.1672454 0.976265 -0.1368505 -0.1678653 0.9765717 -0.1364733 -0.1663814 0.9846498 -0.05150556 -0.166769 0.9847897 -0.05111598 -0.1660615 0.9857508 0.0257821 -0.1662247 0.9857069 0.02566951 -0.1665028 0.9797461 0.1113482 -0.1664314 0.9795793 0.1106759 -0.1678549 0.9676938 0.188361 -0.1675975 0.9673494 0.1864719 -0.1716488 0.9473198 0.2701365 -0.1720805 0.9471834 0.2688876 -0.174766 0.923358 0.3418176 -0.1748448 0.9235875 0.3490505 -0.1585881 0.8914146 0.4244205 -0.1588946 0.8917326 0.417994 -0.1734766 0.852764 0.4927548 -0.1731656 0.8525371 0.4945515 -0.1691135 0.8100968 0.5614636 -0.1688249 0.8103042 0.5600616 -0.1724476 0.759397 0.627106 -0.173362 0.7594502 0.6271526 -0.1729602 0.7071031 0.6857289 -0.1725721 0.7058689 0.6889275 -0.1647057 0.6464565 0.7449268 -0.1648579 0.6466958 0.7444891 -0.165893 0.5819584 0.796023 -0.1663488 0.5839708 0.7926316 -0.1752524 0.5171668 0.8378216 -0.1749105 0.5157366 0.8398721 -0.1692063 0.442563 0.8807084 -0.1687921 0.4425414 0.8807595 -0.1685815 0.3727596 0.912437 -0.1688464 0.3713796 0.9137857 -0.1645384 0.2912933 0.9423094 -0.1649276 0.2912933 0.9423096 -0.1649275 0.2912933 0.9423094 -0.1649275 0.2936066 0.9403205 -0.1720247 0.2178039 0.9607269 -0.1719453 0.2169281 0.9613835 -0.1693637 0.1327742 0.9766033 -0.1691657 0.1322482 0.9768881 -0.1679285 0.05563402 0.9842876 -0.1675793 0.05536091 0.9844136 -0.1669289 0.05536097 0.9844135 -0.1669289 0.05536097 0.9844136 -0.1669289 -0.02998322 0.9856837 -0.1659175 0.4995909 -0.02953153 -0.865758 0.4938871 -0.06837719 -0.8668335 0.4623183 -0.1897134 -0.8661818 0.35317 -0.3532118 -0.8663212 0.2465888 -0.4353093 -0.8658521 0.2465888 -0.4353093 -0.8658522 0.2465887 -0.4353094 -0.865852 0.1146252 -0.4873176 -0.8656688 0.1146252 -0.4873176 -0.865669 0.1146252 -0.4873179 -0.8656688 0.09650546 -0.4908264 -0.8658962 0.05404645 -0.4954324 -0.8669635 -0.02474808 -0.499808 -0.8657826 -0.0686165 -0.495091 -0.8661275 -0.1871359 -0.4624356 -0.8666797 -0.3586609 -0.3486729 -0.865904 -0.4309837 -0.2526413 -0.866271 -0.4756094 -0.1488831 -0.8669657 -0.4908462 -0.09728866 -0.8657973 -0.4953652 -0.05424463 -0.8669896 -0.4998322 0.02453607 -0.8657746 -0.4942857 0.06609851 -0.8667829 -0.4633318 0.1874754 -0.8661274 -0.3483574 0.357913 -0.8663402 -0.3483574 0.357913 -0.8663402 -0.3483574 0.357913 -0.8663402 -0.2527697 0.4309683 -0.8662413 -0.1213381 0.484971 -0.8660718 -0.1213381 0.4849709 -0.8660718 -0.1213381 0.4849711 -0.8660717 -0.09649121 0.4908969 -0.8658578 -0.05405205 0.4953517 -0.8670093 0.0245046 0.499899 -0.865737 0.06860536 0.4948891 -0.8662438 0.1861951 0.4628292 -0.8666721 0.3636614 0.3438253 -0.8657567 0.4302833 0.2523754 -0.8666966 0.4302833 0.2523756 -0.8666965 0.4302833 0.2523757 -0.8666965 0.4762233 0.1489959 -0.8666092 0.4908324 0.09756952 -0.8657736 0.4908325 0.09756952 -0.8657736 0.4908324 0.09756958 -0.8657736 0.4952149 0.05661386 -0.866924 -0.2203961 -0.09483867 -0.970789 -0.3427419 -0.06062054 -0.9374716 -0.3427419 -0.06062054 -0.9374718 -0.3427419 -0.06062054 -0.9374716 -0.2228919 -0.08494031 -0.9711356 -0.2921435 -0.07594668 -0.9533543 -0.2454579 0.09109497 -0.9651178 -0.2194595 -0.07486045 -0.9727454 -0.2194594 -0.07486057 -0.9727454 -0.2194595 -0.07486051 -0.9727454 -0.1987286 0.07376164 -0.977275 -0.1567625 0.08780294 -0.9837257 -0.148108 0.09798336 -0.9841053 -0.1540808 0.08811897 -0.9841211 -0.09440177 0.2180858 -0.9713531 -0.06166023 0.3409846 -0.9380446 -0.0703125 0.2192227 -0.973138 -0.05823069 0.2870868 -0.956133 -0.05823075 0.2870868 -0.956133 -0.05823081 0.2870867 -0.9561331 0.08908766 0.2455017 -0.9652939 -0.07728236 0.2224448 -0.9718774 0.07294434 0.201022 -0.9768671 0.08803701 0.1560721 -0.9838145 0.1006437 0.1465383 -0.9840719 0.0881465 0.1538653 -0.9841523 0.2159904 0.0957036 -0.9716939 0.3430113 0.06017881 -0.9374016 0.2191136 0.0742191 -0.9728724 0.2884919 0.06114459 -0.955528 0.2884919 0.06114453 -0.955528 0.2884919 0.06114447 -0.955528 0.2454579 -0.09109497 -0.9651178 0.2193082 0.07494318 -0.9727731 0.1987434 -0.07376712 -0.9772715 0.1567625 -0.08780294 -0.9837257 0.1471828 -0.09958845 -0.984083 0.1541902 -0.08796286 -0.9841179 0.09367138 -0.2180358 -0.9714351 0.06161421 -0.3410667 -0.9380177 0.07397782 -0.2190252 -0.9729107 0.06126576 -0.2881802 -0.9556144 -0.08837753 -0.2454594 -0.9653699 0.0848937 -0.2230644 -0.9711002 0.08489364 -0.2230642 -0.9711002 0.08489376 -0.2230646 -0.9711001 -0.07239663 -0.2010848 -0.9768949 -0.08742624 -0.1559717 -0.9838849 -0.09961658 -0.1472176 -0.984075 -0.0879051 -0.1541061 -0.9841362 0.4917085 0.09253638 -0.8658291 0.4910133 0.06399184 -0.8687986 0.4190019 0.05461722 -0.9063413 0.4225256 0.003676235 -0.9063436 0.3435491 0.003018021 -0.93913 0.3414326 -0.03958702 -0.9390723 0.4802139 0.1365085 -0.8664641 0.4788804 0.1229199 -0.8692321 0.4091363 0.1049186 -0.9064214 0.41882 0.05491816 -0.9064071 0.3403676 0.04461854 -0.9392333 0.3432194 0.003666758 -0.9392482 0.4529536 0.2137486 -0.8655314 0.4516012 0.2169768 -0.865435 0.4630846 0.1722228 -0.8694205 0.4644472 0.1811099 -0.8668841 0.3939087 0.1536347 -0.9062187 0.4097954 0.1042839 -0.9061969 0.3324597 0.08463066 -0.9393126 0.3399993 0.04504728 -0.9393463 0.4325683 0.2483135 -0.8667325 0.4351266 0.2343704 -0.8693305 0.3721193 0.200511 -0.9062685 0.3936764 0.1537608 -0.9062983 0.3195846 0.1248882 -0.9392916 0.3325149 0.08452051 -0.9393031 0.3862656 0.3175821 -0.8659911 0.3817934 0.3231029 -0.865932 0.4063563 0.2813328 -0.8693252 0.4058058 0.2859666 -0.8680697 0.3454793 0.24356 -0.9062685 0.3720073 0.200554 -0.906305 0.3023369 0.16303 -0.9391558 0.320137 0.1242495 -0.9391881 0.2586727 0.1003969 -0.9607335 0.2689096 0.06842005 -0.9607322 0.2614335 0.05539149 -0.9636309 0.2652146 0.03518933 -0.9635472 0.2789133 0.05689191 -0.9586296 0.2828702 0.003079235 -0.9591533 0.2666723 -0.01765531 -0.9636256 0.2659999 -0.03080475 -0.9634808 0.2784198 -0.01894134 -0.9602727 0.2789929 -0.01444774 -0.9601845 0.3580721 0.3493148 -0.8658889 0.367369 0.3300665 -0.8695378 0.3145516 0.2826929 -0.9061689 0.3458288 0.2433204 -0.9061996 0.2810385 0.1978411 -0.9390828 0.3027768 0.1627017 -0.939071 0.2301235 0.1236394 -0.9652754 0.2262489 0.1320633 -0.9650756 0.2285152 -0.05098485 -0.9722045 0.2943415 0.4031498 -0.8665064 0.2948248 0.4027438 -0.866531 0.2948248 0.4027437 -0.866531 0.3248962 0.3742157 -0.868565 0.3246726 0.3746355 -0.8684676 0.2771858 0.3198975 -0.9059987 0.3153685 0.2822931 -0.9060097 0.2562063 0.229406 -0.9390054 0.2818699 0.1972682 -0.938954 0.214014 0.1498127 -0.9652742 0.2299589 0.1238627 -0.965286 0.1599491 0.08613318 -0.9833602 0.232611 -0.04995203 -0.9712862 0.232611 -0.04995208 -0.9712862 0.232611 -0.04995197 -0.9712862 0.1429898 0.1089749 -0.9837065 0.1469274 0.103362 -0.983732 0.213453 0.1501646 -0.9653438 0.1929714 0.1758297 -0.9653217 0.2532215 0.2307078 -0.939496 0.2239045 0.2594819 -0.9394338 0.2761957 0.3200585 -0.9062442 0.2373389 0.3498849 -0.9062289 0.2772505 0.408755 -0.8695123 0.2242611 0.441771 -0.8686458 0.2581796 0.4278635 -0.8661848 0.262806 0.4250931 -0.8661576 0.1929041 0.4599122 -0.8667576 0.2271851 0.4418331 -0.8678539 0.1934921 0.3763356 -0.9060533 0.2381011 0.3498765 -0.9060323 0.1934158 0.284154 -0.939067 0.2265754 0.2586897 -0.9390118 0.1723647 0.1967614 -0.9651815 0.1945968 0.1749766 -0.9651505 0.1321235 0.1187979 -0.9840886 0.1423263 0.106059 -0.9841214 0.1422648 0.109557 -0.983747 0.1332845 0.1179874 -0.9840296 0.116786 0.1342173 -0.9840462 0.1714931 0.1971269 -0.9652622 0.1462844 0.2165951 -0.9652397 0.1921066 0.2844194 -0.9392554 0.1558653 0.3057975 -0.9392518 0.191791 0.3762393 -0.9064548 0.1458439 0.3965307 -0.9063625 0.1704592 0.4634186 -0.8695902 0.1075724 0.4817385 -0.8696874 0.1529434 0.4765778 -0.8657263 0.147178 0.4783765 -0.8657336 0.05832082 0.4965543 -0.8660442 0.05832082 0.4965544 -0.8660442 0.05832087 0.4965552 -0.8660438 0.1161548 0.4843727 -0.8671167 0.09857821 0.4110329 -0.906275 0.146212 0.3965595 -0.9062906 0.1189852 0.3226799 -0.9389996 0.1575604 0.3057672 -0.9389788 0.1198147 0.2324789 -0.9651933 0.1469259 0.2164205 -0.9651814 0.09973233 0.146923 -0.9841073 0.1153492 0.1349732 -0.9841122 0.02940356 0.499494 -0.8658182 0.05521559 0.4917899 -0.8689614 0.04718542 0.4201943 -0.9062066 0.09911006 0.4111234 -0.9061759 0.08056688 0.334306 -0.9390147 0.1188907 0.3226615 -0.939018 0.09042996 0.2454695 -0.9651774 0.1201893 0.2324076 -0.9651638 0.08220213 0.1589307 -0.9838617 0.08397036 0.1567255 -0.9840661 -0.01352447 0.4982091 -0.8669515 -0.005334138 0.495034 -0.8688573 -0.00455439 0.4220298 -0.9065706 0.04560446 0.4194589 -0.9066281 0.03710234 0.3413308 -0.9392107 0.07925033 0.3340002 -0.9392355 0.06707698 0.2827291 -0.9568516 0.1083459 0.2312301 -0.9668474 -0.09813636 0.4904103 -0.8659487 -0.06389588 0.4899468 -0.8694077 -0.05465459 0.418991 -0.9063441 -0.003658056 0.4225727 -0.9063217 -0.002981424 0.3436057 -0.9391093 0.03751647 0.3414093 -0.9391658 -0.1371394 0.4800714 -0.8664435 -0.1227755 0.4786613 -0.8693731 -0.1049508 0.4091646 -0.9064048 -0.05486726 0.4188279 -0.9064065 -0.04458957 0.3403486 -0.9392415 -0.003768384 0.3431454 -0.9392747 -0.2131937 0.4521669 -0.8660794 -0.2117462 0.4529876 -0.8660057 -0.1743027 0.4625744 -0.8692776 -0.1807743 0.4635406 -0.8674392 -0.153614 0.3939757 -0.9061931 -0.1042822 0.4097564 -0.9062147 -0.0847904 0.3331249 -0.9390625 -0.04333823 0.3411561 -0.9390071 -0.250775 0.4321914 -0.8662116 -0.2327979 0.435338 -0.869647 -0.1994825 0.3730264 -0.9061225 -0.1533082 0.3941977 -0.9061484 -0.1246021 0.3204515 -0.9390342 -0.0847215 0.3332022 -0.9390414 -0.3182969 0.3863291 -0.8657003 -0.3190182 0.3861714 -0.8655052 -0.2821275 0.407455 -0.8685531 -0.2856846 0.4071315 -0.8675416 -0.2427805 0.34591 -0.9063134 -0.1999394 0.3724313 -0.9062667 -0.1623121 0.3022555 -0.9393063 -0.1257799 0.3191196 -0.9393306 -0.1014555 0.2574412 -0.9609532 -0.06809407 0.2678713 -0.9610455 -0.05667102 0.2611001 -0.9636468 -0.03373885 0.2655084 -0.9635182 -0.05512762 0.2790727 -0.9586863 -0.003102421 0.2828695 -0.9591535 0.01762187 0.2667719 -0.9635987 0.02925157 0.2662816 -0.9634515 0.0189622 0.2767421 -0.9607571 0.01473069 0.2775775 -0.9605904 0.01473069 0.2775774 -0.9605904 0.01473069 0.2775775 -0.9605904 -0.3487257 0.3575848 -0.8663277 -0.3319966 0.3657655 -0.8694791 -0.2838866 0.3127028 -0.9064356 -0.2430708 0.3454591 -0.9064076 -0.197665 0.2808718 -0.9391697 -0.1618321 0.3030335 -0.9391385 -0.1232278 0.2306819 -0.9651948 -0.1317072 0.22672 -0.9650136 0.03633338 0.2283812 -0.9728936 0.03633338 0.2283811 -0.9728936 0.03633338 0.2283812 -0.9728937 -0.4029336 0.2971641 -0.8656433 -0.4041538 0.2954888 -0.8656478 -0.3752262 0.325881 -0.8677597 -0.373121 0.3266192 -0.8683898 -0.3183423 0.2787088 -0.9060793 -0.2833249 0.3144891 -0.9059931 -0.2298861 0.2551293 -0.9391812 -0.1978119 0.2807202 -0.9391841 -0.1506009 0.2137208 -0.9652165 -0.123237 0.2305506 -0.9652249 -0.0846821 0.1584425 -0.9837301 0.03703176 0.2269057 -0.9732125 -0.1087888 0.1430181 -0.983723 -0.1035581 0.1465848 -0.9837626 -0.1507713 0.2134264 -0.965255 -0.1752513 0.1939248 -0.9652358 -0.2300822 0.2545968 -0.9392778 -0.2584136 0.225709 -0.9392965 -0.3184865 0.2781981 -0.9061855 -0.3504273 0.2366715 -0.9061939 -0.4095323 0.2765266 -0.8693771 -0.4425007 0.2235116 -0.8684675 -0.4281182 0.2584959 -0.8659646 -0.4259226 0.2620354 -0.8659835 -0.4607608 0.1934082 -0.8661946 -0.4607608 0.1934081 -0.8661945 -0.4607608 0.1934081 -0.8661945 -0.4426247 0.2276229 -0.8673357 -0.3756161 0.1931092 -0.9064334 -0.3505412 0.2355116 -0.906452 -0.2845574 0.1912027 -0.9393981 -0.2586337 0.2249079 -0.939428 -0.1974346 0.1716641 -0.9651689 -0.1748533 0.1947586 -0.9651401 -0.1189157 0.1324409 -0.9840317 -0.1055745 0.1431367 -0.9840559 -0.1100705 0.1428352 -0.9836069 -0.1199503 0.1308644 -0.9841171 -0.1340179 0.1165701 -0.984099 -0.197464 0.1717873 -0.9651409 -0.2161208 0.1474044 -0.9651756 -0.2841408 0.1937696 -0.9389981 -0.3053771 0.1579326 -0.9390433 -0.375652 0.1942437 -0.906176 -0.3967809 0.1459367 -0.906238 -0.4639445 0.1706337 -0.8692753 -0.4825447 0.107299 -0.8692741 -0.4778823 0.1473054 -0.8659847 -0.4770496 0.1505033 -0.8658941 -0.4909172 0.08659082 -0.8668925 -0.484687 0.1144127 -0.8671726 -0.4116218 0.09720373 -0.9061561 -0.396876 0.1463053 -0.906137 -0.3220494 0.1187825 -0.9392418 -0.3054351 0.1564066 -0.9392798 -0.2323667 0.119056 -0.9653142 -0.2165621 0.1457025 -0.9653351 -0.1476519 0.09936022 -0.9840359 -0.1332909 0.1179873 -0.9840288 -0.4995943 0.02931636 -0.8657633 -0.4917356 0.05528652 -0.8689876 -0.4201179 0.04723626 -0.9062393 -0.4115756 0.09698784 -0.9062003 -0.3338791 0.07866293 -0.939328 -0.3220083 0.1179642 -0.9393588 -0.2454972 0.08989793 -0.9652199 -0.2321922 0.1200309 -0.9652355 -0.159455 0.08244127 -0.9837568 -0.1558815 0.08520436 -0.9840941 -0.4981942 -0.01359182 -0.8669589 -0.4950608 -0.005338132 -0.8688421 -0.4229295 -0.004525542 -0.9061513 -0.4202824 0.0474525 -0.9061518 -0.3410567 0.03860634 -0.9392497 -0.3340104 0.07915723 -0.9392397 -0.2826519 0.06703829 -0.9568772 -0.2316288 0.1081084 -0.9667785 -0.4907799 -0.09716176 -0.8658491 -0.4899963 -0.06392127 -0.8693777 -0.419874 -0.0547325 -0.9059306 -0.4234414 -0.003758013 -0.9059157 -0.3428078 -0.002974867 -0.9394009 -0.3407868 0.03764998 -0.9393864 -0.4799611 -0.133947 -0.8670038 -0.4788675 -0.122853 -0.8692486 -0.4099869 -0.1051941 -0.906005 -0.4197165 -0.05496203 -0.9059898 -0.3403682 -0.04458183 -0.9392349 -0.3433109 -0.001857042 -0.9392201 -0.452171 -0.2133774 -0.866032 -0.4528833 -0.2115644 -0.8661046 -0.4625704 -0.174239 -0.8692924 -0.4635247 -0.1808155 -0.8674392 -0.3939245 -0.1535842 -0.9062204 -0.4092602 -0.1059815 -0.9062417 -0.3321793 -0.08598709 -0.9392887 -0.3400283 -0.04509764 -0.9393333 -0.4321729 -0.250812 -0.8662101 -0.4353851 -0.2327542 -0.8696352 -0.3726916 -0.1992876 -0.9063032 -0.3936942 -0.1538432 -0.9062765 -0.3202236 -0.1251028 -0.9390454 -0.3332067 -0.08474445 -0.9390376 -0.3862197 -0.3176329 -0.865993 -0.385418 -0.3183898 -0.8660721 -0.4070333 -0.2818668 -0.8688355 -0.406502 -0.2865049 -0.8675663 -0.3454894 -0.2435591 -0.906265 -0.3728215 -0.1991662 -0.9062764 -0.3035105 -0.1621226 -0.9389343 -0.3207843 -0.1245918 -0.9389219 -0.2587018 -0.1004081 -0.9607246 -0.2688731 -0.06835263 -0.9607472 -0.2614521 -0.05551058 -0.9636189 -0.2651957 -0.03513658 -0.9635542 -0.2788904 -0.05688583 -0.9586366 -0.2829928 -0.001492142 -0.9591209 -0.2665761 0.01920115 -0.9636227 -0.2660867 0.02940404 -0.9635005 -0.2787067 0.01715874 -0.960223 -0.2780762 0.02077418 -0.9603344 -0.3580405 -0.3494054 -0.8658654 -0.3673795 -0.3300222 -0.8695503 -0.3145587 -0.2827095 -0.9061612 -0.3458057 -0.2433043 -0.9062128 -0.2805405 -0.1974506 -0.9393138 -0.301299 -0.1638588 -0.9393452 -0.2295947 -0.1248413 -0.9652466 -0.2262293 -0.1320236 -0.9650856 -0.2286663 0.05136799 -0.9721487 -0.2929449 -0.4042649 -0.8664603 -0.2948699 -0.4030563 -0.8663703 -0.3259313 -0.3731109 -0.8686524 -0.3251237 -0.3751384 -0.8680818 -0.2768102 -0.3193897 -0.9062927 -0.3139008 -0.2827969 -0.9063621 -0.255102 -0.2299138 -0.939182 -0.2813538 -0.1969071 -0.9391846 -0.2144377 -0.1500629 -0.9651412 -0.2304144 -0.1240994 -0.9651469 -0.1568624 -0.08445817 -0.9840026 -0.2275599 0.05121058 -0.9724166 -0.2275599 0.05121058 -0.9724166 -0.2275598 0.05121052 -0.9724166 -0.1422832 -0.109134 -0.9837913 -0.146484 -0.1031085 -0.9838248 -0.213818 -0.1505083 -0.9652094 -0.1939685 -0.1752907 -0.9652199 -0.2546157 -0.2300696 -0.9392758 -0.2249499 -0.2591819 -0.9392669 -0.2771341 -0.3193016 -0.9062247 -0.2373391 -0.3499465 -0.906205 -0.2775683 -0.4092292 -0.8691877 -0.2242503 -0.4417876 -0.8686401 -0.2581652 -0.4275884 -0.866325 -0.2643159 -0.4242699 -0.8661019 -0.1876868 -0.4622254 -0.8666726 -0.2262547 -0.441859 -0.8680837 -0.1928783 -0.3766368 -0.906059 -0.2381106 -0.3498903 -0.9060243 -0.1931796 -0.2837566 -0.9392359 -0.2252774 -0.2591125 -0.9392076 -0.1716834 -0.1974319 -0.965166 -0.1945947 -0.1749036 -0.9651641 -0.1321558 -0.1188126 -0.9840825 -0.1431008 -0.1050458 -0.9841176 -0.1432031 -0.1098356 -0.9835797 -0.1319087 -0.1189014 -0.9841049 -0.1165945 -0.1339972 -0.9840989 -0.1717664 -0.1974319 -0.9651513 -0.1464771 -0.216863 -0.9651503 -0.1918801 -0.2841134 -0.9393943 -0.1557149 -0.3055025 -0.9393727 -0.1919689 -0.3766528 -0.9062452 -0.1459565 -0.3967757 -0.9062371 -0.1703426 -0.4631018 -0.8697816 -0.1070204 -0.4815874 -0.8698393 -0.1529026 -0.4763482 -0.8658599 -0.1470782 -0.4780523 -0.8659297 -0.05854582 -0.4966555 -0.8659709 -0.05854594 -0.4966557 -0.865971 -0.05854588 -0.4966563 -0.8659705 -0.1166211 -0.4844838 -0.866992 -0.09896415 -0.4111121 -0.906197 -0.1463036 -0.3968579 -0.9061453 -0.1189802 -0.3226914 -0.9389963 -0.1583495 -0.3053857 -0.9389702 -0.1203774 -0.2321268 -0.965208 -0.1459717 -0.2170023 -0.9651955 -0.09914064 -0.1473652 -0.9841009 -0.1164694 -0.1341139 -0.9840978 -0.02936846 -0.4996483 -0.8657304 -0.05504125 -0.4917352 -0.8690034 -0.04701596 -0.4200198 -0.9062963 -0.09864896 -0.4110818 -0.9062452 -0.08024388 -0.3343617 -0.9390225 -0.1188799 -0.3227109 -0.9390023 -0.09041839 -0.2454697 -0.9651783 -0.1210033 -0.2320787 -0.9651414 -0.0826075 -0.1584498 -0.9839053 -0.08399516 -0.1566707 -0.9840728 0.01352536 -0.4982423 -0.8669325 0.005345344 -0.4950798 -0.8688311 0.00456202 -0.4220297 -0.9065705 -0.04579502 -0.4196131 -0.9065471 -0.03725141 -0.3412749 -0.9392252 -0.0788213 -0.3340966 -0.9392373 -0.06678843 -0.2830873 -0.9567658 -0.1083514 -0.2312213 -0.9668489 0.09820723 -0.490741 -0.8657532 0.09820723 -0.490741 -0.8657532 0.06413531 -0.4899331 -0.8693976 0.05485296 -0.4189801 -0.906337 0.003633201 -0.4225901 -0.9063137 0.00295943 -0.3435919 -0.9391145 -0.03774631 -0.3414208 -0.9391524 0.1372221 -0.4802408 -0.8663365 0.1223697 -0.4788767 -0.8693118 0.1046389 -0.4094726 -0.9063019 0.054892 -0.4189113 -0.9063665 0.0445978 -0.3403412 -0.9392439 0.003759384 -0.3432196 -0.9392477 0.2133896 -0.4525327 -0.8658401 0.2141885 -0.4522327 -0.8657996 0.1743084 -0.4625897 -0.8692683 0.1807671 -0.4635223 -0.8674506 0.1536054 -0.3939025 -0.9062264 0.1042699 -0.4098179 -0.9061882 0.08478271 -0.3331309 -0.9390611 0.0433408 -0.3411298 -0.9390166 0.2510225 -0.4326374 -0.8659172 0.2330228 -0.4357868 -0.869362 0.199278 -0.3726655 -0.906316 0.1537888 -0.3936787 -0.9062926 0.1250057 -0.3200162 -0.939129 0.08510828 -0.3328732 -0.939123 0.3194555 -0.3846513 -0.8660206 0.3150102 -0.3883072 -0.8660174 0.2832484 -0.4069022 -0.8684474 0.2865095 -0.4064772 -0.8675763 0.243523 -0.3454995 -0.9062708 0.199209 -0.3728339 -0.9062619 0.1616842 -0.3025912 -0.9393066 0.1258062 -0.3191885 -0.9393038 0.1014586 -0.257412 -0.9609606 0.06843608 -0.2677013 -0.9610685 0.05701726 -0.2611678 -0.9636081 0.03373926 -0.2654616 -0.963531 0.05512911 -0.27908 -0.9586841 0.003096878 -0.28285 -0.9591592 -0.01762622 -0.2666082 -0.9636439 -0.02940589 -0.2660661 -0.9635062 -0.01894825 -0.2768475 -0.960727 -0.01435101 -0.277569 -0.9605985 0.3472706 -0.3590873 -0.8662906 0.3313442 -0.3667804 -0.8693004 0.2835108 -0.3137999 -0.906174 0.2433452 -0.3458262 -0.906194 0.197417 -0.2805366 -0.9393219 0.1616585 -0.3026045 -0.9393067 0.1232223 -0.2306715 -0.9651979 0.1317256 -0.2267516 -0.9650036 -0.03646254 -0.2283881 -0.9728872 0.4037516 -0.2947372 -0.8660917 0.3986091 -0.3013702 -0.8661909 0.3752254 -0.3258204 -0.8677828 0.3744965 -0.3260598 -0.8680078 0.3186533 -0.2774589 -0.9063535 0.2837974 -0.3130999 -0.9063264 0.2303397 -0.2541248 -0.9393424 0.1975523 -0.2803519 -0.9393487 0.1507924 -0.2139458 -0.9651367 0.1225914 -0.2313501 -0.9651158 0.08419245 -0.1588923 -0.9836996 -0.0369473 -0.2269147 -0.9732136 0.1080077 -0.1430751 -0.9838008 0.1039913 -0.1458634 -0.983824 0.1516658 -0.2127193 -0.9652709 0.1745102 -0.1945459 -0.9652452 0.2295191 -0.255849 -0.9390753 0.2588381 -0.2261534 -0.9390727 0.31844 -0.2781614 -0.9062132 0.3504492 -0.2366843 -0.9061821 0.4095362 -0.2765897 -0.8693552 0.4424933 -0.2212228 -0.8690571 0.4248557 -0.2637336 -0.8659921 0.4259026 -0.2620381 -0.8659925 0.4610022 -0.1929865 -0.86616 0.4426004 -0.227611 -0.8673511 0.3756161 -0.1931092 -0.9064334 0.3505362 -0.2355809 -0.906436 0.2850898 -0.1915236 -0.9391713 0.2590654 -0.2252368 -0.9392303 0.1974596 -0.1717323 -0.9651517 0.1738988 -0.1956222 -0.9651379 0.1182177 -0.1330129 -0.9840388 0.1055848 -0.1430638 -0.9840654 0.1101709 -0.14294 -0.9835805 0.1101709 -0.14294 -0.9835805 0.1101709 -0.14294 -0.9835805 0.1197536 -0.1306498 -0.9841696 0.1345136 -0.1156823 -0.9841361 0.1979996 -0.1701942 -0.9653134 0.2164567 -0.1462358 -0.965278 0.284933 -0.1924927 -0.9390206 0.3053916 -0.1579081 -0.9390426 0.3756151 -0.1942318 -0.906194 0.3967922 -0.145936 -0.9062333 0.4630953 -0.1703776 -0.8697783 0.4823404 -0.1093826 -0.8691279 0.4779033 -0.1477274 -0.8659013 0.4780424 -0.1470502 -0.8659398 0.4955931 -0.05822432 -0.8666011 0.4955933 -0.05822312 -0.8666011 0.495593 -0.0582239 -0.8666011 0.4837653 -0.1141955 -0.8677158 0.4116234 -0.09720361 -0.9061554 0.3968741 -0.1463054 -0.9061379 0.3220286 -0.1187381 -0.9392545 0.3054596 -0.1564658 -0.939262 0.2328079 -0.1192354 -0.9651857 0.2161407 -0.1473879 -0.9651736 0.1469908 -0.1001883 -0.9840508 0.133278 -0.1179875 -0.9840305 0.4998984 -0.02518451 -0.8657178 0.4907176 -0.05511295 -0.869574 0.4201555 -0.04718071 -0.9062249 0.4115189 -0.09697496 -0.9062275 0.333854 -0.07865756 -0.9393373 0.3220213 -0.1179637 -0.9393545 0.2454851 -0.0899356 -0.9652195 0.2329058 -0.118476 -0.9652556 0.1600024 -0.08133488 -0.9837601 0.1566928 -0.08404254 -0.9840652 0.4981616 0.0135141 -0.866979 0.494361 0.003573894 -0.8692495 0.422885 0.003057479 -0.9061783 0.420281 -0.04752576 -0.9061487 0.3410807 -0.03857231 -0.9392424 0.3340269 -0.0792573 -0.9392254 0.2842873 -0.06749355 -0.9563605 0.2316529 -0.1093508 -0.966633 -0.8925846 -0.06479525 -0.4462 -0.8926241 -0.06204891 -0.4465112 -0.8927078 -0.07333773 -0.4446287 -0.8927078 -0.07333785 -0.4446286 -0.8927078 -0.07333791 -0.4446285 -0.8963571 -0.06474655 -0.4385794 -0.8927303 -0.06255555 -0.446228 -0.8930414 -0.06059712 -0.4458758 -0.8928636 -0.06189733 -0.446053 -0.8927478 -0.06270283 -0.4461724 -0.8927478 -0.06270289 -0.4461724 -0.8927478 -0.06270283 -0.4461724 -0.8928284 -0.06145948 -0.4461841 -0.8924993 -0.06519097 -0.4463129 -0.8927565 -0.05899351 -0.4466605 -0.4986099 0.7431411 -0.4462395 -0.4995935 0.7425833 -0.4460678 -0.495624 0.7447869 -0.4468214 -0.4956243 0.7447866 -0.4468216 -0.4956242 0.7447867 -0.4468215 -0.49652 0.7401633 -0.4534603 -0.4965199 0.7401633 -0.4534603 -0.5001414 0.742201 -0.4460899 -0.5053949 0.7381091 -0.4469574 -0.5015384 0.7410008 -0.4465167 -0.4955124 0.7453044 -0.4460818 -0.502987 0.7404744 -0.4457599 -0.5038855 0.7398196 -0.4458321 -0.5001993 0.7421113 -0.4461743 0.7806696 0.6249086 0.006647467 0.7549657 0.6557644 0 0.6962684 0.7177816 0 0.6669945 0.7450335 0.006606101 0.6368152 0.7710166 0 0.5684723 0.8227024 0 0.5340834 0.845404 0.006866633 0.4984963 0.8668919 0 0.4264481 0.9045121 0 0.3892015 0.9211278 0.006770312 0.3510866 0.936343 0 0.2718556 0.9623382 0 0.2313233 0.9728521 0.006944239 0.1903076 0.9817246 0 0.1080274 0.9941479 0 0.06909847 0.9975888 0.006474554 0.03017973 0.9995446 0 -0.0561943 0.9984199 0 -0.09735512 0.9952263 0.006836116 -0.1383968 0.990377 0 -0.2201297 0.9754706 0 -0.259817 0.9656341 0.00677973 -0.2992191 0.9541845 0 -0.3751191 0.9269766 0 -0.4149515 0.9098152 0.007195174 -0.4541447 0.890928 0 -0.5233136 0.8521403 0 -0.5577086 0.8300094 0.006757557 -0.5909455 0.8067114 0 -0.6578494 0.7531495 0 -0.6885015 0.7252027 0.006835997 -0.7177121 0.69634 0 -0.7727826 0.6346709 0 -0.797675 0.6030509 0.006670296 -0.8212558 0.5705603 0 -0.8661885 0.4997177 0 -0.8864561 0.4627591 0.007043302 -0.9054228 0.4245113 0 -0.9368786 0.3496549 0 -0.9503703 0.311047 0.006794273 -0.9623104 0.2719536 0 -0.9817149 0.1903571 0 -0.988456 0.1513681 0.006531178 -0.9936669 0.1123668 0 -0.9996627 0.02597451 0 -0.9998621 -0.01515454 0.006796061 -0.9984192 -0.05620628 0 -0.9904531 -0.1378504 0 -0.9837468 -0.179425 0.007008075 -0.9753181 -0.2208045 1.85635e-7 -0.9753181 -0.2208044 0 -0.9753181 -0.2208044 0 -0.9545783 -0.2979602 0 -0.9415162 -0.3368995 0.006789922 -0.9270008 -0.3750596 0 -0.8908777 -0.4542432 0 -0.8721975 -0.4891099 0.006568253 -0.8521041 -0.5233724 0 -0.8051467 -0.5930758 0 -0.7806634 -0.6249166 0.006647527 -0.7549518 -0.6557803 0 -0.6962684 -0.7177816 0 -0.6659179 -0.7459937 0.006837666 -0.6346921 -0.7727652 0 -0.5705146 -0.8212876 0 -0.5340935 -0.8453944 0.007249593 -0.4966283 -0.8679634 0 -0.4280204 -0.9037691 0 -0.3892194 -0.9211181 0.007046937 -0.3496667 -0.9368742 0 -0.2730193 -0.9620087 0 -0.231323 -0.972851 0.007118821 -0.1894717 -0.9818862 0 -0.1080785 -0.9941424 0 -0.06924778 -0.9975786 0.006460309 -0.03027266 -0.9995416 0 0.05616223 -0.9984217 0 0.09733909 -0.9952279 0.006841778 0.1383968 -0.990377 0 0.2201297 -0.9754706 0 0.2592748 -0.9657804 0.006692409 0.2980366 -0.9545544 0 0.3766245 -0.926366 0 0.4149184 -0.9098326 0.00690186 0.4523276 -0.891852 0 0.5234175 -0.8520764 0 0.5587103 -0.8293339 0.006938934 0.5929868 -0.8052123 0 0.6558165 -0.7549203 0 0.6873384 -0.7263029 0.007083296 0.7178922 -0.6961543 0 0.7727826 -0.6346709 0 0.7976257 -0.6031161 0.006655931 0.8213296 -0.570454 0 0.8679051 -0.49673 0 0.8865338 -0.4626194 0.006415843 0.9036775 -0.4282138 0 0.9368826 -0.3496443 0 0.9503703 -0.311047 0.006790041 0.9623081 -0.2719621 0 0.9816859 -0.1905068 0 0.9816859 -0.1905068 2.57318e-7 0.9816859 -0.1905068 0 0.9887622 -0.1493383 0.006891727 0.9941598 -0.1079185 0 0.9996627 -0.02597451 0 0.9998949 0.01299023 0.006444036 0.9986618 0.0517168 0 0.9904531 0.1378504 0 0.9837467 0.179425 0.007020711 0.9752441 0.2211318 0 0.9545271 0.2981243 0 0.9408273 0.3388116 0.007125079 0.9254321 0.3789138 0 0.925432 0.3789137 0 0.925432 0.3789137 0 0.8926252 0.4507996 0 0.8721938 0.4891078 0.00719124 0.8501731 0.5265034 0 0.8051467 0.5930758 0 0.4669412 0.4847347 -0.7395933 0.4531503 0.4942921 -0.7418424 0.4531502 0.494292 -0.7418425 0.4531501 0.4942919 -0.7418427 0.4266361 0.5173757 -0.7418248 0.4269737 0.5189312 -0.7405431 0.3799816 0.5542881 -0.740526 0.3815645 0.5501769 -0.7427745 0.3835011 0.5505406 -0.7415066 0.3341962 0.5821455 -0.7412284 0.334472 0.5750362 -0.7466338 0.3367152 0.5744691 -0.7460618 0.2831628 0.6024848 -0.746211 0.2830171 0.6044409 -0.7446828 0.2342891 0.6245253 -0.7450348 0.2325676 0.6270296 -0.7434691 0.2380372 0.63057 -0.7387286 0.1842967 0.6478732 -0.7391179 0.1806948 0.6441454 -0.7432538 0.1841354 0.6447225 -0.7419078 0.1273495 0.6580328 -0.7421422 0.1274083 0.6577875 -0.7423496 0.07823711 0.665483 -0.7423014 0.07823711 0.6654831 -0.7423014 0.07823705 0.665483 -0.7423014 0.07417887 0.6676269 -0.7407914 0.07069343 0.6638352 -0.7445303 0.01764082 0.6673868 -0.7445023 0.01744192 0.6672016 -0.744673 0.01961553 0.6683759 -0.743565 -0.03639245 0.6675181 -0.7437037 -0.03537243 0.6658665 -0.745232 -0.09701931 0.6595905 -0.7453373 -0.09415113 0.6591971 -0.7460529 -0.09300851 0.6616584 -0.7440145 -0.144628 0.6522755 -0.7440561 -0.1432337 0.6571707 -0.7400074 -0.148934 0.6507856 -0.744511 -0.148934 0.6507857 -0.744511 -0.148934 0.6507856 -0.7445111 -0.1993332 0.6372275 -0.7444511 -0.1998895 0.6378878 -0.7437362 -0.2678528 0.6126891 -0.7435503 -0.2678527 0.6126893 -0.7435501 -0.2678527 0.6126894 -0.7435501 -0.2523922 0.6163656 -0.7459167 -0.2520583 0.6185797 -0.7441947 -0.3011257 0.5963194 -0.7441281 -0.3007979 0.6017888 -0.7398452 -0.3023926 0.5981818 -0.7421168 -0.3518384 0.5701637 -0.7423768 -0.3514893 0.5701116 -0.742582 -0.3967356 0.5391238 -0.7429311 -0.397027 0.5391944 -0.742724 -0.4394902 0.5050068 -0.7428436 -0.4400078 0.5049535 -0.7425733 -0.4402921 0.5016874 -0.7446159 -0.4785175 0.4654695 -0.7445531 -0.4767898 0.4648907 -0.7460216 -0.4720268 0.4717389 -0.7447504 -0.4720271 0.4717397 -0.7447498 -0.472027 0.471738 -0.7447509 -0.5162829 0.4226506 -0.7448614 -0.5129155 0.4220845 -0.7475041 -0.5440651 0.3809512 -0.7475757 -0.5494195 0.3790554 -0.7446175 -0.5491444 0.3773593 -0.7456811 -0.5778818 0.3317579 -0.745647 -0.575672 0.332001 -0.7472463 -0.5747316 0.336578 -0.7459215 -0.6011382 0.2855492 -0.7463877 -0.6090267 0.285088 -0.7401428 -0.6332535 0.227522 -0.7397457 -0.6236268 0.2353585 -0.7454502 -0.6236991 0.2355098 -0.7453419 -0.6420573 0.1797582 -0.7452848 -0.6426641 0.1802266 -0.7446485 -0.6433395 0.1836731 -0.7432217 -0.6569558 0.1271557 -0.7431289 -0.6520485 0.1286391 -0.7471846 -0.6595512 0.07931751 -0.7474631 -0.6644786 0.0708515 -0.7439411 -0.6695136 0.07517343 -0.7389862 -0.6730723 0.0209667 -0.7392795 -0.6671044 0.0173915 -0.7447612 -0.6628395 0.009719491 -0.7486985 -0.662082 -0.03602796 -0.748565 -0.6657086 -0.03810143 -0.7452385 -0.6596605 -0.09671795 -0.7453145 -0.6587202 -0.09116739 -0.7468442 -0.6622675 -0.08945614 -0.7439083 -0.6517902 -0.147481 -0.7439213 -0.6526512 -0.1470847 -0.7432447 -0.6507171 -0.149006 -0.7445566 -0.6372752 -0.1993139 -0.7444155 -0.6391564 -0.2012603 -0.742276 -0.6223846 -0.2485346 -0.7422049 -0.6223846 -0.2485348 -0.7422048 -0.6223847 -0.2485346 -0.7422048 -0.6216896 -0.2516278 -0.741745 -0.618601 -0.2519897 -0.7442003 -0.5950695 -0.3034429 -0.7441873 -0.6009752 -0.3032665 -0.7394986 -0.6003677 -0.3036322 -0.7398419 -0.572658 -0.3533465 -0.7397359 -0.56991 -0.3484231 -0.7441801 -0.5381661 -0.3960277 -0.7440023 -0.5388081 -0.3974894 -0.7427571 -0.5050285 -0.4396098 -0.7427582 -0.5050181 -0.4399318 -0.7425745 -0.5022674 -0.4404445 -0.7441346 -0.4654262 -0.4783589 -0.744682 -0.4660418 -0.4809134 -0.7426489 -0.4505286 -0.4916062 -0.7452164 -0.4505286 -0.4916061 -0.7452164 -0.4505287 -0.4916059 -0.7452164 -0.4244734 -0.5147943 -0.7448552 -0.4248435 -0.516397 -0.7435336 -0.4248436 -0.5163971 -0.7435336 -0.4248434 -0.516397 -0.7435336 -0.3817807 -0.5491346 -0.7434344 -0.3815326 -0.5500415 -0.7428911 -0.383417 -0.5506216 -0.74149 -0.3341755 -0.5819774 -0.7413697 -0.3343521 -0.5777831 -0.7445639 -0.3281438 -0.5791311 -0.7462766 -0.3281438 -0.5791311 -0.7462767 -0.3281439 -0.579131 -0.7462767 -0.2831119 -0.6022613 -0.7464108 -0.2830849 -0.6045264 -0.7445876 -0.2375417 -0.6236241 -0.7447597 -0.2339881 -0.6279063 -0.7422826 -0.2358856 -0.6290504 -0.7407115 -0.1838382 -0.6464691 -0.7404602 -0.1818594 -0.6443548 -0.742788 -0.1803158 -0.6441936 -0.743304 -0.1277077 -0.6568512 -0.7431267 -0.1274188 -0.6578421 -0.7422993 -0.07834547 -0.6652667 -0.7424839 -0.07834541 -0.6652669 -0.7424837 -0.07834541 -0.6652669 -0.7424837 -0.07389104 -0.6680731 -0.7404178 -0.07079291 -0.6643542 -0.7440577 -0.01774042 -0.6676652 -0.7442503 -0.01744192 -0.6672016 -0.744673 -0.01962006 -0.6682347 -0.7436918 0.03625947 -0.6676468 -0.7435947 0.0353887 -0.6662613 -0.7448782 0.09708905 -0.6603139 -0.7446873 0.09384644 -0.6597912 -0.7455658 0.09296017 -0.6616144 -0.7440596 0.1446152 -0.6522892 -0.7440466 0.1438874 -0.6548178 -0.7419637 0.1438875 -0.6548178 -0.7419636 0.1438875 -0.6548178 -0.7419636 0.1486501 -0.6494503 -0.745733 0.198857 -0.6357598 -0.745832 0.2007021 -0.6375383 -0.7438169 0.2680881 -0.6125413 -0.7435873 0.2680881 -0.6125414 -0.7435872 0.268088 -0.6125414 -0.7435871 0.2524312 -0.6163408 -0.745924 0.2520294 -0.6185846 -0.7442005 0.3011096 -0.5963768 -0.7440885 0.3008272 -0.601783 -0.7398381 0.3024503 -0.5981955 -0.7420822 0.3504706 -0.5709597 -0.7424119 0.3530307 -0.5726118 -0.7399224 0.3986581 -0.5416895 -0.74003 0.3989151 -0.5417663 -0.7398352 0.4451355 -0.5048834 -0.7395588 0.4400351 -0.5050484 -0.7424926 0.4402741 -0.5014984 -0.7447538 0.4785528 -0.4655038 -0.7445089 0.4767831 -0.4650165 -0.7459474 0.4721127 -0.4718527 -0.7446239 0.5147521 -0.424399 -0.7449267 0.5161877 -0.4247773 -0.7437168 0.5515792 -0.378355 -0.743376 0.5494195 -0.3790554 -0.7446175 0.5491121 -0.3776049 -0.7455807 0.5763886 -0.334249 -0.7456902 0.5797578 -0.3342639 -0.743067 0.5786023 -0.3392899 -0.7416885 0.5786022 -0.3392901 -0.7416884 0.5786022 -0.33929 -0.7416886 0.6070045 -0.2852985 -0.7417212 0.603302 -0.2853636 -0.744711 0.6248186 -0.2345213 -0.7447158 0.6260594 -0.2332428 -0.744075 0.6250901 -0.2315442 -0.7454192 0.6412485 -0.1824647 -0.7453235 0.6431779 -0.1842772 -0.743212 0.6412636 -0.1700544 -0.7482396 0.6511495 -0.1286271 -0.7479702 0.6511495 -0.1286271 -0.7479702 0.6511495 -0.1286271 -0.7479702 0.6578253 -0.126833 -0.7424145 0.6668121 -0.06689274 -0.7422176 0.6628321 -0.07352685 -0.7451493 0.6634991 -0.07418072 -0.7444906 0.6675406 -0.01784926 -0.7443594 0.6671496 -0.01750636 -0.7447181 0.6685085 -0.01960736 -0.7434461 0.6676168 0.03632915 -0.7436182 0.6710814 0.03841066 -0.7403881 0.6650082 0.09752368 -0.7404413 0.6640477 0.09190165 -0.7420207 0.6617515 0.09295511 -0.7439385 0.6517558 0.1474782 -0.743952 0.6526512 0.1470847 -0.7432447 0.6577692 0.1427187 -0.739575 0.6415123 0.2036707 -0.7395811 0.6350157 0.1971139 -0.7469278 0.6174268 0.2471591 -0.7467909 0.6174268 0.24716 -0.7467906 0.6174268 0.2471594 -0.7467908 0.6163696 0.2523921 -0.7459134 0.6186311 0.2521008 -0.7441376 0.5962271 0.3010009 -0.7442526 0.5966672 0.3011139 -0.7438541 0.5959114 0.3013472 -0.7443652 0.5686972 0.3509026 -0.7439429 0.5684757 0.3504832 -0.7443097 0.5381132 0.3960057 -0.7440522 0.5366979 0.3930909 -0.7466157 0.5018435 0.4367516 -0.7465931 0.5019837 0.4372982 -0.7461788 0.4993174 0.4372118 -0.7480161 0.4993174 0.4372119 -0.7480161 0.4993174 0.4372118 -0.7480161 0.4643839 0.4741474 -0.7480186 0.7443667 0.4595264 -0.4845139 0.7056104 0.5166094 -0.4850038 0.7061535 0.5192551 -0.4813744 0.6608954 0.5758543 -0.481258 0.6617848 0.5813978 -0.473305 0.6113287 0.6345831 -0.4728442 0.6105729 0.6258155 -0.485341 0.5553714 0.6749885 -0.4857501 0.5554077 0.6770735 -0.482798 0.4989559 0.7195118 -0.4830588 0.499002 0.7198693 -0.4824782 0.4402883 0.7569776 -0.4828366 0.4396051 0.7607499 -0.4775009 0.4396052 0.7607499 -0.4775009 0.4396051 0.7607499 -0.4775009 0.3726639 0.7958982 -0.4771456 0.3734972 0.7926871 -0.4818165 0.3047723 0.8218577 -0.4813148 0.3047723 0.8218577 -0.4813148 0.3047723 0.8218577 -0.4813148 0.3063627 0.816931 -0.4886368 0.2387118 0.839209 -0.4886152 0.2360517 0.8453932 -0.4791555 0.1669309 0.8616681 -0.4792308 0.1680717 0.8594895 -0.4827318 0.09672957 0.8705998 -0.4823894 0.09528201 0.8728426 -0.4786098 0.02318859 0.8778365 -0.478399 0.02659344 0.8732867 -0.4864805 -0.04635077 0.8726426 -0.4861549 -0.04952126 0.8761886 -0.4794178 -0.1241302 0.8688502 -0.4792609 -0.1216199 0.8665252 -0.4840896 -0.1893745 0.8542575 -0.4841296 -0.1899191 0.8546455 -0.4832307 -0.2617147 0.8353262 -0.4834622 -0.2617147 0.8353262 -0.4834622 -0.2617147 0.8353262 -0.4834622 -0.2635105 0.8364102 -0.4806039 -0.3324362 0.8117937 -0.4800806 -0.3293234 0.8099449 -0.4853198 -0.394111 0.7805262 -0.4852377 -0.3965201 0.7816931 -0.4813812 -0.4600799 0.7461512 -0.4812328 -0.4608061 0.7464526 -0.4800691 -0.5201161 0.7063873 -0.4801003 -0.5192001 0.7062871 -0.4812377 -0.5758416 0.6609142 -0.4812473 -0.5731923 0.6604021 -0.4850975 -0.6260439 0.6106616 -0.4849346 -0.6300457 0.6108841 -0.4794403 -0.6777232 0.5576582 -0.4792793 -0.6799339 0.5577952 -0.4759774 -0.7240245 0.4994133 -0.4757888 -0.7208101 0.4996616 -0.4803864 -0.7601508 0.4383012 -0.4796487 -0.7617995 0.4379834 -0.4773177 -0.795885 0.3726674 -0.4771645 -0.787371 0.3747991 -0.4894615 -0.815738 0.3078758 -0.4896776 -0.8237833 0.3050588 -0.4778288 -0.845858 0.2367411 -0.4779937 -0.8398168 0.2392199 -0.4873209 -0.8565679 0.1691025 -0.4875406 -0.8595562 0.1672428 -0.4829007 -0.8595563 0.1672428 -0.4829007 -0.8595563 0.1672428 -0.4829007 -0.8711085 0.09279817 -0.4822431 -0.8681559 0.09488701 -0.4871363 -0.8728534 0.02694523 -0.4872381 -0.8782057 0.02294588 -0.4777324 -0.8769168 -0.05016541 -0.478017 -0.8761707 -0.04964536 -0.4794376 -0.8693366 -0.1202813 -0.4793605 -0.8711446 -0.1221938 -0.4755795 -0.8578332 -0.1941151 -0.475859 -0.855505 -0.1909995 -0.4812801 -0.8362094 -0.2632193 -0.4811129 -0.8353128 -0.2620105 -0.483325 -0.8113895 -0.3283814 -0.4835419 -0.8135173 -0.3322365 -0.4772932 -0.7827985 -0.3991953 -0.477357 -0.7805876 -0.394102 -0.485146 -0.7458111 -0.4559972 -0.4856259 -0.746055 -0.4566989 -0.4845908 -0.7036999 -0.5191949 -0.4850187 -0.704377 -0.5216289 -0.4814108 -0.6609292 -0.5757948 -0.4812826 -0.6610583 -0.5770643 -0.4795819 -0.6109803 -0.6304235 -0.4788208 -0.6105156 -0.6256695 -0.485601 -0.5553714 -0.6749885 -0.4857501 -0.5554136 -0.6770806 -0.4827812 -0.4989989 -0.7195737 -0.4829223 -0.498993 -0.719816 -0.4825671 -0.4386519 -0.758031 -0.4826733 -0.4380438 -0.7617983 -0.4772641 -0.3726831 -0.7958916 -0.4771416 -0.373513 -0.7927206 -0.4817491 -0.3060255 -0.8213006 -0.4814705 -0.3076003 -0.8164643 -0.4886391 -0.2387036 -0.8392798 -0.4884979 -0.2387036 -0.8392798 -0.4884977 -0.2387036 -0.8392798 -0.4884978 -0.236069 -0.8453567 -0.4792115 -0.1669037 -0.8616173 -0.4793316 -0.1675239 -0.8605105 -0.4811002 -0.09634351 -0.8711187 -0.4815291 -0.09530085 -0.8728265 -0.4786351 -0.02332144 -0.8776432 -0.478747 -0.02657049 -0.8734301 -0.4862242 0.04633158 -0.8724588 -0.4864866 0.0495184 -0.8759624 -0.4798312 0.123497 -0.8683276 -0.4803704 0.1216287 -0.8666754 -0.4838183 0.1894321 -0.8543026 -0.4840276 0.190945 -0.8553936 -0.4814996 0.26323 -0.8362042 -0.4811159 0.2620607 -0.8354607 -0.4830421 0.2620621 -0.8354603 -0.4830421 0.2620607 -0.8354607 -0.4830421 0.3317527 -0.8101034 -0.4833972 0.3305884 -0.8094484 -0.4852884 0.394145 -0.7805936 -0.4851015 0.3965395 -0.7816664 -0.4814087 0.4600799 -0.7461512 -0.4812328 0.4607549 -0.7464052 -0.480192 0.5201936 -0.7064031 -0.4799931 0.5157034 -0.705372 -0.4863129 0.5738372 -0.6585754 -0.4868155 0.5750365 -0.6587598 -0.4851481 0.6260711 -0.6106101 -0.4849643 0.6257405 -0.6105307 -0.4854906 0.6749019 -0.5554255 -0.4858086 0.6770792 -0.5554534 -0.4827373 0.72079 -0.4971822 -0.4829821 0.7176042 -0.4974972 -0.4873818 0.7176042 -0.4974971 -0.4873818 0.7567702 -0.4362375 -0.4868221 0.7582389 -0.4361109 -0.4846453 0.7905609 -0.374003 -0.4849075 0.7927444 -0.3735827 -0.4816558 0.8213211 -0.3056605 -0.4816672 0.8213212 -0.3056606 -0.4816672 0.8213212 -0.3056606 -0.4816672 0.823801 -0.3050648 -0.4777944 0.8448495 -0.2402064 -0.4780483 0.8440291 -0.2405955 -0.4793003 0.8617842 -0.1663018 -0.479241 0.859676 -0.1673763 -0.4826412 0.8706468 -0.09658259 -0.4823339 0.8727678 -0.09530085 -0.4787422 0.8777046 -0.02324867 -0.4786377 0.8781855 -0.02303326 -0.4777653 0.8769358 0.05025672 -0.4779728 0.8717674 0.04546856 -0.4878058 0.8647678 0.119412 -0.487768 0.8647678 0.119412 -0.4877679 0.8647678 0.119412 -0.487768 0.8665632 0.1214637 -0.4840609 0.8534301 0.1930348 -0.4841431 0.8546444 0.1946777 -0.4813354 0.837264 0.2597136 -0.4811841 0.8395516 0.2633401 -0.4751896 0.8141253 0.3333089 -0.4755052 0.8108066 0.3274395 -0.4851557 0.7806628 0.394191 -0.4849528 0.7805814 0.3940117 -0.4852294 0.7440287 0.4588128 -0.4857079 0.8391528 0.5198156 -0.1600455 0.7953801 0.584632 -0.1599249 0.7950733 0.5856677 -0.1576452 0.7418104 0.6517522 -0.1579127 0.7418104 0.6517522 -0.1579127 0.74377 0.6459428 -0.1719427 0.6879202 0.7050122 -0.1724062 0.6867128 0.7079674 -0.164948 0.6254117 0.7626988 -0.1647751 0.6272156 0.7593708 -0.1730803 0.5611003 0.8095811 -0.1724675 0.5604474 0.8107555 -0.1690395 0.4930537 0.8533998 -0.1691359 0.4917761 0.855211 -0.1636168 0.420444 0.8924409 -0.1636346 0.4206298 0.8922755 -0.164058 0.3463958 0.9234596 -0.1650222 0.3462917 0.9235575 -0.1646929 0.2653023 0.9500097 -0.1646099 0.2678114 0.9480043 -0.1719443 0.1890626 0.9668544 -0.1716039 0.1876126 0.9678419 -0.1675814 0.1069715 0.979976 -0.1679408 0.1065409 0.9802435 -0.1666492 0.03000873 0.9855728 -0.1665707 0.02976155 0.9856723 -0.1660254 -0.05564242 0.9844605 -0.1665579 -0.05540049 0.9843407 -0.1673445 -0.1370161 0.9763033 -0.1675064 -0.1363936 0.9760925 -0.1692349 -0.2138416 0.9620356 -0.1695857 -0.2172268 0.962713 -0.1612338 -0.2965273 0.9412196 -0.1617941 -0.2951619 0.941109 -0.1649041 -0.3714261 0.9137286 -0.1647506 -0.3697784 0.9136657 -0.1687576 -0.4459688 0.8790172 -0.1686435 -0.4479829 0.8789234 -0.1637232 -0.5182185 0.8394721 -0.163513 -0.5158078 0.8398 -0.1693468 -0.5838019 0.7941532 -0.1688081 -0.5820828 0.794586 -0.1726638 -0.6456235 0.7437918 -0.173044 -0.6488803 0.7428089 -0.1648915 -0.708087 0.686683 -0.164558 -0.7079301 0.6867441 -0.1649778 -0.7623879 0.6257908 -0.1647748 -0.7623878 0.6257908 -0.1647749 -0.7623878 0.6257908 -0.1647748 -0.7620519 0.6257849 -0.1663438 -0.8103699 0.5618132 -0.1663331 -0.809513 0.5622848 -0.1688925 -0.8544522 0.4912554 -0.1690548 -0.8529847 0.4923589 -0.1732048 -0.8892827 0.42322 -0.173382 -0.8938894 0.4191883 -0.1588802 -0.9258943 0.3429319 -0.1584854 -0.9240019 0.3450257 -0.1648565 -0.9486491 0.2701643 -0.164549 -0.9501054 0.2685052 -0.1587602 -0.9690579 0.1887934 -0.1590093 -0.9695926 0.1877338 -0.1569911 -0.9817468 0.1071946 -0.1571075 -0.9797677 0.1108708 -0.1666221 -0.985678 0.0257802 -0.1666563 -0.9857577 0.02549636 -0.1662284 -0.9845493 -0.0557056 -0.1660112 -0.9844403 -0.05528271 -0.1667964 -0.9764917 -0.1370576 -0.1663708 -0.9761813 -0.1358226 -0.1691812 -0.9618713 -0.2147303 -0.1693944 -0.9624695 -0.2181164 -0.1614866 -0.9416338 -0.2953046 -0.1616206 -0.941463 -0.2940967 -0.1647865 -0.9131202 -0.3729671 -0.1646423 -0.9130057 -0.3694586 -0.1729773 -0.8791772 -0.4437801 -0.1735126 -0.8789081 -0.4480186 -0.1637074 -0.8413246 -0.515198 -0.1635354 -0.8411634 -0.5165179 -0.1601668 -0.7932684 -0.5874665 -0.1600267 -0.7939316 -0.5848267 -0.1662839 -0.7430315 -0.6483648 -0.1659139 -0.7436687 -0.6460524 -0.171969 -0.6880314 -0.7049401 -0.1722565 -0.6866386 -0.7080711 -0.1648115 -0.6254953 -0.7626254 -0.1647972 -0.6258245 -0.7620354 -0.1662706 -0.5616945 -0.810486 -0.166168 -0.5623387 -0.8094424 -0.1690515 -0.491317 -0.8544149 -0.1690647 -0.4899287 -0.856192 -0.1640282 -0.4203661 -0.8924509 -0.1637798 -0.4218446 -0.8907696 -0.1690465 -0.4218447 -0.8907696 -0.1690464 -0.4218446 -0.8907696 -0.1690464 -0.347504 -0.9223762 -0.1687102 -0.3451101 -0.9245907 -0.1613413 -0.2654617 -0.950463 -0.1617101 -0.2689357 -0.9476758 -0.172001 -0.1882457 -0.9670469 -0.1714175 -0.1868066 -0.9680086 -0.1675195 -0.1070043 -0.9800017 -0.1677701 -0.1065529 -0.9802519 -0.1665911 -0.02998173 -0.9855687 -0.1665996 -0.02984899 -0.9856364 -0.1662225 0.05565524 -0.9845125 -0.1662459 0.05537378 -0.9844477 -0.166723 0.1370636 -0.9764667 -0.1665129 0.1364286 -0.9763529 -0.1676975 0.2147936 -0.9622757 -0.1670007 0.2172937 -0.962732 -0.1610298 0.2172937 -0.962732 -0.1610298 0.2172937 -0.962732 -0.1610298 0.2953286 -0.9416185 -0.1616655 0.2939673 -0.9414842 -0.1648959 0.3729286 -0.9131202 -0.16473 0.3711683 -0.9130845 -0.1688519 0.4459863 -0.8790087 -0.1686419 0.4459177 -0.879032 -0.1687016 0.5176964 -0.8386795 -0.1691366 0.5153338 -0.8389841 -0.1747484 0.5811534 -0.7947471 -0.1750367 0.5847869 -0.7939547 -0.1663134 0.6484096 -0.7429599 -0.1660589 0.6460396 -0.7437002 -0.1718806 0.7050388 -0.6878918 -0.1724101 0.7079403 -0.6867539 -0.1648929 0.7626135 -0.6255543 -0.1646288 0.7620795 -0.6258075 -0.1661321 0.8104615 -0.5617012 -0.1662642 0.8094544 -0.5623953 -0.1688055 0.8094543 -0.5623953 -0.1688055 0.8094543 -0.5623953 -0.1688055 0.8543477 -0.4913827 -0.1692132 0.8562479 -0.4898592 -0.1639437 0.892403 -0.4204914 -0.1637195 0.8908478 -0.4217871 -0.168778 0.9242578 -0.342509 -0.1686279 0.9224513 -0.3442565 -0.1748462 0.9468516 -0.270003 -0.1748445 0.9485124 -0.2678888 -0.1689971 0.9673796 -0.1882998 -0.1694698 0.967884 -0.1874049 -0.1675713 0.967884 -0.1874049 -0.1675713 0.967884 -0.187405 -0.1675713 0.9800132 -0.1068277 -0.1678158 0.98021 -0.106565 -0.1668306 0.9802099 -0.106565 -0.1668306 0.98021 -0.106565 -0.1668306 0.9857032 -0.02578085 -0.1665071 0.985755 -0.02567088 -0.166217 0.9847695 0.05151295 -0.1660592 0.9846695 0.05111062 -0.1667745 0.9764963 0.1370552 -0.1663459 0.9761736 0.1356487 -0.1693655 0.9608955 0.218911 -0.1695814 0.960703 0.2178908 -0.1719691 0.9400352 0.2946285 -0.1718374 0.9397717 0.2935684 -0.1750621 0.9130458 0.3685424 -0.1747112 0.9131196 0.3736695 -0.1630459 0.8805875 0.4446669 -0.16382 0.8806678 0.444545 -0.1637192 0.8394469 0.5182815 -0.1634418 0.2258188 -0.44683 -0.8656495 0.1884171 -0.4624624 -0.8663877 0.0695433 -0.4950163 -0.8660962 -0.05295562 -0.4969739 -0.8661482 -0.2462012 -0.4347303 -0.8662531 -0.3370739 -0.3680078 -0.8665747 -0.3370738 -0.368008 -0.8665746 -0.3370738 -0.3680081 -0.8665745 -0.3765634 -0.3297429 -0.8657193 -0.4015758 -0.2954818 -0.8668492 -0.4463031 -0.2257177 -0.8659475 -0.4619756 -0.1882571 -0.8666821 -0.4953044 -0.06694155 -0.8661364 -0.4966295 0.05585569 -0.8661636 -0.4315643 0.2529723 -0.8658853 -0.3532168 0.3532294 -0.866295 -0.3532168 0.3532292 -0.8662949 -0.3532168 0.3532295 -0.8662949 -0.329751 0.3756498 -0.866113 -0.2950437 0.4008654 -0.8673271 -0.2258591 0.4466595 -0.8657269 -0.1884306 0.4624698 -0.8663808 -0.06959384 0.4951226 -0.8660315 0.1371831 0.4799742 -0.8664904 0.2528852 0.4310088 -0.8661875 0.2528851 0.4310088 -0.8661875 0.2528851 0.4310088 -0.8661874 0.3372226 0.3678648 -0.8665775 0.3372227 0.3678649 -0.8665774 0.3372228 0.367865 -0.8665773 0.3765146 0.3298758 -0.8656899 0.4015597 0.2954841 -0.8668559 0.4462679 0.2256814 -0.8659752 0.4628437 0.1886109 -0.8661418 0.4940053 0.06940388 -0.8666845 0.4826323 -0.1281804 -0.8663924 0.4315643 -0.2529723 -0.8658853 0.3530506 -0.3532497 -0.8663544 0.3530505 -0.3532497 -0.8663545 0.3530505 -0.3532499 -0.8663544 0.329751 -0.3756498 -0.866113 0.2950953 -0.4008393 -0.8673216 -0.221274 -0.07415908 -0.9723879 -0.07745909 0.2193792 -0.97256 -0.07745903 0.2193793 -0.97256 -0.07745903 0.2193794 -0.97256 -0.1918751 0.1437944 -0.9708281 -0.2241343 0.2606982 -0.9390422 -0.1741914 0.1534965 -0.9726748 -0.1977421 0.2185918 -0.9555709 -0.04554003 0.2573793 -0.9652368 -0.1772378 0.1533744 -0.9721436 -0.03713262 0.2098259 -0.9770335 -0.002087891 0.1789538 -0.9838553 0.01310598 0.177206 -0.9840865 -3.91886e-6 0.1774169 -0.9841358 0 0.177417 -0.9841358 0 0.177417 -0.9841359 0.140219 0.1903276 -0.9716553 0.2608501 0.2240815 -0.9390127 0.1497843 0.1730884 -0.9734502 0.2191371 0.1975939 -0.9554766 0.2579833 0.04333055 -0.9651773 0.1473464 0.1866229 -0.9713193 0.1473463 0.1866229 -0.9713193 0.1473463 0.1866229 -0.9713192 0.2082363 0.03497123 -0.9774531 0.1796301 0.002787828 -0.9837303 0.1772163 -0.01302462 -0.9840858 0.1773366 0 -0.9841503 0.190606 -0.140119 -0.9716152 0.2241759 -0.2614798 -0.9388149 0.1656731 -0.1547817 -0.9739584 0.1883202 -0.2216762 -0.9567629 0.04552632 -0.2573474 -0.965246 0.1770259 -0.1529281 -0.9722525 0.03713822 -0.2098575 -0.9770265 0.00208795 -0.1789622 -0.9838538 -0.01313412 -0.1772325 -0.9840814 3.13728e-6 -0.177309 -0.9841553 0 -0.1773091 -0.9841553 0 -0.1773091 -0.9841553 -0.1429741 -0.1912749 -0.9710676 -0.2724216 -0.2249672 -0.9355086 -0.2724215 -0.2249671 -0.9355086 -0.2724215 -0.2249671 -0.9355086 -0.1531368 -0.1739962 -0.9727664 -0.2192453 -0.1978591 -0.955397 -0.2192452 -0.1978591 -0.955397 -0.2192452 -0.197859 -0.955397 -0.2575477 -0.04517424 -0.9652091 -0.1522178 -0.1795317 -0.9719044 -0.1522177 -0.1795316 -0.9719044 -0.152218 -0.1795318 -0.9719044 -0.209958 -0.03686487 -0.9770153 -0.1795777 -0.002723813 -0.9837401 -0.177221 0.01080244 -0.9841119 -0.1774168 0 -0.9841358 0.3305557 -0.3750891 -0.8660492 0.3007158 -0.3914914 -0.8696577 0.2574768 -0.3351776 -0.9062901 0.2142343 -0.3643409 -0.9062889 0.1743055 -0.2964157 -0.9390184 0.1377574 -0.3151876 -0.9389781 0.3578674 -0.3480249 -0.8664928 0.3450345 -0.353925 -0.8693034 0.2956966 -0.3032904 -0.9058579 0.2565121 -0.3371948 -0.9058152 0.207925 -0.2732821 -0.9391934 0.1750093 -0.2954584 -0.9391891 0.4123944 -0.283453 -0.865786 0.412714 -0.2831846 -0.8657215 0.3810642 -0.314196 -0.8695235 0.3883391 -0.3114393 -0.8672937 0.3298659 -0.2644733 -0.9062243 0.2961533 -0.3016671 -0.9062506 0.2402849 -0.2447725 -0.9393347 0.2084704 -0.2722557 -0.9393705 0.4326331 -0.2510787 -0.865903 0.4199972 -0.2615818 -0.8690094 0.3592059 -0.2237561 -0.9060378 0.3296478 -0.2655333 -0.9059937 0.2674284 -0.2154207 -0.939189 0.2399419 -0.2456107 -0.9392036 0.4693099 -0.173951 -0.8657304 0.4685899 -0.1758293 -0.8657412 0.44861 -0.2108049 -0.8685104 0.4514074 -0.20876 -0.8675544 0.3829042 -0.1770965 -0.9066538 0.3594113 -0.2207511 -0.9066932 0.2924472 -0.179651 -0.9392551 0.267574 -0.2147937 -0.9392912 0.2171192 -0.1742574 -0.9604654 0.1944329 -0.1990141 -0.9605152 0.1793264 -0.1989838 -0.963456 0.1629732 -0.2129154 -0.9633831 0.1868208 -0.2139393 -0.9588159 0.1439152 -0.2429564 -0.9593023 0.1182317 -0.2393206 -0.9637152 0.1071375 -0.2450944 -0.9635613 0.1235054 -0.2497553 -0.9604003 0.1218181 -0.2502558 -0.9604855 0.480183 -0.137635 -0.866303 0.4707067 -0.1515339 -0.8691793 0.4023385 -0.1295729 -0.9062752 0.3830631 -0.1787024 -0.9062715 0.3115232 -0.1453844 -0.939051 0.2922879 -0.1809778 -0.93905 0.2223007 -0.1377326 -0.9652006 0.2276131 -0.1300238 -0.9650318 0.07399433 -0.2213968 -0.9723726 0.07399433 -0.2213967 -0.9723726 0.07399433 -0.2213968 -0.9723726 0.4966879 -0.05553394 -0.8661509 0.4974377 -0.04981577 -0.8660683 0.4861767 -0.09623366 -0.8685455 0.4874553 -0.09464043 -0.8680039 0.4153709 -0.08067387 -0.9060677 0.4024791 -0.1304644 -0.9060848 0.3266436 -0.1059013 -0.9391958 0.3114952 -0.1445199 -0.9391938 0.2370145 -0.1099736 -0.9652616 0.2224575 -0.1369739 -0.9652725 0.1530499 -0.09434849 -0.9837043 0.07596212 -0.2232827 -0.9717895 0.1659868 -0.06947308 -0.9836778 0.1631346 -0.07549548 -0.9837112 0.2370253 -0.109695 -0.9652907 0.248479 -0.0804255 -0.9652926 0.3266469 -0.105697 -0.9392178 0.3370894 -0.06534284 -0.9392024 0.415315 -0.08053451 -0.9061058 0.4219808 -0.03026431 -0.9060996 0.4923492 -0.03541207 -0.8696771 0.4942969 0.02707403 -0.8688715 0.4942969 0.02707403 -0.8688715 0.4942969 0.02707403 -0.8688715 0.4996606 -0.01451849 -0.8660996 0.49984 -0.01321786 -0.8660169 0.4934578 0.07268053 -0.8667278 0.4954257 0.02510064 -0.8682876 0.4219416 0.02130907 -0.9063727 0.4214448 -0.02926176 -0.9063819 0.3428145 -0.02372545 -0.9391034 0.3372284 -0.06597352 -0.9391084 0.2564371 -0.05019032 -0.9652569 0.2484697 -0.08081239 -0.9652627 0.1689137 -0.05491799 -0.9840998 0.1631198 -0.06979936 -0.9841342 0.171982 -0.06452888 -0.9829844 0.171982 -0.0645287 -0.9829844 0.171982 -0.06452876 -0.9829844 0.1689161 -0.05488216 -0.9841013 0.1744036 -0.0335285 -0.9841033 0.2563284 -0.04927909 -0.9653328 0.2604323 -0.01860123 -0.965313 0.3431079 -0.02449381 -0.9389766 0.343523 0.01634067 -0.9390021 0.4226777 0.02015417 -0.9060559 0.4170891 0.07153153 -0.9060463 0.4865954 0.08341872 -0.8696357 0.4700429 0.1492633 -0.8699312 0.4887285 0.1061067 -0.8659596 0.487834 0.1100743 -0.8659687 0.4639123 0.1858443 -0.8661682 0.4639124 0.1858446 -0.8661681 0.4639124 0.1858447 -0.8661681 0.4782109 0.1414186 -0.8667844 0.4056123 0.1200596 -0.9061262 0.4169673 0.07162511 -0.9060951 0.3386933 0.05819493 -0.9390954 0.343277 0.01689863 -0.9390822 0.2611413 0.01284664 -0.9652152 0.2607288 -0.01977151 -0.9652096 0.1772952 -0.01342666 -0.9840662 0.1744375 -0.03488391 -0.9840502 0.4464812 0.2254371 -0.8659288 0.4524447 0.1994466 -0.8692036 0.3868024 0.1705501 -0.9062542 0.4051762 0.1203919 -0.9062771 0.3292466 0.09788691 -0.9391565 0.3384556 0.05858612 -0.9391568 0.2572706 0.04456144 -0.9653114 0.2607548 0.01386708 -0.9653056 0.1792432 0.009441971 -0.9837595 0.1776304 0.005635261 -0.9840812 0.4243485 0.2618011 -0.8668268 0.4261434 0.2503408 -0.8693281 0.3649216 0.2144162 -0.9060122 0.3874978 0.170021 -0.9060565 0.3138852 0.1376999 -0.9394227 0.3279397 0.09933489 -0.9394617 0.2791412 0.08452171 -0.9565231 0.2548767 0.02214914 -0.9667199 0.3777267 0.3286423 -0.8656309 0.3930937 0.3006309 -0.868964 0.3361055 0.2570672 -0.9060627 0.3647862 0.2144392 -0.9060612 0.2955647 0.1737908 -0.9393818 0.3142459 0.1373338 -0.9393556 0.3493452 0.3566682 -0.8664559 0.3544046 0.3455476 -0.8689041 0.3023709 0.2948389 -0.9064447 0.3345134 0.2576911 -0.9064745 0.2720831 0.209623 -0.939164 0.2969079 0.1729138 -0.9391202 0.2860321 0.410676 -0.8657545 0.2829644 0.4126936 -0.8658031 0.3142585 0.381042 -0.8695106 0.3107962 0.3899276 -0.8668116 0.2631444 0.3301161 -0.90652 0.3021932 0.2947759 -0.9065244 0.2458392 0.2398611 -0.9391644 0.272026 0.20972 -0.9391589 0.2487581 0.433338 -0.8662204 0.2602637 0.41957 -0.8696113 0.2228431 0.3592974 -0.9062265 0.2642942 0.3298502 -0.9062822 0.2147293 0.2680176 -0.9391795 0.2455775 0.2399522 -0.9392096 0.1767945 0.4682552 -0.8657256 0.1757248 0.4684489 -0.8658387 0.2108582 0.4486133 -0.8684958 0.2092555 0.4507254 -0.8677896 0.1781493 0.3837286 -0.9060989 0.2235823 0.3592198 -0.9060751 0.1815068 0.2916554 -0.9391445 0.2151102 0.2679013 -0.9391255 0.1743142 0.2171169 -0.9604556 0.199023 0.1944411 -0.9605116 0.1989772 0.1778082 -0.9637388 0.2115159 0.163065 -0.9636758 0.2124717 0.1888455 -0.9587456 0.2441212 0.1421636 -0.9592677 0.240387 0.1162093 -0.9636958 0.2450659 0.1070861 -0.9635742 0.2497226 0.1235432 -0.9604039 0.2484078 0.1271532 -0.9602738 0.1348081 0.4805825 -0.866526 0.1506986 0.4698433 -0.8697915 0.1291097 0.4024786 -0.906279 0.177217 0.3836641 -0.906309 0.1438947 0.3115156 -0.939283 0.1806912 0.2916959 -0.9392893 0.1376875 0.2222855 -0.9652106 0.1300558 0.2276588 -0.9650166 0.2211927 0.07368975 -0.9724421 0.05294424 0.496985 -0.8661425 0.05836087 0.49656 -0.8660382 0.09435111 0.4874673 -0.8680285 0.09612661 0.4860724 -0.8686157 0.0820862 0.4149992 -0.9061112 0.1299447 0.4026539 -0.9060817 0.105484 0.3268062 -0.9391863 0.1445017 0.3115274 -0.9391857 0.110063 0.2372785 -0.9651866 0.1377128 0.2222968 -0.9652044 0.09467691 0.1527944 -0.9837124 0.222922 0.07603794 -0.9718663 0.06952917 0.1652743 -0.9837937 0.07466006 0.1629083 -0.9838124 0.1087943 0.2373578 -0.9653109 0.08042347 0.2484587 -0.9652981 0.1057989 0.3269234 -0.9391101 0.06535762 0.3372017 -0.9391611 0.08032196 0.4144632 -0.9065145 0.02889204 0.4212543 -0.9064823 0.03380757 0.492915 -0.8694205 -0.02694886 0.4943218 -0.8688611 0.01467239 0.4996805 -0.8660857 0.01307088 0.4997954 -0.8660449 -0.07278931 0.4948062 -0.8659496 -0.023207 0.4965229 -0.8677134 -0.01976501 0.4228156 -0.9060002 0.03122031 0.4223237 -0.9059073 0.0253272 0.3426367 -0.9391266 0.06556701 0.3372483 -0.9391298 0.04987001 0.2564944 -0.9652583 0.08084625 0.2485309 -0.9652442 0.05507177 0.1692638 -0.984031 0.07136988 0.1628812 -0.9840611 0.07382762 0.1583971 -0.9846116 0.05429112 0.1694424 -0.9840436 0.03487277 0.1743961 -0.984058 0.05136388 0.2567392 -0.9651149 0.01864504 0.2610774 -0.9651379 0.02444976 0.3423201 -0.9392653 -0.01781344 0.3428269 -0.9392297 -0.02190619 0.4215819 -0.9065257 -0.07136911 0.4160377 -0.9065424 -0.08367002 0.4877114 -0.8689861 -0.1476832 0.4720681 -0.8691037 -0.1116502 0.4876378 -0.8658773 -0.1065632 0.4888718 -0.8658226 -0.2002053 0.4580234 -0.8661019 -0.2002054 0.4580232 -0.8661019 -0.2002055 0.4580239 -0.8661016 -0.143341 0.4766844 -0.8673093 -0.1215993 0.4043942 -0.9064651 -0.07118606 0.4161282 -0.9065153 -0.05793601 0.3387737 -0.9390824 -0.01696717 0.3432188 -0.9391023 -0.01291573 0.2611129 -0.9652219 0.01778841 0.2607901 -0.9652317 0.01207685 0.1770316 -0.9841311 0.03269088 0.1742125 -0.9841654 -0.2238913 0.447566 -0.8657698 -0.2238913 0.447566 -0.8657698 -0.2238913 0.4475661 -0.8657699 -0.1975455 0.4538276 -0.8689168 -0.1686872 0.3874908 -0.9063088 -0.1209714 0.4050552 -0.906254 -0.0982874 0.3290989 -0.9391664 -0.05830478 0.3384959 -0.9391598 -0.04443705 0.2580053 -0.9651211 -0.01179236 0.2615412 -0.9651204 -0.008049786 0.1786936 -0.9838719 -0.005540609 0.1775865 -0.9840896 -0.2613788 0.4236251 -0.867308 -0.2524908 0.4250022 -0.869265 -0.2156136 0.3628656 -0.9065536 -0.1695118 0.3864403 -0.9066034 -0.1380887 0.3148073 -0.9390569 -0.09789609 0.3294733 -0.939076 -0.08274316 0.2784784 -0.9568716 -0.02202039 0.2549009 -0.9667165 -0.3281363 0.3770148 -0.866133 -0.3001381 0.3925541 -0.8693782 -0.2570167 0.3361069 -0.9060766 -0.2144442 0.3647951 -0.9060565 -0.1743083 0.2964808 -0.9389973 -0.1377594 0.3151456 -0.9389919 -0.3578856 0.3480223 -0.8664862 -0.3450419 0.353872 -0.869322 -0.2956685 0.3032655 -0.9058755 -0.2565507 0.3371506 -0.9058209 -0.2079337 0.2732815 -0.9391915 -0.1750149 0.2954581 -0.9391881 -0.4123749 0.2834558 -0.8657944 -0.4099879 0.2869092 -0.8657905 -0.3829033 0.3134925 -0.8689693 -0.3883666 0.3114645 -0.8672723 -0.3298476 0.2644586 -0.9062352 -0.2961533 0.3016671 -0.9062506 -0.2402809 0.2447637 -0.939338 -0.2084482 0.272257 -0.9393751 -0.4337018 0.2490444 -0.865956 -0.4205571 0.2601608 -0.8691653 -0.3593219 0.2222887 -0.9063529 -0.3299229 0.2639968 -0.9063424 -0.2677221 0.214196 -0.9393855 -0.2404868 0.2442473 -0.9394198 -0.4681736 0.1768755 -0.8657532 -0.4711638 0.169024 -0.8656995 -0.4467627 0.2122912 -0.8691005 -0.4514011 0.2087033 -0.8675714 -0.3836758 0.1774595 -0.9062566 -0.3593199 0.222454 -0.9063131 -0.2917299 0.1806734 -0.9392821 -0.2675479 0.214775 -0.9393029 -0.2171461 0.1743903 -0.9604352 -0.1951966 0.1982699 -0.9605141 -0.1787874 0.1982404 -0.9637095 -0.1624939 0.2122974 -0.9636003 -0.1877895 0.2132341 -0.9587838 -0.1439152 0.2429564 -0.9593023 -0.1172633 0.2392402 -0.9638534 -0.1069313 0.2445724 -0.9637169 -0.1242505 0.2494714 -0.960378 -0.1218166 0.2503131 -0.9604709 -0.2276278 0.1301041 -0.9650174 -0.2222864 0.1376287 -0.9652187 -0.2917242 0.1806744 -0.9392837 -0.3115121 0.1438704 -0.9392878 -0.3836068 0.1771852 -0.9063395 -0.4018375 0.1308801 -0.9063095 -0.4696847 0.1530226 -0.8694714 -0.487527 0.09420919 -0.8680104 -0.4810399 0.1377699 -0.8658061 -0.4818665 0.1351211 -0.8657639 -0.4962472 0.05950063 -0.86614 -0.4875946 0.09472489 -0.8679164 -0.4144828 0.08049952 -0.9064899 -0.4016799 0.130285 -0.9064652 -0.3266807 0.1059163 -0.9391813 -0.3115223 0.1445325 -0.9391828 -0.2374836 0.1101447 -0.9651268 -0.2220488 0.138856 -0.9650976 -0.1524078 0.09527659 -0.9837146 -0.07802361 0.2194795 -0.9724922 -0.1656884 0.06863921 -0.9837866 -0.1625975 0.0752471 -0.9838191 -0.2374977 0.109848 -0.9651572 -0.2490056 0.08064651 -0.9651385 -0.3266364 0.1056974 -0.9392214 -0.3367174 0.06677353 -0.9392352 -0.4150713 0.0822491 -0.9060636 -0.4219473 0.03032374 -0.9061132 -0.4922632 0.03540664 -0.8697261 -0.4953239 -0.02687406 -0.8682925 -0.4999889 0.007263183 -0.8660014 -0.4997878 0.01301896 -0.8660501 -0.4946174 -0.07233971 -0.8660951 -0.4964327 -0.02509003 -0.8677127 -0.4219739 -0.02137136 -0.9063561 -0.4214578 0.02926391 -0.9063758 -0.3420766 0.0237115 -0.939373 -0.3365231 0.06574243 -0.9393776 -0.2570152 0.05025684 -0.9650997 -0.2490243 0.08099269 -0.9651047 -0.1689137 0.05491799 -0.9840998 -0.1625969 0.07112562 -0.9841257 -0.1686159 0.06752395 -0.9833663 -0.1689347 0.05493426 -0.9840952 -0.1743826 0.03352427 -0.9841071 -0.2569004 0.04938906 -0.9651751 -0.2610181 0.01864308 -0.9651539 -0.3423579 0.02444028 -0.9392517 -0.342765 -0.01626789 -0.9392804 -0.4226793 -0.02008062 -0.9060568 -0.4170778 -0.0715928 -0.9060468 -0.4865299 -0.08353054 -0.8696616 -0.4717937 -0.1475328 -0.8692783 -0.4874194 -0.1116231 -0.8660039 -0.4878341 -0.1099494 -0.8659844 -0.463154 -0.1851059 -0.8667318 -0.4631538 -0.1851064 -0.8667318 -0.4631538 -0.1851065 -0.8667318 -0.4767821 -0.1428232 -0.8673411 -0.4052947 -0.1214298 -0.9060856 -0.4170044 -0.07170295 -0.9060718 -0.3379765 -0.05810654 -0.9393591 -0.342486 -0.01685881 -0.9393717 -0.2611287 -0.01284545 -0.9652186 -0.2607709 0.01778435 -0.965237 -0.1774777 0.01208996 -0.9840506 -0.1744918 0.03489834 -0.9840401 -0.446524 -0.2252987 -0.8659428 -0.45283 -0.1978486 -0.8693681 -0.3873029 -0.1692317 -0.9062876 -0.4045867 -0.1220536 -0.9063181 -0.3281953 -0.09904056 -0.9394035 -0.3377421 -0.05850934 -0.9394184 -0.2578526 -0.04466211 -0.9651516 -0.2615396 -0.01184827 -0.96512 -0.1793268 -0.008154034 -0.9837558 -0.1775501 -0.003823578 -0.9841043 -0.4243195 -0.2617837 -0.8668462 -0.4261465 -0.2503404 -0.8693267 -0.3649011 -0.2143464 -0.9060369 -0.3882309 -0.1685064 -0.9060256 -0.3149877 -0.1367495 -0.9391925 -0.3292547 -0.09778112 -0.9391646 -0.2784953 -0.08269101 -0.9568713 -0.254846 -0.02206897 -0.9667299 -0.3776388 -0.3288011 -0.865609 -0.3930913 -0.3006407 -0.8689618 -0.3355429 -0.2565847 -0.906408 -0.3632377 -0.2154313 -0.906448 -0.2950021 -0.1748908 -0.9393547 -0.3142184 -0.1373217 -0.9393666 -0.3480913 -0.3577927 -0.8664969 -0.353344 -0.3463279 -0.8690254 -0.3016628 -0.2956033 -0.9064317 -0.3354669 -0.25665 -0.9064175 -0.272781 -0.2086411 -0.9391802 -0.2959908 -0.1742669 -0.9391595 -0.2856708 -0.4101908 -0.8661039 -0.2854353 -0.4103544 -0.866104 -0.3142367 -0.3811086 -0.8694894 -0.3107836 -0.3898554 -0.8668485 -0.2631678 -0.3300796 -0.9065265 -0.3012005 -0.2957245 -0.9065458 -0.2447502 -0.2403037 -0.9393357 -0.271562 -0.2093714 -0.9393709 -0.2487385 -0.4333038 -0.8662431 -0.2609032 -0.4188477 -0.869768 -0.2237439 -0.3592202 -0.9060351 -0.2655594 -0.3296854 -0.9059723 -0.2156991 -0.2677727 -0.939027 -0.2469652 -0.2393951 -0.9389879 -0.1757375 -0.4685779 -0.8657662 -0.1783679 -0.467522 -0.8657992 -0.178368 -0.467522 -0.8657992 -0.2110399 -0.4489694 -0.8682675 -0.2094641 -0.4510808 -0.8675546 -0.177998 -0.383325 -0.9062994 -0.2224996 -0.3592985 -0.9063104 -0.1806634 -0.2917513 -0.9392774 -0.2138421 -0.2682253 -0.9393225 -0.1730114 -0.2170053 -0.9607163 -0.1990234 -0.1929871 -0.9608047 -0.1989812 -0.1792212 -0.9634761 -0.2123303 -0.163652 -0.9633971 -0.2132942 -0.1894237 -0.958449 -0.2443493 -0.1438297 -0.9589611 -0.240427 -0.1162217 -0.9636843 -0.2450646 -0.1071359 -0.9635691 -0.2496927 -0.1234619 -0.9604222 -0.2502738 -0.1220476 -0.9604517 -0.1296685 -0.2282253 -0.964935 -0.1378389 -0.2225955 -0.9651175 -0.1806939 -0.291784 -0.9392614 -0.1444447 -0.3111855 -0.9393079 -0.1779285 -0.3833511 -0.9063021 -0.1290897 -0.402525 -0.9062613 -0.1507872 -0.4701433 -0.869614 -0.09458529 -0.4864526 -0.8685722 -0.1346126 -0.4807743 -0.86645 -0.1355804 -0.4804126 -0.8664997 -0.05847531 -0.4962013 -0.8662362 -0.05847525 -0.4962013 -0.8662362 -0.05847525 -0.4962015 -0.8662361 -0.09632271 -0.4869456 -0.8681049 -0.08208775 -0.4149876 -0.9061164 -0.1299508 -0.4027014 -0.9060598 -0.1054735 -0.3267794 -0.9391968 -0.1452195 -0.3112797 -0.9391573 -0.1106802 -0.2372077 -0.9651334 -0.1378892 -0.2225175 -0.9651283 -0.09359109 -0.1511105 -0.9840764 -0.2196182 -0.07266575 -0.9728759 -0.2196183 -0.07266575 -0.972876 -0.2196183 -0.07266575 -0.972876 -0.06953352 -0.1652846 -0.9837918 -0.07465803 -0.1629039 -0.9838134 -0.1087943 -0.2373578 -0.9653109 -0.08002203 -0.2486117 -0.965292 -0.1051744 -0.3267599 -0.9392372 -0.0653389 -0.3370944 -0.9392008 -0.08033818 -0.4144523 -0.9065182 -0.02889204 -0.4212543 -0.9064823 -0.03380757 -0.492915 -0.8694205 0.02684593 -0.4942937 -0.8688804 -0.01467061 -0.4998682 -0.8659772 -0.01307088 -0.4997954 -0.8660449 0.07269525 -0.4946944 -0.8660213 0.07269531 -0.4946944 -0.8660213 0.07269519 -0.4946946 -0.8660213 0.02322036 -0.4964834 -0.8677357 0.01977467 -0.4228591 -0.9059796 -0.03108173 -0.4222125 -0.9059639 -0.02521824 -0.3427041 -0.9391049 -0.06594973 -0.3371853 -0.9391256 -0.05015301 -0.2565991 -0.9652159 -0.08092164 -0.2486492 -0.9652075 -0.05508297 -0.1693057 -0.9840231 -0.07139152 -0.1628721 -0.984061 -0.07407754 -0.1587375 -0.9845379 -0.05425417 -0.169408 -0.9840516 -0.03487324 -0.1743664 -0.9840632 -0.05136227 -0.2567313 -0.9651171 -0.01864695 -0.2610574 -0.9651432 -0.02445513 -0.3423492 -0.9392546 0.01788848 -0.3427957 -0.9392397 0.02200073 -0.4215596 -0.9065338 0.07136535 -0.4160379 -0.9065427 0.08362632 -0.4875451 -0.8690837 0.1476593 -0.4721287 -0.8690751 0.1116514 -0.4874429 -0.865987 0.1073665 -0.4887693 -0.8657812 0.2003194 -0.4580121 -0.8660814 0.1433452 -0.4766373 -0.8673346 0.1216111 -0.4043597 -0.9064789 0.07120233 -0.4162161 -0.9064736 0.05795454 -0.338738 -0.9390943 0.01696467 -0.3432148 -0.9391038 0.01291543 -0.2611528 -0.9652112 -0.01765179 -0.2607625 -0.9652417 -0.01198649 -0.177012 -0.9841358 -0.03269267 -0.1742742 -0.9841544 0.2238537 -0.4477073 -0.8657066 0.1975497 -0.4538024 -0.8689291 0.1688238 -0.3878482 -0.9061305 0.1205173 -0.4054315 -0.9061462 0.09787172 -0.3292058 -0.9391724 0.0583015 -0.3385108 -0.9391546 0.04443049 -0.257988 -0.965126 0.01189666 -0.261502 -0.9651296 0.008123815 -0.1786746 -0.9838747 0.00559473 -0.1776335 -0.9840808 0.2603967 -0.424312 -0.8672675 0.2518151 -0.4255626 -0.8691868 0.21492 -0.3632258 -0.906574 0.1701793 -0.3861126 -0.906618 0.1385273 -0.3142957 -0.9391638 0.09782761 -0.3292428 -0.9391641 0.08273035 -0.2784618 -0.9568777 0.02213001 -0.2548701 -0.966722 0.4983864 -0.7432001 -0.4463908 0.4996989 -0.7423336 -0.4463651 0.4952459 -0.7449762 -0.4469251 0.495246 -0.7449761 -0.4469252 0.4952459 -0.7449761 -0.4469251 0.4982753 -0.7429193 -0.4469817 0.4989932 -0.7431257 -0.4458364 0.5055328 -0.7379051 -0.4471383 0.5014305 -0.7411104 -0.4464558 0.497986 -0.7435613 -0.4462358 0.5030684 -0.7402051 -0.4461151 0.5013113 -0.7414397 -0.446043 0.5027248 -0.7405695 -0.4458976 0.9318113 -0.3628783 0.006854474 0.9460405 -0.3240486 0 0.9694588 -0.2452543 0 0.978758 -0.2049047 0.006850779 0.9991471 -0.04072481 0.00683695 0.9999999 6.06164e-4 0 0.9922264 0.1242555 0.006881535 0.9862324 0.1653653 0 0.9694271 0.2453796 0 0.9582059 0.2859938 0.007004022 0.8983859 0.4391549 0.006773591 0.8133289 0.5817669 0.006604254 0.7349974 0.67807 0 0.7068921 0.7072898 0.00670135 0.6777032 0.7353356 0 0.6136717 0.7895613 0 0.5798687 0.81468 0.006989359 0.5450273 0.8384184 0 0.4388967 0.8985119 0.006792545 0.2853953 0.9583864 0.006713271 0.2462685 0.9692016 0 0.1232464 0.9923526 0.00683844 -0.04323911 0.9990392 0.007164895 -0.2054616 0.9786406 0.006940484 -0.2463396 0.9691836 0 -0.4789206 0.8778584 0 -0.5124663 0.8586835 0.006398916 -0.5453686 0.8381963 0 -0.6139882 0.7893154 0 -0.6466235 0.7627776 0.006963491 -0.7374029 0.6754532 0 -0.7634008 0.645892 0.006540596 -0.8596736 0.5107973 0.006881773 -0.880155 0.4746866 0 -0.9318156 0.3628674 0.006859898 -0.9460473 0.3240287 0 -0.969455 0.2452698 0 -0.9787567 0.2049112 0.006853818 -0.9991472 0.0407235 0.006836235 -0.9999999 -6.06125e-4 0 -0.992226 -0.1242595 0.006876111 -0.9862307 -0.1653758 0 -0.9694309 -0.2453643 0 -0.9582086 -0.2859849 0.007003784 -0.8983859 -0.4391549 0.006767928 -0.8133289 -0.5817669 0.006609857 -0.7349676 -0.6781023 0 -0.706892 -0.7072897 0.006712615 -0.6777378 -0.7353038 0 -0.6136314 -0.7895926 0 -0.5798689 -0.8146802 0.006966829 -0.5450723 -0.838389 0 -0.4388967 -0.8985119 0.00680381 -0.2853657 -0.9583951 0.006735861 -0.2462077 -0.9692171 0 -0.1232463 -0.9923524 0.006860971 0.04323911 -0.999039 0.00717616 0.2054308 -0.9786472 0.006918013 0.2462788 -0.969199 0 0.4789698 -0.8778314 0 0.5124663 -0.8586837 0.00638765 0.5453236 -0.8382257 0 0.6140285 -0.7892839 0 0.6466424 -0.7627617 0.006952106 0.7373731 -0.6754857 0 0.7633876 -0.6459077 0.006546378 0.8596816 -0.510784 0.0068928 0.8801695 -0.4746596 0 0.6484081 -0.163545 -0.7435187 0.6484869 -0.1586822 -0.744503 0.6590468 -0.1095956 -0.7440741 0.6596481 -0.1094229 -0.7435664 0.6662534 -0.05462688 -0.743722 0.6659759 -0.0549972 -0.7439432 0.6659322 -0.05500715 -0.7439815 0.6684057 3.93184e-4 -0.7437968 0.6683719 4.12848e-4 -0.7438272 0.6683785 3.93395e-4 -0.7438212 0.6683785 3.9335e-4 -0.7438212 0.6683784 3.93359e-4 -0.7438213 0.6659794 0.05567026 -0.74389 0.6657824 0.05553144 -0.7440767 0.6587632 0.1103963 -0.7442068 0.6587633 0.1103964 -0.7442067 0.6587633 0.1103963 -0.7442067 0.6587057 0.1105252 -0.7442387 0.6590141 0.1103371 -0.7439934 0.6475625 0.1641252 -0.7441276 0.6473163 0.1641851 -0.7443286 0.6487305 0.1627324 -0.7434157 0.6323484 0.2175354 -0.7435145 0.6326195 0.217875 -0.7431844 0.6113624 0.2726359 -0.7429036 0.61129 0.2678626 -0.7446975 0.6109809 0.2679218 -0.7449297 0.5862664 0.3180538 -0.7450729 0.5889009 0.3180825 -0.74298 0.5843592 0.3208538 -0.7453705 0.5576333 0.3647897 -0.7456364 0.5587383 0.3667044 -0.7438679 0.5285857 0.4089635 -0.7438724 0.5278467 0.4107394 -0.7434185 0.5288885 0.4108542 -0.7426141 0.4929932 0.453287 -0.7426228 0.4879977 0.4535477 -0.7457565 0.4515361 0.4898835 -0.7457408 0.4515361 0.4898835 -0.7457408 0.4515361 0.4898834 -0.7457408 0.4523755 0.4931668 -0.7430632 0.400408 0.5366702 -0.7427372 0.4004078 0.5366704 -0.7427372 0.4004079 0.5366705 -0.7427372 0.4093838 0.5268667 -0.7448601 0.4133432 0.5285021 -0.7415072 0.3670728 0.5617163 -0.7414395 0.3670752 0.5617147 -0.7414395 0.3670752 0.5617147 -0.7414395 0.365849 0.56106 -0.7425403 0.3607775 0.5604668 -0.745464 0.316622 0.5863391 -0.7456253 0.3166546 0.5845184 -0.7470397 0.2674252 0.6084944 -0.7471402 0.2673352 0.6097112 -0.7461797 0.2154109 0.6298738 -0.7462286 0.2192751 0.6331483 -0.7423219 0.1641302 0.6493096 -0.7426025 0.1633322 0.6523595 -0.7401012 0.1581436 0.6527353 -0.7408962 0.1094414 0.662848 -0.7407126 0.1116378 0.6566792 -0.7458616 0.05486285 0.6636467 -0.7460316 0.05303186 0.6652705 -0.7447167 0.05402892 0.6660858 -0.7439158 0.05402892 0.6660858 -0.7439157 0.05402886 0.6660857 -0.7439158 0 0.6682193 -0.7439644 0 0.6683664 -0.7438323 0 0.6684381 -0.7437679 -0.05442136 0.6659725 -0.7439886 -0.05623644 0.6688446 -0.7412722 -0.1182385 0.6610452 -0.7409716 -0.1088538 0.6574954 -0.7455539 -0.1088538 0.6574956 -0.7455538 -0.1088538 0.6574955 -0.7455539 -0.1089251 0.6575077 -0.7455327 -0.1646071 0.6458454 -0.7455121 -0.164607 0.6458455 -0.7455121 -0.1646071 0.6458455 -0.7455121 -0.1581194 0.6508225 -0.7425823 -0.2189744 0.6340174 -0.7416685 -0.2750433 0.6116716 -0.7417609 -0.2684231 0.6118736 -0.7440161 -0.3191193 0.5885903 -0.7427815 -0.3190414 0.5880587 -0.7432359 -0.3168399 0.5918457 -0.7411688 -0.36738 0.5616732 -0.7413199 -0.3671981 0.5615118 -0.7415323 -0.4136503 0.5282091 -0.7415447 -0.4136503 0.5282091 -0.7415447 -0.4136503 0.5282092 -0.7415447 -0.4113473 0.5289048 -0.7423296 -0.4113473 0.5289048 -0.7423296 -0.4113473 0.5289047 -0.7423296 -0.4111859 0.5275778 -0.7433626 -0.4541779 0.4913462 -0.7431699 -0.4548069 0.4943729 -0.740774 -0.4555862 0.4910674 -0.7424918 -0.4936491 0.4530862 -0.7423096 -0.4890305 0.4518033 -0.7461388 -0.5195708 0.4170271 -0.7457444 -0.5271294 0.409516 -0.7446014 -0.5274357 0.4102499 -0.7439804 -0.5597051 0.3647384 -0.7441076 -0.5592747 0.3637577 -0.7449109 -0.5596894 0.3671085 -0.742953 -0.5890386 0.3174177 -0.7431552 -0.5864811 0.3174603 -0.745157 -0.6131848 0.2679539 -0.7431051 -0.633119 0.2158321 -0.7433552 -0.6316627 0.2167599 -0.7443235 -0.6321441 0.217767 -0.7436205 -0.6481891 0.1635944 -0.7436987 -0.6483781 0.1635318 -0.7435477 -0.6490436 0.1588185 -0.7439887 -0.6590502 0.1095886 -0.744072 -0.6595841 0.1094183 -0.7436239 -0.6663489 0.0546444 -0.7436351 -0.666007 0.05499517 -0.7439156 -0.6659103 0.05499762 -0.7440019 -0.6683967 -3.9321e-4 -0.7438049 -0.6683915 -4.12888e-4 -0.7438095 -0.6682017 -3.98932e-4 -0.7439802 -0.6660147 -0.05567127 -0.7438582 -0.6657507 -0.05552697 -0.7441054 -0.6585807 -0.1103993 -0.7443679 -0.6585929 -0.1105138 -0.7443401 -0.6590788 -0.1103479 -0.7439345 -0.6475731 -0.1641279 -0.7441176 -0.6473593 -0.1641772 -0.7442928 -0.6485343 -0.1626863 -0.743597 -0.6323055 -0.2175207 -0.7435554 -0.6327086 -0.2179027 -0.7431005 -0.6112833 -0.2726882 -0.7429494 -0.6112835 -0.2726883 -0.7429493 -0.6112835 -0.2726882 -0.7429493 -0.6114075 -0.2678849 -0.744593 -0.6110087 -0.2679145 -0.7449095 -0.5862275 -0.3180327 -0.7451124 -0.5888433 -0.3180514 -0.743039 -0.5842669 -0.3208801 -0.7454316 -0.5576646 -0.3647805 -0.7456175 -0.5587722 -0.3667652 -0.7438125 -0.528702 -0.4090535 -0.7437403 -0.5279138 -0.410757 -0.7433611 -0.5287746 -0.4107972 -0.7427269 -0.4930248 -0.453357 -0.7425591 -0.4880018 -0.453441 -0.7458187 -0.4514929 -0.4898056 -0.7458182 -0.4522521 -0.4929957 -0.7432519 -0.3999875 -0.5368497 -0.742834 -0.3999878 -0.5368502 -0.7428336 -0.3999878 -0.5368501 -0.7428336 -0.4094381 -0.5269365 -0.7447808 -0.413374 -0.528494 -0.7414959 -0.3671796 -0.5619274 -0.7412266 -0.3659231 -0.5612062 -0.7423934 -0.3607616 -0.560423 -0.7455047 -0.316667 -0.586507 -0.7454741 -0.3167154 -0.5845488 -0.74699 -0.2674673 -0.608487 -0.7471311 -0.2673618 -0.6097718 -0.7461207 -0.2154743 -0.6300593 -0.7460538 -0.2192198 -0.6329886 -0.7424744 -0.1641303 -0.6495062 -0.7424305 -0.1632876 -0.6522088 -0.7402437 -0.1632877 -0.6522089 -0.7402437 -0.1632876 -0.6522088 -0.7402438 -0.1587622 -0.6528181 -0.740691 -0.1094712 -0.6630284 -0.7405467 -0.1116203 -0.6565759 -0.7459552 -0.05473935 -0.6636512 -0.7460367 -0.05301076 -0.6650059 -0.7449544 -0.05412364 -0.6663539 -0.7436687 0 -0.668434 -0.7437715 0 -0.6684328 -0.7437726 0 -0.6684477 -0.7437591 0 -0.6684479 -0.7437592 0 -0.6684477 -0.7437592 0.05443614 -0.6661536 -0.7438253 0.05630999 -0.6691869 -0.7409576 0.1183454 -0.6608889 -0.7410941 0.1088502 -0.6574205 -0.7456205 0.10886 -0.6575124 -0.745538 0.1646707 -0.6460921 -0.7452843 0.1579722 -0.6510353 -0.7424271 0.2189381 -0.6339123 -0.7417691 0.2749915 -0.6118722 -0.7416145 0.2749915 -0.6118722 -0.7416145 0.2684257 -0.6118731 -0.7440155 0.2679181 -0.6133963 -0.7429435 0.3191143 -0.5885914 -0.7427828 0.3190461 -0.5880436 -0.7432458 0.3190461 -0.5880436 -0.7432458 0.3190461 -0.5880436 -0.7432458 0.3167054 -0.5918737 -0.7412039 0.36728 -0.5615205 -0.7414851 0.3673147 -0.5616132 -0.7413977 0.4138224 -0.5280627 -0.7415531 0.4114784 -0.5289797 -0.7422035 0.4114785 -0.5289797 -0.7422034 0.411318 -0.5277473 -0.7431691 0.4541425 -0.4913561 -0.7431849 0.4549416 -0.4946106 -0.7405326 0.4556 -0.4909543 -0.7425581 0.4934804 -0.4529734 -0.7424906 0.4890954 -0.4518634 -0.7460598 0.5196192 -0.416627 -0.7459342 0.5271535 -0.4095088 -0.7445883 0.5273222 -0.4102002 -0.7440881 0.5598534 -0.3648351 -0.7439486 0.5593451 -0.3638035 -0.7448357 0.5596937 -0.3671072 -0.7429504 0.5891334 -0.3174565 -0.7430635 0.5863795 -0.3174249 -0.745252 0.6130502 -0.2678757 -0.7432443 0.6331843 -0.2158964 -0.7432808 0.6317265 -0.2167932 -0.7442597 0.6321424 -0.2177673 -0.7436218 0.6481701 -0.1635772 -0.7437191 0.8031915 -0.3509656 -0.4813592 0.8024047 -0.3511229 -0.4825551 0.828504 -0.2843212 -0.4824341 0.8295635 -0.2839171 -0.4808486 0.8493942 -0.2147161 -0.4821066 0.8643693 -0.1433841 -0.4819821 0.8730087 -0.07209181 -0.482347 0.8736285 -0.07167786 -0.4812853 0.8762833 5.43011e-4 -0.481796 0.8762175 5.31783e-4 -0.4819156 0.8731836 0.07283246 -0.4819191 0.8733218 0.0730319 -0.4816383 0.8645306 0.1450623 -0.4811899 0.8641766 0.1447377 -0.4819232 0.8493697 0.2152759 -0.4818999 0.8291837 0.2855728 -0.4805232 0.8023532 0.3515846 -0.4823045 0.802634 0.3522114 -0.4813792 0.7704503 0.4179651 -0.4813643 0.7706791 0.4184169 -0.480605 0.7331746 0.4812009 -0.4805213 0.7321908 0.4780477 -0.4851464 0.6898445 0.536794 -0.4857641 0.6907036 0.5399672 -0.4810033 0.64543 0.593454 -0.4808663 0.6457147 0.5959684 -0.4773619 0.5941765 0.6477721 -0.4768077 0.5939488 0.6451221 -0.4806688 0.5380544 0.692483 -0.480588 0.5381569 0.6887542 -0.4858034 0.4780691 0.7315573 -0.4860802 0.4775643 0.7364495 -0.4791393 0.4181481 0.7718601 -0.4789407 0.4183859 0.77022 -0.4813675 0.351917 0.802662 -0.4815478 0.3513103 0.805103 -0.477902 0.2848761 0.8271389 -0.4844451 0.2124493 0.848577 -0.4845438 0.2127906 0.8480176 -0.4853724 0.1464959 0.8617337 -0.485751 0.144738 0.8648805 -0.4806585 0.06968289 0.8741775 -0.4805809 0.06968283 0.8741776 -0.4805809 0.06968289 0.8741775 -0.4805809 0.07211011 0.8706717 -0.4865502 0 0.8736691 -0.4865207 0 0.8735435 -0.4867463 -0.07319742 0.8706072 -0.4865033 -0.07615506 0.8735294 -0.4807775 -0.07615506 0.8735293 -0.4807775 -0.07615506 0.8735294 -0.4807775 -0.1433256 0.8652815 -0.48036 -0.1450757 0.8667394 -0.4771959 -0.2170995 0.8514328 -0.4774202 -0.2170995 0.8514329 -0.47742 -0.2170994 0.8514329 -0.4774201 -0.212907 0.8482336 -0.4849437 -0.284722 0.8263454 -0.4858877 -0.35389 0.8017632 -0.4815992 -0.4141717 0.7690497 -0.4868516 -0.4780637 0.7310546 -0.4868413 -0.4783399 0.7312344 -0.4862995 -0.5403305 0.6907794 -0.480486 -0.5951457 0.6438758 -0.4808592 -0.5932133 0.6435949 -0.4836152 -0.6443204 0.5940119 -0.481665 -0.6443204 0.5940119 -0.4816648 -0.6921784 0.5377627 -0.4813528 -0.6927689 0.5376891 -0.4805849 -0.7345316 0.4787578 -0.4808892 -0.7345316 0.4787578 -0.4808892 -0.7345316 0.4787579 -0.4808892 -0.7346408 0.4787651 -0.4807152 -0.7710797 0.4173782 -0.4808654 -0.8031069 0.3509481 -0.481513 -0.802473 0.3511522 -0.4824202 -0.8285605 0.2843177 -0.482339 -0.8295495 0.2839278 -0.4808667 -0.8494296 0.2147255 -0.4820398 -0.8643525 0.1433923 -0.4820098 -0.8730193 0.07208901 -0.4823281 -0.8736281 0.07167792 -0.4812859 -0.8762217 -5.43014e-4 -0.4819082 -0.8762651 -5.31784e-4 -0.4818293 -0.873162 -0.07282507 -0.4819593 -0.8733849 -0.07304096 -0.4815225 -0.8645138 -0.1450707 -0.4812178 -0.8642131 -0.1447438 -0.4818558 -0.8494061 -0.2152852 -0.4818317 -0.8290416 -0.2855238 -0.4807977 -0.8023002 -0.3515419 -0.4824237 -0.8026674 -0.3522266 -0.4813125 -0.7705825 -0.4180369 -0.4810903 -0.7706504 -0.4183962 -0.480669 -0.7332169 -0.481258 -0.4803997 -0.7321288 -0.4780073 -0.48528 -0.6899389 -0.5368156 -0.4856063 -0.6906447 -0.5398782 -0.4811876 -0.6453521 -0.5934248 -0.4810069 -0.6453521 -0.5934248 -0.4810069 -0.6453522 -0.5934248 -0.4810069 -0.6456143 -0.5959334 -0.4775412 -0.6456143 -0.5959334 -0.4775412 -0.6456144 -0.5959334 -0.4775412 -0.5942199 -0.6477463 -0.4767888 -0.5939345 -0.6451095 -0.4807032 -0.5380623 -0.6924788 -0.480585 -0.538072 -0.6934633 -0.4791526 -0.4800834 -0.7347247 -0.4792699 -0.4801825 -0.7347103 -0.4791925 -0.4181135 -0.7717139 -0.4792065 -0.4184322 -0.7703002 -0.4811986 -0.3519822 -0.802798 -0.4812732 -0.3513374 -0.8051714 -0.4777667 -0.2848782 -0.8271378 -0.4844456 -0.2848782 -0.8271378 -0.4844455 -0.2848782 -0.8271378 -0.4844457 -0.2124126 -0.8484306 -0.4848159 -0.2128238 -0.8479213 -0.4855261 -0.2128238 -0.8479213 -0.485526 -0.2128238 -0.8479213 -0.4855262 -0.06968188 -0.8741666 -0.480601 -0.07211166 -0.8707107 -0.48648 -0.0721116 -0.8707108 -0.4864801 0 -0.8736568 -0.4865428 0 -0.8736569 -0.4865427 0 -0.8736569 -0.4865427 0.003809392 -0.8782061 -0.4782675 0.003809392 -0.8782061 -0.4782674 0.003809332 -0.878206 -0.4782676 0.07363343 -0.8751115 -0.4782866 0.07363343 -0.8751115 -0.4782865 0.07363337 -0.8751115 -0.4782865 0.07239961 -0.8740795 -0.4803574 0.1432656 -0.8652891 -0.4803642 0.1451251 -0.8666946 -0.4772621 0.1451252 -0.8666947 -0.477262 0.1451251 -0.8666946 -0.4772621 0.2171411 -0.8515982 -0.4771063 0.2171411 -0.8515982 -0.4771062 0.217141 -0.8515982 -0.4771062 0.2129725 -0.8484947 -0.4844581 0.2846918 -0.8262576 -0.4860546 0.3538719 -0.8018464 -0.4814739 0.4142611 -0.7691141 -0.4866737 0.4781064 -0.7310352 -0.4868283 0.4783806 -0.7312966 -0.4861661 0.5402005 -0.6905335 -0.4809855 0.5402005 -0.6905335 -0.4809854 0.5402005 -0.6905335 -0.4809854 0.5951097 -0.6438972 -0.4808751 0.5932635 -0.6436494 -0.4834809 0.644419 -0.5941089 -0.4814135 0.6921538 -0.5376918 -0.4814674 0.6927543 -0.5376778 -0.4806186 0.7345771 -0.4787016 -0.4808756 0.7346401 -0.4787656 -0.4807156 0.7711188 -0.4174356 -0.480753 0.8682808 -0.4682486 -0.1638042 0.9036661 -0.3954265 -0.1643945 0.9035249 -0.3956368 -0.1646643 0.9331287 -0.3193548 -0.1651772 0.9329506 -0.3195646 -0.1657759 0.9560431 -0.241674 -0.1660585 0.9559273 -0.2418342 -0.1664909 0.9726715 -0.1617484 -0.1665759 0.9725466 -0.1619218 -0.1671367 0.9826257 -0.08069634 -0.1671373 0.9859869 5.97561e-4 -0.1668218 0.9859884 5.97711e-4 -0.1668132 0.9826546 0.08217322 -0.1662451 0.9825592 0.08187997 -0.166953 0.9723887 0.1628627 -0.1671409 0.9724432 0.1630522 -0.1666384 0.9555339 0.2418644 -0.1686908 0.9321444 0.3201232 -0.1691984 0.9322718 0.3218899 -0.1650944 0.9031934 0.396324 -0.16483 0.9032011 0.3966071 -0.1641059 0.8669782 0.4706949 -0.1636918 0.8671908 0.4687244 -0.168159 0.82538 0.5388911 -0.1683574 0.8248992 0.5415282 -0.1621382 0.7774811 0.6078026 -0.1615522 0.7782431 0.6049395 -0.1684817 0.7243107 0.6685131 -0.1687135 0.7243624 0.6682685 -0.1694595 0.6675258 0.7250345 -0.1695119 0.6675258 0.7250345 -0.1695119 0.6675258 0.7250346 -0.1695119 0.6677456 0.7245472 -0.1707258 0.606622 0.7763859 -0.1709822 0.6052607 0.7788417 -0.164515 0.6052607 0.7788417 -0.164515 0.6052607 0.7788417 -0.164515 0.5366903 0.8276259 -0.1643137 0.5366902 0.8276259 -0.1643136 0.5366903 0.8276259 -0.1643136 0.5373314 0.8265911 -0.1673981 0.470633 0.8663752 -0.1670288 0.4690747 0.8682167 -0.1617675 0.3947008 0.9045633 -0.1611722 0.3961509 0.9029862 -0.1663748 0.3961505 0.9029864 -0.1663747 0.3961508 0.9029862 -0.1663748 0.3211005 0.9323036 -0.1664471 0.3197795 0.9334895 -0.1622917 0.240166 0.9570908 -0.1621655 0.242695 0.9551526 -0.169655 0.1626527 0.9719197 -0.1700478 0.1626527 0.9719197 -0.1700477 0.1626526 0.9719198 -0.1700477 0.1618623 0.9724579 -0.1677089 0.0809521 0.9827363 -0.1663615 0 0.9860923 -0.1661986 0 0.9860197 -0.1666293 -0.08564037 0.9823173 -0.1664888 -0.0851671 0.982201 -0.167415 -0.1627404 0.9722775 -0.1679053 -0.1618432 0.9721471 -0.1695193 -0.2399349 0.9558972 -0.169387 -0.2399349 0.9558971 -0.169387 -0.2430734 0.9563426 -0.162247 -0.3214374 0.9328969 -0.1624238 -0.3214374 0.9328969 -0.1624237 -0.3214373 0.9328969 -0.1624237 -0.3196677 0.9327877 -0.1664921 -0.3981189 0.9020513 -0.166748 -0.3981189 0.9020513 -0.1667479 -0.3981189 0.9020513 -0.166748 -0.3959631 0.9020999 -0.1715495 -0.4671415 0.8673829 -0.1715399 -0.472901 0.8668313 -0.1580137 -0.5379842 0.8268342 -0.1640684 -0.5379817 0.8268358 -0.1640684 -0.5379842 0.8268342 -0.1640685 -0.6077018 0.7769154 -0.1646237 -0.6077018 0.7769154 -0.1646237 -0.6077018 0.7769154 -0.1646237 -0.6049432 0.7776838 -0.1710312 -0.6682586 0.7242941 -0.1697897 -0.7245445 0.6679754 -0.169836 -0.7277049 0.6665801 -0.1616064 -0.7795266 0.6050232 -0.1621275 -0.7770503 0.6063978 -0.1687446 -0.7770503 0.6063978 -0.1687445 -0.7770503 0.6063978 -0.1687446 -0.8258416 0.5382089 -0.1682764 -0.8257298 0.5382692 -0.1686314 -0.8682711 0.4682852 -0.1637517 -0.9036701 0.3954187 -0.1643912 -0.9034869 0.3956256 -0.1648994 -0.9331201 0.3193744 -0.1651873 -0.9329544 0.3195469 -0.1657885 -0.9560449 0.2416689 -0.1660551 -0.9559009 0.2418441 -0.1666287 -0.9726573 0.161746 -0.1666611 -0.9725643 0.1619248 -0.1670306 -0.9826221 0.08069604 -0.1671584 -0.9859905 -5.9751e-4 -0.166801 -0.9859896 -5.97685e-4 -0.166806 -0.9826589 -0.08218091 -0.1662167 -0.9825489 -0.08187812 -0.1670145 -0.9724029 -0.1628651 -0.1670557 -0.9724396 -0.1630626 -0.166649 -0.9555528 -0.2418551 -0.1685974 -0.9321415 -0.3201297 -0.1692019 -0.9322532 -0.3218793 -0.1652202 -0.9031895 -0.3963319 -0.1648333 -0.9032227 -0.3966112 -0.1639769 -0.8670226 -0.4707309 -0.163353 -0.8671463 -0.4686937 -0.1684741 -0.8253558 -0.5388752 -0.1685274 -0.8248884 -0.541513 -0.162243 -0.777463 -0.607737 -0.1618863 -0.7782248 -0.6049297 -0.1686011 -0.7782248 -0.6049297 -0.168601 -0.7782248 -0.6049298 -0.1686011 -0.7242794 -0.668545 -0.1687216 -0.7243853 -0.6683363 -0.1690931 -0.7243854 -0.6683363 -0.1690931 -0.7243854 -0.6683363 -0.1690931 -0.6675356 -0.7250277 -0.1695023 -0.6677527 -0.7244827 -0.1709716 -0.6039962 -0.7784094 -0.1710773 -0.6043826 -0.7776876 -0.1729851 -0.5388243 -0.8244085 -0.1732603 -0.53737 -0.8265479 -0.1674875 -0.4705779 -0.8662737 -0.1677095 -0.4690666 -0.8681992 -0.1618842 -0.3946654 -0.9044569 -0.1618555 -0.3961282 -0.902939 -0.1666847 -0.3210867 -0.9322475 -0.1667875 -0.3197647 -0.9334584 -0.1624989 -0.2402228 -0.9570769 -0.1621631 -0.24265 -0.9552124 -0.1693821 -0.242644 -0.955214 -0.1693819 -0.2426501 -0.9552124 -0.1693822 -0.1626611 -0.9720008 -0.1695753 -0.1618708 -0.9725012 -0.1674494 -0.08095073 -0.9827193 -0.1664635 0.004276931 -0.9861407 -0.165856 0 -0.9841661 -0.1772487 0.08124053 -0.9808366 -0.177087 0.0851649 -0.9821593 -0.1676611 0.1628231 -0.9723587 -0.167354 0.1628191 -0.9723593 -0.1673538 0.1628191 -0.9723593 -0.1673539 0.1618326 -0.9720834 -0.1698949 0.2399203 -0.9558421 -0.1697177 0.2430191 -0.9563704 -0.1621645 0.3214395 -0.9328979 -0.1624134 0.3196572 -0.9327611 -0.1666617 0.3980888 -0.9020634 -0.1667549 0.3980887 -0.9020634 -0.1667548 0.3980887 -0.9020634 -0.1667548 0.3959453 -0.9020594 -0.1718032 0.467221 -0.8674083 -0.1711941 0.4729412 -0.8667851 -0.1581469 0.5378938 -0.8268128 -0.1644718 0.6077554 -0.7769209 -0.1644008 0.6077554 -0.7769209 -0.1644008 0.6077554 -0.7769209 -0.1644008 0.6049898 -0.7776721 -0.1709197 0.6682788 -0.7243152 -0.1696205 0.7245876 -0.6680152 -0.1694952 0.7276793 -0.6666164 -0.1615716 0.7795487 -0.6050403 -0.1619568 0.7770763 -0.6064033 -0.168605 0.8258173 -0.538193 -0.1684466 0.8257389 -0.5382751 -0.1685679 -0.3073997 -0.3929848 -0.8666421 -0.3945748 -0.3065518 -0.8662199 -0.4578841 -0.2007658 -0.8660458 -0.4993579 -3.04827e-4 -0.8663958 -0.4844607 0.118534 -0.8667454 -0.4844607 0.118534 -0.8667454 -0.4844609 0.118534 -0.8667454 -0.4183708 0.2744104 -0.8658319 -0.3938386 0.3063235 -0.8666356 -0.3069691 0.3938559 -0.8663992 0 0.4999648 -0.8660458 0.1174863 0.4847192 -0.8667436 0.1638231 0.4730227 -0.8656857 0.2005875 0.4564076 -0.8668661 0.3073842 0.3930181 -0.8666324 0.3946131 0.3065463 -0.8662043 0.4579313 0.2008043 -0.8660119 0.4991967 3.04859e-4 -0.8664888 0.4844713 -0.118537 -0.8667392 0.4844713 -0.118537 -0.8667392 0.4844714 -0.118537 -0.866739 0.4183622 -0.2744116 -0.8658357 0.3938363 -0.30635 -0.8666273 0.3069449 -0.3938249 -0.8664219 0.1180738 -0.486575 -0.8656231 0 -0.4999377 -0.8660615 -0.1179186 -0.4846942 -0.8666989 -0.1638332 -0.473052 -0.8656677 -0.2006377 -0.4564344 -0.8668403 -0.1758105 0.1519578 -0.9726251 0.1756817 -0.1518466 -0.9726658 0.1550926 0.1748332 -0.9723064 0.02857488 0.2360706 -0.9713157 0.1102407 0.3220765 -0.9402733 0.1102406 0.3220765 -0.9402733 0.1102406 0.3220764 -0.9402732 0.04573637 0.2298831 -0.972143 0.04573637 0.229883 -0.9721431 0.04573643 0.2298831 -0.9721431 0.08873742 0.2821815 -0.9552483 0.2009996 0.1669536 -0.9652594 0.1638745 0.1361359 -0.9770426 0.1546695 0.09127271 -0.9837412 0.1531055 0.08934354 -0.9841628 0.2362442 -0.02731198 -0.9713098 0.2362443 -0.02731198 -0.9713098 0.2362442 -0.02731204 -0.9713098 0.3281573 -0.1188553 -0.9371159 0.3281573 -0.1188553 -0.937116 0.3281571 -0.1188553 -0.937116 0.2290333 -0.04356217 -0.9724435 0.2841699 -0.08736371 -0.9547854 0.1666477 -0.2020879 -0.965085 0.2284203 -0.04401415 -0.9725672 0.134874 -0.1635619 -0.97727 0.09156811 -0.1546875 -0.9837108 0.07824152 -0.1593726 -0.9841132 0.08737289 -0.1542226 -0.9841653 -0.02852737 -0.23595 -0.9713464 -0.1101843 -0.3221932 -0.9402399 -0.04571181 -0.2300043 -0.9721155 -0.04571187 -0.2300041 -0.9721156 -0.04571193 -0.2300042 -0.9721156 -0.08868336 -0.2821829 -0.9552529 -0.2010303 -0.1669526 -0.9652532 -0.1639794 -0.1361754 -0.9770195 -0.154699 -0.09167098 -0.9836995 -0.1534187 -0.08961951 -0.984089 -0.2363819 0.0273531 -0.9712752 -0.3280594 0.1188226 -0.9371543 -0.3280594 0.1188226 -0.9371544 -0.3280593 0.1188226 -0.9371544 -0.2292088 0.04358333 -0.9724011 -0.2844499 0.08743345 -0.9546956 -0.166567 0.202039 -0.9651092 -0.2285955 0.04412907 -0.9725208 -0.2285952 0.04412907 -0.972521 -0.228596 0.04412925 -0.9725208 -0.1348055 0.1635136 -0.9772875 -0.09156095 0.1546484 -0.9837177 -0.07825756 0.1594052 -0.9841066 -0.08726185 0.154304 -0.9841624 -0.1902731 -0.4565967 -0.869089 -0.1627036 -0.3904396 -0.9061372 -0.20853 -0.3680493 -0.9061209 -0.1692652 -0.2987474 -0.9392015 -0.2034319 -0.2766403 -0.9391942 -0.1222129 -0.4836255 -0.866701 -0.1332495 -0.4757692 -0.8694184 -0.1140899 -0.407358 -0.9061142 -0.1628185 -0.3904447 -0.9061143 -0.1321631 -0.3169236 -0.9391977 -0.1692671 -0.2987449 -0.9392019 -0.04050999 -0.498782 -0.8657803 -0.04114103 -0.4987489 -0.8657697 -0.080531 -0.4877536 -0.8692589 -0.07519936 -0.4922044 -0.8672255 -0.06384545 -0.4178588 -0.9062659 -0.1134209 -0.4072118 -0.906264 -0.09205704 -0.3305269 -0.9392964 -0.1316109 -0.316888 -0.9392874 0 -0.4999541 -0.8660519 -0.01600432 -0.4941478 -0.8692306 -0.01368457 -0.42261 -0.9062084 -0.06403839 -0.4179536 -0.9062085 -0.09220415 -0.3305683 -0.9392673 0.08180296 -0.4940813 -0.8655588 0.0883035 -0.4931046 -0.865477 0.04032438 -0.4935145 -0.8688023 0.04470568 -0.4953939 -0.8675174 0.03795421 -0.4206396 -0.9064337 -0.01279973 -0.4221202 -0.9064496 -0.01040893 -0.3433176 -0.9391617 -0.05269545 -0.3394202 -0.9391577 -0.04276734 -0.2755115 -0.960346 -0.07483881 -0.2683281 -0.9604162 -0.08371275 -0.2527733 -0.9638973 -0.1022616 -0.2462086 -0.963807 -0.08924365 -0.2710381 -0.9584227 -0.1496819 -0.2215623 -0.9635899 -0.1586691 -0.2157623 -0.9634681 -0.1545934 -0.2320381 -0.9603434 -0.1540908 -0.2324573 -0.9603227 0.1236039 -0.4849895 -0.865741 0.1031557 -0.4835414 -0.8692218 0.08808219 -0.4128752 -0.9065185 0.03834563 -0.4203958 -0.9065303 0.03116339 -0.3417124 -0.9392879 -0.009376347 -0.3429312 -0.9393137 -0.007165968 -0.2615634 -0.9651597 7.68329e-5 -0.2621732 -0.9650208 -0.1551787 -0.1747437 -0.9723087 0.2001231 -0.4581826 -0.8660367 0.2052668 -0.4561727 -0.8658939 0.1615083 -0.4688585 -0.8683817 0.1623218 -0.469012 -0.8681471 0.1381464 -0.3991542 -0.9064168 0.08773368 -0.4131329 -0.9064349 0.07137042 -0.3360646 -0.939131 0.03013956 -0.3422901 -0.9391108 0.02297973 -0.2609263 -0.9650852 -0.007903158 -0.2618151 -0.9650858 -0.005297064 -0.175471 -0.9844704 -0.1545354 -0.1723005 -0.9728471 0.02160578 -0.1779331 -0.9838054 0.01620727 -0.1784263 -0.9838198 0.02367991 -0.2605637 -0.9651662 0.07153594 -0.3359238 -0.9391687 0.111493 -0.324837 -0.9391754 0.1373255 -0.4000941 -0.9061272 0.1841751 -0.3807003 -0.9061716 0.2151249 -0.4446684 -0.8694777 0.2710633 -0.4143983 -0.8687915 0.2361551 -0.44134 -0.8657078 0.2386341 -0.4398495 -0.8657866 0.3079676 -0.3929728 -0.8664458 0.3079676 -0.3929729 -0.8664458 0.3079677 -0.3929729 -0.8664457 0.2695994 -0.4171994 -0.867906 0.2293556 -0.3549249 -0.9063247 0.1846789 -0.3801383 -0.906305 0.1501471 -0.3090539 -0.9391175 0.1111727 -0.3251711 -0.9390977 0.08456265 -0.2473353 -0.9652328 0.03754884 -0.1737967 -0.9840654 0.01938295 -0.1765547 -0.9841 0.02200806 -0.1780769 -0.9837704 0.02200806 -0.1780768 -0.9837704 0.02200812 -0.1780769 -0.9837705 0.03712058 -0.1740603 -0.9840352 0.05776816 -0.1682905 -0.9840433 0.08480602 -0.2470878 -0.9652748 0.1144896 -0.2348757 -0.9652593 0.1504358 -0.3086489 -0.9392045 0.1858406 -0.2887557 -0.9391931 0.2289136 -0.355684 -0.9061388 0.2706803 -0.3250588 -0.9061287 0.3159747 -0.3794468 -0.8695862 0.3639616 -0.3340891 -0.8694347 0.3400275 -0.3664052 -0.8660997 0.3384355 -0.3679419 -0.8660718 0.3893206 -0.3121321 -0.8666043 0.3893207 -0.3121321 -0.8666043 0.3893207 -0.3121321 -0.8666043 0.3620833 -0.3419862 -0.8671455 0.3074634 -0.2904006 -0.9061644 0.2707014 -0.3250093 -0.90614 0.2196541 -0.2637186 -0.9392576 0.186131 -0.288266 -0.9392859 0.1417781 -0.2195758 -0.9652386 0.1143733 -0.2350322 -0.965235 0.07776504 -0.1598203 -0.9840784 0.05872297 -0.1676792 -0.9840911 0.3977935 -0.2930595 -0.8694117 0.3404457 -0.2508121 -0.9061954 0.3074793 -0.2902218 -0.9062162 0.2495379 -0.2355286 -0.9392855 0.2197691 -0.263539 -0.9392811 0.1673423 -0.2006734 -0.96526 0.09751254 -0.1507608 -0.9837492 0.09295439 -0.1514105 -0.9840907 0.4388737 -0.2364823 -0.8668714 0.4303183 -0.2432968 -0.8692714 0.3681215 -0.2081326 -0.906183 0.340423 -0.2510235 -0.9061455 0.2492731 -0.2364169 -0.9391326 0.2113028 -0.200405 -0.9566552 0.1452659 -0.2105439 -0.9667312 0.4737049 -0.1615113 -0.865747 0.4566095 -0.1895306 -0.8692446 0.3905841 -0.1621235 -0.9061788 0.298898 -0.1691361 -0.9391767 0.2763971 -0.2036144 -0.9392262 0.4836033 -0.1220448 -0.866737 0.4072225 -0.1138558 -0.9062047 0.3905734 -0.1617988 -0.9062415 0.3171463 -0.1313812 -0.9392322 0.2988449 -0.1687868 -0.9392566 0.4986981 -0.04119175 -0.8657965 0.4988246 -0.04089957 -0.8657374 0.4876298 -0.08108985 -0.8692766 0.4919989 -0.07561212 -0.8673062 0.4179241 -0.06422889 -0.9062088 0.3305518 -0.09273386 -0.939221 0.4995649 2.92892e-4 -0.8662765 0.4938574 -0.0154007 -0.8694066 0.4224722 -0.01317465 -0.9062802 0.4178407 -0.06386154 -0.9062731 0.4932537 0.08258479 -0.8659564 0.4934982 0.08270239 -0.8658061 0.4936202 0.04126238 -0.8686982 0.4949866 0.04447591 -0.8677616 0.4210312 0.03783178 -0.9062568 0.4226136 -0.01319026 -0.906214 0.3395114 -0.05182522 -0.9391732 0.2748337 -0.04195249 -0.9605761 0.2672967 -0.07510316 -0.9606831 0.2537059 -0.08301991 -0.9637122 0.2468019 -0.1022314 -0.9636585 0.2463218 -0.1391249 -0.9591506 0.2214651 -0.1492304 -0.9636824 0.2153621 -0.1586558 -0.9635598 0.231225 -0.1545988 -0.9605386 0.2327112 -0.1528829 -0.9604542 0.2622301 0.001372694 -0.9650045 0.2613813 -0.008185982 -0.9652009 0.3432214 -0.01074945 -0.9391931 0.3420241 0.03076761 -0.9391874 0.421019 0.03787392 -0.9062608 0.4134204 0.08829516 -0.9062492 0.4830691 0.1031705 -0.8694826 0.4691244 0.1613856 -0.8682609 0.4847416 0.1215931 -0.8661645 0.484627 0.1229169 -0.8660418 0.456629 0.2036328 -0.8660392 0.4691092 0.1613299 -0.8682795 0.39972 0.1374671 -0.9062709 0.4134308 0.0883181 -0.9062423 0.3358217 0.07173889 -0.9391897 0.3420029 0.03070431 -0.9391973 0.2604748 0.02338486 -0.9651974 0.261373 -0.008177042 -0.9652032 0.1769277 -0.1521472 -0.9723929 0.1780946 0.02271449 -0.9837512 0.1786509 0.01605188 -0.9837816 0.2603744 0.02339524 -0.9652243 0.2557674 0.05477595 -0.9651854 0.3356776 0.07188963 -0.9392298 0.3247147 0.1114693 -0.9392205 0.3999499 0.1372961 -0.9061954 0.3804093 0.1848523 -0.9061558 0.4442632 0.2158777 -0.8694982 0.4145911 0.2712141 -0.8686525 0.4380593 0.2405301 -0.8661694 0.4398764 0.2375903 -0.8660599 0.4180278 0.2692797 -0.8676066 0.3556364 0.2290875 -0.9061136 0.3804487 0.1846895 -0.9061725 0.3088232 0.1499205 -0.9392296 0.3248258 0.1114345 -0.9391861 0.255815 0.05447059 -0.9651899 0.1737893 0.03699731 -0.9840877 0.1680102 0.05791372 -0.9840827 0.2472376 0.08522468 -0.9651997 0.2352585 0.1143532 -0.9651823 0.3086849 0.1500479 -0.9392546 0.2883182 0.1861961 -0.939257 0.3551852 0.2293719 -0.9062186 0.3251605 0.2701606 -0.9062471 0.3800373 0.3157542 -0.8694084 0.335419 0.3638401 -0.8689733 0.3665277 0.3406339 -0.8658095 0.2986197 0.4001345 -0.8664404 0.2986196 0.4001344 -0.8664403 0.2986198 0.4001343 -0.8664403 0.3405795 0.3625798 -0.8674916 0.2890732 0.3077509 -0.9064911 0.235108 0.1143665 -0.9652174 0.1679546 0.05784934 -0.9840959 0.2510274 0.3404901 -0.9061191 0.2906572 0.3073386 -0.9061244 0.2361987 0.2497553 -0.9390594 0.2649211 0.2192325 -0.9390176 0.2195625 0.1420762 -0.9651978 0.1505115 0.09739083 -0.9837995 0.1511332 0.09345328 -0.984086 0.2369023 0.4387047 -0.8668423 0.2435678 0.430393 -0.8691585 0.2082962 0.368067 -0.9061675 0.2507818 0.3404972 -0.9061844 0.2037071 0.2765903 -0.9391493 0.2354784 0.2500444 -0.9391633 0.1995561 0.2119111 -0.9566981 0.2096813 0.1459931 -0.9668091 0.1902781 0.4566087 -0.8690816 0.1627126 0.3904612 -0.9061263 0.2085546 0.3680441 -0.9061174 0.1692875 0.2987462 -0.9391978 0.2034229 0.2766598 -0.9391905 0.1222576 0.4836582 -0.8666763 0.133246 0.4757567 -0.8694257 0.114093 0.4073693 -0.9061087 0.1627917 0.3904464 -0.9061183 0.1321314 0.3169027 -0.9392092 0.1692792 0.2987661 -0.939193 0.04045963 0.4988372 -0.8657507 0.04123371 0.4987469 -0.8657663 0.08055233 0.4878829 -0.8691845 0.07520604 0.4920732 -0.8672993 0.06387335 0.4179161 -0.9062374 0.1134557 0.4072377 -0.906248 0.09208619 0.330549 -0.9392857 0.1316395 0.3168727 -0.9392885 0 0.4999936 -0.8660292 0.01600515 0.4941739 -0.8692159 0.01368343 0.4225749 -0.9062248 0.0640341 0.4179258 -0.9062218 0.09216547 0.3305549 -0.9392758 -0.08185338 0.4940912 -0.8655483 -0.08820354 0.493109 -0.8654846 -0.04032707 0.4935472 -0.8687835 -0.04472875 0.495354 -0.8675389 -0.03798079 0.4206799 -0.9064137 0.01277387 0.4221765 -0.9064237 0.01039057 0.3433178 -0.939162 0.05269777 0.3394351 -0.9391523 0.04276615 0.2755037 -0.9603483 0.074817 0.2683286 -0.9604178 0.08374518 0.2527864 -0.963891 0.1022802 0.2462081 -0.9638052 0.08920699 0.2710102 -0.9584339 0.1496915 0.221587 -0.9635828 0.1586815 0.2158049 -0.9634566 0.154534 0.2319489 -0.9603744 0.1542112 0.2325065 -0.9602915 -1.08477e-4 0.2621915 -0.9650158 0.007189571 0.2615751 -0.9651564 0.009410381 0.3428993 -0.9393251 -0.03116893 0.3417227 -0.9392839 -0.08805692 0.4128819 -0.9065178 -0.1031386 0.483568 -0.8692091 -0.118209 0.4864956 -0.8656493 -0.1235745 0.4850339 -0.8657202 -0.205094 0.4561209 -0.865962 -0.1622057 0.4686658 -0.8683558 -0.1381693 0.3992205 -0.9063842 -0.08773827 0.4131327 -0.9064345 -0.07137113 0.3361114 -0.9391142 -0.03014272 0.3422601 -0.9391217 -0.0229783 0.2609101 -0.9650896 0.007918715 0.2617988 -0.96509 0.005301952 0.1753214 -0.9844971 0.1544009 0.1723041 -0.9728677 -0.02160239 0.1779053 -0.9838106 -0.01622885 0.1783915 -0.9838258 -0.02371126 0.2605555 -0.9651677 -0.071527 0.3359093 -0.9391747 -0.1114549 0.324793 -0.9391951 -0.1372893 0.4000689 -0.9061437 -0.1841955 0.3807425 -0.9061496 -0.2151334 0.4446859 -0.8694666 -0.2710993 0.4144533 -0.8687542 -0.2362003 0.4412078 -0.8657627 -0.2386456 0.4398707 -0.8657725 -0.3077667 0.3930018 -0.8665041 -0.3077667 0.3930017 -0.866504 -0.2695938 0.4171526 -0.8679303 -0.2293646 0.3549034 -0.9063308 -0.1846297 0.380037 -0.9063574 -0.1501575 0.3090752 -0.9391087 -0.1111958 0.3251703 -0.9390953 -0.08458197 0.2473237 -0.9652341 -0.03755474 0.1738241 -0.9840604 -0.01938295 0.1765547 -0.9841 -0.0220474 0.1780662 -0.9837715 -0.03711295 0.1740245 -0.9840417 -0.05775147 0.168312 -0.9840406 -0.08478218 0.2470884 -0.9652768 -0.1144872 0.2349185 -0.9652493 -0.150413 0.30865 -0.9392077 -0.1858627 0.2887544 -0.939189 -0.228955 0.3557054 -0.9061199 -0.2706907 0.3250966 -0.9061118 -0.3159343 0.37943 -0.8696082 -0.3639424 0.3340408 -0.8694612 -0.3400614 0.3665258 -0.8660353 -0.3384789 0.3679358 -0.8660574 -0.3889496 0.3122176 -0.8667401 -0.3621192 0.3420228 -0.867116 -0.3074599 0.2904009 -0.9061654 -0.2706675 0.3249658 -0.9061658 -0.2196497 0.2637188 -0.9392585 -0.186158 0.2883167 -0.939265 -0.1417654 0.2195561 -0.9652449 -0.114397 0.2350315 -0.9652324 -0.0777595 0.1597595 -0.9840887 -0.05871093 0.1676449 -0.9840977 -0.3978369 0.2930901 -0.8693815 -0.340408 0.2507843 -0.9062172 -0.3074975 0.2902628 -0.906197 -0.2495465 0.2355628 -0.9392747 -0.2197584 0.2634913 -0.9392969 -0.1674099 0.2007266 -0.9652372 -0.09752678 0.1507828 -0.9837445 -0.09294426 0.1514106 -0.9840916 -0.4387884 0.2364544 -0.8669222 -0.4303622 0.2433226 -0.8692426 -0.3681623 0.2081557 -0.906161 -0.3403776 0.25099 -0.9061717 -0.2492484 0.2364185 -0.9391388 -0.2112737 0.2003999 -0.9566627 -0.1452376 0.2105447 -0.9667353 -0.4736088 0.1614608 -0.865809 -0.4566815 0.189548 -0.8692029 -0.3906453 0.1621401 -0.9061496 -0.2988567 0.1691127 -0.9391942 -0.2764454 0.20365 -0.9392043 -0.4836452 0.1220645 -0.8667109 -0.4071774 0.1138432 -0.9062264 -0.3905419 0.1617757 -0.9062592 -0.3171232 0.1313621 -0.9392427 -0.2989236 0.1688148 -0.9392264 -0.4987372 0.04119068 -0.8657739 -0.4986646 0.04089361 -0.86583 -0.4876552 0.08108854 -0.8692625 -0.4919981 0.07561218 -0.8673067 -0.4179704 0.06423604 -0.9061868 -0.3305976 0.09274667 -0.9392036 -0.4995371 -2.92897e-4 -0.8662925 -0.493784 0.01539927 -0.8694483 -0.422547 0.01317769 -0.9062452 -0.4177852 0.06385308 -0.9062993 -0.4933488 -0.08260071 -0.8659008 -0.4934247 -0.08270782 -0.8658473 -0.4935583 -0.04125678 -0.8687337 -0.4949852 -0.04447597 -0.8677625 -0.4210796 -0.03783595 -0.9062343 -0.422501 0.01318675 -0.9062666 -0.3394522 0.05181616 -0.9391951 -0.2747723 0.04194313 -0.9605941 -0.2673268 0.07511162 -0.9606741 -0.2536737 0.08300125 -0.9637222 -0.2468376 0.1022462 -0.9636477 -0.2463216 0.1391112 -0.9591526 -0.2213889 0.1491983 -0.9637048 -0.2153204 0.158625 -0.9635742 -0.2312467 0.1546189 -0.9605301 -0.2327933 0.1528799 -0.9604349 -0.2622301 -0.001372694 -0.9650045 -0.2613813 0.008185982 -0.9652009 -0.3432816 0.01075136 -0.939171 -0.3419768 -0.03076332 -0.9392048 -0.4210172 -0.03787392 -0.9062618 -0.4133936 -0.08828455 -0.9062624 -0.4831417 -0.1031799 -0.8694413 -0.4691244 -0.1613856 -0.8682609 -0.484929 -0.1216366 -0.8660534 -0.484929 -0.1216366 -0.8660534 -0.484929 -0.1216366 -0.8660534 -0.4845926 -0.1228987 -0.8660634 -0.4567794 -0.2037659 -0.8659285 -0.4690885 -0.161332 -0.8682903 -0.3997451 -0.1374836 -0.9062573 -0.4134858 -0.08832985 -0.906216 -0.3357743 -0.07172906 -0.9392075 -0.342037 -0.03070998 -0.9391846 -0.2604543 -0.02338498 -0.965203 -0.2613431 0.008177101 -0.9652114 -0.1768369 0.1520692 -0.9724217 -0.1781023 -0.02271443 -0.9837499 -0.1786689 -0.01605182 -0.9837783 -0.2604669 -0.02340084 -0.9651992 -0.255697 -0.05475586 -0.9652051 -0.3357034 -0.07188892 -0.9392206 -0.3247389 -0.1114855 -0.9392102 -0.3999267 -0.1372976 -0.9062053 -0.3803867 -0.1848303 -0.9061698 -0.4442844 -0.2158752 -0.869488 -0.4145952 -0.2711918 -0.8686575 -0.4380954 -0.2406151 -0.8661275 -0.4398236 -0.2375618 -0.8660945 -0.4180247 -0.2692973 -0.8676026 -0.355613 -0.2290897 -0.9061222 -0.380523 -0.1847122 -0.9061367 -0.3088439 -0.1499194 -0.9392229 -0.3247691 -0.1114151 -0.939208 -0.2558782 -0.054484 -0.9651725 -0.1738163 -0.03701275 -0.9840823 -0.167952 -0.05789917 -0.9840934 -0.2472074 -0.08522534 -0.9652074 -0.2351942 -0.1143333 -0.9652003 -0.3086586 -0.1500493 -0.9392631 -0.2883014 -0.1861971 -0.939262 -0.3551651 -0.2293737 -0.9062259 -0.3251785 -0.2701756 -0.9062363 -0.3799973 -0.315721 -0.8694379 -0.3353492 -0.3637954 -0.8690189 -0.3666067 -0.3406226 -0.8657805 -0.2982763 -0.4003319 -0.8664674 -0.2982763 -0.4003319 -0.8664674 -0.2982763 -0.4003319 -0.8664674 -0.3405343 -0.3625317 -0.8675293 -0.2890893 -0.307768 -0.9064803 -0.2352246 -0.1144232 -0.9651822 -0.168049 -0.05787283 -0.9840784 -0.2510171 -0.3404709 -0.9061292 -0.2906727 -0.3073259 -0.9061238 -0.236241 -0.2497709 -0.9390446 -0.2648749 -0.2191942 -0.9390396 -0.2195081 -0.1420409 -0.9652153 -0.1508635 -0.09761959 -0.9837229 -0.1515341 -0.09265142 -0.9841002 -0.2368975 -0.4387671 -0.8668119 -0.2435736 -0.4303563 -0.8691751 -0.2083066 -0.3680449 -0.906174 -0.2507941 -0.3405264 -0.9061701 -0.2037026 -0.2765905 -0.9391501 -0.2354468 -0.2500231 -0.939177 -0.199558 -0.211911 -0.9566977 -0.2096996 -0.1459925 -0.9668053 -0.9974783 -0.07096868 7.33667e-4 -0.9974784 -0.07096868 7.33643e-4 -0.9974784 -0.07096868 7.33667e-4 -0.9976179 -0.06898438 1.24972e-4 -0.9976519 -0.06848669 5.31945e-4 -0.9976489 -0.06853091 -5.02654e-4 -0.9976738 -0.06816089 0.001101493 -0.9977957 -0.06572651 0.009160816 -0.9977957 -0.06572645 0.009160757 -0.9977957 -0.06572639 0.009160697 -0.9975876 -0.06941491 -8.85052e-4 -0.9975808 -0.06951177 -9.22202e-4 0.1514019 -0.9884458 0.007234811 0.1944329 -0.9809159 0 0.2718852 -0.9623297 0 0.31169 -0.9501588 0.006907165 0.3510866 -0.936343 0 0.4644243 -0.8855874 0.006724476 0.4997882 -0.8661476 0 0.5705772 -0.8212441 0 0.6041248 -0.7968602 0.006870627 0.6367265 -0.7710897 0 0.6984097 -0.7156983 0 0.7262926 -0.6873542 0.006588339 0.7530767 -0.6579327 0 0.8299851 -0.5577449 0.006742596 0.8935715 -0.448921 0 0.9106579 -0.4131091 0.006578743 0.9263917 -0.3765617 0 0.9545783 -0.2979602 0 0.9657813 -0.2592713 0.006695091 0.9755281 -0.219875 0 0.9755281 -0.219875 0 0.9755281 -0.219875 0 0.9909793 -0.1340156 0 0.9954239 -0.09533792 0.006488859 0.9984292 -0.05602848 0 0.9996673 0.02579426 0 0.9975723 0.06926912 0.007172524 0.9936672 0.1123632 0 0.9810606 0.1937017 0 0.9723671 0.2333589 0.006767511 0.9620373 0.2729185 0 0.9368196 0.3498128 0 0.9211402 0.3891672 0.007055222 0.9036835 0.4282013 0 0.865108 0.5015859 0 0.8443942 0.5356824 0.006571114 0.8227272 0.5684366 0 0.770949 0.6368969 0 0.7450637 0.6669607 0.006601393 0.7178022 0.6962472 0 0.6249458 0.78064 0.006647288 0.5214934 0.8532553 0 0.4865359 0.8736347 0.006720304 0.4506812 0.8926851 0 0.3751191 0.9269766 0 0.3368585 0.9415309 0.006789624 0.216939 0.9761852 0 0.1773641 0.9841229 0.006660103 0.1378063 0.9904593 0 0.0561943 0.9984199 0 0.01297962 0.9998901 0.007171034 -0.03030484 0.9995408 0 -0.1080468 0.9941459 0 -0.1514018 0.9884458 0.007240474 -0.194464 0.9809098 0 -0.2718556 0.9623382 0 -0.3110089 0.9503827 0.00680238 -0.3497256 0.9368522 0 -0.4652769 0.8851385 0.006883382 -0.5017381 0.8650197 0 -0.570599 0.8212289 0 -0.6030511 0.7976748 0.006666779 -0.6346921 0.7727652 0 -0.6984829 0.7156268 0 -0.7273268 0.6862571 0.006862759 -0.7552378 0.655451 0 -0.8299851 0.5577449 0.006739795 -0.8918361 0.452359 0 -0.909838 0.4149064 0.006896674 -0.926387 0.376573 0 -0.9545271 0.2981243 0 -0.9663195 0.2572493 0.007029533 -0.9764134 0.2159097 0 -0.9903702 0.1384443 0 -0.9954361 0.09515869 0.007196426 -0.9986526 0.05189484 0 -0.9996627 -0.02597451 0 -0.9975785 -0.06918048 0.007162094 -0.9936669 -0.1123668 0 -0.9819051 -0.1893745 0 -0.9728331 -0.2313982 0.007114291 -0.9620348 -0.2729269 0 -0.9354583 -0.3534372 0 -0.921112 -0.3892454 0.006387531 -0.9054228 -0.4245113 0 -0.8650297 -0.5017207 0 -0.8444396 -0.5356109 0.006554424 -0.8226531 -0.5685437 0 -0.7710376 -0.6367896 0 -0.7439414 -0.6682096 0.006867527 -0.7156434 -0.6984659 0 -0.6249458 -0.78064 0.006652891 -0.5233939 -0.8520908 0 -0.4865348 -0.8736327 0.007052659 -0.4489688 -0.8935475 0 -0.3765615 -0.9263916 0 -0.3375732 -0.941274 0.006905496 -0.2201297 -0.9754706 0 -0.1773635 -0.9841188 0.007234811 -0.1341578 -0.99096 0 -0.05616223 -0.9984217 0 -0.01295161 -0.9998906 0.0071612 0.03014224 -0.9995456 0 0.1080785 -0.9941424 0 0.1830269 -0.6435074 -0.7432358 0.1632309 -0.6528033 -0.7397322 0.1632308 -0.6528033 -0.7397322 0.1632309 -0.652803 -0.7397324 0.2368817 -0.6286718 -0.7407151 0.2330731 -0.6253767 -0.7447019 0.2826855 -0.6044082 -0.7448353 0.2826856 -0.6044083 -0.7448353 0.2826855 -0.6044083 -0.7448353 0.2864105 -0.6052024 -0.7427646 0.2860511 -0.606735 -0.7416519 0.336511 -0.5800207 -0.7418466 0.3335233 -0.5784479 -0.7444194 0.3372029 -0.5746381 -0.7457113 0.379262 -0.5478999 -0.7456314 0.3817036 -0.5490835 -0.7435118 0.4259656 -0.5151813 -0.7437349 0.4262979 -0.5150279 -0.7436509 0.4264179 -0.5180057 -0.7415106 0.4669718 -0.4816292 -0.7416 0.4659798 -0.4777781 -0.7447086 0.4655044 -0.478605 -0.744475 0.504063 -0.4376693 -0.7445577 0.5061633 -0.4381641 -0.7428398 0.5404862 -0.3951449 -0.7427888 0.5385535 -0.3964301 -0.7435076 0.5387715 -0.3970893 -0.7429977 0.5387715 -0.3970893 -0.7429976 0.5387715 -0.3970893 -0.7429975 0.5709002 -0.3500715 -0.7426459 0.5718699 -0.3519608 -0.7410051 0.5719159 -0.3453639 -0.7440671 0.5962128 -0.3009839 -0.7442708 0.5962202 -0.3011716 -0.744189 0.6157243 -0.2586522 -0.7443002 0.6214541 -0.2515279 -0.7419761 0.6214126 -0.2512567 -0.7421027 0.6391189 -0.2012459 -0.7423121 0.6395611 -0.201728 -0.7418001 0.6380341 -0.1970688 -0.7443631 0.6516816 -0.1448586 -0.7445315 0.6523253 -0.1445769 -0.7440223 0.657855 -0.1157953 -0.7441897 0.6655631 -0.09170317 -0.7406864 0.6613807 -0.08834564 -0.7448293 0.6659839 -0.03828644 -0.744983 0.6675368 -0.03949493 -0.7435286 0.6621909 -0.03236597 -0.7486359 0.662841 0.01794397 -0.7485452 0.66755 0.02070534 -0.7442771 0.6641571 0.07276171 -0.7440438 0.6653643 0.07374411 -0.7428675 0.6562995 0.1297824 -0.7432547 0.6544814 0.1267607 -0.7453764 0.6510476 0.1288804 -0.7480153 0.6391296 0.178519 -0.7480939 0.6435878 0.1829528 -0.7431844 0.6360194 0.1994295 -0.7454578 0.6238721 0.2351416 -0.7453134 0.6243952 0.2356464 -0.7447157 0.6046804 0.2826014 -0.7446464 0.6053092 0.2863996 -0.7426818 0.6065428 0.2860805 -0.7417978 0.5800108 0.3365658 -0.7418295 0.5784491 0.3335106 -0.7444242 0.5747565 0.3371805 -0.7456301 0.5478498 0.3792859 -0.745656 0.548436 0.3803219 -0.7446968 0.5146303 0.4252668 -0.7445158 0.5149317 0.4237346 -0.7451807 0.5154642 0.4236963 -0.7448344 0.4761762 0.4673392 -0.7448828 0.4802935 0.4687095 -0.7413701 0.481211 0.4682362 -0.7410741 0.481211 0.4682362 -0.7410742 0.4812111 0.468236 -0.7410742 0.4418334 0.5059391 -0.7408164 0.441294 0.5034731 -0.7428152 0.3955637 0.5401996 -0.7427744 0.3955796 0.5402539 -0.7427265 0.3901029 0.5383495 -0.7469937 0.3490497 0.5660841 -0.746802 0.3548095 0.5694314 -0.7415243 0.3548095 0.5694314 -0.7415242 0.3548095 0.5694314 -0.7415242 0.3437048 0.5696579 -0.7465634 0.3011574 0.5932374 -0.7465746 0.3010759 0.5961878 -0.7442537 0.2514505 0.6187547 -0.7442549 0.2514505 0.6187548 -0.7442548 0.2514505 0.6187547 -0.7442548 0.2507468 0.619513 -0.7438613 0.2506291 0.6194964 -0.7439149 0.1972061 0.6386188 -0.7438251 0.1962015 0.6377151 -0.7448654 0.2057976 0.6409035 -0.7395201 0.1459736 0.6570022 -0.7396215 0.1474618 0.6517574 -0.7439538 0.07830178 0.6638492 -0.7437561 0.07830172 0.6638495 -0.7437558 0.07830172 0.6638494 -0.7437559 0.09131693 0.6600283 -0.74567 0.09151953 0.6602321 -0.7454648 0.03521364 0.6659796 -0.7451384 0.03957808 0.6729706 -0.7386096 0.03305077 0.6680583 -0.7433747 -0.01812863 0.6681581 -0.7437986 -0.01771938 0.6674136 -0.7444765 -0.07239341 0.6636667 -0.7445172 -0.07397532 0.6657951 -0.7424585 -0.1294435 0.6559671 -0.7436072 -0.1290618 0.6565101 -0.7431942 -0.1837823 0.6432351 -0.7432851 -0.1826374 0.6421291 -0.7445226 -0.1541665 0.6553232 -0.7394486 -0.1541665 0.6553233 -0.7394486 -0.1541665 0.6553232 -0.7394487 -0.2369462 0.6288428 -0.7405493 -0.2330105 0.6252468 -0.7448306 -0.2330105 0.6252468 -0.7448306 -0.2857381 0.6032899 -0.7445772 -0.2853674 0.6030453 -0.7449174 -0.2850211 0.6044518 -0.7439093 -0.3352267 0.5777224 -0.7442177 -0.3321431 0.5761093 -0.7468461 -0.3285836 0.579788 -0.7455727 -0.3285835 0.579788 -0.7455727 -0.3285837 0.579788 -0.7455727 -0.3807333 0.5469795 -0.7455574 -0.3830956 0.5480586 -0.7435521 -0.4210308 0.5192729 -0.7436994 -0.4263368 0.5181571 -0.7414514 -0.4262496 0.5132212 -0.7449265 -0.4658628 0.4775111 -0.744953 -0.4674407 0.4833303 -0.7401967 -0.4718971 0.4721075 -0.7445991 -0.5040032 0.4376471 -0.7446112 -0.5015795 0.4371137 -0.7465586 -0.5304607 0.4010866 -0.7468207 -0.5304607 0.4010866 -0.7468206 -0.5304606 0.4010867 -0.7468207 -0.5385106 0.3965126 -0.7434946 -0.5370581 0.3919553 -0.7469537 -0.5682416 0.3455957 -0.7467699 -0.5719038 0.3520022 -0.7409592 -0.5718395 0.3547943 -0.739676 -0.6018434 0.3009791 -0.7397271 -0.5907968 0.3012599 -0.7484661 -0.611368 0.2562263 -0.7487172 -0.6166796 0.2496842 -0.7465682 -0.6201846 0.2544597 -0.7420387 -0.6399616 0.1984745 -0.7423322 -0.6377854 0.1962587 -0.7447901 -0.6380309 0.196847 -0.7444245 -0.6509974 0.1477118 -0.7445694 -0.6517898 0.1473974 -0.7439383 -0.6640849 0.07792651 -0.7435852 -0.6640849 0.07792639 -0.7435851 -0.6640847 0.07792729 -0.7435852 -0.6601259 0.090954 -0.7456281 -0.6609249 0.09164613 -0.744835 -0.6661022 0.03526538 -0.7450264 -0.6630056 0.03367108 -0.7478569 -0.6675374 0.03915476 -0.7435461 -0.6683984 -0.01809507 -0.7435833 -0.6676754 -0.01785278 -0.7442384 -0.6639868 -0.07576376 -0.7438961 -0.6648712 -0.07644581 -0.7430359 -0.6573906 -0.1235081 -0.7433595 -0.6597635 -0.1274704 -0.7405833 -0.6597635 -0.1274704 -0.7405832 -0.6597635 -0.1274703 -0.7405832 -0.6563301 -0.1299362 -0.7432008 -0.6434217 -0.182876 -0.7433472 -0.6435495 -0.1830343 -0.7431976 -0.6359135 -0.1993021 -0.7455822 -0.6247909 -0.232387 -0.7454078 -0.6254103 -0.2331792 -0.7446405 -0.6017065 -0.2888026 -0.7446761 -0.6008443 -0.2842714 -0.7471118 -0.6020967 -0.2837629 -0.7462963 -0.6020967 -0.2837629 -0.7462963 -0.5773739 -0.3313741 -0.7462109 -0.5805672 -0.3376853 -0.7408849 -0.5788391 -0.3394981 -0.7414085 -0.5516214 -0.3818213 -0.7415703 -0.5521751 -0.3830278 -0.7405353 -0.5131974 -0.4341437 -0.74037 -0.5149148 -0.4237206 -0.7452005 -0.5154399 -0.4237035 -0.744847 -0.477573 -0.465749 -0.7449846 -0.4775679 -0.4658882 -0.7449007 -0.487998 -0.4614958 -0.7408642 -0.4403353 -0.5071598 -0.7408736 -0.4398061 -0.5047187 -0.7428524 -0.3953946 -0.5405029 -0.7426438 -0.3955178 -0.5401847 -0.7428097 -0.3938963 -0.5395376 -0.7441405 -0.3505516 -0.5684838 -0.7442713 -0.3520388 -0.5694611 -0.7428209 -0.3437274 -0.5694296 -0.7467272 -0.3011106 -0.5932137 -0.7466123 -0.3010857 -0.5962402 -0.7442077 -0.2582898 -0.6159335 -0.7442529 -0.2515506 -0.6214438 -0.7419771 -0.2493947 -0.6199982 -0.7439117 -0.1980274 -0.6384034 -0.7437918 -0.1957873 -0.6362209 -0.7462508 -0.2051596 -0.6393408 -0.7410486 -0.1463183 -0.6555026 -0.7408828 -0.1471309 -0.6531396 -0.7428063 -0.07808202 -0.6648238 -0.7429082 -0.0914604 -0.660904 -0.7448765 -0.0916078 -0.6609135 -0.7448499 -0.03538966 -0.6661897 -0.7449423 -0.03961294 -0.6731564 -0.7384384 -0.03271955 -0.667692 -0.7437183 0.01813352 -0.6683396 -0.7436352 0.01765942 -0.6674611 -0.7444353 0.07241892 -0.6636655 -0.7445158 0.07398444 -0.6659664 -0.7423039 0.1301141 -0.6563282 -0.7431715 0.1292611 -0.6575244 -0.7422622 0.1841534 -0.6447203 -0.7419053 0.02669572 -0.8775441 -0.4787525 0.09693312 -0.8725851 -0.4787477 0.09555345 -0.8712057 -0.481529 0.1704488 -0.8599481 -0.4810786 0.1668167 -0.8569791 -0.4876055 0.2388769 -0.8398675 -0.4874017 0.2381916 -0.8394557 -0.4884456 0.3046461 -0.8174212 -0.4888899 0.3089632 -0.8201623 -0.4815347 0.3748741 -0.7921919 -0.4815616 0.372754 -0.7911098 -0.484974 0.4368247 -0.7577562 -0.4847574 0.4402828 -0.7590122 -0.4796371 0.5006119 -0.7202552 -0.4802292 0.4987964 -0.7196602 -0.4830026 0.5584294 -0.6746601 -0.4826909 0.5562375 -0.6743163 -0.4856928 0.608459 -0.6277006 -0.4855613 0.6129778 -0.6281135 -0.4793036 0.6638248 -0.5745729 -0.4787512 0.6620379 -0.5745977 -0.4811894 0.7058197 -0.5196958 -0.4813883 0.7020521 -0.5198137 -0.486741 0.7444192 -0.4564121 -0.4873685 0.7444192 -0.4564122 -0.4873685 0.7444192 -0.4564122 -0.4873685 0.7455386 -0.4563845 -0.4856804 0.7805891 -0.3940648 -0.485174 0.780627 -0.3941351 -0.4850557 0.8105778 -0.3281238 -0.4850758 0.8116383 -0.3276893 -0.483594 0.8350054 -0.2629293 -0.4833574 0.8364769 -0.2622894 -0.4811556 0.8557827 -0.189733 -0.4812872 0.8539571 -0.1906599 -0.484155 0.866899 -0.1194071 -0.4839712 0.868999 -0.1181197 -0.4805085 0.8758272 -0.05050486 -0.479975 0.8769503 -0.04951423 -0.4780234 0.8781197 0.02719587 -0.4776675 0.8730219 0.02272325 -0.4871516 0.8680367 0.09613406 -0.4871043 0.8708196 0.09885144 -0.4815617 0.860668 0.1665722 -0.4811492 0.861517 0.1678203 -0.4791919 0.8442121 0.2402099 -0.4791715 0.8447616 0.2408005 -0.4779046 0.8220303 0.3101614 -0.4775628 0.8205277 0.3077047 -0.481718 0.7921248 0.3747429 -0.4817742 0.7911477 0.3727156 -0.4849418 0.757788 0.4369131 -0.4846282 0.7582031 0.4382828 -0.4827383 0.7198361 0.4991825 -0.4823412 0.7209779 0.5034632 -0.4761468 0.6791045 0.5587238 -0.4760723 0.6785527 0.5567409 -0.479172 0.6263831 0.6147317 -0.4793215 0.6259079 0.610702 -0.4850592 0.5762881 0.6575081 -0.4853609 0.5764257 0.6604391 -0.4812002 0.5178359 0.7070863 -0.481534 0.5177554 0.7082012 -0.4799796 0.4603599 0.7466777 -0.4801471 0.4605396 0.7459246 -0.4811441 0.3950999 0.7823964 -0.4814061 0.3944662 0.7851846 -0.4773696 0.3297076 0.8146452 -0.4771226 0.3303306 0.812429 -0.4804591 0.2586872 0.8379332 -0.4805715 0.2588399 0.8374286 -0.4813681 0.19344 0.8547992 -0.4815595 0.1942468 0.8532075 -0.4840509 0.1199339 0.8669214 -0.4838009 0.1182494 0.8696324 -0.4793292 0.04634392 0.8762992 -0.4795331 0.04930222 0.8722645 -0.486543 -0.02318412 0.8735737 -0.4861395 -0.02672404 0.8775722 -0.4786992 -0.09694892 0.8726384 -0.4786473 -0.09504103 0.8708355 -0.4822995 -0.1695547 0.8592519 -0.482636 -0.1668629 0.8569014 -0.4877261 -0.2388703 0.840013 -0.4871543 -0.2395653 0.8402693 -0.4863703 -0.3052315 0.8190808 -0.485737 -0.3076836 0.820526 -0.4817343 -0.3748286 0.7922316 -0.4815316 -0.3727871 0.7911278 -0.4849194 -0.4369366 0.7578756 -0.48447 -0.4369366 0.7578756 -0.4844699 -0.4369366 0.7578757 -0.4844699 -0.44311 0.760104 -0.4752849 -0.5039609 0.7212352 -0.4752297 -0.4987852 0.7197642 -0.482859 -0.4987852 0.7197642 -0.482859 -0.556472 0.6763262 -0.4826198 -0.5543799 0.6758948 -0.4856225 -0.5543799 0.6758949 -0.4856225 -0.6104047 0.6258599 -0.4854951 -0.6107444 0.6258251 -0.4851127 -0.6592112 0.5744853 -0.485188 -0.662117 0.5744935 -0.4812051 -0.7058717 0.5196612 -0.4813497 -0.7067637 0.5196957 -0.4800016 -0.7495089 0.4558922 -0.4799988 -0.745538 0.456385 -0.4856808 -0.7789852 0.3972507 -0.4851537 -0.7843081 0.3959825 -0.4775547 -0.8145381 0.3296377 -0.4773539 -0.8103706 0.3311283 -0.4833773 -0.8362216 0.2593011 -0.4832146 -0.8375276 0.2588498 -0.4811906 -0.8549312 0.1932853 -0.4813873 -0.8583937 0.1916455 -0.4758492 -0.8714518 0.1202125 -0.4755218 -0.8685691 0.1218329 -0.4803586 -0.8761761 0.04650795 -0.4797422 -0.877123 0.04583603 -0.4780737 -0.8781906 -0.02344167 -0.4777361 -0.8777081 -0.0228452 -0.4786511 -0.8722444 -0.1003325 -0.478668 -0.8708932 -0.09885972 -0.4814269 -0.8607348 -0.1666701 -0.4809955 -0.8614989 -0.1678168 -0.4792257 -0.8442715 -0.2401503 -0.4790967 -0.8446556 -0.240682 -0.4781519 -0.8231806 -0.3067509 -0.477784 -0.8218755 -0.3044391 -0.4814953 -0.8218754 -0.3044391 -0.4814952 -0.792038 -0.3748797 -0.4818103 -0.7934868 -0.3776159 -0.4772682 -0.7596325 -0.4418138 -0.477241 -0.7582948 -0.4381477 -0.482717 -0.7196994 -0.4992814 -0.4824427 -0.7196051 -0.49883 -0.4830498 -0.6762653 -0.5563879 -0.482802 -0.6767696 -0.5589547 -0.4791165 -0.6282674 -0.6128088 -0.4793177 -0.6278296 -0.6087461 -0.4850342 -0.5744164 -0.6592657 -0.4851954 -0.5745596 -0.6619838 -0.4813094 -0.5179002 -0.7072197 -0.4812689 -0.5177448 -0.7082443 -0.4799275 -0.4603862 -0.7466662 -0.4801397 -0.4605671 -0.7459169 -0.48113 -0.3951057 -0.7824741 -0.4812755 -0.3944943 -0.7851693 -0.4773713 -0.3297044 -0.8145684 -0.4772562 -0.3310037 -0.8103175 -0.4835515 -0.2593743 -0.8362376 -0.4831476 -0.258817 -0.8374435 -0.4813547 -0.1925671 -0.8550213 -0.4815148 -0.1934603 -0.853388 -0.4840479 -0.1199527 -0.8667465 -0.4841094 -0.1182183 -0.8696056 -0.4793857 -0.04654747 -0.8763086 -0.4794963 -0.04932391 -0.872648 -0.4858527 0.02310627 -0.8734429 -0.4863781 0.02971297 -0.9855736 -0.1666188 0.1075034 -0.9801737 -0.1664412 0.1065277 -0.9798461 -0.1689777 0.1883421 -0.9673528 -0.1695758 0.1918515 -0.9681037 -0.161147 0.2694693 -0.9493615 -0.1615524 0.2681415 -0.9492168 -0.1645835 0.3477281 -0.9229709 -0.1649543 0.3461121 -0.9229111 -0.1686469 0.4200638 -0.8916339 -0.1689245 0.4223487 -0.8915517 -0.1635762 0.4949643 -0.853337 -0.1637876 0.4926148 -0.8536523 -0.1691402 0.5615161 -0.8100057 -0.1690874 0.5625243 -0.8099271 -0.166086 0.6274015 -0.7607595 -0.1661697 0.6274015 -0.7607595 -0.1661697 0.6274015 -0.7607596 -0.1661697 0.6279678 -0.7606287 -0.1646229 0.6888396 -0.7059432 -0.1647551 0.6889612 -0.7058827 -0.1645058 0.7450107 -0.6463556 -0.1648741 0.7418857 -0.6478391 -0.1729456 0.7418856 -0.6478391 -0.1729456 0.7418856 -0.6478391 -0.1729456 0.7915146 -0.5861839 -0.1728962 0.7963674 -0.583286 -0.1599265 0.841827 -0.5155056 -0.159942 0.8405964 -0.5163519 -0.1636409 0.8806336 -0.4445374 -0.1639242 0.8822253 -0.44318 -0.1589653 0.9154772 -0.3696997 -0.1588196 0.9137125 -0.3714643 -0.1647542 0.9411495 -0.2951527 -0.1646885 0.942004 -0.2940955 -0.1616675 0.9631701 -0.21503 -0.1614485 0.9617721 -0.2169947 -0.1670563 0.976839 -0.1328985 -0.167701 0.9771302 -0.1323568 -0.1664282 0.984408 -0.05585813 -0.1667959 0.984408 -0.05585813 -0.1667959 0.984408 -0.05585819 -0.1667959 0.9845603 -0.05546569 -0.1660265 0.9857517 0.02578216 -0.1662194 0.9856844 0.02549433 -0.1666627 0.9797139 0.1113445 -0.1666229 0.979584 0.1106733 -0.1678291 0.9676996 0.1883664 -0.1675584 0.9682431 0.1911669 -0.1611233 0.9490527 0.270455 -0.1617194 0.9488626 0.2693564 -0.1646419 0.9235029 0.3462535 -0.1650784 0.923418 0.3448048 -0.1685494 0.8917142 0.4199914 -0.1686807 0.891514 0.42243 -0.1635716 0.854146 0.493566 -0.1637901 0.8539495 0.4952052 -0.159819 0.809287 0.5651019 -0.1603581 0.809287 0.5651018 -0.160358 0.8092868 0.5651018 -0.1603581 0.8102878 0.5600802 -0.1724642 0.7614856 0.6247003 -0.1728854 0.7614855 0.6247003 -0.1728854 0.7614856 0.6247003 -0.1728854 0.760549 0.6280141 -0.1648142 0.7605489 0.6280141 -0.1648142 0.760549 0.6280141 -0.1648142 0.7059549 0.6887856 -0.1649304 0.7071338 0.6857987 -0.1721687 0.6478465 0.7421265 -0.1718812 0.6466193 0.7445815 -0.1657769 0.5820275 0.7960024 -0.166206 0.583909 0.7927222 -0.1750485 0.5171908 0.8378073 -0.1749076 0.5144539 0.8417316 -0.1637836 0.4428306 0.8814826 -0.1639804 0.4442068 0.8799333 -0.1685162 0.3712413 0.9130861 -0.1686825 0.3700283 0.9142898 -0.1647827 0.2912427 0.9423873 -0.1645716 0.293608 0.9403293 -0.1719747 0.2186932 0.960583 -0.1716204 0.2141688 0.9637263 -0.1592589 0.1330206 0.9783492 -0.1585515 0.1358901 0.9766605 -0.1663374 0.05565178 0.9844263 -0.1667569 0.05541151 0.9845608 -0.166041 -0.03000909 0.9856303 -0.1662297 -0.02987968 0.9855698 -0.1666116 -0.1069934 0.9801771 -0.1667492 -0.1065189 0.9800406 -0.1678518 -0.1884089 0.9677302 -0.1673334 -0.192025 0.9684374 -0.1589197 -0.270663 0.9495236 -0.1585762 -0.2681093 0.9492183 -0.1646273 -0.3463058 0.9234675 -0.1651673 -0.3446915 0.9234765 -0.1684609 -0.4201781 0.8916079 -0.1687774 -0.4223333 0.8915306 -0.1637306 -0.4967224 0.8523377 -0.1636685 -0.4943117 0.8526747 -0.1691212 -0.4943117 0.8526747 -0.1691211 -0.4943116 0.8526747 -0.1691212 -0.5614379 0.8100999 -0.168895 -0.5625934 0.8098128 -0.166409 -0.6253569 0.7624433 -0.16616 -0.6259883 0.7622457 -0.1646827 -0.6888338 0.7059485 -0.1647563 -0.6889066 0.705849 -0.1648786 -0.744842 0.6465596 -0.1648368 -0.7449721 0.6463477 -0.1650801 -0.794732 0.5843313 -0.1641893 -0.7963728 0.5833014 -0.1598436 -0.8418151 0.5154983 -0.1600277 -0.8405998 0.5163502 -0.1636295 -0.8805875 0.4446669 -0.16382 -0.8791367 0.4457997 -0.1684675 -0.9124798 0.3727055 -0.1687342 -0.9136871 0.3714717 -0.1648777 -0.9423587 0.2911498 -0.1649001 -0.9403006 0.2937378 -0.1719093 -0.9614461 0.2146353 -0.1719102 -0.9626318 0.2130004 -0.1672454 -0.976265 0.1368505 -0.1678653 -0.9765717 0.1364733 -0.1663814 -0.9846498 0.05150556 -0.166769 -0.9847897 0.05111598 -0.1660615 -0.9857508 -0.0257821 -0.1662247 -0.9857069 -0.02566951 -0.1665028 -0.9797461 -0.1113482 -0.1664314 -0.9795793 -0.1106759 -0.1678549 -0.9676938 -0.188361 -0.1675975 -0.9673494 -0.1864719 -0.1716488 -0.9473198 -0.2701365 -0.1720805 -0.9471834 -0.2688876 -0.174766 -0.923358 -0.3418176 -0.1748448 -0.9235875 -0.3490505 -0.1585881 -0.8914146 -0.4244205 -0.1588946 -0.8917326 -0.417994 -0.1734766 -0.852764 -0.4927548 -0.1731656 -0.8525371 -0.4945515 -0.1691135 -0.8100968 -0.5614636 -0.1688249 -0.8103042 -0.5600616 -0.1724476 -0.759397 -0.627106 -0.173362 -0.7594502 -0.6271526 -0.1729602 -0.7071031 -0.6857289 -0.1725721 -0.7058689 -0.6889275 -0.1647057 -0.6464565 -0.7449268 -0.1648579 -0.6466958 -0.7444891 -0.165893 -0.5819584 -0.796023 -0.1663488 -0.5839708 -0.7926316 -0.1752524 -0.5171668 -0.8378216 -0.1749105 -0.5157366 -0.8398721 -0.1692063 -0.442563 -0.8807084 -0.1687921 -0.4425414 -0.8807595 -0.1685815 -0.3727596 -0.912437 -0.1688464 -0.3713796 -0.9137857 -0.1645384 -0.2912933 -0.9423094 -0.1649276 -0.2912933 -0.9423096 -0.1649275 -0.2912933 -0.9423094 -0.1649275 -0.2936066 -0.9403205 -0.1720247 -0.2178039 -0.9607269 -0.1719453 -0.2169281 -0.9613835 -0.1693637 -0.1327742 -0.9766033 -0.1691657 -0.1322482 -0.9768881 -0.1679285 -0.05563402 -0.9842876 -0.1675793 -0.05536091 -0.9844136 -0.1669289 -0.05536097 -0.9844135 -0.1669289 -0.05536097 -0.9844136 -0.1669289 0.02998322 -0.9856837 -0.1659175 -0.4995909 0.02953153 -0.865758 -0.4938871 0.06837719 -0.8668335 -0.4623183 0.1897134 -0.8661818 -0.35317 0.3532118 -0.8663212 -0.2465888 0.4353093 -0.8658521 -0.2465888 0.4353093 -0.8658522 -0.2465887 0.4353094 -0.865852 -0.1146252 0.4873176 -0.8656688 -0.1146252 0.4873176 -0.865669 -0.1146252 0.4873179 -0.8656688 -0.09650546 0.4908264 -0.8658962 -0.05404645 0.4954324 -0.8669635 0.02474808 0.499808 -0.8657826 0.0686165 0.495091 -0.8661275 0.1871359 0.4624356 -0.8666797 0.2929449 0.4042649 -0.8664603 0.4309837 0.2526413 -0.866271 0.4756094 0.1488831 -0.8669657 0.4908462 0.09728866 -0.8657973 0.4953652 0.05424463 -0.8669896 0.4998322 -0.02453607 -0.8657746 0.4942857 -0.06609851 -0.8667829 0.4633318 -0.1874754 -0.8661274 0.3483574 -0.357913 -0.8663402 0.3483574 -0.357913 -0.8663402 0.3483574 -0.357913 -0.8663402 0.2527697 -0.4309683 -0.8662413 0.1213381 -0.484971 -0.8660718 0.1213381 -0.4849709 -0.8660718 0.1213381 -0.4849711 -0.8660717 0.09649121 -0.4908969 -0.8658578 0.05405205 -0.4953517 -0.8670093 -0.0245046 -0.499899 -0.865737 -0.06860536 -0.4948891 -0.8662438 -0.1861951 -0.4628292 -0.8666721 -0.2943415 -0.4031498 -0.8665064 -0.4302833 -0.2523754 -0.8666966 -0.4302833 -0.2523756 -0.8666965 -0.4302833 -0.2523757 -0.8666965 -0.4762233 -0.1489959 -0.8666092 -0.4908324 -0.09756952 -0.8657736 -0.4908325 -0.09756952 -0.8657736 -0.4908324 -0.09756958 -0.8657736 -0.4952149 -0.05661386 -0.866924 -0.2285555 0.05086284 -0.9722014 0.2286533 -0.05126553 -0.9721572 0.2203961 0.09483867 -0.970789 0.3427419 0.06062054 -0.9374716 0.3427419 0.06062054 -0.9374718 0.3427419 0.06062054 -0.9374716 0.2228919 0.08494031 -0.9711356 0.2921435 0.07594668 -0.9533543 0.2194595 0.07486045 -0.9727454 0.2194594 0.07486057 -0.9727454 0.2194595 0.07486051 -0.9727454 0.1987286 -0.07376164 -0.977275 0.148108 -0.09798336 -0.9841053 0.1540808 -0.08811897 -0.9841211 0.09440177 -0.2180858 -0.9713531 0.06166023 -0.3409846 -0.9380446 0.0703125 -0.2192227 -0.973138 0.05823069 -0.2870868 -0.956133 0.05823075 -0.2870868 -0.956133 0.05823081 -0.2870867 -0.9561331 -0.08908766 -0.2455017 -0.9652939 0.07728236 -0.2224448 -0.9718774 -0.07294434 -0.201022 -0.9768671 -0.08803701 -0.1560721 -0.9838145 -0.1006437 -0.1465383 -0.9840719 -0.0881465 -0.1538653 -0.9841523 -0.2159904 -0.0957036 -0.9716939 -0.3430113 -0.06017881 -0.9374016 -0.2191136 -0.0742191 -0.9728724 -0.2884919 -0.06114459 -0.955528 -0.2884919 -0.06114453 -0.955528 -0.2884919 -0.06114447 -0.955528 -0.2193082 -0.07494318 -0.9727731 -0.1987434 0.07376712 -0.9772715 -0.1471828 0.09958845 -0.984083 -0.1541902 0.08796286 -0.9841179 -0.09367138 0.2180358 -0.9714351 -0.06161421 0.3410667 -0.9380177 -0.07397782 0.2190252 -0.9729107 -0.06126576 0.2881802 -0.9556144 0.08837753 0.2454594 -0.9653699 -0.0848937 0.2230644 -0.9711002 -0.08489364 0.2230642 -0.9711002 -0.08489376 0.2230646 -0.9711001 0.07239663 0.2010848 -0.9768949 0.08742624 0.1559717 -0.9838849 0.09961658 0.1472176 -0.984075 0.0879051 0.1541061 -0.9841362 -0.4917085 -0.09253638 -0.8658291 -0.4910133 -0.06399184 -0.8687986 -0.4190019 -0.05461722 -0.9063413 -0.4225256 -0.003676235 -0.9063436 -0.3435491 -0.003018021 -0.93913 -0.3414326 0.03958702 -0.9390723 -0.4802139 -0.1365085 -0.8664641 -0.4788804 -0.1229199 -0.8692321 -0.4091363 -0.1049186 -0.9064214 -0.41882 -0.05491816 -0.9064071 -0.3403676 -0.04461854 -0.9392333 -0.3432194 -0.003666758 -0.9392482 -0.4529536 -0.2137486 -0.8655314 -0.4516012 -0.2169768 -0.865435 -0.4630846 -0.1722228 -0.8694205 -0.4644472 -0.1811099 -0.8668841 -0.3939087 -0.1536347 -0.9062187 -0.4097954 -0.1042839 -0.9061969 -0.3324597 -0.08463066 -0.9393126 -0.3399993 -0.04504728 -0.9393463 -0.4325683 -0.2483135 -0.8667325 -0.4351266 -0.2343704 -0.8693305 -0.3721193 -0.200511 -0.9062685 -0.3936764 -0.1537608 -0.9062983 -0.3195846 -0.1248882 -0.9392916 -0.3325149 -0.08452051 -0.9393031 -0.3862656 -0.3175821 -0.8659911 -0.3817934 -0.3231029 -0.865932 -0.4063563 -0.2813328 -0.8693252 -0.4058058 -0.2859666 -0.8680697 -0.3454793 -0.24356 -0.9062685 -0.3720073 -0.200554 -0.906305 -0.3023369 -0.16303 -0.9391558 -0.320137 -0.1242495 -0.9391881 -0.2586727 -0.1003969 -0.9607335 -0.2689096 -0.06842005 -0.9607322 -0.2614335 -0.05539149 -0.9636309 -0.2652146 -0.03518933 -0.9635472 -0.2789133 -0.05689191 -0.9586296 -0.2828702 -0.003079235 -0.9591533 -0.2666723 0.01765531 -0.9636256 -0.2659999 0.03080475 -0.9634808 -0.2784198 0.01894134 -0.9602727 -0.2789929 0.01444774 -0.9601845 -0.2262568 -0.1320679 -0.9650731 -0.2301235 -0.1236394 -0.9652754 -0.3027635 -0.1626946 -0.9390766 -0.2810385 -0.1978411 -0.9390828 -0.3458328 -0.2433201 -0.9061982 -0.3145507 -0.2826887 -0.9061705 -0.3673707 -0.3300663 -0.8695373 -0.3250362 -0.374377 -0.8684431 -0.3636677 -0.3438387 -0.8657487 -0.3580721 -0.3493148 -0.8658889 -0.2948078 -0.4030644 -0.8663876 -0.3245562 -0.3744966 -0.8685711 -0.2771858 -0.3198975 -0.9059987 -0.3153685 -0.2822931 -0.9060097 -0.2562063 -0.229406 -0.9390054 -0.2818699 -0.1972682 -0.938954 -0.214014 -0.1498127 -0.9652742 -0.2299589 -0.1238627 -0.965286 -0.1599491 -0.08613318 -0.9833602 -0.232611 0.04995203 -0.9712862 -0.232611 0.04995208 -0.9712862 -0.232611 0.04995197 -0.9712862 -0.1429898 -0.1089749 -0.9837065 -0.1469274 -0.103362 -0.983732 -0.213453 -0.1501646 -0.9653438 -0.1929714 -0.1758297 -0.9653217 -0.2532215 -0.2307078 -0.939496 -0.2239045 -0.2594819 -0.9394338 -0.2761957 -0.3200585 -0.9062442 -0.2373389 -0.3498849 -0.9062289 -0.2772505 -0.408755 -0.8695123 -0.2242611 -0.441771 -0.8686458 -0.2581796 -0.4278635 -0.8661848 -0.262806 -0.4250931 -0.8661576 -0.1929041 -0.4599122 -0.8667576 -0.2271851 -0.4418331 -0.8678539 -0.1934921 -0.3763356 -0.9060533 -0.2381011 -0.3498765 -0.9060323 -0.1934158 -0.284154 -0.939067 -0.2265754 -0.2586897 -0.9390118 -0.1723647 -0.1967614 -0.9651815 -0.1945968 -0.1749766 -0.9651505 -0.1321235 -0.1187979 -0.9840886 -0.1423263 -0.106059 -0.9841214 -0.1422648 -0.109557 -0.983747 -0.1332845 -0.1179874 -0.9840296 -0.116786 -0.1342173 -0.9840462 -0.1714931 -0.1971269 -0.9652622 -0.1462844 -0.2165951 -0.9652397 -0.1921066 -0.2844194 -0.9392554 -0.1558653 -0.3057975 -0.9392518 -0.191791 -0.3762393 -0.9064548 -0.1458439 -0.3965307 -0.9063625 -0.1704592 -0.4634186 -0.8695902 -0.1075724 -0.4817385 -0.8696874 -0.1529434 -0.4765778 -0.8657263 -0.147178 -0.4783765 -0.8657336 -0.05832082 -0.4965543 -0.8660442 -0.05832082 -0.4965544 -0.8660442 -0.05832087 -0.4965552 -0.8660438 -0.1161548 -0.4843727 -0.8671167 -0.09857821 -0.4110329 -0.906275 -0.146212 -0.3965595 -0.9062906 -0.1189852 -0.3226799 -0.9389996 -0.1575604 -0.3057672 -0.9389788 -0.1198147 -0.2324789 -0.9651933 -0.1469259 -0.2164205 -0.9651814 -0.09973233 -0.146923 -0.9841073 -0.1153492 -0.1349732 -0.9841122 -0.02940356 -0.499494 -0.8658182 -0.05521559 -0.4917899 -0.8689614 -0.04718542 -0.4201943 -0.9062066 -0.09911006 -0.4111234 -0.9061759 -0.08056688 -0.334306 -0.9390147 -0.1188907 -0.3226615 -0.939018 -0.09042996 -0.2454695 -0.9651774 -0.1201893 -0.2324076 -0.9651638 -0.08220213 -0.1589307 -0.9838617 -0.08397036 -0.1567255 -0.9840661 0.01352447 -0.4982091 -0.8669515 0.005334138 -0.495034 -0.8688573 0.00455439 -0.4220298 -0.9065706 -0.04560446 -0.4194589 -0.9066281 -0.03710234 -0.3413308 -0.9392107 -0.07925033 -0.3340002 -0.9392355 -0.06707698 -0.2827291 -0.9568516 -0.1083459 -0.2312301 -0.9668474 0.09813636 -0.4904103 -0.8659487 0.06389588 -0.4899468 -0.8694077 0.05465459 -0.418991 -0.9063441 0.003658056 -0.4225727 -0.9063217 0.002981424 -0.3436057 -0.9391093 -0.03751647 -0.3414093 -0.9391658 0.1371394 -0.4800714 -0.8664435 0.1227755 -0.4786613 -0.8693731 0.1049508 -0.4091646 -0.9064048 0.05486726 -0.4188279 -0.9064065 0.04458957 -0.3403486 -0.9392415 0.003768384 -0.3431454 -0.9392747 0.2131937 -0.4521669 -0.8660794 0.2117462 -0.4529876 -0.8660057 0.1743027 -0.4625744 -0.8692776 0.1807743 -0.4635406 -0.8674392 0.153614 -0.3939757 -0.9061931 0.1042822 -0.4097564 -0.9062147 0.0847904 -0.3331249 -0.9390625 0.04333823 -0.3411561 -0.9390071 0.250775 -0.4321914 -0.8662116 0.2327979 -0.435338 -0.869647 0.1994825 -0.3730264 -0.9061225 0.1533082 -0.3941977 -0.9061484 0.1246021 -0.3204515 -0.9390342 0.0847215 -0.3332022 -0.9390414 0.3182969 -0.3863291 -0.8657003 0.3190182 -0.3861714 -0.8655052 0.2821275 -0.407455 -0.8685531 0.2856846 -0.4071315 -0.8675416 0.2427805 -0.34591 -0.9063134 0.1999394 -0.3724313 -0.9062667 0.1623121 -0.3022555 -0.9393063 0.1257799 -0.3191196 -0.9393306 0.1014555 -0.2574412 -0.9609532 0.06809407 -0.2678713 -0.9610455 0.05667102 -0.2611001 -0.9636468 0.03373885 -0.2655084 -0.9635182 0.05512762 -0.2790727 -0.9586863 0.003102421 -0.2828695 -0.9591535 -0.01762187 -0.2667719 -0.9635987 -0.02925157 -0.2662816 -0.9634515 -0.0189622 -0.2767421 -0.9607571 -0.01473069 -0.2775775 -0.9605904 -0.01473069 -0.2775774 -0.9605904 -0.01473069 -0.2775775 -0.9605904 0.3487257 -0.3575848 -0.8663277 0.3319966 -0.3657655 -0.8694791 0.2838866 -0.3127028 -0.9064356 0.2430708 -0.3454591 -0.9064076 0.197665 -0.2808718 -0.9391697 0.1618321 -0.3030335 -0.9391385 0.1232278 -0.2306819 -0.9651948 0.1317072 -0.22672 -0.9650136 -0.03633338 -0.2283812 -0.9728936 -0.03633338 -0.2283811 -0.9728936 -0.03633338 -0.2283812 -0.9728937 0.4029336 -0.2971641 -0.8656433 0.4041538 -0.2954888 -0.8656478 0.3752262 -0.325881 -0.8677597 0.373121 -0.3266192 -0.8683898 0.3183423 -0.2787088 -0.9060793 0.2833249 -0.3144891 -0.9059931 0.2298861 -0.2551293 -0.9391812 0.1978119 -0.2807202 -0.9391841 0.1506009 -0.2137208 -0.9652165 0.123237 -0.2305506 -0.9652249 0.0846821 -0.1584425 -0.9837301 -0.03703176 -0.2269057 -0.9732125 0.1087888 -0.1430181 -0.983723 0.1035581 -0.1465848 -0.9837626 0.1507713 -0.2134264 -0.965255 0.1752513 -0.1939248 -0.9652358 0.2300822 -0.2545968 -0.9392778 0.2584136 -0.225709 -0.9392965 0.3184865 -0.2781981 -0.9061855 0.3504273 -0.2366715 -0.9061939 0.4095323 -0.2765266 -0.8693771 0.4425007 -0.2235116 -0.8684675 0.4281182 -0.2584959 -0.8659646 0.4259226 -0.2620354 -0.8659835 0.4607608 -0.1934082 -0.8661946 0.4607608 -0.1934081 -0.8661945 0.4607608 -0.1934081 -0.8661945 0.4426247 -0.2276229 -0.8673357 0.3505412 -0.2355116 -0.906452 0.2845574 -0.1912027 -0.9393981 0.2586337 -0.2249079 -0.939428 0.1974346 -0.1716641 -0.9651689 0.1748533 -0.1947586 -0.9651401 0.1189157 -0.1324409 -0.9840317 0.1055745 -0.1431367 -0.9840559 0.1100705 -0.1428352 -0.9836069 0.1199503 -0.1308644 -0.9841171 0.1340179 -0.1165701 -0.984099 0.197464 -0.1717873 -0.9651409 0.2161208 -0.1474044 -0.9651756 0.2841408 -0.1937696 -0.9389981 0.3053771 -0.1579326 -0.9390433 0.375652 -0.1942437 -0.906176 0.3967809 -0.1459367 -0.906238 0.4639445 -0.1706337 -0.8692753 0.4825447 -0.107299 -0.8692741 0.4778823 -0.1473054 -0.8659847 0.4770496 -0.1505033 -0.8658941 0.4909172 -0.08659082 -0.8668925 0.484687 -0.1144127 -0.8671726 0.4116218 -0.09720373 -0.9061561 0.396876 -0.1463053 -0.906137 0.3220494 -0.1187825 -0.9392418 0.3054351 -0.1564066 -0.9392798 0.2323667 -0.119056 -0.9653142 0.2165621 -0.1457025 -0.9653351 0.1476519 -0.09936022 -0.9840359 0.1332909 -0.1179873 -0.9840288 0.4995943 -0.02931636 -0.8657633 0.4917356 -0.05528652 -0.8689876 0.4201179 -0.04723626 -0.9062393 0.4115756 -0.09698784 -0.9062003 0.3338791 -0.07866293 -0.939328 0.3220083 -0.1179642 -0.9393588 0.2454972 -0.08989793 -0.9652199 0.2321922 -0.1200309 -0.9652355 0.159455 -0.08244127 -0.9837568 0.1558815 -0.08520436 -0.9840941 0.4981942 0.01359182 -0.8669589 0.4950608 0.005338132 -0.8688421 0.4229295 0.004525542 -0.9061513 0.4202824 -0.0474525 -0.9061518 0.3410567 -0.03860634 -0.9392497 0.3340104 -0.07915723 -0.9392397 0.2826519 -0.06703829 -0.9568772 0.2316288 -0.1081084 -0.9667785 0.4907799 0.09716176 -0.8658491 0.4899963 0.06392127 -0.8693777 0.419874 0.0547325 -0.9059306 0.4234414 0.003758013 -0.9059157 0.3428078 0.002974867 -0.9394009 0.3407868 -0.03764998 -0.9393864 0.4799611 0.133947 -0.8670038 0.4788675 0.122853 -0.8692486 0.4099869 0.1051941 -0.906005 0.4197165 0.05496203 -0.9059898 0.3403682 0.04458183 -0.9392349 0.3433109 0.001857042 -0.9392201 0.452171 0.2133774 -0.866032 0.4528833 0.2115644 -0.8661046 0.4625704 0.174239 -0.8692924 0.4635247 0.1808155 -0.8674392 0.3939245 0.1535842 -0.9062204 0.4092602 0.1059815 -0.9062417 0.3321793 0.08598709 -0.9392887 0.3400283 0.04509764 -0.9393333 0.4321729 0.250812 -0.8662101 0.4353851 0.2327542 -0.8696352 0.3726916 0.1992876 -0.9063032 0.3936942 0.1538432 -0.9062765 0.3202236 0.1251028 -0.9390454 0.3332067 0.08474445 -0.9390376 0.3862197 0.3176329 -0.865993 0.385418 0.3183898 -0.8660721 0.4070333 0.2818668 -0.8688355 0.406502 0.2865049 -0.8675663 0.3454894 0.2435591 -0.906265 0.3728215 0.1991662 -0.9062764 0.3035105 0.1621226 -0.9389343 0.3207843 0.1245918 -0.9389219 0.2587018 0.1004081 -0.9607246 0.2688731 0.06835263 -0.9607472 0.2614521 0.05551058 -0.9636189 0.2651957 0.03513658 -0.9635542 0.2788904 0.05688583 -0.9586366 0.2829928 0.001492142 -0.9591209 0.2665761 -0.01920115 -0.9636227 0.2660867 -0.02940404 -0.9635005 0.2787067 -0.01715874 -0.960223 0.2780762 -0.02077418 -0.9603344 0.2262123 0.1320499 -0.965086 0.2295843 0.1248357 -0.9652498 0.301299 0.1638588 -0.9393452 0.2805448 0.1974503 -0.9393126 0.3458057 0.2433043 -0.9062128 0.3145543 0.2827057 -0.9061639 0.3673875 0.3300311 -0.8695435 0.3266277 0.3739849 -0.8680148 0.3584576 0.3489463 -0.8658779 0.3584576 0.3489463 -0.8658779 0.3584576 0.3489463 -0.8658779 0.3580483 0.3494129 -0.8658593 0.2948651 0.403057 -0.8663716 0.3245792 0.374445 -0.8685846 0.2768102 0.3193897 -0.9062927 0.3139008 0.2827969 -0.9063621 0.255102 0.2299138 -0.939182 0.2813538 0.1969071 -0.9391846 0.2144377 0.1500629 -0.9651412 0.2304144 0.1240994 -0.9651469 0.1568624 0.08445817 -0.9840026 0.2275599 -0.05121058 -0.9724166 0.2275599 -0.05121058 -0.9724166 0.2275598 -0.05121052 -0.9724166 0.1422832 0.109134 -0.9837913 0.146484 0.1031085 -0.9838248 0.213818 0.1505083 -0.9652094 0.1939685 0.1752907 -0.9652199 0.2546157 0.2300696 -0.9392758 0.2249499 0.2591819 -0.9392669 0.2771341 0.3193016 -0.9062247 0.2373391 0.3499465 -0.906205 0.2775683 0.4092292 -0.8691877 0.2242503 0.4417876 -0.8686401 0.2581652 0.4275884 -0.866325 0.2643159 0.4242699 -0.8661019 0.1876868 0.4622254 -0.8666726 0.2262547 0.441859 -0.8680837 0.1928783 0.3766368 -0.906059 0.2381106 0.3498903 -0.9060243 0.1931796 0.2837566 -0.9392359 0.2252774 0.2591125 -0.9392076 0.1716834 0.1974319 -0.965166 0.1945947 0.1749036 -0.9651641 0.1321558 0.1188126 -0.9840825 0.1431008 0.1050458 -0.9841176 0.1432031 0.1098356 -0.9835797 0.1319087 0.1189014 -0.9841049 0.1165945 0.1339972 -0.9840989 0.1717664 0.1974319 -0.9651513 0.1464771 0.216863 -0.9651503 0.1918801 0.2841134 -0.9393943 0.1557149 0.3055025 -0.9393727 0.1919689 0.3766528 -0.9062452 0.1459565 0.3967757 -0.9062371 0.1703426 0.4631018 -0.8697816 0.1070204 0.4815874 -0.8698393 0.1529026 0.4763482 -0.8658599 0.1470782 0.4780523 -0.8659297 0.05854582 0.4966555 -0.8659709 0.05854594 0.4966557 -0.865971 0.05854588 0.4966563 -0.8659705 0.1166211 0.4844838 -0.866992 0.09896415 0.4111121 -0.906197 0.1463036 0.3968579 -0.9061453 0.1189802 0.3226914 -0.9389963 0.1583495 0.3053857 -0.9389702 0.1203774 0.2321268 -0.965208 0.1459717 0.2170023 -0.9651955 0.09914064 0.1473652 -0.9841009 0.1164694 0.1341139 -0.9840978 0.02936846 0.4996483 -0.8657304 0.05504125 0.4917352 -0.8690034 0.04701596 0.4200198 -0.9062963 0.09864896 0.4110818 -0.9062452 0.08024388 0.3343617 -0.9390225 0.1188799 0.3227109 -0.9390023 0.09041839 0.2454697 -0.9651783 0.1210033 0.2320787 -0.9651414 0.0826075 0.1584498 -0.9839053 0.08399516 0.1566707 -0.9840728 -0.01352536 0.4982423 -0.8669325 -0.005345344 0.4950798 -0.8688311 -0.00456202 0.4220297 -0.9065705 0.04579502 0.4196131 -0.9065471 0.03725141 0.3412749 -0.9392252 0.0788213 0.3340966 -0.9392373 0.06678843 0.2830873 -0.9567658 0.1083514 0.2312213 -0.9668489 -0.09820723 0.490741 -0.8657532 -0.09820723 0.490741 -0.8657532 -0.06413531 0.4899331 -0.8693976 -0.05485296 0.4189801 -0.906337 -0.003633201 0.4225901 -0.9063137 -0.00295943 0.3435919 -0.9391145 0.03774631 0.3414208 -0.9391524 -0.1372221 0.4802408 -0.8663365 -0.1223697 0.4788767 -0.8693118 -0.1046389 0.4094726 -0.9063019 -0.054892 0.4189113 -0.9063665 -0.0445978 0.3403412 -0.9392439 -0.003759384 0.3432196 -0.9392477 -0.2133896 0.4525327 -0.8658401 -0.2141885 0.4522327 -0.8657996 -0.1743084 0.4625897 -0.8692683 -0.1807671 0.4635223 -0.8674506 -0.1536054 0.3939025 -0.9062264 -0.1042699 0.4098179 -0.9061882 -0.08478271 0.3331309 -0.9390611 -0.0433408 0.3411298 -0.9390166 -0.2510225 0.4326374 -0.8659172 -0.2330228 0.4357868 -0.869362 -0.199278 0.3726655 -0.906316 -0.1537888 0.3936787 -0.9062926 -0.1250057 0.3200162 -0.939129 -0.08510828 0.3328732 -0.939123 -0.3194555 0.3846513 -0.8660206 -0.3150102 0.3883072 -0.8660174 -0.2832484 0.4069022 -0.8684474 -0.2865095 0.4064772 -0.8675763 -0.243523 0.3454995 -0.9062708 -0.199209 0.3728339 -0.9062619 -0.1616842 0.3025912 -0.9393066 -0.1258062 0.3191885 -0.9393038 -0.1014586 0.257412 -0.9609606 -0.06843608 0.2677013 -0.9610685 -0.05701726 0.2611678 -0.9636081 -0.03373926 0.2654616 -0.963531 -0.05512911 0.27908 -0.9586841 -0.003096878 0.28285 -0.9591592 0.01762622 0.2666082 -0.9636439 0.02940589 0.2660661 -0.9635062 0.01894825 0.2768475 -0.960727 0.01435101 0.277569 -0.9605985 -0.3472706 0.3590873 -0.8662906 -0.3313442 0.3667804 -0.8693004 -0.2835108 0.3137999 -0.906174 -0.2433452 0.3458262 -0.906194 -0.197417 0.2805366 -0.9393219 -0.1616585 0.3026045 -0.9393067 -0.1232223 0.2306715 -0.9651979 -0.1317256 0.2267516 -0.9650036 0.03646254 0.2283881 -0.9728872 -0.4037516 0.2947372 -0.8660917 -0.3986091 0.3013702 -0.8661909 -0.3752254 0.3258204 -0.8677828 -0.3744965 0.3260598 -0.8680078 -0.3186533 0.2774589 -0.9063535 -0.2837974 0.3130999 -0.9063264 -0.2303397 0.2541248 -0.9393424 -0.1975523 0.2803519 -0.9393487 -0.1507924 0.2139458 -0.9651367 -0.1225914 0.2313501 -0.9651158 -0.08419245 0.1588923 -0.9836996 0.0369473 0.2269147 -0.9732136 -0.1080077 0.1430751 -0.9838008 -0.1039913 0.1458634 -0.983824 -0.1516658 0.2127193 -0.9652709 -0.1745102 0.1945459 -0.9652452 -0.2295191 0.255849 -0.9390753 -0.2588381 0.2261534 -0.9390727 -0.31844 0.2781614 -0.9062132 -0.3504492 0.2366843 -0.9061821 -0.4095362 0.2765897 -0.8693552 -0.4424933 0.2212228 -0.8690571 -0.4248557 0.2637336 -0.8659921 -0.4259026 0.2620381 -0.8659925 -0.4610022 0.1929865 -0.86616 -0.4426004 0.227611 -0.8673511 -0.3505362 0.2355809 -0.906436 -0.2850898 0.1915236 -0.9391713 -0.2590654 0.2252368 -0.9392303 -0.1974596 0.1717323 -0.9651517 -0.1738988 0.1956222 -0.9651379 -0.1182177 0.1330129 -0.9840388 -0.1055848 0.1430638 -0.9840654 -0.1101709 0.14294 -0.9835805 -0.1101709 0.14294 -0.9835805 -0.1101709 0.14294 -0.9835805 -0.1197536 0.1306498 -0.9841696 -0.1345136 0.1156823 -0.9841361 -0.1979996 0.1701942 -0.9653134 -0.2164567 0.1462358 -0.965278 -0.284933 0.1924927 -0.9390206 -0.3053916 0.1579081 -0.9390426 -0.3756151 0.1942318 -0.906194 -0.3967922 0.145936 -0.9062333 -0.4630953 0.1703776 -0.8697783 -0.4823404 0.1093826 -0.8691279 -0.4779033 0.1477274 -0.8659013 -0.4780424 0.1470502 -0.8659398 -0.4955931 0.05822432 -0.8666011 -0.4955933 0.05822312 -0.8666011 -0.495593 0.0582239 -0.8666011 -0.4837653 0.1141955 -0.8677158 -0.4116234 0.09720361 -0.9061554 -0.3968741 0.1463054 -0.9061379 -0.3220286 0.1187381 -0.9392545 -0.3054596 0.1564658 -0.939262 -0.2328079 0.1192354 -0.9651857 -0.2161407 0.1473879 -0.9651736 -0.1469908 0.1001883 -0.9840508 -0.133278 0.1179875 -0.9840305 -0.4998984 0.02518451 -0.8657178 -0.4907176 0.05511295 -0.869574 -0.4201555 0.04718071 -0.9062249 -0.4115189 0.09697496 -0.9062275 -0.333854 0.07865756 -0.9393373 -0.3220213 0.1179637 -0.9393545 -0.2454851 0.0899356 -0.9652195 -0.2329058 0.118476 -0.9652556 -0.1600024 0.08133488 -0.9837601 -0.1566928 0.08404254 -0.9840652 -0.4981616 -0.0135141 -0.866979 -0.494361 -0.003573894 -0.8692495 -0.422885 -0.003057479 -0.9061783 -0.420281 0.04752576 -0.9061487 -0.3410807 0.03857231 -0.9392424 -0.3340269 0.0792573 -0.9392254 -0.2842873 0.06749355 -0.9563605 -0.2316529 0.1093508 -0.966633 -0.07125836 0.9974574 0.001005828 -0.06759136 0.9977126 -0.001066505 -0.06997424 0.9975487 4.49258e-4 -0.06962883 0.9975647 -0.004081606 -0.06909984 0.9976098 2.89342e-4 -0.06909984 0.9976098 2.89375e-4 -0.06909984 0.9976098 2.89369e-4 -0.06965577 0.9975706 0.001080095 -0.07771563 0.996701 0.02339899 -0.07011008 0.9975367 -0.002252757 0.9085377 -0.4178031 0 0.868322 -0.4960011 0 0.9085377 -0.4178029 0 0.9569893 -0.2901232 0 0.9570119 -0.290049 0 0.993444 -0.1143203 0 0.9934347 -0.1144005 0 0.9979366 0.06420814 0 0.9979469 0.06404644 0 0.9707933 0.2399177 0 0.9707744 0.2399942 0 0.9120773 0.4100185 0 0.9121076 0.4099511 0 0.8242062 0.5662899 0 0.824282 0.5661796 0 0.7090559 0.7051524 0 0.7090557 0.7051525 0 0.572323 0.8200283 0 0.5723611 0.8200017 0 0.4166091 0.9090857 0 0.4166396 0.9090718 0 0.2481585 0.9687195 0 0.2481781 0.9687145 0 0.07049363 0.9975123 0 0.07050508 0.9975115 0 -0.1086135 0.9940841 0 -0.108631 0.9940822 0 -0.2840205 0.9588183 0 -0.2840204 0.9588183 0 -0.4507747 0.8926378 0 -0.4507746 0.8926379 0 -0.6030277 0.7977203 0 -0.6030275 0.7977206 0 -0.7356528 0.6773589 0 -0.7356123 0.6774028 0 -0.8446552 0.535311 0 -0.8445816 0.5354269 0 -0.9274097 0.3740472 0 -0.9274379 0.3739774 0 -0.9785014 0.2062408 0 -0.9784849 0.2063186 0 -0.9996856 0.0250774 0 -0.9996835 0.02515852 0 -0.9881494 -0.1534957 0 -0.988174 -0.1533372 0 -0.945227 -0.3264138 0 -0.9452019 -0.3264865 0 -0.8713603 -0.4906439 0 -0.8712908 -0.4907672 0 -0.7697239 -0.638377 0 -0.7696838 -0.6384254 0 -0.6440981 -0.764943 0 -0.6440578 -0.7649768 0 -0.4957549 -0.8684626 0 -0.4957197 -0.8684826 0 -0.3335601 -0.9427288 0 -0.3335855 -0.9427199 0 -0.1597958 -0.9871502 0 -0.1597957 -0.9871502 0 0.01899725 -0.9998195 0 0.01899725 -0.9998195 0 0.1969099 -0.9804217 0 0.1969097 -0.9804217 0 0.3692464 -0.9293316 0 0.3692184 -0.9293426 0 0.5294085 -0.8483671 0 0.5293717 -0.8483901 0 0.6714577 -0.7410429 0 0.6714174 -0.7410795 0 0.7937337 -0.6082655 0 0.7937728 -0.6082144 0 0.8683219 -0.4960013 0 1.27593e-6 0 -1 6.37521e-7 0 -1 3.66849e-6 0 -1 2.2373e-6 0 -1 6.34144e-7 0 -1 -2.55347e-6 0 -1 -3.60459e-6 0 -1 1.27703e-6 0 -1 -6.37086e-7 0 -1 3.65861e-6 0 -1 -1.89417e-6 0 -1 9.57492e-7 0 -1 4.49796e-7 0 -1 9.0271e-7 0 -1 -1.27381e-6 0 -1 -3.59754e-6 0 -1 1.2768e-6 0 -1 9.0068e-7 0 -1 1.27683e-6 0 -1 -1.2672e-6 0 -1 3.6295e-6 0 -1 -1.26517e-6 0 -1 1.27675e-6 0 -1 3.04019e-6 0 -1 -7.207e-6 0 -1 1.27216e-6 0 -1 -6.34325e-7 0 -1 -6.37924e-7 0 -1 -5.05321e-6 0 -1 1.91718e-6 0 -1 -1.27715e-6 0 -1 -0.8601006 0.5101245 0 -0.9142948 0.4050495 0 -0.8601007 0.5101243 0 -0.7484749 0.6631631 0 -0.7485902 0.663033 0 -0.5589091 0.8292291 0 -0.5589627 0.8291929 0 -0.3356828 0.9419751 0 -0.3356828 0.9419752 0 -0.0904349 0.9959024 0 -0.09043478 0.9959024 0 0.1602436 0.9870775 0 0.399762 0.9166191 0 0.3997192 0.9166377 0 0.614904 0.7886021 0 0.6149599 0.7885584 0 0.7940831 0.6078093 0 0.7941393 0.6077359 0 0.9187583 0.3948206 0 0.9187581 0.3948209 0 0.9878493 0.1554146 0 0.9878316 0.155528 0 0.9950172 -0.09970283 0 0.9950173 -0.09970289 0 0.9393644 -0.3429207 0 0.9393269 -0.3430234 0 0.8262103 -0.5633619 0 0.8262102 -0.563362 0 0.6578775 -0.753125 0 0.6578772 -0.7531253 0 0.4507436 -0.8926535 0 0.4506968 -0.8926772 0 0.2153168 -0.9765443 0 0.2153167 -0.9765443 0 -0.03503596 -0.9993861 0 -0.03503596 -0.9993861 0 -0.2825828 -0.9592429 0 -0.2825827 -0.9592431 0 -0.5109747 -0.8595958 0 -0.7109062 -0.7032869 0 -0.710848 -0.7033457 0 -0.8622269 -0.5065225 0 -0.8622774 -0.5064364 0 -0.9613376 -0.275373 0 -0.9613375 -0.2753732 0 -0.9996119 -0.02786189 0 -0.9996086 -0.02797794 0 -0.9756211 0.219462 0 -0.975645 0.2193559 0 -0.975645 0.219356 0 -0.975645 0.219356 -4.02121e-7 -0.9142948 0.4050496 0 0.09472674 -0.9955034 0 0.09472662 -0.9955034 0 0.2259421 -0.9741408 0 0.2259423 -0.9741408 0 0.3984616 -0.9171851 0 0.3984614 -0.9171851 0 0.5528305 -0.8332939 0 0.55283 -0.833294 0 0.6942061 -0.7197763 0 0.6942058 -0.7197767 0 0.8114191 -0.5844648 0 0.9028617 -0.4299312 0 0.9028616 -0.4299315 0 0.965012 -0.262206 0 0.9650117 -0.2622073 0 0.9963182 -0.08573305 0 0.9963182 -0.08573311 0 0.9956106 0.09359335 0 0.9956107 0.09359216 0 0.9628496 0.2700386 0 0.9628491 0.2700398 0 0.899535 0.4368488 0 0.8995354 0.4368478 0 0.8064427 0.5913122 0 0.8064421 0.5913133 0 0.6885444 0.7251943 0 0.688543 0.7251957 0 0.5469134 0.8371892 0 0.5469124 0.8371899 0 0.3903163 0.9206809 0 0.390316 0.9206809 0 0.2175665 0.9760456 0 0.2175666 0.9760455 0 0.04184877 0.9991241 0 0.04184871 0.9991241 0 -0.1394452 0.9902298 0 -0.1394448 0.9902299 0 -0.3123937 0.9499527 0 -0.3123942 0.9499526 0 -0.4770342 0.8788847 0 -0.4770341 0.8788848 0 -0.6271412 0.7789056 0 -0.6271398 0.7789068 0 -0.7557353 0.6548773 0 -0.7557339 0.6548789 0 -0.8601011 0.5101237 0 -0.8600988 0.5101274 0 -0.9378907 0.346931 0 -0.9378907 0.3469311 0 -0.9846273 0.1746688 0 -0.9846269 0.1746714 0 -0.9999921 -0.003996133 0 -0.9999921 -0.00399357 0 -0.9832518 -0.1822529 0 -0.9832518 -0.182253 0 -0.9347677 -0.3552595 0 -0.8563535 -0.51639 0 -0.8563547 -0.5163882 0 -0.7503671 -0.6610214 0 -0.7503669 -0.6610215 0 -0.6213248 -0.7835532 0 -0.6213247 -0.7835534 0 -0.4689328 -0.883234 0 -0.4689316 -0.8832346 0 -0.3066456 -0.9518238 0 -0.3066461 -0.9518237 0 -0.1283214 -0.9917327 0 -0.1283216 -0.9917326 0 -2.55237e-6 0 -1 3.60397e-6 0 -1 -1.91726e-6 0 -1 3.60834e-6 0 -1 -6.3656e-7 0 -1 -1.89356e-6 0 -1 2.23799e-6 0 -1 6.33874e-7 0 -1 -1.91561e-6 0 -1 1.80012e-6 0 -1 3.61313e-6 0 -1 -1.27245e-6 0 -1 -3.649e-6 0 -1 -1.59765e-6 0 -1 -1.91163e-6 0 -1 -1.27775e-6 0 -1 3.60148e-6 0 -1 -1.44659e-5 0 -1 -2.69429e-6 0 -1 1.45121e-5 0 -1 -2.52108e-6 0 -1 1.27835e-6 0 -1 -1.27666e-6 0 -1 -9.02657e-7 0 -1 4.53424e-7 0 -1 -1.2687e-6 0 -1 -1.27565e-6 0 -1 1.27616e-6 0 -1 1.26898e-6 0 -1 -1.27498e-6 0 -1 -9.00784e-7 0 -1 -4.51746e-7 0 -1 -3.42533e-7 0 -1 0.01601809 0.9998718 0 -0.111536 0.9937605 0 0.01601821 0.9998718 0 0.1995047 0.979897 0 0.199504 0.979897 0 0.4387549 0.8986068 0 0.4387561 0.8986063 0 0.6493765 0.7604671 0 0.6493728 0.7604703 0 0.8173679 0.5761163 0 0.8173659 0.5761189 0 0.9346688 0.3555197 0 0.9346675 0.3555231 0 0.9937632 0.111512 0 0.9937635 0.1115085 0 0.9902484 -0.1393136 0 0.9902484 -0.1393138 0 0.9246883 -0.380725 0 0.9246895 -0.3807222 0 0.8011293 -0.5984914 0 0.8011311 -0.5984891 0 0.6264217 -0.7794844 0 0.6264235 -0.779483 0 0.4112796 -0.9115092 0 0.4112778 -0.9115101 0 0.1754855 -0.9844821 0 0.1754848 -0.9844822 0 -0.07579851 -0.9971233 0 -0.07579845 -0.9971233 0 -0.3230614 -0.9463781 0 -0.3230606 -0.9463784 0 -0.5468489 -0.8372314 0 -0.5468504 -0.8372303 0 -0.7400738 -0.6725257 0 -0.7400746 -0.6725248 0 -0.8826617 -0.470009 0 -0.8826608 -0.4700106 0 -0.9720444 -0.2347973 0 -0.972044 -0.2347992 0 -0.999902 0.01399952 0 -0.999902 0.01399952 0 -0.9650356 0.2621189 0 -0.9650352 0.2621207 0 -0.8695346 0.4938722 0 -0.8695359 0.4938698 0 -0.7187407 0.6952783 0 -0.7187405 0.6952785 0 -0.5258582 0.8505722 0 -0.5258589 0.8505719 0 -0.2952603 0.955417 0 -0.111536 0.9937605 0 -0.8150797 -0.5793489 0 -0.8625558 -0.505962 0 -0.8150798 -0.5793488 0 -0.7302349 -0.6831962 0 -0.7302752 -0.683153 0 -0.5976042 -0.8017913 0 -0.597604 -0.8017914 0 -0.4429706 -0.8965362 0 -0.4429704 -0.8965364 0 -0.2770682 -0.9608502 0 -0.2770681 -0.9608504 0 -0.1006055 -0.9949265 0 -0.1006055 -0.9949265 0 0.07875025 -0.9968944 0 0.07874381 -0.996895 0 0.2552238 -0.9668821 0 0.2552238 -0.9668821 0 0.4236751 -0.9058143 0 0.4236438 -0.9058288 0 0.5794487 -0.8150088 0 0.5794484 -0.815009 0 0.7145182 -0.6996169 0 0.7145993 -0.6995341 0 0.8282678 -0.5603324 0 0.8283054 -0.5602769 0 0.9156839 -0.4018995 0 0.9156838 -0.4018996 0 0.9721939 -0.2341773 0 0.9721754 -0.234254 0 0.9984441 -0.05576306 0 0.9984441 -0.05576312 0 0.9924383 0.1227455 0 0.9924482 0.1226655 0 0.95442 0.2984672 0 0.954443 0.2983934 0 0.8850663 0.4654653 0 0.8851329 0.4653383 0 0.7892996 0.6140084 0 0.7892601 0.6140592 0 0.665277 0.7465968 0 0.6652768 0.7465969 0 0.5220259 0.8529297 0 0.5220618 0.8529077 0 0.3619918 0.9321813 0 0.3619915 0.9321814 0 0.1894279 0.9818947 0 0.1894127 0.9818976 0 0.01088452 0.9999408 0 0.01088273 0.9999409 0 -0.1673604 0.9858958 0 -0.1673737 0.9858936 0 -0.3411475 0.9400098 0 -0.3411474 0.9400098 0 -0.5031561 0.8641957 0 -0.5031912 0.8641752 0 -0.6505586 0.7594561 0 -0.6505585 0.7594562 0 -0.7743438 0.6327651 0 -0.7744231 0.6326682 0 -0.8757715 0.4827261 0 -0.8758057 0.4826639 0 -0.9472079 0.3206201 0 -0.9472325 0.3205475 0 -0.9894323 0.1449962 0 -0.9894206 0.1450757 0 -0.9994381 -0.03351849 0 -0.9994324 -0.03369176 0 -0.9994323 -0.03369176 0 -0.9994323 -0.03369176 -2.09078e-7 -0.9772828 -0.2119396 0 -0.977266 -0.2120171 0 -0.9240729 -0.3822164 0 -0.9240729 -0.3822166 0 -0.8624144 -0.5062031 0 -6.34389e-7 0 -1 9.00161e-7 0 -1 -1.27274e-6 0 -1 1.82599e-6 0 -1 7.22131e-6 0 -1 6.38733e-7 0 -1 -7.19747e-6 0 -1 2.86978e-6 0 -1 -7.33073e-6 0 -1 -6.3955e-7 0 -1 -6.38068e-7 0 -1 1.58414e-6 0 -1 -4.71354e-6 0 -1 -6.38491e-7 0 -1 -2.53949e-6 0 -1 -6.3885e-7 0 -1 -1.27321e-6 0 -1 1.57535e-6 0 -1 -6.00137e-7 0 -1 1.80167e-6 0 -1 6.39275e-7 0 -1 -1.80012e-6 0 -1 1.27249e-6 0 -1 2.51925e-6 0 -1 -1.28042e-6 0 -1 1.27667e-6 0 -1 -7.21876e-6 0 -1 1.27698e-6 0 -1 0.8738703 0.4861591 0 0.8032348 0.5956627 0 0.8737718 0.4863362 0 0.9490234 0.3152057 0 0.9490234 0.315206 0 0.9976969 0.0678308 0 0.9976969 0.06783086 0 0.9837586 -0.1794966 0 0.9837586 -0.1794967 0 0.9079519 -0.4190745 0 0.9079517 -0.4190748 0 0.7758424 -0.6309267 0 0.7758421 -0.6309271 0 0.5928294 -0.8053282 0 0.5928845 -0.8052876 0 0.3737577 -0.9275264 0 0.3737576 -0.9275264 0 0.1326897 -0.9911577 0 -0.1184239 -0.9929632 0 -0.1184376 -0.9929616 0 -0.3613616 -0.9324258 0 -0.3614003 -0.9324108 0 -0.5836889 -0.8119775 0 -0.5835782 -0.812057 0 -0.7643099 -0.6448493 0 -0.7643097 -0.6448494 0 -0.9023333 -0.4310389 0 -0.9023333 -0.431039 0 -0.9807323 -0.1953566 0 -0.9807101 -0.1954682 0 -0.9984385 0.05586242 0 -0.9984385 0.05586242 0 -0.9529895 0.3030034 0 -0.9529894 0.3030036 0 -0.8476518 0.5305531 0 -0.8476516 0.5305535 0 -0.688773 0.7249771 0 -0.6887152 0.7250321 0 -0.4892982 0.8721166 0 -0.4892483 0.8721445 0 -0.2547029 0.9670194 0 -0.2546743 0.9670269 0 -0.007211863 0.999974 0 0.2414339 0.9704173 0 0.2414339 0.9704173 0 0.4763759 0.8792418 0 0.4763756 0.879242 0 0.6792798 0.7338795 0 0.6792795 0.7338798 0 0.8032988 0.5955763 0 0.8032988 0.5955763 0 0.8032988 0.5955762 0 -0.9085377 0.4178031 0 -0.868322 0.4960011 0 -0.9085377 0.4178029 0 -0.9569893 0.2901232 0 -0.9570119 0.290049 0 -0.993444 0.1143203 0 -0.9934347 0.1144005 0 -0.9979366 -0.06420814 0 -0.9979469 -0.06404644 0 -0.9707933 -0.2399177 0 -0.9707744 -0.2399942 0 -0.9120773 -0.4100185 0 -0.9121076 -0.4099511 0 -0.8242062 -0.5662899 0 -0.824282 -0.5661796 0 -0.7090559 -0.7051524 0 -0.7090557 -0.7051525 0 -0.572323 -0.8200283 0 -0.5723611 -0.8200017 0 -0.4166091 -0.9090857 0 -0.4166396 -0.9090718 0 -0.2481585 -0.9687195 0 -0.2481781 -0.9687145 0 -0.07049363 -0.9975123 0 -0.07050508 -0.9975115 0 0.1086135 -0.9940841 0 0.108631 -0.9940822 0 0.2840205 -0.9588183 0 0.2840204 -0.9588183 0 0.4507747 -0.8926378 0 0.4507746 -0.8926379 0 0.6030277 -0.7977203 0 0.6030275 -0.7977206 0 0.7356528 -0.6773589 0 0.7356123 -0.6774028 0 0.8446552 -0.535311 0 0.8445816 -0.5354269 0 0.9274097 -0.3740472 0 0.9274379 -0.3739774 0 0.9785014 -0.2062408 0 0.9784849 -0.2063186 0 0.9996856 -0.0250774 0 0.9996835 -0.02515852 0 0.9881494 0.1534957 0 0.988174 0.1533372 0 0.945227 0.3264138 0 0.9452019 0.3264865 0 0.8713603 0.4906439 0 0.8712908 0.4907672 0 0.7697239 0.638377 0 0.7696838 0.6384254 0 0.6440981 0.764943 0 0.6440578 0.7649768 0 0.4957549 0.8684626 0 0.4957197 0.8684826 0 0.3335601 0.9427288 0 0.3335855 0.9427199 0 0.1597958 0.9871502 0 0.1597957 0.9871502 0 -0.01899725 0.9998195 0 -0.01899725 0.9998195 0 -0.1969099 0.9804217 0 -0.1969097 0.9804217 0 -0.3692464 0.9293316 0 -0.3692184 0.9293426 0 -0.5294085 0.8483671 0 -0.5293717 0.8483901 0 -0.6714577 0.7410429 0 -0.6714174 0.7410795 0 -0.7937337 0.6082655 0 -0.7937728 0.6082144 0 -0.8683219 0.4960013 0 -4.49796e-7 0 -1 -9.0271e-7 0 -1 1.27381e-6 0 -1 3.59754e-6 0 -1 -1.2768e-6 0 -1 -1.27593e-6 0 -1 -6.37521e-7 0 -1 -3.66849e-6 0 -1 6.37924e-7 0 -1 -3.04019e-6 0 -1 7.207e-6 0 -1 -1.27216e-6 0 -1 3.60459e-6 0 -1 -1.27703e-6 0 -1 6.37086e-7 0 -1 -3.65861e-6 0 -1 2.52556e-6 0 -1 -9.57492e-7 0 -1 -2.2373e-6 0 -1 -6.34144e-7 0 -1 2.55347e-6 0 -1 5.05321e-6 0 -1 -1.91718e-6 0 -1 1.27715e-6 0 -1 -4.73332e-7 0 -1 -9.0068e-7 0 -1 -1.27683e-6 0 -1 1.2672e-6 0 -1 -3.6295e-6 0 -1 1.26517e-6 0 -1 -1.27675e-6 0 -1 0.8601006 -0.5101245 0 0.9142948 -0.4050495 0 0.8601007 -0.5101243 0 0.7484749 -0.6631631 0 0.7485902 -0.663033 0 0.5589091 -0.8292291 0 0.5589627 -0.8291929 0 0.3356828 -0.9419751 0 0.3356828 -0.9419752 0 0.0904349 -0.9959024 0 0.09043478 -0.9959024 0 -0.1602436 -0.9870775 0 -0.399762 -0.9166191 0 -0.3997192 -0.9166377 0 -0.614904 -0.7886021 0 -0.6149599 -0.7885584 0 -0.7940831 -0.6078093 0 -0.7941393 -0.6077359 0 -0.9187583 -0.3948206 0 -0.9187581 -0.3948209 0 -0.9878493 -0.1554146 0 -0.9878316 -0.155528 0 -0.9950172 0.09970283 0 -0.9950173 0.09970289 0 -0.9393644 0.3429207 0 -0.9393269 0.3430234 0 -0.8262103 0.5633619 0 -0.8262102 0.563362 0 -0.6578775 0.753125 0 -0.6578772 0.7531253 0 -0.4507436 0.8926535 0 -0.4506968 0.8926772 0 -0.2153168 0.9765443 0 -0.2153167 0.9765443 0 0.03503596 0.9993861 0 0.03503596 0.9993861 0 0.2825828 0.9592429 0 0.2825827 0.9592431 0 0.5109747 0.8595958 0 0.7109062 0.7032869 0 0.710848 0.7033457 0 0.8622269 0.5065225 0 0.8622774 0.5064364 0 0.9613376 0.275373 0 0.9613375 0.2753732 0 0.9996119 0.02786189 0 0.9996086 0.02797794 0 0.9756211 -0.219462 0 0.975645 -0.2193559 0 0.975645 -0.219356 0 0.975645 -0.219356 -4.02121e-7 0.9142948 -0.4050496 0 -0.09472674 0.9955034 0 -0.09472662 0.9955034 0 -0.2259421 0.9741408 0 -0.2259423 0.9741408 0 -0.3984616 0.9171851 0 -0.3984614 0.9171851 0 -0.5528305 0.8332939 0 -0.55283 0.833294 0 -0.6942061 0.7197763 0 -0.6942058 0.7197767 0 -0.8114191 0.5844648 0 -0.9028617 0.4299312 0 -0.9028616 0.4299315 0 -0.965012 0.262206 0 -0.9650117 0.2622073 0 -0.9963182 0.08573305 0 -0.9963182 0.08573311 0 -0.9956106 -0.09359335 0 -0.9956107 -0.09359216 0 -0.9628496 -0.2700386 0 -0.9628491 -0.2700398 0 -0.899535 -0.4368488 0 -0.8995354 -0.4368478 0 -0.8064427 -0.5913122 0 -0.8064421 -0.5913133 0 -0.6885444 -0.7251943 0 -0.688543 -0.7251957 0 -0.5469134 -0.8371892 0 -0.5469124 -0.8371899 0 -0.3903163 -0.9206809 0 -0.390316 -0.9206809 0 -0.2175665 -0.9760456 0 -0.2175666 -0.9760455 0 -0.04184877 -0.9991241 0 -0.04184871 -0.9991241 0 0.1394452 -0.9902298 0 0.1394448 -0.9902299 0 0.3123937 -0.9499527 0 0.3123942 -0.9499526 0 0.4770342 -0.8788847 0 0.4770341 -0.8788848 0 0.6271412 -0.7789056 0 0.6271398 -0.7789068 0 0.7557353 -0.6548773 0 0.7557339 -0.6548789 0 0.8601011 -0.5101237 0 0.8600988 -0.5101274 0 0.9378907 -0.346931 0 0.9378907 -0.3469311 0 0.9846273 -0.1746688 0 0.9846269 -0.1746714 0 0.9999921 0.003996133 0 0.9999921 0.00399357 0 0.9832518 0.1822529 0 0.9832518 0.182253 0 0.9347677 0.3552595 0 0.8563535 0.51639 0 0.8563547 0.5163882 0 0.7503671 0.6610214 0 0.7503669 0.6610215 0 0.6213248 0.7835532 0 0.6213247 0.7835534 0 0.4689328 0.883234 0 0.4689316 0.8832346 0 0.3066456 0.9518238 0 0.3066461 0.9518237 0 0.1283214 0.9917327 0 0.1283216 0.9917326 0 2.55237e-6 0 -1 -3.60397e-6 0 -1 1.91726e-6 0 -1 -3.60834e-6 0 -1 6.3656e-7 0 -1 1.89356e-6 0 -1 -2.23799e-6 0 -1 -3.61313e-6 0 -1 1.27245e-6 0 -1 3.649e-6 0 -1 9.02657e-7 0 -1 -4.53424e-7 0 -1 1.2687e-6 0 -1 1.27565e-6 0 -1 -1.27616e-6 0 -1 1.59765e-6 0 -1 1.91163e-6 0 -1 1.27775e-6 0 -1 -3.60148e-6 0 -1 1.44659e-5 0 -1 2.69429e-6 0 -1 -1.45121e-5 0 -1 9.00784e-7 0 -1 4.51746e-7 0 -1 3.42533e-7 0 -1 2.52108e-6 0 -1 -1.27835e-6 0 -1 1.27666e-6 0 -1 -1.26895e-6 0 -1 1.27498e-6 0 -1 -6.33874e-7 0 -1 1.91561e-6 0 -1 -0.01601809 -0.9998718 0 0.111536 -0.9937605 0 -0.01601821 -0.9998718 0 -0.1995047 -0.979897 0 -0.199504 -0.979897 0 -0.4387549 -0.8986068 0 -0.4387561 -0.8986063 0 -0.6493765 -0.7604671 0 -0.6493728 -0.7604703 0 -0.8173679 -0.5761163 0 -0.8173659 -0.5761189 0 -0.9346688 -0.3555197 0 -0.9346675 -0.3555231 0 -0.9937632 -0.111512 0 -0.9937635 -0.1115085 0 -0.9902484 0.1393136 0 -0.9902484 0.1393138 0 -0.9246883 0.380725 0 -0.9246895 0.3807222 0 -0.8011293 0.5984914 0 -0.8011311 0.5984891 0 -0.6264217 0.7794844 0 -0.6264235 0.779483 0 -0.4112796 0.9115092 0 -0.4112778 0.9115101 0 -0.1754855 0.9844821 0 -0.1754848 0.9844822 0 0.07579851 0.9971233 0 0.07579845 0.9971233 0 0.3230614 0.9463781 0 0.3230606 0.9463784 0 0.5468489 0.8372314 0 0.5468504 0.8372303 0 0.7400738 0.6725257 0 0.7400746 0.6725248 0 0.8826617 0.470009 0 0.8826608 0.4700106 0 0.9720444 0.2347973 0 0.972044 0.2347992 0 0.999902 -0.01399952 0 0.999902 -0.01399952 0 0.9650356 -0.2621189 0 0.9650352 -0.2621207 0 0.8695346 -0.4938722 0 0.8695359 -0.4938698 0 0.7187407 -0.6952783 0 0.7187405 -0.6952785 0 0.5258582 -0.8505722 0 0.5258589 -0.8505719 0 0.2952603 -0.955417 0 0.111536 -0.9937605 0 0.9635698 0.2674572 0 0.982963 0.1838037 0 0.963549 0.2675324 0 0.9182789 0.3959345 0 0.9182493 0.396003 0 0.8335837 0.5523933 0 0.8336023 0.5523653 0 0.7217509 0.692153 0 0.7217305 0.6921741 0 0.5853804 0.8107588 0 0.5853804 0.8107589 0 0.4324141 0.9016751 0 0.4323823 0.9016904 0 0.2637405 0.9645938 0 0.2637299 0.9645966 0 0.08733922 0.9961787 0 0.08733916 0.9961787 0 -0.09204024 0.9957554 0 -0.09204387 0.995755 0 -0.267618 0.9635251 0 -0.2676073 0.9635281 0 -0.4366848 0.8996146 0 -0.4366686 0.8996225 0 -0.5890769 0.8080771 0 -0.5890574 0.8080912 0 -0.7247313 0.6890317 0 -0.724731 0.689032 0 -0.8356495 0.5492632 0 -0.8356307 0.5492918 0 -0.9205783 0.3905581 0 -0.9205783 0.3905582 0 -0.9754272 0.2203223 0 -0.9754184 0.220361 0 -0.9991245 0.04183632 0 -0.9991245 0.04183632 0 -0.99062 -0.1366465 0 -0.9906144 -0.1366864 0 -0.9508088 -0.3097788 0 -0.9508206 -0.3097422 0 -0.8791087 -0.4766213 0 -0.8791087 -0.4766215 0 -0.7806534 -0.6249642 0 -0.7806333 -0.6249893 0 -0.6556203 -0.7550908 0 -0.65562 -0.7550911 0 -0.5111991 -0.8594623 0 -0.5112167 -0.8594519 0 -0.3491623 -0.9370623 0 -0.3491753 -0.9370574 0 -0.1764979 -0.9843011 0 -0.176512 -0.9842986 0 0.002507746 -0.9999969 0 0.002507746 -0.9999969 0 0.1805634 -0.9835634 0 0.1805489 -0.9835661 0 0.3537559 -0.9353379 0 0.3537557 -0.9353379 0 0.5140955 -0.857733 0 0.5140774 -0.8577438 0 0.660451 -0.7508692 0 0.6604308 -0.750887 0 0.7830812 -0.6219195 0 0.7831009 -0.6218948 0 0.8818849 -0.4714647 0 0.8818681 -0.4714963 0 0.9517892 -0.3067532 0 0.9517891 -0.3067533 0 0.991 -0.1338623 0 0.9910053 -0.1338226 0 0.9988781 0.04735654 0 0.9988743 0.0474376 0 0.982963 0.1838038 0 -3.60438e-6 0 -1 1.5966e-6 0 -1 -7.20606e-6 0 -1 1.90805e-6 0 -1 6.77463e-7 0 -1 1.27868e-6 0 -1 -1.91692e-6 0 -1 3.62792e-6 0 -1 -1.26682e-6 0 -1 2.55639e-6 0 -1 1.27681e-6 0 -1 1.26886e-6 0 -1 -1.26404e-6 0 -1 1.27945e-6 0 -1 1.90863e-6 0 -1 1.59618e-6 0 -1 1.26915e-6 0 -1 -1.59525e-6 0 -1 -1.27816e-6 0 -1 -6.38178e-7 0 -1 3.15516e-7 0 -1 0 0 -1 -4.53793e-7 0 -1 1.26902e-6 0 -1 -0.9872097 -0.1594274 0 -0.9581159 -0.286381 0 -0.9872279 -0.1593143 0 -0.9997126 0.02397525 0 -0.999714 0.02391725 0 -0.9624515 0.2714539 0 -0.9624667 0.2714001 0 -0.8643771 0.5028442 0 -0.864377 0.5028445 0 -0.7120671 0.7021116 0 -0.7120959 0.7020823 0 -0.514486 0.8574989 0 -0.5144858 0.857499 0 -0.2858934 0.9582615 0 -0.2858774 0.9582663 0 -0.03821843 0.9992695 0 -0.03822064 0.9992694 0 0.2118092 0.9773111 0 0.2118211 0.9773085 0 0.4478507 0.8941085 0 0.4478502 0.8941086 0 0.6564983 0.7543275 0 0.6565557 0.7542775 0 0.8238598 0.5667938 0 0.8238596 0.5667941 0 0.9379336 0.3468149 0 0.9379335 0.3468152 0 0.9950193 0.09968364 0 0.9950135 0.09974122 0 0.9890409 -0.1476422 0 0.9890324 -0.1476991 0 0.9204097 -0.3909553 0 0.9203888 -0.3910048 0 0.7929531 -0.6092827 0 0.7928969 -0.6093558 0 0.6183663 -0.78589 0 0.6183378 -0.7859125 0 0.4038733 -0.914815 0 0.4038732 -0.914815 0 0.1633598 -0.9865666 0 0.1633689 -0.9865651 0 -0.087269 -0.9961848 0 -0.3328284 -0.9429875 0 -0.3328283 -0.9429875 0 -0.5551719 -0.8317357 0 -0.5551716 -0.831736 0 -0.7456682 -0.6663175 0 -0.7456969 -0.6662855 0 -0.8884606 -0.458953 0 -0.8884131 -0.4590447 0 -0.9580841 -0.2864875 0 0.7136036 -0.7005498 0 0.6472015 -0.762319 0 0.7136037 -0.7005496 0 0.8011208 -0.5985026 0 0.8011195 -0.5985044 0 0.8959131 -0.4442293 0 0.960422 -0.278549 0 0.9604213 -0.2785514 0 0.9947661 -0.1021786 0 0.9947663 -0.1021761 0 0.9970228 0.07710689 0 0.9970226 0.07710945 0 0.9672974 0.2536454 0 0.9063942 0.4224331 0 0.9063931 0.4224354 0 0.8166729 0.5771009 0 0.8166716 0.5771027 0 0.7000924 0.7140523 0 0.7000923 0.7140524 0 0.5608572 0.8279127 0 0.4044475 0.9145612 0 0.4044474 0.9145613 0 0.2342981 0.9721649 0 0.2342969 0.9721651 0 0.05857408 0.9982831 0 0.05857378 0.9982831 0 -0.1227048 0.9924432 0 -0.1227048 0.9924433 0 -0.2957468 0.9552664 0 -0.2957462 0.9552666 0 -0.4628913 0.8864151 0 -0.4628916 0.8864149 0 -0.61356 0.7896482 0 -0.613559 0.7896488 0 -0.7446506 0.6674546 0 -0.7446498 0.6674554 0 -0.8515409 0.5242882 0 -0.8515396 0.5242903 0 -0.9320407 0.3623536 0 -0.9320398 0.3623559 0 -0.9814893 0.1915177 0 -0.9814892 0.1915179 0 -0.9999198 0.01267236 0 -0.9999198 0.01267367 0 -0.9861488 -0.1658629 0 -0.9861491 -0.1658617 0 -0.9405323 -0.3397045 0 -0.9405327 -0.3397035 0 -0.8648108 -0.502098 0 -0.8648107 -0.5020983 0 -0.7613798 -0.6483062 0 -0.7613795 -0.6483065 0 -0.6331846 -0.7740009 0 -0.6331838 -0.7740015 0 -0.4852184 -0.874393 0 -0.4852183 -0.8743931 0 -0.3207674 -0.947158 0 -0.3207671 -0.9471581 0 -0.1477786 -0.9890206 0 -0.1477785 -0.9890206 0 0.03345352 -0.9994404 0 0.0334534 -0.9994403 0 0.2092275 -0.977867 0 0.2092279 -0.9778669 0 0.3819572 -0.92418 0 0.3819562 -0.9241805 0 0.5408406 -0.8411251 0 0.5408426 -0.8411239 0 0.6472038 -0.7623171 0 9.59413e-7 0 -1 -1.27418e-6 0 -1 3.60189e-6 0 -1 -1.91522e-6 0 -1 4.75628e-7 0 -1 -1.75555e-6 0 -1 1.27632e-6 0 -1 1.27601e-6 0 -1 -1.80323e-6 0 -1 -4.57353e-7 0 -1 3.60023e-6 0 -1 2.36632e-7 0 -1 -3.19602e-7 0 -1 1.80302e-6 0 -1 1.27956e-6 0 -1 -1.27387e-6 0 -1 -6.30943e-7 0 -1 -1.27799e-6 0 -1 -9.01096e-7 0 -1 -1.27505e-6 0 -1 2.53704e-6 0 -1 -6.38537e-7 0 -1 1.27867e-6 0 -1 -1.27337e-6 0 -1 1.2753e-6 0 -1 -1.80074e-6 0 -1 1.26934e-6 0 -1 3.16802e-6 0 -1 -1.91428e-6 0 -1 -0.6312551 0.7755753 0 -0.7293381 0.6841534 0 -0.6312516 0.7755781 0 -0.4786641 0.8779982 0 -0.4786654 0.8779974 0 -0.2472183 0.9689599 0 -0.2472198 0.9689595 0 0.003982782 0.9999921 0 0.2551333 0.9669059 0 0.2551327 0.9669061 0 0.4832655 0.875474 0 0.4832651 0.8754742 0 0.6866718 0.7269676 0 0.6866716 0.7269678 0 0.8472701 0.5311623 0 0.8472707 0.5311614 0 0.9519354 0.3062989 0 0.951936 0.3062974 0 0.9982501 0.0591343 0 0.9982501 0.05913436 0 0.9817172 -0.1903459 0 0.9029417 -0.4297632 0 0.9029409 -0.429765 0 0.7688927 -0.639378 0 0.7688934 -0.639377 0 0.5832241 -0.8123114 0 0.5832231 -0.812312 0 0.3632466 -0.931693 0 0.3632463 -0.9316931 0 0.1236491 -0.9923261 0 0.1236495 -0.992326 0 -0.1276834 -0.991815 0 -0.1276838 -0.991815 0 -0.3710821 -0.9286001 0 -0.371082 -0.9286001 0 -0.5931423 -0.8050977 0 -0.5931404 -0.805099 0 -0.7716974 -0.63599 0 -0.7716974 -0.6359901 0 -0.9069547 -0.4212282 0 -0.9829279 -0.1839913 0 -0.9829266 -0.1839984 0 -0.9977845 0.06652998 0 -0.9977843 0.06653362 0 -0.9498662 0.3126567 0 -0.9498661 0.3126569 0 -0.842165 0.5392201 0 -0.8421615 0.5392254 0 -0.7293379 0.6841537 0 -0.2487807 -0.9685599 0 -0.3355524 -0.9420216 0 -0.2488003 -0.9685549 0 -0.1171626 -0.9931128 0 -0.1171578 -0.9931133 0 0.06188058 -0.9980837 0 0.06187808 -0.9980838 0 0.2393892 -0.9709237 0 0.239389 -0.9709237 0 0.4080603 -0.912955 0 0.4080602 -0.9129551 0 0.5663021 -0.8241979 0 0.5663209 -0.8241848 0 0.7029107 -0.7112782 0 0.7029104 -0.7112784 0 0.818993 -0.5738036 0 0.8190119 -0.5737767 0 0.9082982 -0.4183235 0 0.9083135 -0.41829 0 0.9684083 -0.2493702 0 0.9684181 -0.2493321 0 0.9973679 -0.07250821 0 0.9973679 -0.07250821 0 0.9942828 0.1067795 0 0.9942785 0.1068196 0 0.9592422 0.2825855 0 0.9592531 0.2825483 0 0.8932463 0.4495677 0 0.8932462 0.4495678 0 0.7988093 0.6015844 0 0.7987897 0.6016104 0 0.6779696 0.7350899 0 0.5372961 0.8433938 0 0.5373142 0.8433821 0 0.3771579 0.926149 0 0.205488 0.9786597 0 0.205488 0.9786597 0 0.02757149 0.9996199 0 0.02757036 0.99962 0 -0.1513398 0.9884818 0 -0.1513398 0.9884818 0 -0.3255174 0.9455361 0 -0.3255048 0.9455404 0 -0.4886513 0.8724792 0 -0.4886512 0.8724792 0 -0.6373658 0.7705615 0 -0.6373854 0.7705453 0 -0.7646685 0.6444239 0 -0.7646484 0.6444478 0 -0.8666061 0.498993 0 -0.866641 0.4989324 0 -0.9423124 0.334735 0 -0.9868335 0.16174 0 -0.9868335 0.1617401 0 -0.9998603 -0.01672118 0 -0.9998595 -0.01676177 0 -0.9807549 -0.1952434 0 -0.9807471 -0.1952825 0 -0.9298312 -0.3679865 0 -0.9298034 -0.3680567 0 -0.8497316 -0.5272157 0 -0.8496949 -0.5272747 0 -0.7409406 -0.6715707 0 -0.7409605 -0.6715487 0 -0.6101298 -0.7923015 0 -0.6101297 -0.7923016 0 -0.4592637 -0.8883 0 -0.4592469 -0.8883087 0 -0.335578 -0.9420126 0 -3.60584e-6 0 -1 6.40336e-7 0 -1 1.90642e-6 0 -1 -3.66268e-6 0 -1 -1.27655e-6 0 -1 -1.2685e-6 0 -1 1.27578e-6 0 -1 -6.39353e-7 0 -1 -1.2721e-6 0 -1 3.65273e-6 0 -1 1.7981e-6 0 -1 -1.8277e-6 0 -1 1.26134e-6 0 -1 1.80386e-6 0 -1 1.27825e-6 0 -1 1.26922e-6 0 -1 1.75718e-6 0 -1 2.0752e-6 0 -1 -6.3338e-7 0 -1 -2.21526e-6 0 -1 6.39458e-7 0 -1 -1.91457e-6 0 -1 -1.59112e-6 0 -1 7.30183e-6 0 -1 -1.28025e-6 0 -1 -1.26817e-6 0 -1 1.27969e-6 0 -1 -6.38126e-7 0 -1 -3.17182e-7 0 -1 7.98898e-7 0 -1 0.3507497 0.9364693 0 0.232729 0.9725418 0 0.3507497 0.9364692 0 0.5227223 0.8525031 0 0.7166143 0.6974697 0 0.7166141 0.69747 0 0.8670348 0.4982477 0 0.8670096 0.4982915 0 0.9646725 0.2634524 0 0.9646724 0.2634525 0 0.9998006 0.01997143 0 0.9998018 0.01991343 0 0.9719513 -0.2351825 0 0.971938 -0.2352374 0 0.8844865 -0.4665659 0 0.8844863 -0.4665662 0 0.7413833 -0.6710819 0 0.7413831 -0.671082 0 0.5509914 -0.834511 0 0.5510179 -0.8344934 0 0.3251941 -0.9456474 0 0.3251759 -0.9456536 0 0.08015203 -0.9967827 0 0.08014267 -0.9967834 0 -0.1707317 -0.9853176 0 -0.1707414 -0.9853159 0 -0.4095507 -0.9122874 0 -0.409529 -0.9122971 0 -0.6237288 -0.7816409 0 -0.6237002 -0.7816636 0 -0.8003146 -0.5995803 0 -0.8002589 -0.5996549 0 -0.9223235 -0.3864187 0 -0.9223028 -0.3864683 0 -0.9901973 -0.1396762 0 -0.9901973 -0.1396763 0 -0.9941843 0.107692 0 -0.9941781 0.1077495 0 -0.9363007 0.3511995 0 -0.9363006 0.3511998 0 -0.8186784 0.5742522 0 -0.8187057 0.5742134 0 -0.6513434 0.7587832 0 -0.651372 0.7587586 0 -0.4411035 0.8974563 0 -0.4411493 0.8974338 0 -0.2045536 0.9788554 0 -0.2045651 0.978853 0 0.04536801 0.9989703 0 0.04537063 0.9989703 0 0.2327814 0.9725292 0 -0.9635698 -0.2674572 0 -0.982963 -0.1838037 0 -0.963549 -0.2675324 0 -0.9182789 -0.3959345 0 -0.9182493 -0.396003 0 -0.8335837 -0.5523933 0 -0.8336023 -0.5523653 0 -0.7217509 -0.692153 0 -0.7217305 -0.6921741 0 -0.5853804 -0.8107588 0 -0.5853804 -0.8107589 0 -0.4324141 -0.9016751 0 -0.4323823 -0.9016904 0 -0.2637405 -0.9645938 0 -0.2637299 -0.9645966 0 -0.08733922 -0.9961787 0 -0.08733916 -0.9961787 0 0.09204024 -0.9957554 0 0.09204387 -0.995755 0 0.267618 -0.9635251 0 0.2676073 -0.9635281 0 0.4366848 -0.8996146 0 0.4366686 -0.8996225 0 0.5890769 -0.8080771 0 0.5890574 -0.8080912 0 0.7247313 -0.6890317 0 0.724731 -0.689032 0 0.8356495 -0.5492632 0 0.8356307 -0.5492918 0 0.9205783 -0.3905581 0 0.9205783 -0.3905582 0 0.9754272 -0.2203223 0 0.9754184 -0.220361 0 0.9991245 -0.04183632 0 0.9991245 -0.04183632 0 0.99062 0.1366465 0 0.9906144 0.1366864 0 0.9508088 0.3097788 0 0.9508206 0.3097422 0 0.8791087 0.4766213 0 0.8791087 0.4766215 0 0.7806534 0.6249642 0 0.7806333 0.6249893 0 0.6556203 0.7550908 0 0.65562 0.7550911 0 0.5111991 0.8594623 0 0.5112167 0.8594519 0 0.3491623 0.9370623 0 0.3491753 0.9370574 0 0.1764979 0.9843011 0 0.176512 0.9842986 0 -0.002507746 0.9999969 0 -0.002507746 0.9999969 0 -0.1805634 0.9835634 0 -0.1805489 0.9835661 0 -0.3537559 0.9353379 0 -0.3537557 0.9353379 0 -0.5140955 0.857733 0 -0.5140774 0.8577438 0 -0.660451 0.7508692 0 -0.6604308 0.750887 0 -0.7830812 0.6219195 0 -0.7831009 0.6218948 0 -0.8818849 0.4714647 0 -0.8818681 0.4714963 0 -0.9517892 0.3067532 0 -0.9517891 0.3067533 0 -0.991 0.1338623 0 -0.9910053 0.1338226 0 -0.9988781 -0.04735654 0 -0.9988743 -0.0474376 0 -0.982963 -0.1838038 0 -1.59618e-6 0 -1 -6.77463e-7 0 -1 1.59525e-6 0 -1 -1.27945e-6 0 -1 -1.90863e-6 0 -1 0 0 -1 4.53793e-7 0 -1 -1.27868e-6 0 -1 1.91692e-6 0 -1 -3.62792e-6 0 -1 -1.27681e-6 0 -1 -1.26886e-6 0 -1 1.26404e-6 0 -1 -1.26901e-6 0 -1 1.27816e-6 0 -1 6.38178e-7 0 -1 -2.55639e-6 0 -1 3.60438e-6 0 -1 -1.5966e-6 0 -1 7.20606e-6 0 -1 -1.90805e-6 0 -1 -6.30886e-7 0 -1 0.9872097 0.1594274 0 0.9581159 0.286381 0 0.9872279 0.1593143 0 0.9997126 -0.02397525 0 0.999714 -0.02391725 0 0.9624515 -0.2714539 0 0.9624667 -0.2714001 0 0.8643771 -0.5028442 0 0.864377 -0.5028445 0 0.7120671 -0.7021116 0 0.7120959 -0.7020823 0 0.514486 -0.8574989 0 0.5144858 -0.857499 0 0.2858934 -0.9582615 0 0.2858774 -0.9582663 0 0.03821843 -0.9992695 0 0.03822064 -0.9992694 0 -0.2118092 -0.9773111 0 -0.2118211 -0.9773085 0 -0.4478507 -0.8941085 0 -0.4478502 -0.8941086 0 -0.6564983 -0.7543275 0 -0.6565557 -0.7542775 0 -0.8238598 -0.5667938 0 -0.8238596 -0.5667941 0 -0.9379336 -0.3468149 0 -0.9379335 -0.3468152 0 -0.9950193 -0.09968364 0 -0.9950135 -0.09974122 0 -0.9890409 0.1476422 0 -0.9890324 0.1476991 0 -0.9204097 0.3909553 0 -0.9203888 0.3910048 0 -0.7929531 0.6092827 0 -0.7928969 0.6093558 0 -0.6183663 0.78589 0 -0.6183378 0.7859125 0 -0.4038733 0.914815 0 -0.4038732 0.914815 0 -0.1633598 0.9865666 0 -0.1633689 0.9865651 0 0.087269 0.9961848 0 0.3328284 0.9429875 0 0.3328283 0.9429875 0 0.5551719 0.8317357 0 0.5551716 0.831736 0 0.7456682 0.6663175 0 0.7456969 0.6662855 0 0.8884606 0.458953 0 0.8884131 0.4590447 0 0.9580841 0.2864875 0 -0.7136036 0.7005498 0 -0.6472015 0.762319 0 -0.7136037 0.7005496 0 -0.8011208 0.5985026 0 -0.8011195 0.5985044 0 -0.8959131 0.4442293 0 -0.960422 0.278549 0 -0.9604213 0.2785514 0 -0.9947661 0.1021786 0 -0.9947663 0.1021761 0 -0.9970228 -0.07710689 0 -0.9970226 -0.07710945 0 -0.9672974 -0.2536454 0 -0.9063942 -0.4224331 0 -0.9063931 -0.4224354 0 -0.8166729 -0.5771009 0 -0.8166716 -0.5771027 0 -0.7000924 -0.7140523 0 -0.7000923 -0.7140524 0 -0.5608572 -0.8279127 0 -0.4044475 -0.9145612 0 -0.4044474 -0.9145613 0 -0.2342981 -0.9721649 0 -0.2342969 -0.9721651 0 -0.05857408 -0.9982831 0 -0.05857378 -0.9982831 0 0.1227048 -0.9924432 0 0.1227048 -0.9924433 0 0.2957468 -0.9552664 0 0.2957462 -0.9552666 0 0.4628913 -0.8864151 0 0.4628916 -0.8864149 0 0.61356 -0.7896482 0 0.613559 -0.7896488 0 0.7446506 -0.6674546 0 0.7446498 -0.6674554 0 0.8515409 -0.5242882 0 0.8515396 -0.5242903 0 0.9320407 -0.3623536 0 0.9320398 -0.3623559 0 0.9814893 -0.1915177 0 0.9814892 -0.1915179 0 0.9999198 -0.01267236 0 0.9999198 -0.01267367 0 0.9861488 0.1658629 0 0.9861491 0.1658617 0 0.9405323 0.3397045 0 0.9405327 0.3397035 0 0.8648108 0.502098 0 0.8648107 0.5020983 0 0.7613798 0.6483062 0 0.7613795 0.6483065 0 0.6331846 0.7740009 0 0.6331838 0.7740015 0 0.4852184 0.874393 0 0.4852183 0.8743931 0 0.3207674 0.947158 0 0.3207671 0.9471581 0 0.1477786 0.9890206 0 0.1477785 0.9890206 0 -0.03345352 0.9994404 0 -0.0334534 0.9994403 0 -0.2092275 0.977867 0 -0.2092279 0.9778669 0 -0.3819572 0.92418 0 -0.3819562 0.9241805 0 -0.5408406 0.8411251 0 -0.5408426 0.8411239 0 -0.6472038 0.7623171 0 -3.60189e-6 0 -1 1.91522e-6 0 -1 1.75555e-6 0 -1 -9.59413e-7 0 -1 1.27418e-6 0 -1 -1.27632e-6 0 -1 1.80323e-6 0 -1 4.57353e-7 0 -1 -1.27601e-6 0 -1 -1.80302e-6 0 -1 -1.27956e-6 0 -1 1.27387e-6 0 -1 6.30943e-7 0 -1 1.27799e-6 0 -1 9.01096e-7 0 -1 1.27505e-6 0 -1 -2.53704e-6 0 -1 6.38537e-7 0 -1 -1.27867e-6 0 -1 1.27337e-6 0 -1 -3.60023e-6 0 -1 -2.36632e-7 0 -1 3.19602e-7 0 -1 -1.2753e-6 0 -1 1.80074e-6 0 -1 -1.26934e-6 0 -1 -3.16802e-6 0 -1 1.91428e-6 0 -1 0.6312551 -0.7755753 0 0.7293381 -0.6841534 0 0.6312516 -0.7755781 0 0.4786641 -0.8779982 0 0.4786654 -0.8779974 0 0.2472183 -0.9689599 0 0.2472198 -0.9689595 0 -0.003982782 -0.9999921 0 -0.2551333 -0.9669059 0 -0.2551327 -0.9669061 0 -0.4832655 -0.875474 0 -0.4832651 -0.8754742 0 -0.6866718 -0.7269676 0 -0.6866716 -0.7269678 0 -0.8472701 -0.5311623 0 -0.8472707 -0.5311614 0 -0.9519354 -0.3062989 0 -0.951936 -0.3062974 0 -0.9982501 -0.0591343 0 -0.9982501 -0.05913436 0 -0.9817172 0.1903459 0 -0.9029417 0.4297632 0 -0.9029409 0.429765 0 -0.7688927 0.639378 0 -0.7688934 0.639377 0 -0.5832241 0.8123114 0 -0.5832231 0.812312 0 -0.3632466 0.931693 0 -0.3632463 0.9316931 0 -0.1236491 0.9923261 0 -0.1236495 0.992326 0 0.1276834 0.991815 0 0.1276838 0.991815 0 0.3710821 0.9286001 0 0.371082 0.9286001 0 0.5931423 0.8050977 0 0.5931404 0.805099 0 0.7716974 0.63599 0 0.7716974 0.6359901 0 0.9069547 0.4212282 0 0.9829279 0.1839913 0 0.9829266 0.1839984 0 0.9977845 -0.06652998 0 0.9977843 -0.06653362 0 0.9498662 -0.3126567 0 0.9498661 -0.3126569 0 0.842165 -0.5392201 0 0.8421615 -0.5392254 0 0.7293379 -0.6841537 0 1.01165e-5 0 1 6.29342e-7 0 1 -8.8578e-6 0 1 -2.66917e-6 0 1 1.11863e-5 0 1 -1.57639e-5 0 1 3.2099e-6 0 1 -5.20437e-6 0 1 -5.16793e-6 0 1 0 0 1 1.70758e-5 0 1 1.28462e-5 0 1 -8.81349e-6 0 1 3.94098e-6 0 1 -2.52385e-5 0 1 2.02118e-5 0 1 4.59327e-6 0 1 9.46348e-6 0 1 9.70968e-5 0 1 -6.63746e-5 0 1 1.01239e-5 0 1 -1.0354e-5 0 1 -6.90017e-6 0 1 0.5256839 0.7242364 -0.446249 0.5290182 0.7215003 -0.4467405 0.5265462 0.7236343 -0.4462091 0.5274858 0.7267743 -0.4399522 0.5274858 0.7267743 -0.4399521 0.5274858 0.7267743 -0.4399521 0.5269007 0.7233442 -0.4462611 0.530049 0.7214152 -0.4456548 0.5237225 0.7253492 -0.4467475 0.5294572 0.7214583 -0.4462881 0.5220289 0.7269824 -0.4460748 0.5246229 0.725162 -0.4459942 0.525849 0.7242559 -0.4460227 0.8543077 -0.5197204 0.007020235 0.8755766 -0.4830794 0 0.9121627 -0.4098284 0 0.9282319 -0.3719395 0.006820201 0.9427805 -0.3334141 0 0.9672278 -0.2539108 0 0.9768661 -0.2137425 0.006846189 0.9848839 -0.1732157 0 0.9957789 -0.09178519 0 0.9987178 -0.05015254 0.00690037 0.9999629 -0.008622944 0 0.9973027 0.07339823 0 0.9933502 0.1149244 0.006914973 0.9876959 0.156387 0 0.9715996 0.2366315 0 0.9610124 0.276421 0.006824016 0.9488562 0.3157086 0 0.9187639 0.3948073 0 0.9021415 0.4313894 0.00663346 0.8841913 0.4671251 0 0.8420894 0.5393381 0 0.8191174 0.5735851 0.006846129 0.7947877 0.6068878 0 0.7404772 0.6720817 0 0.7124708 0.7016695 0.006724834 0.683357 0.7300844 0 0.6217573 0.78321 0 0.5895738 0.8076867 0.006705999 0.5564876 0.830856 0 0.48067 0.8769016 0 0.445833 0.8950925 0.006505966 0.4104195 0.9118968 0 0.3327539 0.9430138 0 0.2939933 0.9557837 0.006747007 0.2547861 0.9669975 0 0.1729291 0.9849343 0 0.1319366 0.9912344 0.006873428 0.09073191 0.9958754 0 0.01294189 0.9999163 0 -0.03244721 0.9994451 0.007537066 -0.07775956 0.9969722 0 -0.1555052 0.9878351 0 -0.1946606 0.9808485 0.006593167 -0.2335466 0.9723456 0 -0.3194068 0.9476178 0 -0.3565888 0.9342386 0.006541907 -0.3932753 0.9194208 0 -0.4670046 0.884255 0 -0.5039485 0.8637053 0.00700891 -0.5399753 0.841681 0 -0.605762 0.795646 0 -0.6398149 0.7684955 0.007196426 -0.6725646 0.7400385 0 -0.7279272 0.6856544 0 -0.7570931 0.6532672 0.007212936 -0.7847298 0.6198382 0 -0.8314737 0.5555642 0 -0.8543636 0.5196281 0.007043242 -0.8756669 0.4829158 0 -0.9120995 0.4099689 0 -0.9282182 0.3719735 0.006831407 -0.9428035 0.3333489 0 -0.9672291 0.2539055 0 -0.9768562 0.2137882 0.006840527 -0.9848695 0.1732976 0 -0.9957948 0.09161186 0 -0.9987158 0.05019629 0.006865203 -0.9999606 0.008881688 0 -0.9972838 -0.07365554 0 -0.9933468 -0.1149559 0.00688064 -0.9877252 -0.1562018 0 -0.9715752 -0.2367312 0 -0.9610048 -0.2764476 0.006818532 -0.948868 -0.3156732 0 -0.9187947 -0.3947359 0 -0.9021325 -0.4314077 0.006661534 -0.8841379 -0.4672261 0 -0.842191 -0.5391793 0 -0.8191486 -0.5735405 0.006857931 -0.7947442 -0.6069446 0 -0.740478 -0.6720806 0 -0.7124005 -0.7017408 0.006746411 -0.6832081 -0.7302238 0 -0.6218613 -0.7831274 0 -0.5896248 -0.8076496 0.006706595 -0.5564902 -0.8308542 0 -0.4805963 -0.876942 0 -0.4457723 -0.895123 0.006482958 -0.4103654 -0.9119212 0 -0.3328112 -0.9429936 0 -0.2940661 -0.9557613 0.006747961 -0.2548609 -0.9669778 0 -0.1728428 -0.9849494 0 -0.1319284 -0.9912357 0.006850481 -0.09079629 -0.9958696 0 -0.01294189 -0.9999163 0 0.03244721 -0.9994453 0.007514536 0.07775908 -0.9969723 0 0.155588 -0.9878221 0 0.1946751 -0.9808456 0.006592631 0.2334762 -0.9723626 0 0.3194613 -0.9475994 0 0.3566535 -0.9342138 0.006543099 0.3933506 -0.9193887 0 0.4669563 -0.8842805 0 0.5038769 -0.8637473 0.006997108 0.5398833 -0.84174 0 0.6057158 -0.7956812 0 0.6398437 -0.768471 0.00723052 0.6726764 -0.7399368 0 0.7278279 -0.6857599 0 0.7570928 -0.6532673 0.007224202 0.7848278 -0.6197139 0 0.8314529 -0.5555955 0 0.6109785 -0.2741741 -0.7426533 0.6135266 -0.2645263 -0.7440505 0.6135267 -0.2645261 -0.7440504 0.6135252 -0.2645254 -0.7440518 0.6299879 -0.2232145 -0.7438351 0.6303716 -0.2231462 -0.7435304 0.6468155 -0.1703947 -0.7433676 0.6477939 -0.1695979 -0.7426976 0.6475154 -0.1692441 -0.7430211 0.6475154 -0.1692441 -0.743021 0.6475154 -0.1692441 -0.7430211 0.6589595 -0.1160382 -0.743174 0.6587645 -0.1160909 -0.7433387 0.6583507 -0.1142575 -0.7439891 0.6656675 -0.06112396 -0.7437409 0.6654151 -0.06121551 -0.7439594 0.6684921 -0.006880164 -0.7436875 0.6690539 -0.005894422 -0.7431906 0.6687858 -0.005682468 -0.7434335 0.6671268 0.04929715 -0.7433113 0.6669125 0.0493201 -0.743502 0.6669476 0.04972249 -0.7434438 0.6603901 0.1037293 -0.7437239 0.6610298 0.1041718 -0.7430934 0.6496605 0.1604575 -0.7430981 0.6493535 0.1582038 -0.7438492 0.6487069 0.1584383 -0.7443633 0.6333633 0.211197 -0.7444776 0.6329721 0.2112981 -0.7447815 0.6347097 0.2099272 -0.7436895 0.6140063 0.2631594 -0.7441394 0.6145018 0.2635323 -0.7435982 0.590671 0.3129534 -0.7437527 0.5906711 0.3129534 -0.7437525 0.5906711 0.3129534 -0.7437525 0.5906884 0.3130629 -0.7436928 0.5929472 0.3128747 -0.7419724 0.5648923 0.3616864 -0.7416736 0.5620766 0.3614426 -0.7439282 0.5650954 0.3602307 -0.7422271 0.5319771 0.4079642 -0.7420012 0.5311579 0.4060188 -0.7436533 0.5024104 0.4408401 -0.7438037 0.4969612 0.4493288 -0.7423835 0.4951817 0.4489413 -0.7438057 0.4570833 0.4877198 -0.743777 0.4624713 0.4895622 -0.7392221 0.4536938 0.4899275 -0.7444011 0.4160183 0.5221332 -0.744517 0.4160183 0.5221333 -0.744517 0.4160183 0.5221333 -0.744517 0.4164236 0.5242307 -0.7428147 0.37019 0.5580329 -0.7426699 0.3698171 0.5535214 -0.7462235 0.3251063 0.5805465 -0.7465063 0.3226646 0.5869817 -0.7425228 0.3207695 0.5864423 -0.7437691 0.2750328 0.6093569 -0.7436673 0.2748437 0.6108741 -0.7424917 0.2758306 0.6104388 -0.7424837 0.2215127 0.6323817 -0.7423109 0.2216805 0.6313487 -0.7431398 0.172828 0.6467041 -0.7429026 0.1714732 0.6480908 -0.7420076 0.1727275 0.6489129 -0.7409976 0.1149346 0.661594 -0.7410016 0.1154281 0.6604869 -0.741912 0.1182422 0.6608905 -0.741109 0.06075525 0.668748 -0.7410027 0.06192088 0.6659201 -0.7434489 0.06192082 0.6659201 -0.7434489 0.06192082 0.6659201 -0.7434489 0.009960651 0.6683392 -0.74379 0.005908906 0.6707193 -0.7416878 0.004365086 0.6684892 -0.743709 -0.05018806 0.6669561 -0.7434048 -0.05102062 0.6651496 -0.7449651 -0.03953146 0.6710646 -0.7403443 -0.1063999 0.6637491 -0.7403488 -0.1031545 0.6595689 -0.7445321 -0.1570562 0.6486798 -0.7446798 -0.1592494 0.6491426 -0.7438102 -0.1579698 0.6522969 -0.7413193 -0.210354 0.6369199 -0.7416766 -0.2105331 0.6365717 -0.7419247 -0.2105331 0.6365718 -0.7419247 -0.2105332 0.6365718 -0.7419247 -0.2152256 0.6312584 -0.7451113 -0.2625404 0.6131579 -0.7450571 -0.2616734 0.6124166 -0.7459712 -0.313089 0.5882011 -0.7456507 -0.3142407 0.5879811 -0.7453396 -0.3136104 0.595736 -0.7394236 -0.3626849 0.5671659 -0.7394475 -0.3620305 0.5603802 -0.7449215 -0.3613312 0.5622849 -0.7438249 -0.4054058 0.5313944 -0.7438187 -0.4038314 0.530687 -0.7451789 -0.4386959 0.5022948 -0.7451483 -0.4386959 0.5022948 -0.7451482 -0.4386959 0.5022948 -0.7451483 -0.4483859 0.4957824 -0.7437404 -0.4482256 0.4951462 -0.7442609 -0.4884957 0.4559142 -0.7439854 -0.4889299 0.457448 -0.7427577 -0.4889639 0.4608895 -0.7406046 -0.5270816 0.4159798 -0.7410438 -0.5220341 0.4151238 -0.7450857 -0.5552504 0.3697636 -0.7449644 -0.5565171 0.369867 -0.7439672 -0.5845326 0.3241098 -0.7438244 -0.5849942 0.3238272 -0.7435845 -0.5850503 0.32394 -0.7434911 -0.6099078 0.2741838 -0.7435293 -0.6109642 0.2740579 -0.742708 -0.6126972 0.2671083 -0.7438113 -0.6302792 0.2230747 -0.7436302 -0.6298081 0.2231731 -0.7439997 -0.646245 0.1702296 -0.7439014 -0.6472046 0.1693603 -0.7432653 -0.6474503 0.1695742 -0.7430024 -0.6589281 0.1160968 -0.7431927 -0.6589435 0.1160667 -0.7431838 -0.6589235 0.1143569 -0.7434664 -0.66587 0.06117111 -0.7435559 -0.6655751 0.06129121 -0.74381 -0.6686965 0.005900263 -0.743512 -0.6686804 0.005921304 -0.7435265 -0.6686757 0.005944788 -0.7435305 -0.6669943 -0.04928457 -0.743431 -0.6666982 -0.0494315 -0.7436868 -0.6666765 -0.04915827 -0.7437245 -0.6604019 -0.1038847 -0.7436917 -0.6607217 -0.1041511 -0.7433704 -0.6497374 -0.1602013 -0.743086 -0.6492038 -0.1583678 -0.743945 -0.6491193 -0.1584314 -0.7440052 -0.6336661 -0.2112016 -0.7442185 -0.6330303 -0.2113464 -0.7447183 -0.6345587 -0.2099094 -0.7438234 -0.6143532 -0.2632661 -0.7438152 -0.6143403 -0.2633548 -0.7437945 -0.5906914 -0.3135133 -0.7435006 -0.590573 -0.3132022 -0.7437257 -0.5933244 -0.3129269 -0.7416488 -0.5653399 -0.3617971 -0.7412785 -0.5616646 -0.3615713 -0.7441768 -0.5651724 -0.360049 -0.7422567 -0.5318595 -0.4078646 -0.7421401 -0.5311053 -0.4059306 -0.743739 -0.5024457 -0.4408026 -0.743802 -0.4967004 -0.4493486 -0.742546 -0.495558 -0.4491688 -0.7434176 -0.4574314 -0.487888 -0.7434526 -0.4620609 -0.4893988 -0.7395867 -0.4539294 -0.4896714 -0.744426 -0.4160457 -0.5222356 -0.7444299 -0.4165048 -0.5244523 -0.7426126 -0.3701522 -0.5581591 -0.7425941 -0.3698147 -0.5535287 -0.7462193 -0.3249294 -0.5803555 -0.7467319 -0.3227074 -0.5870596 -0.7424426 -0.3209791 -0.5865001 -0.7436331 -0.2751033 -0.609575 -0.7434625 -0.2748135 -0.6107611 -0.7425958 -0.2759524 -0.6107082 -0.7422168 -0.2214977 -0.6324238 -0.7422796 -0.2217433 -0.6315175 -0.7429776 -0.1728976 -0.6463417 -0.7432017 -0.1715391 -0.6481558 -0.7419356 -0.1726783 -0.6490818 -0.7408611 -0.1149258 -0.6617537 -0.7408605 -0.1154047 -0.6604089 -0.7419851 -0.1184862 -0.6607972 -0.7411533 -0.06072223 -0.6683846 -0.7413332 -0.06195408 -0.665774 -0.743577 -0.009805083 -0.6684775 -0.7436677 -0.005957603 -0.6705413 -0.7418484 -0.004358589 -0.6687516 -0.7434732 0.05017715 -0.6668843 -0.74347 0.05017721 -0.6668843 -0.74347 0.05017721 -0.6668843 -0.74347 0.05096364 -0.6651474 -0.744971 0.03955268 -0.6714494 -0.7399942 0.1064516 -0.6638271 -0.7402715 0.1064516 -0.6638271 -0.7402713 0.1064516 -0.6638271 -0.7402713 0.103136 -0.659372 -0.7447091 0.1571065 -0.6485452 -0.7447863 0.1571065 -0.6485453 -0.7447863 0.1591444 -0.6489148 -0.7440314 0.1579737 -0.6522755 -0.7413373 0.2104701 -0.6369969 -0.7415776 0.2105265 -0.6368914 -0.7416522 0.2105266 -0.6368915 -0.7416521 0.2105266 -0.6368916 -0.7416521 0.2153329 -0.6314809 -0.7448918 0.2625402 -0.6132688 -0.7449658 0.2625402 -0.6132689 -0.7449658 0.2625402 -0.6132688 -0.7449658 0.2617517 -0.6126795 -0.7457278 0.3136134 -0.5879257 -0.7456474 0.3141714 -0.5877853 -0.7455232 0.3134477 -0.5955983 -0.7396035 0.3624797 -0.5669068 -0.7397468 0.3621298 -0.5608295 -0.744535 0.3614607 -0.5618489 -0.7440914 0.405177 -0.5312515 -0.7440453 0.4036099 -0.5305693 -0.7453826 0.4383414 -0.5022079 -0.7454154 0.4484623 -0.495634 -0.7437933 0.4482536 -0.4950506 -0.7443075 0.4884963 -0.4558292 -0.744037 0.4891645 -0.4577205 -0.7424353 0.4888903 -0.4610689 -0.7405416 0.5273565 -0.416161 -0.7407465 0.5220021 -0.4152459 -0.7450401 0.555345 -0.3697327 -0.7449092 0.5565497 -0.369835 -0.7439587 0.584213 -0.3242546 -0.7440122 0.5852801 -0.323985 -0.7432907 0.5850574 -0.3235011 -0.7436767 0.6096528 -0.2743573 -0.7436745 0.6886129 -0.5440806 -0.4793627 0.7308783 -0.485688 -0.4795039 0.7275276 -0.4860263 -0.4842334 0.7655606 -0.4237716 -0.4840814 0.7682912 -0.4233294 -0.4801259 0.8001797 -0.3590937 -0.4803793 0.7999148 -0.3591973 -0.4807428 0.8264805 -0.2925736 -0.4809685 0.8270906 -0.2923288 -0.480068 0.8483685 -0.2221167 -0.4805571 0.8464073 -0.2230411 -0.4835778 0.8622242 -0.1519562 -0.4831964 0.8627739 -0.1516519 -0.4823101 0.8723834 -0.08025324 -0.4821894 0.8727145 -0.08002978 -0.4816271 0.8763172 -0.007724225 -0.4816727 0.8759111 -0.008003532 -0.4824063 0.8737628 0.06456607 -0.4820476 0.8738179 0.06458526 -0.481945 0.865503 0.1364007 -0.4819746 0.865916 0.1369397 -0.4810791 0.8520603 0.2075906 -0.4805201 0.8517643 0.2072255 -0.481202 0.8316691 0.2773306 -0.4810554 0.8318077 0.2777988 -0.4805454 0.8062029 0.3457506 -0.4800973 0.8054047 0.3441938 -0.4825494 0.7738564 0.4101417 -0.4826285 0.7739735 0.4105995 -0.482051 0.7378547 0.472454 -0.4820349 0.737877 0.4723924 -0.4820612 0.6961003 0.5321096 -0.4819791 0.6961003 0.5321096 -0.4819791 0.6958826 0.5312316 -0.4832602 0.6492698 0.5870661 -0.4835308 0.6492698 0.5870662 -0.4835308 0.6492698 0.5870662 -0.4835308 0.6492352 0.5862527 -0.4845633 0.6492356 0.5862523 -0.4845632 0.5979421 0.6380732 -0.485106 0.598107 0.640008 -0.4823461 0.5448462 0.6859025 -0.4823695 0.5448371 0.6873147 -0.4803656 0.4871868 0.7292058 -0.4805289 0.4871837 0.729208 -0.4805287 0.4871836 0.729208 -0.4805288 0.4871048 0.728833 -0.4811772 0.4223598 0.7683695 -0.480854 0.4223598 0.7683695 -0.480854 0.4226555 0.7671568 -0.4825276 0.3594022 0.7988156 -0.4824146 0.3586688 0.8009349 -0.4794371 0.2908 0.828234 -0.4790239 0.2922705 0.8241155 -0.4851923 0.2236014 0.8451347 -0.4855409 0.2214442 0.8499634 -0.4780426 0.1512673 0.8652443 -0.477986 0.1512674 0.8652443 -0.4779859 0.1523337 0.8633023 -0.4811484 0.1523337 0.8633022 -0.4811483 0.1523338 0.8633023 -0.4811484 0.08123415 0.872888 -0.4811108 0.08123415 0.8728881 -0.4811108 0.08123415 0.8728881 -0.4811108 0.08011859 0.8746828 -0.4780282 0.007737994 0.8780922 -0.4784289 0.007680535 0.878499 -0.4776824 -0.06590282 0.8758962 -0.4779777 -0.06590288 0.8758963 -0.4779775 -0.06590288 0.8758963 -0.4779775 -0.06068634 0.870436 -0.4885268 -0.06068634 0.8704361 -0.4885268 -0.06068634 0.870436 -0.4885268 -0.1347877 0.8618901 -0.4888534 -0.1367444 0.8636097 -0.485262 -0.2083942 0.8494824 -0.4847181 -0.2083942 0.8494825 -0.484718 -0.2083942 0.8494824 -0.484718 -0.209037 0.849929 -0.4836573 -0.2744196 0.830938 -0.4839793 -0.278738 0.8337106 -0.4766887 -0.3453691 0.8082798 -0.4768689 -0.343297 0.8071434 -0.4802779 -0.343297 0.8071434 -0.4802778 -0.343297 0.8071433 -0.4802779 -0.4134871 0.77369 -0.4800336 -0.4134871 0.7736901 -0.4800335 -0.4134871 0.7736901 -0.4800336 -0.4099692 0.772188 -0.4854393 -0.4710724 0.7366741 -0.4851824 -0.4710724 0.7366742 -0.4851824 -0.4710725 0.7366742 -0.4851824 -0.4714493 0.7367896 -0.4846407 -0.5296589 0.6960538 -0.4847378 -0.5334464 0.6968886 -0.4793551 -0.5334464 0.6968886 -0.4793551 -0.588716 0.6509531 -0.4792428 -0.588716 0.6509531 -0.4792428 -0.588716 0.6509531 -0.4792427 -0.586876 0.6506283 -0.4819331 -0.6406631 0.597913 -0.4817166 -0.6379394 0.597676 -0.4856097 -0.6843972 0.544245 -0.4851784 -0.688794 0.544128 -0.4790486 -0.730897 0.4857876 -0.4793745 -0.7277749 0.486186 -0.4837015 -0.7657625 0.4239032 -0.4836465 -0.7682431 0.4234507 -0.4800958 -0.8002768 0.3589837 -0.4802997 -0.7995846 0.3591525 -0.4813253 -0.8261433 0.2927376 -0.481448 -0.8272733 0.2923038 -0.4797681 -0.8486015 0.2220669 -0.4801687 -0.8464879 0.2230271 -0.4834432 -0.8623457 0.1518996 -0.4829973 -0.8628132 0.1516518 -0.4822396 -0.8724183 0.0803408 -0.4821118 -0.8726405 0.08021521 -0.4817304 -0.8762018 0.007756114 -0.481882 -0.8762091 0.007775962 -0.4818685 -0.8739503 -0.06457996 -0.4817057 -0.8738613 -0.06447362 -0.4818814 -0.8655355 -0.1364448 -0.4819037 -0.8659342 -0.1367889 -0.4810892 -0.8518283 -0.2078127 -0.4808352 -0.8513771 -0.2072162 -0.4818906 -0.8313266 -0.2770884 -0.4817864 -0.831685 -0.2777386 -0.4807926 -0.8060323 -0.3455446 -0.4805321 -0.8060336 -0.3455413 -0.4805321 -0.8060336 -0.3455414 -0.4805321 -0.8053783 -0.3441551 -0.482621 -0.7735736 -0.4102535 -0.4829866 -0.7738038 -0.410693 -0.4822438 -0.7378696 -0.4722316 -0.4822299 -0.7378731 -0.4723181 -0.48214 -0.6959868 -0.5319476 -0.4823217 -0.6960057 -0.5315501 -0.4827326 -0.6493873 -0.5874754 -0.4828757 -0.6491042 -0.585992 -0.4850538 -0.5979449 -0.6377986 -0.4854637 -0.5981675 -0.6398833 -0.4824365 -0.5447959 -0.6860084 -0.4822758 -0.5447126 -0.687148 -0.4807453 -0.4871003 -0.7290699 -0.4808228 -0.487126 -0.728965 -0.4809558 -0.4222972 -0.7682446 -0.4811086 -0.4226214 -0.7671175 -0.48262 -0.3593516 -0.7986643 -0.4827027 -0.3587526 -0.8012183 -0.4789007 -0.2907224 -0.8283081 -0.478943 -0.2907223 -0.8283081 -0.478943 -0.2907224 -0.8283081 -0.4789429 -0.2923408 -0.8240349 -0.4852871 -0.2236455 -0.845068 -0.4856365 -0.2214771 -0.849994 -0.4779729 -0.151206 -0.8652812 -0.4779385 -0.1523069 -0.8632789 -0.4811988 -0.08123844 -0.8730266 -0.4808586 -0.08009409 -0.8743911 -0.4785659 -0.007797658 -0.8783905 -0.4778801 -0.007621109 -0.8782658 -0.4781121 0.06589841 -0.8758283 -0.4781029 0.06061601 -0.8702676 -0.4888355 0.134824 -0.8620111 -0.4886301 0.1367288 -0.8636312 -0.4852284 0.2082909 -0.8493312 -0.4850275 0.2090562 -0.8498865 -0.4837236 0.2745181 -0.8308672 -0.484045 0.2786482 -0.8336371 -0.4768695 0.3452562 -0.8081592 -0.4771551 0.3433065 -0.8071191 -0.4803117 0.4134861 -0.7735817 -0.480209 0.4099647 -0.7720714 -0.4856283 0.471037 -0.7367011 -0.4851761 0.4712786 -0.7366029 -0.4850904 0.5294813 -0.6960541 -0.4849314 0.5336021 -0.6970543 -0.4789406 0.5889545 -0.6509107 -0.4790073 0.586884 -0.6505828 -0.4819847 0.6405607 -0.5977511 -0.4820536 0.6378932 -0.5976117 -0.4857494 0.684094 -0.5441897 -0.4856677 0.7737962 -0.6110094 -0.1670542 0.8198333 -0.54769 -0.1670606 0.8197413 -0.5477728 -0.16724 0.8635131 -0.4757845 -0.167255 0.8630653 -0.4761739 -0.1684541 0.8991854 -0.403789 -0.1685822 0.899068 -0.4039304 -0.1688702 0.9293411 -0.3284757 -0.1686086 0.9291977 -0.3286284 -0.1691004 0.953148 -0.2511637 -0.1685992 0.953785 -0.2503807 -0.1661435 0.9711661 -0.1707031 -0.1664243 0.9711183 -0.1707989 -0.1666044 0.9819062 -0.09004992 -0.1665869 0.9816701 -0.09048557 -0.167739 0.9858192 -0.009001016 -0.1675694 0.9860411 -0.008501231 -0.1662853 0.9833139 0.07267844 -0.166769 0.9831999 0.07236653 -0.1675743 0.9737311 0.1539826 -0.1677416 0.9737619 0.1541934 -0.1673687 0.9579468 0.2330549 -0.1674022 0.9579886 0.2333304 -0.1667782 0.9352765 0.3123295 -0.1664586 0.9351532 0.31115 -0.1693346 0.9061828 0.3872707 -0.1698655 0.906175 0.389401 -0.1649665 0.8713621 0.4622716 -0.1644179 0.8715102 0.460419 -0.1687735 0.8300519 0.5314136 -0.1691557 0.8300265 0.5315958 -0.1687067 0.7834424 0.5980724 -0.1689004 0.7833724 0.5981692 -0.168883 0.7315465 0.6605674 -0.1687914 0.7305803 0.6631304 -0.1628208 0.6737615 0.7209864 -0.161939 0.6741172 0.7201955 -0.163965 0.6127884 0.7730113 -0.1641467 0.6131747 0.7724189 -0.1654864 0.5480393 0.8199343 -0.1654112 0.5480393 0.8199343 -0.1654111 0.5480393 0.8199343 -0.1654112 0.548587 0.8190705 -0.1678563 0.4756614 0.8633693 -0.1683446 0.4742367 0.865179 -0.1629881 0.4032905 0.9005733 -0.162249 0.4046345 0.8990499 -0.1672734 0.3295363 0.9291741 -0.1674558 0.3282992 0.9303997 -0.1630221 0.2487556 0.9547691 -0.1629005 0.2510917 0.9529638 -0.1697442 0.1711503 0.9705275 -0.1696586 0.1711502 0.9705275 -0.1696586 0.1704809 0.9709969 -0.1676348 0.08992403 0.9816902 -0.1679232 0.08946621 0.981986 -0.1664313 0.08946412 0.9819862 -0.1664312 0.08946615 0.9819861 -0.1664313 0.00861752 0.9859372 -0.166894 0.0127387 0.9841709 -0.1767638 -0.06845378 0.9817999 -0.1771534 -0.0768035 0.9847415 -0.1561581 -0.1544586 0.9755054 -0.1566261 -0.1535296 0.9752779 -0.1589396 -0.2357822 0.958717 -0.1589609 -0.2300509 0.9577857 -0.1724044 -0.2300527 0.9577853 -0.1724044 -0.2300508 0.9577856 -0.1724044 -0.3123305 0.9342172 -0.1723021 -0.314975 0.9344433 -0.1661525 -0.3859366 0.9073997 -0.1663697 -0.3881573 0.9074513 -0.1608293 -0.4627812 0.8716637 -0.1613563 -0.4604662 0.8718717 -0.1667656 -0.5314074 0.8304995 -0.1669636 -0.5327014 0.8303376 -0.1636117 -0.5995981 0.7833032 -0.1640675 -0.5969117 0.7840217 -0.1703128 -0.6599934 0.731675 -0.1704712 -0.6599958 0.7316729 -0.1704711 -0.6599958 0.7316729 -0.1704711 -0.6637984 0.7303827 -0.1609746 -0.7202011 0.6747266 -0.1614142 -0.7175543 0.6758915 -0.1681862 -0.7735527 0.6110841 -0.1679069 -0.773595 0.6110469 -0.167847 -0.8197318 0.5476332 -0.1677425 -0.8196734 0.5476783 -0.1678813 -0.8633654 0.4758781 -0.1677511 -0.863165 0.4760169 -0.1683866 -0.8992478 0.4039375 -0.1678929 -0.8990512 0.4041022 -0.1685483 -0.8990513 0.4041017 -0.1685482 -0.8990512 0.4041022 -0.1685483 -0.9294272 0.3283979 -0.1682856 -0.9292692 0.3285657 -0.1688296 -0.9531854 0.2511351 -0.1684301 -0.95379 0.2503761 -0.1661222 -0.9711802 0.1707056 -0.1663392 -0.9710546 0.1708745 -0.1668981 -0.9818471 0.09024679 -0.1668289 -0.9818035 0.09032863 -0.1670411 -0.9859498 0.008744537 -0.1668131 -0.9859448 0.00875622 -0.1668421 -0.983237 -0.07254159 -0.1672808 -0.9832612 -0.07261621 -0.167106 -0.9738265 -0.1538386 -0.1673191 -0.973865 -0.1540173 -0.1669303 -0.9580059 -0.2331727 -0.1668989 -0.9580289 -0.2334319 -0.1664041 -0.935306 -0.3123357 -0.1662805 -0.9352038 -0.3111233 -0.1691045 -0.9062251 -0.387245 -0.1696985 -0.9062248 -0.3893458 -0.1648225 -0.8713094 -0.4624323 -0.1642447 -0.8714327 -0.4605074 -0.1689321 -0.830088 -0.5313546 -0.1691631 -0.8300837 -0.5314294 -0.1689493 -0.7832781 -0.5981987 -0.1692154 -0.7832792 -0.5981798 -0.1692767 -0.73153 -0.6604112 -0.1694728 -0.7306106 -0.6631311 -0.1626818 -0.6737894 -0.7207711 -0.1627786 -0.6737893 -0.7207711 -0.1627786 -0.6737893 -0.7207711 -0.1627786 -0.6739805 -0.7203586 -0.1638103 -0.6739814 -0.7203578 -0.1638102 -0.6739805 -0.7203586 -0.1638103 -0.6128566 -0.7730981 -0.163481 -0.6133006 -0.7723516 -0.1653347 -0.5479161 -0.8200509 -0.1652413 -0.5479161 -0.8200509 -0.1652412 -0.547916 -0.8200508 -0.1652413 -0.5485619 -0.8190195 -0.1681876 -0.5485619 -0.8190195 -0.1681876 -0.5485619 -0.8190194 -0.1681877 -0.4756794 -0.8634181 -0.1680429 -0.4741955 -0.8652694 -0.1626269 -0.4741955 -0.8652694 -0.1626269 -0.4741955 -0.8652694 -0.1626269 -0.4032496 -0.9005971 -0.1622177 -0.4032496 -0.9005971 -0.1622177 -0.4032496 -0.9005972 -0.1622177 -0.4046085 -0.8991337 -0.1668849 -0.3296655 -0.9292426 -0.1668205 -0.3283494 -0.9303609 -0.1631426 -0.2487154 -0.9548048 -0.1627529 -0.2487154 -0.9548048 -0.1627528 -0.2487154 -0.9548048 -0.1627528 -0.2511585 -0.9529238 -0.1698701 -0.171218 -0.9704645 -0.1699505 -0.1703979 -0.9710199 -0.1675862 -0.0899235 -0.9817261 -0.1677135 -0.0899266 -0.9817258 -0.1677134 -0.08992654 -0.9817258 -0.1677134 -0.0895313 -0.9819964 -0.1663354 -0.08952873 -0.9819966 -0.1663354 -0.0895313 -0.9819963 -0.1663354 -0.008553743 -0.9859944 -0.1665586 -0.01273751 -0.9840719 -0.1773142 0.06838655 -0.9818059 -0.1771456 0.07679617 -0.9846426 -0.1567844 0.1543725 -0.9755018 -0.1567334 0.1543725 -0.9755019 -0.1567333 0.1543725 -0.9755019 -0.1567333 0.1536143 -0.9753059 -0.1586854 0.2358291 -0.958759 -0.1586378 0.2299709 -0.9577645 -0.1726283 0.3122559 -0.9341856 -0.1726081 0.3150479 -0.9345082 -0.1656486 0.3859978 -0.9074956 -0.1657029 0.3859978 -0.9074956 -0.1657029 0.3859978 -0.9074957 -0.1657029 0.3882424 -0.9074601 -0.160574 0.4628744 -0.8717415 -0.160668 0.460447 -0.8719356 -0.1664844 0.531435 -0.8306174 -0.1662879 0.5325903 -0.830377 -0.1637737 0.5996504 -0.7833392 -0.1637048 0.5996504 -0.7833392 -0.1637047 0.5996504 -0.7833392 -0.1637047 0.5968106 -0.7840005 -0.1707644 0.6600576 -0.7316862 -0.1701751 0.6600575 -0.7316861 -0.170175 0.6600576 -0.7316862 -0.170175 0.6639481 -0.7303297 -0.1605972 0.7202522 -0.6747567 -0.16106 0.7175044 -0.6760304 -0.1678402 0.717504 -0.6760309 -0.1678401 0.7175044 -0.6760305 -0.1678402 0.7735082 -0.611139 -0.1679115 -0.3398975 -0.3666573 -0.8660441 -0.3698429 -0.3352243 -0.8665108 -0.4418132 -0.2330163 -0.8663166 -0.4986254 -0.03675812 -0.8660379 -0.4986254 -0.03675812 -0.8660379 -0.4986256 -0.03675818 -0.8660377 -0.4920065 0.08536744 -0.8663961 -0.4574095 0.1992235 -0.8666526 -0.4574094 0.1992234 -0.8666525 -0.4574108 0.1992238 -0.8666518 -0.4377867 0.2423958 -0.8657871 -0.4152577 0.2765326 -0.8666549 -0.3640031 0.3431012 -0.8659003 -0.3347957 0.3698365 -0.8666793 -0.2328214 0.4422615 -0.8661403 -0.1177759 0.4863254 -0.865804 0.08793324 0.491445 -0.8664581 0.2052792 0.4544354 -0.866804 0.2400771 0.4389054 -0.8658666 0.2754208 0.4151859 -0.8670433 0.3398454 0.3669738 -0.8659303 0.3697506 0.3352115 -0.866555 0.4417618 0.2331042 -0.8663193 0.4985128 0.03714781 -0.8660861 0.4985128 0.03714776 -0.8660861 0.498513 0.03714781 -0.866086 0.4920059 -0.08538275 -0.8663948 0.4584192 -0.1977112 -0.8664653 0.437932 -0.2421311 -0.8657876 0.4152107 -0.2764292 -0.8667104 0.3639748 -0.3432561 -0.8658508 0.3349049 -0.3698556 -0.866629 0.2327603 -0.4422696 -0.8661526 0.1177773 -0.4863063 -0.8658146 -0.08814209 -0.4913586 -0.8664858 -0.205339 -0.4544296 -0.8667927 -0.2402087 -0.4389101 -0.8658278 -0.2753506 -0.4152122 -0.867053 -0.1749153 -0.151086 -0.9729223 0.1752498 0.1512279 -0.97284 0.06804651 0.2263239 -0.9716724 0.175361 0.301977 -0.9370478 0.08075982 0.2220304 -0.9716895 0.1334651 0.2683234 -0.9540387 0.2271813 0.129799 -0.9651637 0.0849471 0.2147652 -0.9729645 0.08494704 0.2147652 -0.9729645 0.08494913 0.2147639 -0.9729647 0.1842696 0.1052795 -0.9772211 0.1678727 0.06352329 -0.9837599 0.170894 0.04845088 -0.9840974 0.166207 0.06204044 -0.9841374 0.2284535 -0.06796836 -0.9711793 0.3012577 -0.1729317 -0.9377306 0.2166648 -0.08321189 -0.9726933 0.2625697 -0.1371506 -0.9551162 0.1302056 -0.2270122 -0.9651488 0.2184654 -0.08257007 -0.9723452 0.1056416 -0.1841647 -0.9772018 0.06372243 -0.1676613 -0.9837831 0.04802066 -0.1712017 -0.9840651 0.06476229 -0.1652714 -0.9841195 -0.06811565 -0.2265661 -0.9716112 -0.1755946 -0.3021377 -0.9369522 -0.08066767 -0.2221577 -0.9716681 -0.1332461 -0.2683314 -0.9540671 -0.2272395 -0.1298299 -0.9651458 -0.08516305 -0.214437 -0.9730181 -0.1840955 -0.1051787 -0.9772648 -0.1678561 -0.06362497 -0.9837562 -0.1711045 -0.048339 -0.9840664 -0.1662719 -0.0619986 -0.984129 -0.1662721 -0.06199866 -0.984129 -0.166272 -0.06199866 -0.984129 -0.2283347 0.0680443 -0.971202 -0.3016032 0.1734255 -0.9375283 -0.2164989 0.08338302 -0.9727156 -0.2623558 0.1371853 -0.95517 -0.2623558 0.1371853 -0.95517 -0.2623557 0.1371853 -0.95517 -0.1302142 0.2269892 -0.9651529 -0.2178779 0.08288735 -0.97245 -0.2178777 0.08288735 -0.9724501 -0.2178781 0.08288747 -0.97245 -0.1056735 0.1842012 -0.9771914 -0.06369781 0.1676602 -0.9837849 -0.04801571 0.1711841 -0.9840683 -0.06479942 0.16535 -0.9841039 -0.2444257 -0.436569 -0.8658312 -0.2668333 -0.4168395 -0.8689333 -0.2280086 -0.3561928 -0.9061671 -0.2689533 -0.3263156 -0.9061911 -0.2183361 -0.264899 -0.9392327 -0.2484904 -0.236783 -0.9392477 -0.2051684 -0.4546 -0.8667438 -0.213555 -0.4460685 -0.8691475 -0.1823937 -0.3809689 -0.906419 -0.2268266 -0.3562887 -0.906426 -0.184311 -0.2895054 -0.9392637 -0.2182263 -0.2649171 -0.939253 -0.1285286 -0.4831159 -0.8660713 -0.1292029 -0.4830136 -0.866028 -0.1634149 -0.4665666 -0.8692589 -0.1593062 -0.4713384 -0.8674456 -0.1353218 -0.4003909 -0.9062975 -0.1829031 -0.3810359 -0.9062882 -0.1485666 -0.3094958 -0.9392232 -0.1845279 -0.2895212 -0.9392161 -0.08541691 -0.4918293 -0.8664917 -0.1011188 -0.4828468 -0.8698471 -0.08662641 -0.4136775 -0.9062929 -0.1353653 -0.4003776 -0.9062969 -0.1099825 -0.3253108 -0.9391894 -0.1486729 -0.3095297 -0.9391953 -0.00325489 -0.4999462 -0.8660504 -0.007343411 -0.4997776 -0.8661227 -0.04483169 -0.4935019 -0.8685885 -0.04286605 -0.4947312 -0.8679884 -0.03652989 -0.4215797 -0.9060553 -0.08785086 -0.4140698 -0.9059959 -0.07133597 -0.3362446 -0.9390692 -0.1110918 -0.3254227 -0.9390202 -0.08972066 -0.2627996 -0.9606699 -0.1201286 -0.2501031 -0.9607381 -0.1250479 -0.2367235 -0.9634963 -0.1439747 -0.2259004 -0.9634523 -0.1367315 -0.2488927 -0.9588311 -0.17956 -0.2179855 -0.9592917 -0.185027 -0.1924715 -0.9637011 -0.1935958 -0.1844688 -0.9635829 -0.1923674 -0.2016466 -0.9603819 -0.1924308 -0.201493 -0.9604015 -0.04415488 -0.2580338 -0.9651264 -0.05296415 -0.2557134 -0.9653007 -0.06957733 -0.3358776 -0.9393323 -0.02823668 -0.3419481 -0.9392945 -0.03474605 -0.4208287 -0.9064745 0.01518702 -0.4220539 -0.9064437 0.01776218 -0.4937183 -0.8694406 0.07851272 -0.4896327 -0.8683868 0.02940654 -0.499679 -0.8657115 0.03822833 -0.4988586 -0.8658398 0.117958 -0.4862776 -0.8658061 0.117958 -0.4862776 -0.8658061 0.07684981 -0.490833 -0.8678578 0.06536746 -0.4175032 -0.9063212 0.01462739 -0.4223755 -0.906303 0.0119071 -0.343649 -0.9390227 -0.03015667 -0.3426165 -0.9389913 -0.02295756 -0.2607697 -0.9651281 -0.05530536 -0.2560319 -0.965085 -0.03808683 -0.1763565 -0.9835892 -0.1744071 -0.1493306 -0.9732845 -0.009664654 -0.1788679 -0.9838256 -0.01486539 -0.1784287 -0.9838407 -0.02169704 -0.2604566 -0.9652417 0.01003301 -0.2612379 -0.9652224 0.01317507 -0.343047 -0.9392259 0.05348002 -0.339146 -0.9392125 0.06579107 -0.4171676 -0.9064451 0.1154468 -0.4062473 -0.906441 0.135109 -0.4754285 -0.8693178 0.1951069 -0.4556522 -0.8685128 0.1614048 -0.4733505 -0.8659606 0.1569456 -0.474797 -0.8659885 0.2352051 -0.4408876 -0.8661968 0.2352051 -0.4408876 -0.8661968 0.2352052 -0.4408876 -0.8661967 0.1931052 -0.4582485 -0.8675937 0.1640668 -0.3893357 -0.9063663 0.1152053 -0.4064374 -0.9063864 0.09370988 -0.3306051 -0.9391053 0.05275392 -0.3395931 -0.9390919 0.04014408 -0.2583889 -0.9652065 0.009884595 -0.261277 -0.9652134 0.006710112 -0.1775345 -0.9840918 -0.01123291 -0.1770951 -0.9841297 -0.01089215 -0.1775381 -0.9840537 0.006554424 -0.1775833 -0.984084 0.02815049 -0.1755178 -0.9840738 0.04133957 -0.2577087 -0.9653379 0.07150626 -0.251097 -0.9653171 0.09406328 -0.3302983 -0.9391779 0.1336277 -0.3163932 -0.9391693 0.164312 -0.3890367 -0.9064502 0.2095278 -0.366676 -0.9064474 0.2450391 -0.4288251 -0.86952 0.3000587 -0.3934174 -0.8690153 0.2708438 -0.4209859 -0.8656873 0.2715864 -0.4205947 -0.8656449 0.3278552 -0.3756403 -0.8668364 0.3278552 -0.3756403 -0.8668365 0.3278555 -0.3756407 -0.8668362 0.2973651 -0.3994754 -0.8671756 0.2524988 -0.3392031 -0.9061929 0.2089377 -0.3676786 -0.9061775 0.1696963 -0.2986254 -0.9391624 0.1335976 -0.3164882 -0.9391416 0.101618 -0.2407083 -0.9652634 0.07102978 -0.2513975 -0.9652741 0.04831653 -0.1710218 -0.9840819 0.02831685 -0.1754401 -0.9840828 0.3653776 -0.3418798 -0.8658046 0.340846 -0.3577089 -0.8694069 0.2916812 -0.3061118 -0.9062106 0.2524594 -0.3391732 -0.9062151 0.2046831 -0.2749908 -0.9394068 0.1707447 -0.2971926 -0.9394269 0.1302981 -0.2267959 -0.9651871 0.1007946 -0.2413571 -0.9651877 0.06908214 -0.1653976 -0.9838045 0.06503033 -0.1652351 -0.984108 0.3916234 -0.3090455 -0.8666729 0.381103 -0.3148656 -0.8692642 0.3257724 -0.2691459 -0.9063293 0.2918661 -0.3055293 -0.9063477 0.2372661 -0.2483761 -0.9391561 0.2039468 -0.2764524 -0.9391378 0.1728248 -0.2342664 -0.9566875 0.1066132 -0.232762 -0.9666724 0.4374523 -0.2427965 -0.8658437 0.4173189 -0.2658547 -0.8690031 0.3563694 -0.2270244 -0.9063447 0.3258245 -0.2690911 -0.9063269 0.2649564 -0.2188199 -0.9391038 0.2370542 -0.248739 -0.9391136 0.455083 -0.2047946 -0.8665787 0.4453288 -0.2144557 -0.869305 0.3808127 -0.1833939 -0.9062828 0.3563951 -0.2273617 -0.9062501 0.2894774 -0.1846742 -0.9392009 0.2650887 -0.2180755 -0.9392396 0.4840325 -0.1265152 -0.865856 0.48359 -0.1273804 -0.8659763 0.4656935 -0.165005 -0.8694268 0.4718335 -0.1595987 -0.8671225 0.4003054 -0.1354095 -0.9063223 0.3807757 -0.183059 -0.9063661 0.3094273 -0.1487565 -0.9392158 0.2894448 -0.1847507 -0.9391959 0.4919731 -0.08662217 -0.8662906 0.483597 -0.1011684 -0.8694246 0.4137766 -0.08655554 -0.9062545 0.4003886 -0.1358358 -0.9062216 0.3252161 -0.1103347 -0.939181 0.3095582 -0.1491162 -0.9391157 0.5000719 -0.004237711 -0.8659735 0.5000309 -0.005149602 -0.8659923 0.4932931 -0.04529482 -0.8686832 0.4953643 -0.04220581 -0.8676595 0.4211277 -0.03587859 -0.9062915 0.4137344 -0.08641815 -0.9062868 0.3361677 -0.07021218 -0.9391814 0.3252508 -0.1101773 -0.9391875 0.2628847 -0.08905524 -0.9607085 0.2498004 -0.120325 -0.9607922 0.2359781 -0.1253011 -0.9636462 0.2254647 -0.1439142 -0.9635633 0.2498161 -0.1361665 -0.9586713 0.218306 -0.1795846 -0.9592143 0.1916269 -0.1852727 -0.9638223 0.1841745 -0.1932519 -0.9637082 0.202103 -0.1919621 -0.9603671 0.2009645 -0.1927989 -0.9604384 0.4984489 0.03686743 -0.866135 0.4936981 0.01757556 -0.8694558 0.4224286 0.01504057 -0.9062714 0.4210895 -0.03590762 -0.9063081 0.3421416 -0.02917343 -0.9391955 0.336054 -0.07002687 -0.9392358 0.2559908 -0.0533424 -0.9652065 0.2583467 -0.04447609 -0.9650279 0.1480114 -0.1795277 -0.9725546 0.1480113 -0.1795276 -0.9725546 0.1480113 -0.1795277 -0.9725546 0.4855074 0.1185799 -0.8661532 0.4852575 0.1198456 -0.8661191 0.4900529 0.0769717 -0.8682877 0.4902152 0.07746624 -0.8681522 0.4175212 0.06597739 -0.9062688 0.4224147 0.01499921 -0.9062787 0.3431876 0.01218152 -0.939188 0.3420763 -0.02913546 -0.9392205 0.2605248 -0.02218747 -0.9652122 0.2559553 -0.05335509 -0.9652151 0.17552 -0.03658515 -0.983796 0.1470527 -0.1790677 -0.9727848 0.1793929 -0.008536279 -0.9837406 0.1787696 -0.01530015 -0.983772 0.2606014 -0.02230679 -0.9651888 0.2613543 0.009334564 -0.9651979 0.3430726 0.01225525 -0.939229 0.3390741 0.05353814 -0.9392351 0.4176514 0.06594592 -0.9062111 0.4067459 0.1154999 -0.9062106 0.4753001 0.1349656 -0.8694103 0.4552661 0.1951158 -0.8687133 0.4753081 0.1572334 -0.8656557 0.4745911 0.1584107 -0.8658346 0.4414444 0.2338742 -0.8662735 0.4414443 0.2338742 -0.8662735 0.4414446 0.2338743 -0.8662734 0.4581019 0.1929024 -0.8677163 0.3894802 0.1640043 -0.9063156 0.4063187 0.1158565 -0.9063567 0.3302316 0.09416252 -0.9391914 0.3391281 0.0535053 -0.9392175 0.2582668 0.04074764 -0.9652139 0.2612755 0.009303808 -0.9652194 0.1776759 0.00632584 -0.9840688 0.1772174 -0.01095724 -0.9841108 0.1806731 -0.006769418 -0.98352 0.180673 -0.006769418 -0.9835199 0.1806731 -0.006769478 -0.98352 0.1775978 0.006280004 -0.9840832 0.1755572 0.02760756 -0.9840821 0.2583889 0.04063141 -0.9651861 0.2515828 0.07147133 -0.9651932 0.3303225 0.09384077 -0.9391918 0.31659 0.1331762 -0.9391672 0.3896223 0.1638998 -0.9062733 0.3671958 0.2092449 -0.9063023 0.4291589 0.2445557 -0.8694913 0.3921697 0.3007383 -0.8693444 0.422087 0.2690779 -0.8657018 0.4211089 0.2707856 -0.8656457 0.3749068 0.3289033 -0.8667569 0.399487 0.2975596 -0.8671035 0.3389015 0.2524327 -0.9063242 0.367127 0.20932 -0.9063129 0.2983858 0.1701185 -0.9391623 0.3165725 0.1332187 -0.939167 0.2410949 0.1014543 -0.9651841 0.2516158 0.07136088 -0.9651928 0.1709641 0.04848664 -0.9840836 0.1754555 0.02785462 -0.9840933 0.3433546 0.3634649 -0.866026 0.357947 0.3412016 -0.8691694 0.3057484 0.2914482 -0.9064083 0.3385943 0.2525682 -0.9064013 0.2750504 0.2051736 -0.9392822 0.2978208 0.170594 -0.9392553 0.2269846 0.1300148 -0.9651809 0.2409878 0.101525 -0.9652034 0.1653026 0.0696339 -0.9837816 0.1651589 0.06533384 -0.9841006 0.3105198 0.3897269 -0.8670009 0.3148318 0.3817167 -0.8690071 0.2691367 0.3263128 -0.9061377 0.3069668 0.2910794 -0.906115 0.2493026 0.2363961 -0.9391301 0.276055 0.2046971 -0.9390915 0.2338054 0.1733698 -0.9567016 0.2321824 0.1072276 -0.9667439 0.2444546 0.436532 -0.8658417 0.2669005 0.4168612 -0.8689022 0.2280199 0.3561479 -0.9061819 0.2689273 0.326376 -0.9061771 0.2182714 0.2648963 -0.9392485 0.2486038 0.2367469 -0.9392269 0.2052026 0.4546265 -0.8667219 0.2135384 0.4461205 -0.8691248 0.1823682 0.380992 -0.9064144 0.2268933 0.3562399 -0.9064285 0.1843887 0.2895063 -0.9392481 0.2181339 0.2649426 -0.9392673 0.1286076 0.4831506 -0.8660402 0.1290614 0.4829596 -0.8660793 0.1634618 0.466655 -0.8692028 0.1592899 0.4712965 -0.8674712 0.1353214 0.400385 -0.9063003 0.1828423 0.381038 -0.9062996 0.148515 0.3094844 -0.9392353 0.184558 0.2894863 -0.939221 0.08544027 0.4917976 -0.8665075 0.1011362 0.4828441 -0.8698467 0.0866487 0.4136878 -0.9062861 0.1353589 0.4003933 -0.906291 0.1099616 0.3252947 -0.9391975 0.1486397 0.3094994 -0.9392105 0.003261804 0.4999393 -0.8660544 0.007452189 0.4998468 -0.8660818 0.04482561 0.49344 -0.868624 0.0428406 0.4947448 -0.8679818 0.03651005 0.4216136 -0.9060404 0.08786517 0.414066 -0.9059963 0.07135456 0.3362749 -0.9390568 0.111074 0.3253911 -0.9390332 0.08972531 0.2628279 -0.9606617 0.120182 0.250227 -0.9606992 0.1250483 0.2367135 -0.9634987 0.1440156 0.2258902 -0.9634486 0.1367248 0.2488929 -0.958832 0.1795114 0.2180387 -0.9592887 0.1850197 0.1924938 -0.963698 0.1936701 0.1844331 -0.9635748 0.1924751 0.2015849 -0.9603734 0.1923329 0.2016897 -0.9603799 0.04416692 0.2580558 -0.9651199 0.05296641 0.2556961 -0.9653053 0.06957888 0.335885 -0.9393297 0.02821642 0.3419206 -0.9393051 0.03471875 0.4208364 -0.906472 -0.01518607 0.4220399 -0.9064501 -0.01776444 0.4936879 -0.8694578 -0.07848751 0.4895899 -0.8684132 -0.02940869 0.4997152 -0.8656905 -0.03827083 0.4988626 -0.8658357 -0.117762 0.4863041 -0.8658179 -0.07682406 0.4908196 -0.8678677 -0.06534695 0.4174996 -0.9063243 -0.01462739 0.4223774 -0.906302 -0.01190805 0.3436753 -0.9390131 0.03015667 0.3426191 -0.9389904 0.02295702 0.2607666 -0.9651289 0.05527007 0.256009 -0.9650931 0.03809648 0.1764881 -0.9835653 0.1744194 0.1491935 -0.9733033 0.009665548 0.1788886 -0.9838219 0.01486396 0.1784113 -0.9838438 0.02169817 0.2604745 -0.965237 -0.01003301 0.2612379 -0.9652224 -0.01317358 0.3430147 -0.9392377 -0.05348002 0.339146 -0.9392125 -0.06579756 0.4172131 -0.9064238 -0.1154559 0.4062124 -0.9064554 -0.1351365 0.4754494 -0.8693021 -0.1951312 0.4557278 -0.8684677 -0.1613826 0.4733479 -0.8659663 -0.1569952 0.4748912 -0.8659278 -0.2348477 0.4412855 -0.866091 -0.1930573 0.458219 -0.8676199 -0.1640436 0.3893501 -0.9063643 -0.1152034 0.4064701 -0.9063721 -0.09369927 0.3305975 -0.9391091 -0.05275857 0.3396229 -0.9390808 -0.04014319 0.2583832 -0.9652082 -0.00985378 0.2613057 -0.9652059 -0.006694316 0.1775381 -0.9840912 0.01123291 0.1770928 -0.9841301 0.01087605 0.1772987 -0.984097 -0.006515324 0.1775897 -0.9840831 -0.02817898 0.1754916 -0.9840776 -0.04136097 0.2576963 -0.9653403 -0.07152652 0.2511102 -0.9653122 -0.09408628 0.3303006 -0.9391749 -0.1336458 0.316401 -0.9391641 -0.1643142 0.3889949 -0.9064678 -0.2095553 0.3666115 -0.9064671 -0.2450935 0.4287775 -0.8695281 -0.3000472 0.3932864 -0.8690786 -0.2706478 0.4211636 -0.8656622 -0.2716408 0.4204601 -0.8656932 -0.3280639 0.3757321 -0.8667178 -0.2973504 0.3995795 -0.8671326 -0.2524478 0.3392397 -0.9061935 -0.2089251 0.3677528 -0.9061503 -0.1696423 0.2986072 -0.9391781 -0.13358 0.3164326 -0.9391629 -0.1016088 0.2406894 -0.965269 -0.07103866 0.2514249 -0.9652664 -0.04831653 0.1710238 -0.9840816 -0.02833706 0.1754041 -0.9840887 -0.3653748 0.3418453 -0.8658193 -0.3409487 0.3577158 -0.8693639 -0.2917309 0.3060851 -0.9062037 -0.2524913 0.3392368 -0.9061825 -0.2046821 0.2750056 -0.9394025 -0.17071 0.2972281 -0.939422 -0.1302959 0.2268676 -0.9651706 -0.1008129 0.2414739 -0.9651566 -0.06905329 0.1653878 -0.9838082 -0.06503552 0.1652534 -0.9841045 -0.3916203 0.3090621 -0.8666685 -0.3811155 0.3149393 -0.8692321 -0.3257316 0.2691736 -0.9063358 -0.2919717 0.3055184 -0.9063173 -0.2373048 0.2483189 -0.9391615 -0.2038825 0.2763679 -0.9391767 -0.1728006 0.2342448 -0.9566972 -0.1065979 0.2327045 -0.9666879 -0.4375975 0.2426317 -0.8658167 -0.4172974 0.2658203 -0.8690239 -0.3563894 0.2270226 -0.9063374 -0.3257619 0.2690148 -0.9063721 -0.2649455 0.2187881 -0.9391144 -0.2371076 0.2487166 -0.939106 -0.4552986 0.2046775 -0.8664931 -0.4452624 0.2143871 -0.8693559 -0.3808403 0.1833695 -0.9062761 -0.3563923 0.2274159 -0.9062376 -0.289435 0.1846908 -0.9392107 -0.2651042 0.2182232 -0.9392009 -0.4839123 0.1267375 -0.8658906 -0.4838072 0.1274408 -0.8658461 -0.4838066 0.1274428 -0.8658462 -0.4838066 0.1274428 -0.8658462 -0.4658581 0.1648838 -0.8693616 -0.4718682 0.159582 -0.8671066 -0.4003324 0.1353902 -0.9063132 -0.3808708 0.1831991 -0.9062978 -0.3094216 0.1488332 -0.9392055 -0.2894748 0.184675 -0.9392015 -0.4918928 0.08666783 -0.8663315 -0.4836186 0.1011334 -0.8694166 -0.4137505 0.08652234 -0.9062695 -0.4003793 0.1356589 -0.9062523 -0.3252418 0.1102035 -0.9391875 -0.3094515 0.1490439 -0.9391623 -0.5002052 0.004450678 -0.8658955 -0.5003045 0.004409551 -0.8658384 -0.4932926 0.04531621 -0.8686823 -0.4951527 0.04229432 -0.867776 -0.4211264 0.03596824 -0.9062886 -0.4138075 0.08656799 -0.9062392 -0.3360924 0.07030898 -0.9392011 -0.3252747 0.110162 -0.939181 -0.2629088 0.08903658 -0.9607037 -0.2498008 0.1203143 -0.9607935 -0.235954 0.1253331 -0.963648 -0.2254774 0.143844 -0.9635709 -0.2497913 0.1360797 -0.9586901 -0.2182592 0.1796593 -0.9592109 -0.1915832 0.1852997 -0.9638257 -0.1841934 0.1932213 -0.9637108 -0.2021045 0.1919241 -0.9603744 -0.2010549 0.1928856 -0.9604021 -0.4984986 -0.03696256 -0.8661022 -0.4936794 -0.01758331 -0.8694662 -0.4223628 -0.0150429 -0.9063022 -0.4211796 0.03586727 -0.9062679 -0.3421228 0.02913248 -0.9392036 -0.3360883 0.07009172 -0.9392188 -0.2560145 0.05338853 -0.9651975 -0.2584135 0.04440158 -0.9650135 -0.147926 0.1792998 -0.9726097 -0.4855965 -0.1185171 -0.8661118 -0.4852943 -0.1196445 -0.8661263 -0.4900487 -0.07708537 -0.8682801 -0.4901612 -0.07751482 -0.8681783 -0.4175199 -0.06602507 -0.906266 -0.4223581 -0.01504778 -0.9063042 -0.3432348 -0.01222914 -0.9391701 -0.3420757 0.02919065 -0.9392189 -0.2604764 0.02222704 -0.9652243 -0.2560182 0.05339419 -0.9651963 -0.1753086 0.03655546 -0.9838346 -0.1469225 0.1789562 -0.9728251 -0.1469225 0.1789562 -0.9728251 -0.1469225 0.1789561 -0.9728251 -0.1793479 0.008611679 -0.9837481 -0.1787517 0.01526147 -0.9837759 -0.2606402 0.02225434 -0.9651796 -0.2612819 -0.009332597 -0.9652175 -0.3430964 -0.01225519 -0.9392203 -0.3391718 -0.05356663 -0.9391982 -0.4175953 -0.06595313 -0.9062365 -0.4067445 -0.11553 -0.9062075 -0.4752483 -0.1349847 -0.8694355 -0.4553264 -0.1951234 -0.8686799 -0.4748929 -0.1570779 -0.8659119 -0.4745887 -0.1584413 -0.8658302 -0.4413964 -0.2342622 -0.8661931 -0.4413986 -0.2342583 -0.8661931 -0.4580322 -0.1928715 -0.8677598 -0.3895233 -0.1640244 -0.9062933 -0.4063755 -0.1158175 -0.9063362 -0.3301905 -0.09410381 -0.9392118 -0.3390622 -0.05357152 -0.9392375 -0.2582662 -0.04080581 -0.9652116 -0.2613666 -0.009344279 -0.9651944 -0.1776053 -0.006350755 -0.9840814 -0.1771692 0.01094532 -0.9841195 -0.1803715 0.006768584 -0.9835754 -0.1803715 0.006768524 -0.9835754 -0.1803716 0.006768465 -0.9835753 -0.1776703 -0.006282508 -0.9840701 -0.175557 -0.02766162 -0.9840806 -0.2583242 -0.04070132 -0.9652006 -0.2515389 -0.07138776 -0.9652109 -0.3304381 -0.09378153 -0.939157 -0.3166503 -0.1331938 -0.9391444 -0.3895938 -0.1638762 -0.9062899 -0.3672357 -0.2092565 -0.9062834 -0.4290933 -0.244503 -0.8695386 -0.3921433 -0.3007139 -0.8693646 -0.4223178 -0.2690477 -0.8655987 -0.4209107 -0.270949 -0.8656911 -0.3753029 -0.3289219 -0.8665784 -0.3753029 -0.3289219 -0.8665784 -0.375303 -0.3289223 -0.8665782 -0.3995903 -0.2974783 -0.8670837 -0.3389506 -0.2523337 -0.9063335 -0.367075 -0.2093542 -0.9063259 -0.2983626 -0.1701642 -0.9391614 -0.3165483 -0.1332941 -0.9391645 -0.2410687 -0.1015126 -0.9651845 -0.251617 -0.07129728 -0.9651973 -0.1708785 -0.04841846 -0.9841017 -0.1754872 -0.02788066 -0.9840869 -0.3432448 -0.3635491 -0.8660342 -0.357854 -0.3412569 -0.869186 -0.3056696 -0.2914972 -0.9064191 -0.3385457 -0.2524838 -0.9064429 -0.2751114 -0.205172 -0.9392647 -0.2978209 -0.1705911 -0.9392558 -0.2269846 -0.1300177 -0.9651806 -0.2410264 -0.1014911 -0.9651973 -0.165285 -0.06959706 -0.9837871 -0.1651201 -0.06536859 -0.9841049 -0.3104736 -0.3897097 -0.8670251 -0.3148708 -0.3817148 -0.8689938 -0.2691702 -0.3263115 -0.9061282 -0.3069026 -0.2910507 -0.9061459 -0.2493696 -0.2364895 -0.9390887 -0.2760856 -0.2046065 -0.9391023 -0.2338676 -0.173318 -0.9566959 -0.23215 -0.1071926 -0.9667555 -0.5257286 -0.7241641 -0.4463135 -0.529063 -0.7215554 -0.4465985 -0.5260987 -0.7239657 -0.4461992 -0.5275759 -0.7268006 -0.4398008 -0.5269263 -0.7233172 -0.4462744 -0.5297454 -0.7216391 -0.4456533 -0.5237575 -0.7253381 -0.4467244 -0.5294225 -0.7214604 -0.4463258 -0.52195 -0.7270648 -0.4460326 -0.5245836 -0.7251926 -0.4459908 -0.5260803 -0.7240418 -0.4460976 -0.2198069 -0.9755434 0 0.01091802 -0.9999404 0 0.01091802 -0.9999404 0 0.2414687 -0.9704087 0 0.2414688 -0.9704087 0 0.4579836 -0.8889608 0 0.4579492 -0.8889784 0 0.65166 -0.7585113 0 0.6516181 -0.7585472 0 0.8084529 -0.5885611 0 0.8084932 -0.5885056 0 0.9219137 -0.3873955 0 0.9219137 -0.3873955 0 0.9869787 -0.1608508 0 0.9976196 0.06895685 0 0.9976255 0.06887269 0 0.9552131 0.295919 0 0.8600319 0.5102405 0 0.8600319 0.5102404 0 0.7185203 0.695506 0 0.7184782 0.6955496 0 0.5420808 0.8403264 0 0.5420809 0.8403264 0 0.3308389 0.9436873 0 0.3308654 0.943678 0 0.106033 0.9943627 0 0.1060153 0.9943645 0 -0.1293535 0.9915986 0 -0.1293427 0.9916 0 -0.3504624 0.9365769 0 -0.3504903 0.9365664 0 -0.5593267 0.8289474 0 -0.5593659 0.828921 0 -0.7352268 0.6778212 0 -0.8708814 0.4914934 0 -0.8708814 0.4914932 0 -0.9613367 0.2753759 0 -0.9613368 0.2753757 0 -0.9988068 0.04883599 0 -0.9988068 0.04883599 0 -0.9824507 -0.186523 0 -0.9824351 -0.1866046 0 -0.9143152 -0.4050033 0 -0.9143154 -0.4050033 0 -0.7956166 -0.6058006 0 -0.7956166 -0.6058005 0 -0.6345884 -0.7728503 0 -0.63463 -0.7728163 0 -0.4387098 -0.8986288 0 -0.4386764 -0.8986452 0 -0.2197706 -0.9755517 0 4.92786e-6 0 1 3.96021e-6 0 1 -7.44225e-6 0 1 2.50415e-6 0 1 1.49428e-6 0 1 8.12744e-6 0 1 -9.31918e-6 0 1 4.85312e-6 0 1 -2.74099e-6 0 1 -9.22727e-7 0 1 8.86283e-7 0 1 5.69583e-6 0 1 -7.06574e-6 0 1 5.66739e-6 0 1 -1.10186e-5 0 1 0.0935983 0.8900472 -0.4461562 0.09453898 0.889897 -0.4462575 0.09504735 0.8897835 -0.4463759 0.09402984 0.8896709 -0.4468155 0.09393459 0.8899959 -0.4461878 0.09468257 0.8899004 -0.4462202 0.09431523 0.8900101 -0.4460794 0.0940572 0.8900294 -0.4460955 0.09484684 0.889877 -0.4462321 0.09391856 0.8900394 -0.4461044 0.09416186 0.8899623 -0.4462072 -0.02268564 -0.9997193 0.006851851 0.01852381 -0.9998285 0 0.1012461 -0.9948614 0 0.1422017 -0.9898142 0.006828665 0.1828389 -0.983143 0 0.2634119 -0.9646834 0 0.3035936 -0.9527764 0.006938636 0.3432351 -0.9392496 0 0.4189324 -0.9080174 0 0.4555011 -0.8902098 0.006721138 0.4911768 -0.87106 0 0.5632037 -0.8263181 0 0.5964478 -0.8026236 0.006745994 0.6286894 -0.7776566 0 0.6916339 -0.7222483 0 0.719918 -0.6940276 0.006623029 0.7472006 -0.6645987 0 0.7999285 -0.6000953 0 0.8241587 -0.5663173 0.006883561 0.8470268 -0.5315504 0 0.8888329 -0.4582315 0 0.9066597 -0.4218092 0.006724536 0.9230939 -0.384575 0 0.951811 -0.3066852 0 0.9633711 -0.2680882 0.00669372 0.9734104 -0.2290682 0 0.9897945 -0.1425026 0 0.9945637 -0.1039289 0.006481468 0.9979068 -0.06466925 0 0.9998506 0.01728945 0 0.9981393 0.06055378 0.007165133 0.9945938 0.103843 0 0.9945938 0.103843 0 0.9945938 0.103843 0 0.9833001 0.1819916 0 0.9748785 0.2226318 0.006872773 0.9648385 0.262844 0 0.9396897 0.3420284 0 0.9245066 0.3811033 0.006923437 0.907842 0.4193124 0 0.8708879 0.4914818 0 0.8495535 0.5274567 0.006943464 0.8267662 0.5625457 0 0.7766204 0.629969 0 0.7499811 0.6614238 0.006846606 0.7220429 0.6918483 0 0.664958 0.7468808 0 0.6332995 0.7738763 0.006874978 0.6007257 0.7994552 0 0.5283997 0.8489958 0 0.4949913 0.8688741 0.006430506 0.4609596 0.8874212 0 0.3854779 0.9227172 0 0.3466144 0.9379823 0.006918787 0.3071539 0.9516599 0 0.2242245 0.9745376 0 0.1857265 0.9825798 0.006525874 0.1468829 0.9891539 0 0.06479096 0.9978989 0 0.0237962 0.9996937 0.00680387 -0.01731783 0.99985 0 -0.1037787 0.9946004 0 -0.142625 0.9897556 0.006479799 -0.1811292 0.9834593 0 -0.2638775 0.9645562 0 -0.303187 0.9529069 0.006797909 -0.3421543 0.9396438 0 -0.4176378 0.9086136 0 -0.4558076 0.8900505 0.007045626 -0.4933702 0.8698195 0 -0.5626928 0.8266662 0 -0.5968623 0.8023138 0.006951808 -0.6299911 0.7766024 0 -0.689622 0.7241696 0 -0.7199081 0.6940333 0.007096171 -0.7491349 0.6624175 0 -0.799476 0.6006981 0 -0.8239939 0.5665562 0.006943881 -0.8469367 0.5316938 0 -0.8891971 0.4575243 0 -0.9065861 0.42197 0.006574928 -0.9227116 0.3854911 0 -0.9520945 0.3058042 0 -0.963411 0.2679474 0.006595134 -0.973383 0.2291848 0 -0.9891498 0.1469107 0 -0.9945657 0.1038625 0.007192909 -0.9981546 0.06072437 0 -0.9981546 0.06072437 0 -0.9981546 0.06072437 0 -0.9998506 -0.01728945 0 -0.9982693 -0.05841112 0.006821095 -0.9950424 -0.09945201 0 -0.9826228 -0.185614 0 -0.9743565 -0.2249125 0.006620168 -0.9646479 -0.263542 0 -0.9399382 -0.3413448 0 -0.9246935 -0.380649 0.006965875 -0.9079214 -0.4191405 0 -0.8703666 -0.4924045 0 -0.8494335 -0.527652 0.006791114 -0.8270902 -0.5620694 0 -0.7787334 -0.6273551 0 -0.7513412 -0.6598765 0.00703901 -0.7227641 -0.6910949 0 -0.6637349 -0.7479679 0 -0.6312401 -0.7755555 0.007045984 -0.5977442 -0.801687 0 -0.5312637 -0.8472065 0 -0.4963695 -0.8680853 0.006727635 -0.4606983 -0.8875569 0 -0.3835863 -0.9235051 0 -0.3459116 -0.9382432 0.006718933 -0.3075333 -0.9515373 0 -0.2266941 -0.9739661 0 -0.1869294 -0.9823502 0.006746709 -0.1466279 -0.9891918 0 -0.06395757 -0.9979527 0 0.06734859 -0.6647436 -0.7440298 0.06642812 -0.665174 -0.7437278 0.06642806 -0.6651739 -0.7437278 0.06642818 -0.6651737 -0.7437279 0.1225849 -0.6567406 -0.7440866 0.1228354 -0.6570281 -0.7437914 0.1761972 -0.6450365 -0.7435607 0.175768 -0.6447411 -0.7439184 0.1751346 -0.6459238 -0.7430413 0.2298986 -0.628587 -0.7429839 0.2287108 -0.6277636 -0.7440458 0.2292352 -0.6272561 -0.7443124 0.2791246 -0.6065853 -0.7444083 0.2795965 -0.6068356 -0.7440271 0.3298271 -0.5807781 -0.7442519 0.3287791 -0.580869 -0.7446446 0.3282716 -0.5842812 -0.742195 0.3774166 -0.5539937 -0.7420564 0.3770933 -0.5517003 -0.7439271 0.3770777 -0.551788 -0.7438699 0.3770777 -0.5517881 -0.7438699 0.3770777 -0.551788 -0.7438699 0.4200091 -0.519804 -0.7439061 0.4212781 -0.5203426 -0.7428112 0.4614415 -0.4852255 -0.7427167 0.4614414 -0.4852254 -0.7427167 0.4614415 -0.4852256 -0.7427167 0.4627605 -0.4846082 -0.7422989 0.4627317 -0.4845302 -0.7423678 0.500253 -0.4455305 -0.7424618 0.4980031 -0.4392852 -0.7476775 0.4960414 -0.4483073 -0.7436151 0.4960415 -0.4483073 -0.7436151 0.4960415 -0.4483072 -0.7436151 0.5358499 -0.3998416 -0.7436341 0.5375837 -0.4001393 -0.7422212 0.5683345 -0.3550717 -0.7422399 0.5663679 -0.3569867 -0.7428243 0.5666632 -0.3574324 -0.7423846 0.5951037 -0.3075736 -0.7424622 0.5929222 -0.3041937 -0.7455933 0.5932338 -0.306694 -0.7443201 0.6163804 -0.2567121 -0.7444288 0.6170661 -0.2566026 -0.7438983 0.6382601 -0.1984232 -0.7438092 0.6382602 -0.1984232 -0.7438092 0.6382603 -0.1984233 -0.7438092 0.6344637 -0.2059917 -0.7449988 0.6341844 -0.2057347 -0.7453077 0.6495533 -0.1499644 -0.7453799 0.6514561 -0.1518565 -0.7433335 0.6508655 -0.1506192 -0.7441022 0.6610789 -0.09681224 -0.7440445 0.6597679 -0.09713363 -0.7451654 0.6653249 -0.04526728 -0.7451803 0.6675466 -0.04429459 -0.7432493 0.6688251 0.01326167 -0.7433015 0.6702448 0.01464259 -0.7419957 0.6680773 0.01681154 -0.743902 0.6680773 0.01681149 -0.743902 0.6680773 0.01681149 -0.743902 0.6650249 0.06549942 -0.7439434 0.6638495 0.06469541 -0.7450627 0.6603724 0.07767474 -0.7469102 0.6603724 0.07767474 -0.7469103 0.6603724 0.07767462 -0.7469103 0.6538814 0.1205248 -0.7469357 0.6589422 0.1246259 -0.7417975 0.6457255 0.181373 -0.7417159 0.6440526 0.1763932 -0.7443667 0.6450771 0.1759912 -0.7435743 0.628176 0.229718 -0.7433872 0.6253165 0.2260625 -0.7469103 0.6321121 0.2170457 -0.7438585 0.6059753 0.2803897 -0.7444297 0.6048871 0.2789332 -0.7458605 0.581185 0.325309 -0.745921 0.581245 0.3304287 -0.7436203 0.578937 0.3307273 -0.7452861 0.5515285 0.3746298 -0.7452979 0.5566625 0.3750411 -0.7412632 0.5495883 0.379137 -0.7444514 0.519515 0.41987 -0.7441865 0.5209088 0.4231928 -0.7413245 0.4874955 0.4613695 -0.7412735 0.4868742 0.4632374 -0.7405166 0.4820494 0.4623226 -0.7442353 0.4421256 0.5011683 -0.7438786 0.4447566 0.5019599 -0.7417734 0.4433827 0.5022625 -0.7423909 0.4023849 0.5355392 -0.7424852 0.4024004 0.5355143 -0.7424947 0.3531193 0.5693007 -0.7424309 0.3564355 0.5655307 -0.7437263 0.3534964 0.5642578 -0.7460922 0.3059058 0.591125 -0.7463197 0.3088438 0.5932347 -0.74343 0.3040094 0.592311 -0.7461542 0.2562189 0.6149936 -0.7457445 0.2561339 0.6152856 -0.7455328 0.1990807 0.636923 -0.7447792 0.2027909 0.6347889 -0.7455998 0.2075141 0.6390864 -0.7406123 0.1539115 0.6541045 -0.7405799 0.1516524 0.6515603 -0.7432839 0.1512752 0.6512654 -0.743619 0.09666913 0.6614674 -0.7437177 0.09720903 0.6598945 -0.7450435 0.0421614 0.6655825 -0.7451324 0.04391771 0.6619315 -0.7482766 -0.006551682 0.6632782 -0.7483443 -0.01475608 0.6700724 -0.7421491 -0.01680779 0.6678228 -0.7441306 -0.06548768 0.6646411 -0.7442874 -0.06834137 0.6685805 -0.7404928 -0.07826441 0.6656866 -0.742116 -0.07826435 0.6656866 -0.7421159 -0.07826459 0.6656863 -0.7421162 -0.1209183 0.6592114 -0.7421718 -0.1212976 0.6596911 -0.7416837 -0.181156 0.645722 -0.7417719 -0.1773348 0.6443329 -0.7439002 -0.1771678 0.6448343 -0.7435054 -0.2285585 0.6285881 -0.7433963 -0.2267116 0.6270051 -0.7452962 -0.2178099 0.6337377 -0.7422503 -0.2825652 0.6077218 -0.74218 -0.2789642 0.6048981 -0.7458401 -0.321038 0.5833919 -0.7460487 -0.3318118 0.583593 -0.7411614 -0.3321312 0.5815429 -0.7426282 -0.3763136 0.5540332 -0.7425869 -0.3763149 0.5545741 -0.7421823 -0.3752619 0.5562763 -0.7414413 -0.4235422 0.5210775 -0.7410063 -0.4196561 0.5193652 -0.7444116 -0.4585859 0.4848738 -0.7447124 -0.4626261 0.4833942 -0.7431738 -0.4622606 0.4820092 -0.7442998 -0.4995779 0.4436158 -0.7440611 -0.5012721 0.4486577 -0.7398869 -0.502433 0.4430472 -0.7424758 -0.5369126 0.4004381 -0.7425458 -0.5320332 0.3997056 -0.7464424 -0.5652198 0.3506903 -0.746688 -0.5636876 0.3523519 -0.7470639 -0.5666214 0.3586325 -0.7418376 -0.5955685 0.3081375 -0.7418555 -0.592498 0.3034312 -0.746241 -0.5924981 0.3034312 -0.746241 -0.5924981 0.3034312 -0.7462409 -0.5924462 0.3037748 -0.7461425 -0.6148873 0.2562229 -0.7458308 -0.6177492 0.2559076 -0.7435706 -0.6257335 0.234853 -0.7438426 -0.6257336 0.2348529 -0.7438426 -0.6257334 0.2348537 -0.7438424 -0.6396786 0.2083614 -0.7398627 -0.6349002 0.2029151 -0.7454712 -0.649542 0.1498457 -0.7454136 -0.6515474 0.1517494 -0.7432753 -0.6514049 0.1511475 -0.7435228 -0.6609933 0.09967285 -0.7437427 -0.6653541 0.09808832 -0.7400558 -0.6712102 0.0425232 -0.7400465 -0.6675272 0.04420417 -0.7432722 -0.6688438 -0.01306408 -0.7432883 -0.6677445 -0.01174151 -0.744298 -0.6683153 -0.01118868 -0.743794 -0.6648477 -0.06880927 -0.743803 -0.6632294 -0.06759023 -0.7453579 -0.660412 -0.07801622 -0.7468397 -0.6604121 -0.07801288 -0.7468399 -0.660412 -0.07801353 -0.74684 -0.6542442 -0.1203291 -0.7466495 -0.6589486 -0.1243324 -0.7418411 -0.6476146 -0.1738836 -0.7418625 -0.6476146 -0.1738836 -0.7418624 -0.6476146 -0.1738835 -0.7418624 -0.6481321 -0.1748787 -0.7411763 -0.6444076 -0.1767522 -0.7439742 -0.6279308 -0.2287111 -0.7439047 -0.6292938 -0.2306408 -0.7421551 -0.626024 -0.2348843 -0.7435882 -0.626024 -0.2348842 -0.7435882 -0.626024 -0.2348842 -0.7435883 -0.6068453 -0.2812093 -0.7434112 -0.6055808 -0.2795206 -0.7450774 -0.582693 -0.3250409 -0.7448606 -0.582679 -0.3278629 -0.7436338 -0.5823952 -0.3280077 -0.7437922 -0.5519039 -0.3772159 -0.7437139 -0.5525121 -0.3772082 -0.7432661 -0.5506222 -0.3785036 -0.7440096 -0.5194898 -0.4202378 -0.7439963 -0.5185722 -0.4179916 -0.7458995 -0.4833094 -0.4586003 -0.7457197 -0.481925 -0.4618984 -0.7445792 -0.485903 -0.4626141 -0.7415433 -0.4457056 -0.5010915 -0.7417909 -0.4413384 -0.4994786 -0.7454808 -0.4416373 -0.4995136 -0.7452803 -0.3997077 -0.5339757 -0.7450528 -0.4000144 -0.5360943 -0.743365 -0.35285 -0.5684615 -0.7432014 -0.35285 -0.5684616 -0.7432014 -0.35285 -0.5684616 -0.7432014 -0.3549205 -0.5660219 -0.7440772 -0.3566144 -0.5668036 -0.7426708 -0.3079013 -0.5945096 -0.7428022 -0.3066514 -0.5936587 -0.7439989 -0.3089089 -0.5938798 -0.7428877 -0.257418 -0.6179266 -0.7429016 -0.257449 -0.6176546 -0.743117 -0.1955991 -0.6403218 -0.7427846 -0.204817 -0.6355158 -0.7444258 -0.2056379 -0.6363608 -0.7434769 -0.152418 -0.6511269 -0.7435069 -0.1512683 -0.6497409 -0.7449528 -0.1523692 -0.6504787 -0.7440841 -0.09752202 -0.6611009 -0.7439322 -0.09731829 -0.661494 -0.7436094 -0.04307007 -0.6672406 -0.743596 -0.04284405 -0.6678462 -0.7430652 0.0124576 -0.6686503 -0.7434727 0.01243603 -0.6687354 -0.7433965 0.01292639 -0.6681404 -0.7439229 0.06748306 -0.6649886 -0.7437984 -0.1277314 -0.8666486 -0.4822916 -0.05609834 -0.8744276 -0.481902 -0.05627161 -0.8741716 -0.4823459 0.01628726 -0.8758414 -0.4823242 0.01639956 -0.876077 -0.4818922 0.08831483 -0.8715909 -0.4822134 0.08870929 -0.871928 -0.4815313 0.1610618 -0.8616631 -0.4812442 0.160372 -0.8611087 -0.4824652 0.2303372 -0.8448641 -0.4828556 0.2311998 -0.8454855 -0.4813534 0.3000218 -0.82367 -0.4812014 0.2989141 -0.8230136 -0.4830105 0.3662846 -0.7951019 -0.4833722 0.3668292 -0.7952655 -0.4826895 0.4313836 -0.7622311 -0.4826097 0.4318647 -0.7623363 -0.4820127 0.4932925 -0.724147 -0.4819478 0.4932925 -0.724147 -0.4819478 0.4932925 -0.724147 -0.4819478 0.493062 -0.7241657 -0.4821556 0.55134 -0.6807795 -0.4822484 0.5506379 -0.6806826 -0.4831866 0.6045944 -0.6330536 -0.4834343 0.6045945 -0.6330536 -0.4834343 0.6045944 -0.6330537 -0.4834343 0.6026107 -0.6328656 -0.4861499 0.6523914 -0.5811445 -0.4864736 0.6586076 -0.5813551 -0.4777682 0.7048965 -0.5246283 -0.4773741 0.7009217 -0.5248458 -0.4829553 0.740719 -0.4668451 -0.4831056 0.7402538 -0.4668842 -0.4837803 0.7773986 -0.401858 -0.4839025 0.7807763 -0.4009926 -0.4791589 0.8105337 -0.3371349 -0.4789314 0.8073356 -0.3380876 -0.4836385 0.8324281 -0.2703179 -0.4837268 0.838449 -0.2679335 -0.4745684 0.8577584 -0.1981766 -0.474317 0.8513246 -0.2014053 -0.4844402 0.865459 -0.1275441 -0.484472 0.8682597 -0.1255865 -0.4799512 0.8754144 -0.05814099 -0.4798638 0.8764953 -0.05729883 -0.4779886 0.8781909 0.0192793 -0.4779219 0.8732351 0.01520156 -0.4870619 0.8692711 0.08476364 -0.4870144 0.8720322 0.0876246 -0.481541 0.8612841 0.1627989 -0.481338 0.8622299 0.1641365 -0.4791857 0.8464147 0.2317932 -0.479431 0.8435838 0.2280701 -0.4861589 0.8218866 0.2971633 -0.4860005 0.8245533 0.3015624 -0.4787194 0.7974895 0.3676949 -0.4783421 0.7965496 0.3658473 -0.4813157 0.7622882 0.4334862 -0.4806314 0.7617812 0.4320638 -0.4827113 0.7244664 0.4919893 -0.4827991 0.7244845 0.4917955 -0.4829695 0.6796225 0.5522711 -0.4828147 0.6791654 0.5501767 -0.4858394 0.6332916 0.6024636 -0.4857774 0.6338431 0.6071421 -0.4791885 0.5808193 0.658137 -0.4790666 0.5805557 0.6526432 -0.4868388 0.5247089 0.6983975 -0.4867458 0.5247982 0.6996323 -0.4848729 0.4663043 0.740069 -0.4846218 0.4657289 0.7443091 -0.4786446 0.403653 0.7800874 -0.478046 0.403604 0.7806373 -0.4771889 0.3376796 0.8112133 -0.4773946 0.3388109 0.8071666 -0.4834144 0.2663773 0.8338246 -0.483508 0.2664562 0.8335759 -0.483893 0.2004941 0.8519434 -0.4837298 0.2006186 0.8517124 -0.484085 0.127513 0.8656538 -0.4841324 0.1261624 0.8678815 -0.4804839 0.05808281 0.8752315 -0.4802044 0.05718207 0.876609 -0.4777939 0.05718207 0.876609 -0.4777939 0.05718207 0.876609 -0.4777939 -0.01934236 0.8782757 -0.4777634 -0.0151925 0.8733243 -0.4869022 -0.08883386 0.8691021 -0.4865904 -0.09134584 0.8716428 -0.4815546 -0.1585 0.8621014 -0.4813095 -0.1605449 0.8637803 -0.4776076 -0.2332131 0.8473153 -0.4771463 -0.2280193 0.8436547 -0.4860599 -0.2971457 0.8220139 -0.485796 -0.2997971 0.8235019 -0.4816288 -0.3668661 0.7956159 -0.4820836 -0.3699937 0.7970684 -0.4772703 -0.4342478 0.7638011 -0.4775319 -0.4308361 0.7626185 -0.4824868 -0.4920986 0.7246171 -0.4824614 -0.4920987 0.7246171 -0.4824614 -0.4918743 0.7244989 -0.4828675 -0.5503615 0.6811044 -0.4829069 -0.5520352 0.6814885 -0.4804485 -0.6066084 0.6338665 -0.4798328 -0.6030359 0.6334553 -0.4848527 -0.6536927 0.5805091 -0.4854845 -0.6571641 0.5808728 -0.4803354 -0.7014359 0.5269471 -0.479911 -0.7062461 0.5268083 -0.4729582 -0.7471445 0.46702 -0.472935 -0.7415097 0.4676806 -0.4810804 -0.7783823 0.4027872 -0.481543 -0.7812222 0.4021908 -0.4774251 -0.8118221 0.3361966 -0.4774062 -0.8076953 0.3375359 -0.4834229 -0.8322726 0.2710202 -0.4836016 -0.8339958 0.2703099 -0.4810236 -0.8540163 0.1970447 -0.4814869 -0.8523203 0.1978808 -0.484142 -0.8655731 0.1276199 -0.4842483 -0.8627527 0.1291093 -0.4888647 -0.8705601 0.05781859 -0.4886536 -0.8767197 0.05326706 -0.4780433 -0.8782212 -0.01544183 -0.4780053 -0.8779198 -0.0152831 -0.4785639 -0.8735379 -0.08898943 -0.4785525 -0.8720192 -0.08761334 -0.4815666 -0.8612222 -0.1625452 -0.4815345 -0.8586792 -0.1593801 -0.4871018 -0.8432076 -0.2275205 -0.4870681 -0.846754 -0.2326809 -0.4784007 -0.8245391 -0.3020218 -0.4784539 -0.8237348 -0.3009338 -0.4805206 -0.7962513 -0.3674834 -0.4805621 -0.7951367 -0.3652166 -0.4841223 -0.762509 -0.4292314 -0.4840875 -0.7648614 -0.4353314 -0.474841 -0.7265323 -0.4965645 -0.474947 -0.7265323 -0.4965645 -0.4749469 -0.7265322 -0.4965645 -0.474947 -0.7250304 -0.4915486 -0.4824011 -0.6820581 -0.5496227 -0.482402 -0.6826515 -0.5529986 -0.4776815 -0.6341978 -0.6078811 -0.4777801 -0.6338787 -0.6057959 -0.4808422 -0.5826535 -0.6550611 -0.4810507 -0.5827152 -0.6563522 -0.4792127 -0.5247398 -0.7032424 -0.4796857 -0.5249553 -0.6999295 -0.4842734 -0.4648944 -0.7412877 -0.4841135 -0.4648134 -0.7412112 -0.4843082 -0.4024391 -0.7770318 -0.4840088 -0.4018787 -0.7795605 -0.4803947 -0.3373479 -0.8094612 -0.4805924 -0.3375722 -0.8086075 -0.4818703 -0.2687431 -0.8340269 -0.4818466 -0.2689955 -0.8332698 -0.4830144 -0.1995958 -0.8527214 -0.4827297 -0.1992595 -0.8534853 -0.481517 -0.1275706 -0.867061 -0.4815921 -0.1445204 -0.9751677 -0.1678147 -0.06333941 -0.983883 -0.1672198 -0.06305366 -0.9839972 -0.1666548 0.01846283 -0.9859542 -0.1659926 0.01826727 -0.9858185 -0.1668182 0.09979164 -0.980973 -0.166534 0.09982365 -0.9809318 -0.1667578 0.1805605 -0.969353 -0.1665911 0.1802312 -0.9693076 -0.1672113 0.2599885 -0.9509521 -0.1676197 0.2599885 -0.9509521 -0.1676197 0.2599885 -0.9509521 -0.1676197 0.2597202 -0.9508711 -0.1684924 0.3363841 -0.9264172 -0.1691065 0.3385854 -0.9265147 -0.1641049 0.4131764 -0.8958863 -0.1633189 0.4134023 -0.8958519 -0.1629362 0.4863506 -0.8585525 -0.1623291 0.4842156 -0.8588172 -0.1672375 0.5550001 -0.8148208 -0.1674578 0.5554141 -0.8147981 -0.1661905 0.6201617 -0.7666737 -0.1661652 0.6197984 -0.7667263 -0.1672746 0.6798698 -0.7139946 -0.1672987 0.6826843 -0.712931 -0.1602238 0.7400268 -0.6533657 -0.1596041 0.7363324 -0.6550835 -0.1693525 0.7888787 -0.5907147 -0.1694889 0.7880771 -0.591117 -0.1717998 0.8331957 -0.5254949 -0.1721629 0.8351885 -0.5242172 -0.1663029 0.8770847 -0.4506269 -0.1663069 0.8759032 -0.451591 -0.1698805 0.9089885 -0.3805852 -0.1699854 0.9102941 -0.3793427 -0.1657226 0.9394477 -0.3000687 -0.1655203 0.9375615 -0.3023713 -0.1719018 0.9586118 -0.2268804 -0.1720141 0.9586118 -0.2268804 -0.1720141 0.9586118 -0.2268805 -0.172014 0.9594426 -0.2257009 -0.1689053 0.9754424 -0.1413119 -0.1689475 0.9758669 -0.1405718 -0.1671034 0.9838282 -0.06433224 -0.1671631 0.9839941 -0.06400787 -0.1663092 0.9859157 0.01700192 -0.166377 0.9859029 0.01726263 -0.1664258 0.9811177 0.09845775 -0.166476 0.9822754 0.1022921 -0.1570711 0.9701716 0.1846523 -0.1570687 0.9690697 0.1792542 -0.1696233 0.9514223 0.2571329 -0.1693463 0.9517631 0.2591094 -0.1643453 0.9262757 0.3389016 -0.1647999 0.9262105 0.3371307 -0.168751 0.8956458 0.4114525 -0.1688954 0.8956243 0.4136782 -0.1634858 0.8580536 0.486741 -0.1637902 0.8583711 0.4843422 -0.1691502 0.8154204 0.5536327 -0.1690582 0.8152161 0.5547704 -0.1662913 0.766216 0.6206809 -0.1663383 0.7659984 0.6214747 -0.1643647 0.7659985 0.6214746 -0.1643647 0.7659984 0.6214746 -0.1643648 0.71228 0.6822504 -0.1648991 0.7120946 0.6825266 -0.1645563 0.6556792 0.7368198 -0.164868 0.6556217 0.7366478 -0.1658623 0.5916346 0.7888609 -0.1663345 0.5920356 0.7880952 -0.1685227 0.5228187 0.8355102 -0.1690663 0.5213454 0.8375192 -0.1635875 0.4530899 0.8762654 -0.1639171 0.4543152 0.874785 -0.168372 0.3815765 0.9087606 -0.1689779 0.38023 0.9101094 -0.1647005 0.3003292 0.9395102 -0.1646908 0.3025527 0.9375155 -0.1718331 0.2258801 0.9588826 -0.1718208 0.2213261 0.9621226 -0.1591697 0.1420741 0.9770419 -0.1587583 0.1448249 0.9754056 -0.1661615 0.06418901 0.9838922 -0.1668415 0.06389403 0.9840561 -0.1659854 -0.01714944 0.9859246 -0.1663089 -0.01707398 0.9858553 -0.1667273 -0.1027774 0.9806684 -0.166512 -0.1023071 0.9805299 -0.1676139 -0.1801652 0.9692777 -0.1674557 -0.1784647 0.9688402 -0.1717529 -0.257027 0.9509448 -0.1721659 -0.2602709 0.9514287 -0.1644462 -0.3374058 0.9267842 -0.1650102 -0.3374558 0.9268171 -0.1647233 -0.3374558 0.9268171 -0.1647233 -0.3374558 0.9268171 -0.1647233 -0.4153169 0.8947361 -0.1641926 -0.4113409 0.894851 -0.173322 -0.4844853 0.857486 -0.1731816 -0.4861796 0.8573474 -0.1690706 -0.5536755 0.8154067 -0.1689834 -0.5548086 0.8151748 -0.1663656 -0.6207209 0.7661609 -0.1664424 -0.6212744 0.7661039 -0.16463 -0.6801584 0.7142747 -0.1649134 -0.6802532 0.714266 -0.1645596 -0.7390383 0.6531128 -0.1651246 -0.7387303 0.653274 -0.1658635 -0.7903867 0.5895854 -0.1663672 -0.7871822 0.5913774 -0.1749774 -0.8327149 0.5253664 -0.17486 -0.8347398 0.5239573 -0.1693471 -0.8764172 0.4510001 -0.1687954 -0.876491 0.4509981 -0.1684169 -0.9094206 0.3800446 -0.1688796 -0.9093871 0.3801925 -0.1687269 -0.9093871 0.3801925 -0.1687269 -0.9093871 0.3801925 -0.1687269 -0.9377064 0.3040333 -0.1681383 -0.9395446 0.3018759 -0.1616384 -0.9612925 0.2232367 -0.1614997 -0.9592363 0.2261151 -0.1695223 -0.9592362 0.2261151 -0.1695223 -0.9592363 0.2261151 -0.1695223 -0.9746339 0.1461961 -0.1694566 -0.9754051 0.1446889 -0.1662832 -0.9842277 0.05982947 -0.1664824 -0.9842277 0.05982947 -0.1664824 -0.9842277 0.05982947 -0.1664824 -0.9842473 0.05986529 -0.1663532 -0.9859145 -0.01717716 -0.1663658 -0.9858791 -0.01708787 -0.1665853 -0.9810821 -0.09853994 -0.1666368 -0.9809193 -0.09800714 -0.1679048 -0.9692199 -0.1800957 -0.1678642 -0.9700088 -0.1832311 -0.1597164 -0.951872 -0.2615209 -0.1598329 -0.951722 -0.2600131 -0.1631516 -0.9267374 -0.3384301 -0.1631653 -0.926613 -0.336689 -0.1674182 -0.8959307 -0.411418 -0.167462 -0.895763 -0.4137171 -0.1626252 -0.8575709 -0.4879879 -0.1626042 -0.8578528 -0.4852414 -0.1692029 -0.8158333 -0.553027 -0.1690487 -0.815629 -0.5541831 -0.1662244 -0.7661439 -0.6207976 -0.166235 -0.7669844 -0.6178633 -0.1731473 -0.7121424 -0.680462 -0.1726989 -0.7119321 -0.6809468 -0.1716517 -0.6542129 -0.7366128 -0.1714847 -0.6538903 -0.7371235 -0.1705186 -0.5912331 -0.7883254 -0.1702544 -0.5898258 -0.7908425 -0.1633211 -0.5241865 -0.8357916 -0.163343 -0.5241865 -0.8357916 -0.163343 -0.5241866 -0.8357917 -0.163343 -0.5240156 -0.8358706 -0.1634877 -0.4520679 -0.8768067 -0.1638433 -0.453891 -0.8746339 -0.1702898 -0.453891 -0.8746339 -0.1702898 -0.453891 -0.8746339 -0.1702898 -0.3796422 -0.9093594 -0.1701099 -0.3783785 -0.910668 -0.1658729 -0.3029609 -0.9384505 -0.165908 -0.3031877 -0.93822 -0.1667948 -0.2241744 -0.9601617 -0.1668397 -0.2235882 -0.9606334 -0.1648995 -0.1436704 -0.9756105 -0.165961 -0.1436703 -0.9756106 -0.1659609 -0.1436703 -0.9756106 -0.1659609 -0.4875564 0.1132261 -0.8657186 -0.4745981 0.1516588 -0.8670389 -0.4221062 0.2671651 -0.8662847 -0.3460592 0.3607056 -0.8661031 -0.1625897 0.4728509 -0.866012 -0.05811595 0.4951766 -0.8668465 -0.05811595 0.4951766 -0.8668465 -0.05811595 0.4951767 -0.8668465 -0.01258057 0.499862 -0.8660137 0.0315665 0.4982303 -0.86647 0.113277 0.4874979 -0.8657449 0.1541399 0.4747286 -0.8665297 0.2652686 0.4233803 -0.8662458 0.3607368 0.3460396 -0.866098 0.4732831 0.1625149 -0.8657899 0.4732831 0.162515 -0.8657898 0.4732831 0.1625151 -0.8657898 0.4953327 0.05800253 -0.8667649 0.4953325 0.05800271 -0.866765 0.4953326 0.05800253 -0.8667649 0.4997867 0.01273185 -0.866055 0.4980257 -0.0339275 -0.8664984 0.4876839 -0.1129729 -0.8656799 0.4746588 -0.1540196 -0.8665893 0.4226005 -0.2665411 -0.8662359 0.3451702 -0.3613108 -0.8662055 0.1716316 -0.4695053 -0.8660874 0.04962426 -0.4964917 -0.8666219 0.0096758 -0.500528 -0.8656664 -0.0321151 -0.4974355 -0.8669064 -0.114169 -0.4872327 -0.865777 -0.1535208 -0.4749216 -0.8665339 -0.2662284 -0.4231922 -0.8660433 -0.3621807 -0.3448085 -0.8659864 -0.4669786 -0.1753845 -0.8667015 -0.4669786 -0.1753845 -0.8667014 -0.4669787 -0.1753845 -0.8667014 -0.4951176 -0.05839943 -0.8668611 -0.4951177 -0.05839961 -0.8668609 -0.4951177 -0.05839973 -0.866861 -0.4999333 -0.008442699 -0.8660229 -0.4972128 0.03155297 -0.8670548 0.08564376 0.2170147 -0.9724041 -0.2171135 0.08400803 -0.9725248 -0.2171135 0.08400809 -0.9725248 -0.2171136 0.08400809 -0.9725248 -0.08454358 -0.2170716 -0.9724878 0.2171466 -0.0829516 -0.972608 0.2342563 0.0534473 -0.9707046 0.348001 0.001674652 -0.9374927 0.2330179 0.03562819 -0.9718196 0.233018 0.03562819 -0.9718196 0.233018 0.03562831 -0.9718196 0.2957136 0.01352077 -0.9551811 0.2254155 -0.1320415 -0.9652735 0.226937 0.02551615 -0.9735752 0.2269369 0.02551615 -0.9735752 0.2269371 0.02551621 -0.9735752 0.1836822 -0.1075194 -0.9770877 0.1385648 -0.1141459 -0.9837534 0.1273422 -0.124127 -0.9840613 0.133125 -0.1171607 -0.98415 0.05494648 -0.2314367 -0.971297 9.71402e-4 -0.3476773 -0.9376137 0.03484863 -0.2294767 -0.9726902 0.03484857 -0.2294766 -0.9726902 0.03484857 -0.2294766 -0.9726902 0.01186656 -0.2954409 -0.9552873 -0.1321745 -0.2255744 -0.9652182 0.03531289 -0.2294123 -0.9726886 -0.1076279 -0.1837095 -0.9770706 -0.1142894 -0.1388816 -0.983692 -0.1243575 -0.1270145 -0.9840745 -0.1115499 -0.1378634 -0.9841496 -0.2296948 -0.05539387 -0.9716851 -0.3453456 -0.001999557 -0.9384735 -0.2329935 -0.0349881 -0.9718487 -0.2957543 -0.01322776 -0.9551725 -0.2957543 -0.0132277 -0.9551725 -0.2957541 -0.01322788 -0.9551725 -0.2261784 0.1309558 -0.965243 -0.2271216 -0.02383512 -0.9735748 -0.1831939 0.1060445 -0.9773406 -0.1394591 0.1127535 -0.9837875 -0.1278338 0.1233803 -0.9840914 -0.1352956 0.1143985 -0.9841789 -0.1352956 0.1143985 -0.984179 -0.1352956 0.1143985 -0.984179 -0.05523192 0.2343192 -0.9705895 -0.001690566 0.3480121 -0.9374886 -0.03671324 0.2275476 -0.9730747 -0.03671318 0.2275474 -0.9730747 -0.03671318 0.2275475 -0.9730747 -0.0129798 0.2961323 -0.9550588 0.1327629 0.2258272 -0.9650783 -0.04923892 0.2346928 -0.9708218 0.1074126 0.1827332 -0.9772775 0.1138177 0.13862 -0.9837836 0.1246165 0.1267996 -0.9840694 0.1082779 0.1406261 -0.9841241 -0.4998773 -0.009681999 -0.8660422 -0.4936952 0.02130758 -0.8693739 -0.4219369 0.01825946 -0.9064414 -0.4165217 0.06933915 -0.9064777 -0.3391624 0.05647146 -0.9390314 -0.3296555 0.09794723 -0.9390068 -0.4961098 -0.05136168 -0.8667393 -0.4921601 -0.0373007 -0.8697052 -0.4220463 -0.03194445 -0.9060114 -0.4228383 0.02010184 -0.9059822 -0.3433878 0.01630473 -0.9390522 -0.3391237 0.05648034 -0.9390448 -0.4821388 -0.1322107 -0.8660616 -0.4826811 -0.1295219 -0.8661656 -0.4859732 -0.08942955 -0.8693863 -0.4883605 -0.09668183 -0.8672696 -0.4146714 -0.08210927 -0.9062592 -0.4214476 -0.03287589 -0.9062567 -0.3422179 -0.02672302 -0.9392405 -0.3428278 0.01507902 -0.9392773 -0.468827 -0.1707797 -0.8666231 -0.4688701 -0.1545061 -0.8696487 -0.4013949 -0.1321801 -0.9063171 -0.414541 -0.08234387 -0.9062977 -0.3368628 -0.06681632 -0.9391801 -0.34239 -0.02636545 -0.939188 -0.4356398 -0.2452068 -0.8660783 -0.4367482 -0.2437393 -0.8659344 -0.4497075 -0.2083564 -0.8685337 -0.4498592 -0.2108044 -0.8678643 -0.3829619 -0.1794242 -0.9061717 -0.4018767 -0.1317852 -0.9061611 -0.3266905 -0.1071358 -0.9390396 -0.3374544 -0.06602001 -0.939024 -0.2729903 -0.05338245 -0.9605345 -0.2771408 -0.02135443 -0.960592 -0.2673967 -0.009720087 -0.9635375 -0.2675516 0.01173168 -0.9634721 -0.2836464 -0.005841016 -0.9589112 -0.2782707 0.0462864 -0.9593869 -0.2589757 0.06372046 -0.9637798 -0.2561371 0.0761249 -0.9636383 -0.2708324 0.06612092 -0.960353 -0.2701385 0.06813228 -0.9604079 -0.2457819 -0.09014183 -0.9651247 -0.2480426 -0.08158963 -0.9653073 -0.3264223 -0.1073545 -0.9391079 -0.3111533 -0.1457647 -0.9391147 -0.3829911 -0.1794636 -0.9061515 -0.3588225 -0.2238413 -0.9061686 -0.4189602 -0.2613075 -0.8695923 -0.3861629 -0.3123679 -0.8679312 -0.4121776 -0.2834523 -0.8658894 -0.4130616 -0.2819936 -0.8659444 -0.3628547 -0.3442881 -0.8659113 -0.3860465 -0.3125048 -0.8679338 -0.3282233 -0.2656552 -0.906475 -0.3575677 -0.2244281 -0.9065194 -0.2906938 -0.1825171 -0.9392468 -0.3103075 -0.1464754 -0.9392839 -0.2363479 -0.1115425 -0.9652451 -0.2485226 -0.08102446 -0.9652314 -0.1721306 -0.05608558 -0.9834762 -0.2202699 0.08332544 -0.9718735 -0.1592679 -0.08205914 -0.9838191 -0.1622306 -0.07565397 -0.9838485 -0.23725 -0.1107758 -0.965112 -0.2217695 -0.1390216 -0.965138 -0.2908599 -0.1823908 -0.9392199 -0.2671876 -0.2155531 -0.9392272 -0.3289025 -0.2654476 -0.9062896 -0.293866 -0.303712 -0.9063122 -0.3433033 -0.3547811 -0.8696397 -0.2968078 -0.3965321 -0.868716 -0.3312617 -0.3744841 -0.8660413 -0.3310812 -0.3748523 -0.865951 -0.2637119 -0.4248031 -0.8660244 -0.2637119 -0.4248032 -0.8660244 -0.2637119 -0.4248033 -0.8660244 -0.3010867 -0.3957649 -0.8675926 -0.2559579 -0.3364763 -0.9062392 -0.294279 -0.3036366 -0.9062035 -0.2391399 -0.2466892 -0.9391254 -0.26791 -0.2153186 -0.9390752 -0.2038062 -0.1637031 -0.9652276 -0.2209424 -0.1397075 -0.9652286 -0.1501215 -0.09491282 -0.9841012 -0.1591745 -0.07826972 -0.984143 -0.1609362 -0.08944499 -0.9829034 -0.1609362 -0.08944511 -0.9829034 -0.1609362 -0.08944505 -0.9829034 -0.1510075 -0.09402525 -0.9840509 -0.1384739 -0.1115766 -0.9840608 -0.2034344 -0.1639479 -0.9652645 -0.1818859 -0.18757 -0.9652642 -0.2391616 -0.2466765 -0.9391232 -0.207762 -0.2736422 -0.9391247 -0.2555413 -0.3365661 -0.9063234 -0.2123948 -0.3653855 -0.9063012 -0.2482461 -0.4270349 -0.8694913 -0.1899806 -0.4559724 -0.8694806 -0.2307292 -0.4436893 -0.86597 -0.2295445 -0.4443811 -0.8659301 -0.1460506 -0.4776821 -0.8663077 -0.1460506 -0.4776821 -0.8663077 -0.1460506 -0.4776823 -0.8663076 -0.1974107 -0.4567859 -0.867396 -0.1677312 -0.3880542 -0.9062452 -0.2128143 -0.3654017 -0.9061963 -0.1727674 -0.2966576 -0.9392262 -0.2068555 -0.2737961 -0.9392798 -0.1575757 -0.2086074 -0.9652217 -0.1821532 -0.1875408 -0.9652195 -0.1237117 -0.127326 -0.9841156 -0.1372241 -0.1125848 -0.984121 -0.1134431 -0.4874395 -0.8657561 -0.1395732 -0.4741173 -0.8693286 -0.1193949 -0.4055892 -0.9062242 -0.1677107 -0.3881445 -0.9062103 -0.136283 -0.3153752 -0.9391302 -0.1737586 -0.2965232 -0.9390857 -0.1321616 -0.2255389 -0.9652283 -0.15745 -0.2085795 -0.9652482 -0.1082291 -0.143439 -0.9837235 -0.1107057 -0.1387235 -0.984124 -0.07275575 -0.4932206 -0.8668564 -0.08170384 -0.4877598 -0.8691462 -0.0698294 -0.4169196 -0.9062572 -0.1192857 -0.4055272 -0.9062664 -0.0968948 -0.3294093 -0.9392023 -0.1357372 -0.3153806 -0.9392074 -0.1147876 -0.2667373 -0.9569091 -0.146102 -0.2093608 -0.9668621 0.009327054 -0.5003408 -0.8657784 -0.02221685 -0.4940986 -0.869122 -0.01898813 -0.4222203 -0.9062944 -0.06965881 -0.4167952 -0.9063274 -0.05660063 -0.3386939 -0.9391927 -0.09693455 -0.3294587 -0.9391809 0.05039089 -0.4965671 -0.8665345 0.03755122 -0.4929138 -0.8692675 0.03210014 -0.4214164 -0.906299 -0.01901078 -0.4222699 -0.9062708 -0.01543974 -0.3429915 -0.9392116 -0.05663996 -0.3387107 -0.9391842 0.1309635 -0.4828193 -0.8658719 0.1318543 -0.4827342 -0.8657842 0.09068506 -0.4859165 -0.8692879 0.09764796 -0.4882398 -0.8672295 0.08289009 -0.4144275 -0.9062998 0.03207123 -0.4214898 -0.9062659 0.02604615 -0.3422976 -0.9392306 -0.01546347 -0.3430427 -0.9391926 0.1716418 -0.469343 -0.8661733 0.1537293 -0.4693472 -0.869529 0.1316346 -0.4018517 -0.906194 0.08258551 -0.4147458 -0.906182 0.06704932 -0.3366967 -0.9392229 0.02595883 -0.3423941 -0.9391978 0.2450073 -0.4360858 -0.8659102 0.2469795 -0.4347149 -0.8660393 0.2069838 -0.4498481 -0.8687891 0.2115771 -0.4500495 -0.8675774 0.1797308 -0.3822744 -0.9064013 0.1322786 -0.4013389 -0.9063275 0.1074572 -0.325954 -0.9392588 0.0671457 -0.3366709 -0.9392253 0.05437177 -0.2725659 -0.9605996 0.02099424 -0.2769299 -0.9606608 0.009111821 -0.2668657 -0.9636906 -0.01203733 -0.2669288 -0.9636411 0.007220387 -0.2846042 -0.9586179 -0.04665648 -0.2790132 -0.9591532 -0.06460285 -0.2591008 -0.9636874 -0.0755003 -0.256514 -0.9635872 -0.06597357 -0.2705857 -0.9604327 -0.06630462 -0.2704926 -0.9604362 0.09063434 -0.24609 -0.9650002 0.0812878 -0.2485876 -0.9651924 0.1068058 -0.3266072 -0.9391061 0.1460098 -0.311026 -0.9391188 0.1795911 -0.382534 -0.9063194 0.2239792 -0.3583943 -0.9063041 0.2615966 -0.4185183 -0.8697183 0.3119878 -0.3861432 -0.8680767 0.2820169 -0.4129756 -0.8659779 0.282017 -0.4129756 -0.8659779 0.282017 -0.4129755 -0.865978 0.2821057 -0.4126952 -0.8660826 0.3443781 -0.3619384 -0.8662589 0.3443781 -0.3619384 -0.8662589 0.3443781 -0.3619384 -0.8662588 0.3122428 -0.3855898 -0.8682309 0.2658885 -0.3283616 -0.9063565 0.2240653 -0.3582325 -0.9063467 0.1822379 -0.2913525 -0.9390969 0.1460943 -0.3110709 -0.9390907 0.111162 -0.23667 -0.9652101 0.08143323 -0.2484492 -0.9652159 0.05569326 -0.1699376 -0.9838798 -0.08441793 -0.218318 -0.9722197 0.08195525 -0.1595561 -0.9837812 0.07611626 -0.1622528 -0.9838091 0.1110678 -0.2366883 -0.9652163 0.1391901 -0.2214145 -0.9651952 0.1827164 -0.2906644 -0.9392172 0.2156747 -0.2671638 -0.939206 0.2655849 -0.3290276 -0.9062039 0.3032062 -0.2947002 -0.9062107 0.3541624 -0.3441902 -0.8695414 0.3967806 -0.296039 -0.8688648 0.3714765 -0.3356329 -0.8656533 0.3754503 -0.3312703 -0.8656195 0.4237481 -0.2651441 -0.866104 0.3960936 -0.3004127 -0.8676763 0.3366909 -0.2552895 -0.906348 0.3033201 -0.2942455 -0.9063203 0.2463505 -0.2389131 -0.9392721 0.2157714 -0.2669532 -0.9392437 0.1644806 -0.203437 -0.9651733 0.1390642 -0.2215899 -0.9651731 0.09445357 -0.1504766 -0.9840911 0.07882231 -0.1589645 -0.9841328 0.08187085 -0.1598911 -0.9837337 0.09431988 -0.1506299 -0.9840805 0.1117628 -0.1382034 -0.9840778 0.1645079 -0.2033945 -0.9651776 0.1878398 -0.1821109 -0.9651693 0.2464146 -0.2389432 -0.9392477 0.2731235 -0.2076561 -0.9392989 0.3366003 -0.2559707 -0.9061894 0.3653382 -0.2129411 -0.9061922 0.4265064 -0.2486407 -0.8696379 0.4563177 -0.1900035 -0.8692945 0.4443896 -0.2297682 -0.8658664 0.4450817 -0.2282884 -0.8659023 0.4765227 -0.1481825 -0.8665842 0.4765227 -0.1481825 -0.8665842 0.4765228 -0.1481825 -0.8665842 0.4570537 -0.1969023 -0.8673705 0.3881433 -0.1672485 -0.9062962 0.3653857 -0.2123534 -0.9063109 0.2969287 -0.1725215 -0.9391857 0.2729846 -0.2085828 -0.939134 0.2077749 -0.1587008 -0.965217 0.1879597 -0.1818493 -0.9651954 0.1276437 -0.1234547 -0.9841068 0.1121511 -0.1377547 -0.9840965 0.4875331 -0.1134778 -0.8656987 0.4738549 -0.1403423 -0.8693479 0.4056989 -0.1201855 -0.9060707 0.3882311 -0.1683096 -0.9060622 0.315347 -0.1367022 -0.9390788 0.2968829 -0.1733386 -0.9390497 0.2254782 -0.1316379 -0.965314 0.2081516 -0.1577222 -0.9652962 0.1429588 -0.1083618 -0.9837787 0.1400931 -0.1097891 -0.9840327 0.4939616 -0.0722385 -0.8664776 0.4881348 -0.081891 -0.8689179 0.4166918 -0.06987488 -0.9063583 0.4054009 -0.1188846 -0.9063755 0.3293831 -0.0965498 -0.939247 0.3153596 -0.1355087 -0.9392474 0.2668582 -0.114638 -0.9568934 0.2092019 -0.1462952 -0.9668673 0.4998773 0.009681999 -0.8660422 0.493685 -0.02131515 -0.8693796 0.4219233 -0.01832681 -0.9064463 0.4165585 -0.069377 -0.9064579 0.3383691 -0.0564019 -0.9393217 0.3293402 -0.09599053 -0.9393194 0.4964455 0.04892259 -0.8666883 0.4931913 0.03733783 -0.8691192 0.4220555 0.03190988 -0.9060083 0.4228497 -0.02010172 -0.9059769 0.3433742 -0.01630353 -0.9390572 0.3389153 -0.05843126 -0.9390007 0.4832422 0.1318027 -0.8655086 0.4821973 0.1351999 -0.8655673 0.4858714 0.08953624 -0.8694322 0.4884007 0.09700238 -0.8672112 0.41463 0.08231478 -0.9062596 0.4214255 0.03293365 -0.9062649 0.3421763 0.02674555 -0.9392551 0.3428726 -0.01503521 -0.9392617 0.4697658 0.1718985 -0.8658932 0.4698025 0.1542257 -0.8691951 0.401739 0.1319047 -0.9062048 0.4147463 0.08216995 -0.9062195 0.3368605 0.0667386 -0.9391864 0.3424255 0.02632111 -0.9391763 0.4341424 0.2480536 -0.8660195 0.4362967 0.2443242 -0.8659971 0.4497056 0.2080455 -0.8686092 0.4498857 0.2114873 -0.8676843 0.3825638 0.1798065 -0.9062641 0.4016149 0.1320589 -0.9062373 0.3257876 0.1070569 -0.9393622 0.3361863 0.06766861 -0.9393613 0.272826 0.05489879 -0.9604958 0.2771353 0.02129566 -0.9605948 0.2661248 0.008211553 -0.9639037 0.266277 -0.01167637 -0.9638258 0.2838192 0.007651507 -0.9588473 0.2780873 -0.04784554 -0.9593635 0.2603502 -0.06382739 -0.9634022 0.2577993 -0.07515329 -0.9632713 0.2709055 -0.0661652 -0.9603294 0.270379 -0.0680285 -0.9603475 0.2459854 0.09150338 -0.9649448 0.2485923 0.08196121 -0.9651343 0.3256224 0.1073268 -0.9393886 0.3104233 0.1455561 -0.9393885 0.3829188 0.1795958 -0.906156 0.3583028 0.2247085 -0.9061596 0.4187754 0.262623 -0.8692851 0.3858411 0.3117561 -0.8682942 0.4110623 0.2836468 -0.8663559 0.4141218 0.2790284 -0.8663985 0.3631984 0.3437219 -0.865992 0.3866227 0.3114747 -0.8680475 0.3292708 0.2652001 -0.9062283 0.3581942 0.2247825 -0.9061843 0.2909728 0.1825618 -0.9391518 0.3115772 0.1445507 -0.9391618 0.2376838 0.1102336 -0.9650674 0.2492092 0.08105301 -0.965052 0.1683773 0.05482494 -0.9841969 0.2156092 -0.08276695 -0.9729658 0.1591948 0.0819233 -0.9838423 0.1615722 0.07673263 -0.9838733 0.2359409 0.1120816 -0.9652822 0.2210841 0.1392281 -0.9652654 0.2904446 0.1829289 -0.9392438 0.2673127 0.2153238 -0.9392442 0.3292533 0.2652743 -0.9062129 0.294359 0.303457 -0.9062376 0.3441539 0.354821 -0.8692873 0.2979575 0.3965708 -0.8683046 0.3312435 0.3752626 -0.8657111 0.331956 0.374728 -0.8656699 0.26343 0.4246278 -0.8661963 0.2634301 0.424628 -0.8661962 0.2634299 0.4246281 -0.866196 0.2998504 0.3961427 -0.8678483 0.2551153 0.3371619 -0.9062219 0.2943505 0.3034473 -0.9062438 0.2387278 0.2461541 -0.9393707 0.2664141 0.2158103 -0.9393878 0.2033337 0.1646913 -0.9651592 0.2218362 0.1386637 -0.9651742 0.1508192 0.09432792 -0.9840508 0.1593977 0.07852852 -0.9840862 0.1585082 0.07438832 -0.9845515 0.150991 0.09404069 -0.9840519 0.1385151 0.1115903 -0.9840534 0.2038996 0.1643034 -0.9651058 0.1822569 0.1879586 -0.9651187 0.2386497 0.2461486 -0.939392 0.2076089 0.2728239 -0.9393965 0.2563514 0.3369119 -0.9059661 0.2132912 0.3656203 -0.905996 0.2490384 0.4268473 -0.8693568 0.1901307 0.4563633 -0.8692426 0.2283356 0.4449663 -0.8659491 0.2309918 0.4435905 -0.8659506 0.148855 0.4765092 -0.8664764 0.148855 0.4765092 -0.8664764 0.1488551 0.4765094 -0.8664762 0.1971887 0.4571025 -0.8672796 0.1674484 0.3881691 -0.9062482 0.2120774 0.3656406 -0.9062727 0.1719084 0.2964501 -0.9394493 0.2070685 0.2729545 -0.9394779 0.1581969 0.2085533 -0.9651317 0.1820981 0.1880968 -0.9651218 0.1234647 0.1275085 -0.984123 0.1367762 0.1129202 -0.9841451 0.1134782 0.4875904 -0.8656663 0.1402149 0.4738621 -0.8693645 0.1200604 0.4057391 -0.9060692 0.1684867 0.3882789 -0.9060087 0.136512 0.314556 -0.9393716 0.1725623 0.2962918 -0.9393793 0.1316322 0.226077 -0.9651748 0.157559 0.2087345 -0.965197 0.107981 0.1431185 -0.9837974 0.1099535 0.1393151 -0.9841248 0.0721746 0.4940009 -0.8664606 0.08193939 0.4880569 -0.8689571 0.06995803 0.4166679 -0.9063629 0.1187354 0.4055401 -0.9063329 0.09646898 0.3294288 -0.9392393 0.1375146 0.3146322 -0.9391998 0.116456 0.2664288 -0.9567935 0.1477786 0.2090303 -0.9666788 -0.004931747 0.4999231 -0.8660557 0.02135396 0.4947067 -0.8687976 0.01821267 0.4219402 -0.9064407 0.06941372 0.4165284 -0.906469 0.05639934 0.3384606 -0.9392889 0.0959835 0.3293459 -0.9393181 -0.0489223 0.4964596 -0.8666802 -0.03739869 0.4931508 -0.8691396 -0.03193569 0.4211024 -0.9064508 0.01826393 0.4219946 -0.9064144 0.01483637 0.3427432 -0.939312 0.05639338 0.338407 -0.9393085 -0.1327215 0.482852 -0.865586 -0.1352812 0.4822072 -0.865549 -0.08913844 0.4859578 -0.8694248 -0.09662216 0.4884625 -0.8672189 -0.08202582 0.4146907 -0.906258 -0.03116583 0.4216993 -0.9062001 -0.02535355 0.3429559 -0.9390093 0.01690226 0.3436224 -0.9389559 -0.1708125 0.4698182 -0.8660797 -0.1548191 0.4698179 -0.8690813 -0.1322702 0.4014297 -0.9062885 -0.08217489 0.4144768 -0.9063423 -0.06677281 0.33682 -0.9391985 -0.02648341 0.3424236 -0.9391724 -0.2480564 0.4341699 -0.866005 -0.2409963 0.4379574 -0.8660913 -0.2091234 0.4497658 -0.8683192 -0.2106356 0.4498425 -0.8679139 -0.1792399 0.3828427 -0.9062586 -0.1320346 0.4015836 -0.9062547 -0.1070953 0.3258001 -0.9393535 -0.06761246 0.3362087 -0.9393574 -0.0548616 0.2728269 -0.9604977 -0.02143067 0.2771741 -0.9605808 -0.008215963 0.266071 -0.9639185 0.01309859 0.2662405 -0.9638177 -0.007508039 0.2851419 -0.958456 0.04657435 0.2795068 -0.9590134 0.06538176 0.2586028 -0.9637686 0.07473731 0.2564038 -0.963676 0.06455683 0.2713507 -0.9603131 0.06800866 0.2702781 -0.9603773 -0.09199833 0.2459348 -0.9649106 -0.08147513 0.2486525 -0.96516 -0.1068221 0.3260256 -0.9393063 -0.1463556 0.310418 -0.9392661 -0.1799819 0.3817004 -0.9065933 -0.2250123 0.3573514 -0.9064599 -0.2632829 0.4180231 -0.8694475 -0.3124736 0.3843944 -0.8686779 -0.2791724 0.4141664 -0.8663309 -0.280398 0.4131935 -0.8663995 -0.3435223 0.3630363 -0.8661392 -0.3115743 0.3863661 -0.868126 -0.265772 0.3295654 -0.9059536 -0.2237542 0.35943 -0.9059494 -0.1816262 0.2918031 -0.9390755 -0.1453862 0.3115779 -0.9390325 -0.1104883 0.2367032 -0.9652792 -0.08260399 0.2478678 -0.9652658 -0.05598986 0.1679885 -0.9841977 0.08569449 0.2163882 -0.9725393 0.08569449 0.2163881 -0.9725393 0.08569449 0.2163881 -0.9725393 -0.08282405 0.1596914 -0.9836865 -0.07599091 0.1629087 -0.9837105 -0.1104697 0.23684 -0.9652479 -0.1385902 0.2214006 -0.9652847 -0.1821087 0.2909373 -0.9392508 -0.217029 0.2661222 -0.9391899 -0.2668161 0.3271229 -0.9065318 -0.3030278 0.2938916 -0.906533 -0.3548403 0.3441318 -0.869288 -0.3968462 0.2959366 -0.8688698 -0.3748742 0.3307008 -0.8660868 -0.3724908 0.3333506 -0.8660994 -0.4245598 0.26332 -0.866263 -0.3962112 0.2998865 -0.8678046 -0.3370981 0.2550835 -0.9062547 -0.3026371 0.2952854 -0.9062104 -0.2461482 0.240195 -0.9389981 -0.216437 0.2672618 -0.9390028 -0.1644533 0.203044 -0.9652608 -0.1384844 0.2215751 -0.9652599 -0.09426856 0.1508039 -0.9840587 -0.07917737 0.1590913 -0.9840838 -0.07957255 0.1593413 -0.9840115 -0.09543526 0.1496363 -0.9841246 -0.1113944 0.138276 -0.9841093 -0.1640602 0.2036399 -0.965202 -0.1876782 0.181919 -0.965237 -0.2465493 0.2389919 -0.9391998 -0.273916 0.2072522 -0.9391575 -0.3371294 0.2551333 -0.9062289 -0.3652446 0.2130585 -0.9062023 -0.4261754 0.2485878 -0.8698154 -0.4563454 0.1901116 -0.8692562 -0.4449544 0.2285282 -0.8659044 -0.4450829 0.2280348 -0.8659685 -0.4662202 0.1746426 -0.8672594 -0.4571303 0.1971704 -0.8672692 -0.3881543 0.1674551 -0.9062533 -0.365233 0.2128915 -0.9062463 -0.2968848 0.1730451 -0.9391032 -0.2738233 0.2077783 -0.9390682 -0.208226 0.1579794 -0.9652381 -0.1877296 0.1818868 -0.965233 -0.127676 0.1237242 -0.9840687 -0.1107995 0.1389865 -0.9840763 -0.4874206 0.1133569 -0.865778 -0.473886 0.1402559 -0.8693448 -0.4057881 0.1200768 -0.906045 -0.3882272 0.1684686 -0.9060342 -0.3152107 0.1367717 -0.9391143 -0.2968982 0.1729061 -0.9391246 -0.2260445 0.1316326 -0.9651823 -0.2081123 0.1585219 -0.9651736 -0.1425694 0.1085888 -0.9838102 -0.1392384 0.1103606 -0.9840901 -0.4926978 0.07425743 -0.8670265 -0.4880413 0.08193558 -0.8689662 -0.4167145 0.06999111 -0.906339 -0.4054986 0.1186836 -0.9063582 -0.3294485 0.09647923 -0.9392313 -0.31515 0.1358557 -0.9392678 -0.2665351 0.1149099 -0.9569508 -0.2091601 0.1465305 -0.9668408 -0.1075051 -0.9942035 -0.001439213 -0.1023221 -0.9947502 0.001565814 -0.1050083 -0.9944713 -2.37268e-4 -0.1049621 -0.9944762 3.4005e-4 -0.1043151 -0.9945429 0.00167036 -0.104187 -0.9945561 0.001796007 -0.1067075 -0.9942768 -0.005205392 -0.1067075 -0.9942768 -0.005205392 -0.1067075 -0.9942768 -0.005205392 -0.1044486 -0.9945276 0.002366662 -0.1044486 -0.9945275 0.00236684 -0.1044486 -0.9945276 0.002366781 0.9261364 -0.3706762 -0.06979024 0.9261363 -0.3706763 -0.06979024 0.9261363 -0.3706764 -0.06979024 0.8771116 -0.475187 -0.06980443 0.8771116 -0.475187 -0.06980443 0.8771115 -0.475187 -0.06980443 0.8660084 -0.494993 -0.07079339 0.8660089 -0.4949917 -0.07079339 0.8660072 -0.4949948 -0.07079321 0.9903881 -0.1162989 -0.07487308 0.9903875 -0.1163041 -0.07487273 0.9903879 -0.1163017 -0.07487261 0.9670309 -0.2449311 -0.06971538 0.9670309 -0.244931 -0.06971538 0.9670309 -0.2449311 -0.06971538 0.9365968 -0.343403 -0.06972038 0.9279968 -0.3661214 -0.06911689 0.9360619 -0.3449753 -0.06913965 -0.8172127 -0.3647142 -0.4462588 -0.8194922 -0.3587862 -0.4468837 -0.8192962 -0.3592603 -0.4468623 -0.8195415 -0.3657038 -0.4411491 -0.817839 -0.3638086 -0.4458504 -0.8139482 -0.3708028 -0.4472066 -0.813948 -0.3708032 -0.4472066 -0.813948 -0.3708029 -0.4472066 -0.8173465 -0.3645301 -0.4461641 -0.8187851 -0.3615314 -0.4459666 -0.8181728 -0.3629219 -0.4459608 -0.817434 -0.3646347 -0.4459183 -0.817434 -0.3646348 -0.4459183 -0.8174341 -0.3646347 -0.4459183 -0.8171713 -0.3652629 -0.4458859 -0.8768869 -0.4806519 0.006571054 -0.8571106 -0.5151326 0 -0.8102141 -0.5861342 0 -0.7862833 -0.6178311 0.006595134 -0.7610589 -0.6486829 0 -0.7028467 -0.7113415 0 -0.672774 -0.7398163 0.006863892 -0.641416 -0.7671934 0 -0.5783244 -0.8158069 0 -0.5431839 -0.8395841 0.007063806 -0.5067918 -0.8620685 0 -0.4351289 -0.9003682 0 -0.3972631 -0.9176788 0.006912708 -0.3586719 -0.9334638 0 -0.2810282 -0.9596995 0 -0.2400036 -0.9707466 0.007023513 -0.1986098 -0.9800788 0 -0.1213659 -0.9926079 0 -0.07784879 -0.9969391 0.007221698 -0.03447717 -0.9994055 0 0.0432766 -0.9990632 0 0.08662563 -0.996215 0.007192671 0.1298798 -0.9915298 0 0.2110133 -0.9774832 0 0.2506368 -0.9680576 0.006765723 0.2901685 -0.9569756 0 0.3676856 -0.9299502 0 0.4061124 -0.913797 0.006910383 0.4437718 -0.8961399 0 0.5150824 -0.8571407 0 0.5522233 -0.8336647 0.007254838 0.5881322 -0.8087649 0 0.6486873 -0.7610552 0 0.6794815 -0.7336608 0.006838023 0.7093286 -0.704878 0 0.766789 -0.6418992 0 0.7929118 -0.609297 0.006939649 0.8177959 -0.5755084 0 0.8601498 -0.5100416 0 0.8811174 -0.4728453 0.007054865 0.9003211 -0.4352264 0 0.9334151 -0.3587983 0 0.9473761 -0.3200504 0.006798207 0.9596819 -0.2810885 0 0.9799308 -0.199338 0 0.9873951 -0.1581228 0.006943821 0.9931755 -0.1166307 0 0.9992414 -0.03894531 0 0.9999647 0.004411041 0.007163405 0.9988771 0.04737776 0 0.9915222 0.129938 0 0.9856215 0.168842 0.006536126 0.9781661 0.2078254 0 0.9573243 0.2890158 0 0.9444684 0.3285298 0.006913781 0.9299795 0.3676113 0 0.8953005 0.445463 0 0.8764736 0.4814032 0.006709218 0.8563491 0.5163975 0 0.8107862 0.5853424 0 0.7865099 0.617542 0.006654739 0.7611479 0.6485785 0 0.7027568 0.7114301 0 0.6739547 0.7387432 0.00660634 0.6439522 0.7650658 0 0.5755308 0.8177802 0 0.5421586 0.84025 0.006650924 0.5081036 0.8612959 0 0.4332934 0.901253 0 0.3962652 0.9181116 0.006718575 0.3586997 0.933453 0 0.2810282 0.9596995 0 0.2420154 0.9702493 0.006698429 0.2027449 0.9792316 0 0.1165963 0.9931795 0 0.07785624 0.9969437 0.006450593 0.03893333 0.9992418 0 -0.04758524 0.9988672 0 -0.08877897 0.996028 0.006825327 -0.1298798 0.9915298 0 -0.2068637 0.9783698 0 -0.2486345 0.9685713 0.007119178 -0.2901183 0.9569908 0 -0.3714115 0.9284684 0 -0.4061141 0.9138009 0.006263256 -0.4403073 0.8978471 0 -0.5183266 0.8551828 0 -0.551189 0.8343555 0.006452918 -0.5832446 0.8122968 0 -0.6511963 0.7589094 0 -0.6817658 0.7315388 0.006816685 -0.7113887 0.7027989 0 -0.7650082 0.6440207 0 -0.7911061 0.6116404 0.006875157 -0.8157587 0.5783925 0 -0.8631578 0.5049343 0 -0.8819832 0.4712376 0.006402909 -0.8995664 0.4367843 0 -0.9334151 0.3587983 0 -0.9473762 0.3200505 0.006789803 -0.9596819 0.2810885 0 -0.9801005 0.1985022 0 -0.9871124 0.1598955 0.006532192 -0.9926661 0.1208884 0 -0.9994005 0.03462249 0 -0.9999558 -0.006495416 0.006801962 -0.9988674 -0.04758203 0 -0.9921392 -0.1251394 0 -0.9856632 -0.1685668 0.007301867 -0.9772793 -0.2119557 0 -0.9570571 -0.2898996 0 -0.9570571 -0.2898996 1.60835e-7 -0.9570571 -0.2898996 0 -0.9444961 -0.328455 0.006677627 -0.9305596 -0.3661404 0 -0.8953005 -0.445463 0 -0.5390655 -0.3895634 -0.7467589 -0.5650426 -0.3632122 -0.7408129 -0.5650427 -0.3632116 -0.7408131 -0.5650428 -0.3632114 -0.7408132 -0.5084216 -0.4357606 -0.7427114 -0.507866 -0.4339696 -0.7441388 -0.4683418 -0.4762059 -0.7442337 -0.4685392 -0.4745433 -0.7451709 -0.4748945 -0.4748479 -0.7409418 -0.4300841 -0.5159278 -0.7408416 -0.4294927 -0.5119192 -0.7439589 -0.431964 -0.5110352 -0.7431353 -0.3856911 -0.5466296 -0.7432622 -0.385423 -0.5442493 -0.7451455 -0.3401752 -0.5732355 -0.7454408 -0.3390876 -0.5750626 -0.7445285 -0.3399952 -0.575269 -0.7439549 -0.2895335 -0.6027433 -0.7435529 -0.2863958 -0.600389 -0.7466663 -0.3000234 -0.5997024 -0.7418511 -0.240176 -0.6263067 -0.7416573 -0.2402766 -0.6259325 -0.7419404 -0.1842921 -0.6449296 -0.7416889 -0.1883928 -0.6416152 -0.7435308 -0.1890603 -0.6421726 -0.7428799 -0.1329865 -0.6560341 -0.7429226 -0.1364419 -0.6601357 -0.7386505 -0.1275473 -0.6571528 -0.7428876 -0.0819385 -0.6645768 -0.7427138 -0.08024942 -0.6687303 -0.7391616 -0.01976907 -0.6733227 -0.7390844 -0.01976895 -0.673323 -0.7390841 -0.01976901 -0.673323 -0.7390841 -0.02672696 -0.6708919 -0.7410734 -0.02500736 -0.6685051 -0.743287 0.03237581 -0.6683784 -0.7431166 0.03418284 -0.6646528 -0.74637 0.03139621 -0.6667076 -0.7446579 0.08465743 -0.6621544 -0.7445701 0.08596307 -0.6638182 -0.7429373 0.1535304 -0.6520902 -0.7424331 0.1382415 -0.6530491 -0.7445914 0.1379544 -0.6537234 -0.7440528 0.1943916 -0.6390795 -0.7441703 0.195096 -0.6354963 -0.7470489 0.1946684 -0.6361038 -0.7466433 0.2445419 -0.6187734 -0.7465378 0.2490428 -0.6226659 -0.7417984 0.2975208 -0.6010215 -0.7417914 0.2952814 -0.5995321 -0.7438886 0.3448644 -0.5725438 -0.743816 0.343396 -0.5722921 -0.7446885 0.3430733 -0.5735185 -0.7438933 0.3909558 -0.5421664 -0.7437804 0.3953886 -0.5440624 -0.7400433 0.39125 -0.5482336 -0.7391641 0.39125 -0.5482336 -0.739164 0.39125 -0.5482336 -0.739164 0.4382252 -0.5114409 -0.7391799 0.4382252 -0.5114409 -0.7391799 0.4382252 -0.5114409 -0.7391799 0.436267 -0.510544 -0.7409562 0.4748759 -0.4747415 -0.741022 0.4774278 -0.4744964 -0.7395377 0.4768754 -0.4671736 -0.7445393 0.5095382 -0.4311115 -0.7446569 0.5145783 -0.4317023 -0.740839 0.5198885 -0.4194968 -0.744136 0.5198885 -0.4194968 -0.744136 0.5198885 -0.4194968 -0.7441361 0.5451807 -0.3855261 -0.7444109 0.5493343 -0.3860466 -0.7410803 0.5815929 -0.3355952 -0.7410301 0.5815929 -0.3355952 -0.7410302 0.5815928 -0.3355952 -0.7410302 0.5750443 -0.3391449 -0.7445166 0.5766374 -0.3433647 -0.7413434 0.6034514 -0.2928801 -0.7416654 0.6003381 -0.2884165 -0.745929 0.600126 -0.2934648 -0.7441285 0.6226133 -0.2406923 -0.7445937 0.6259346 -0.2401617 -0.741976 0.6450525 -0.1844071 -0.7415533 0.6415682 -0.1884228 -0.7435639 0.6421324 -0.1892955 -0.7428548 0.6421323 -0.1892955 -0.7428548 0.6421324 -0.1892955 -0.7428548 0.6560268 -0.1329938 -0.7429277 0.6532877 -0.1306838 -0.7457459 0.6562649 -0.1389607 -0.7416241 0.6656398 -0.07872956 -0.7421088 0.6633345 -0.07964891 -0.7440722 0.6678239 -0.01944988 -0.7440653 0.6678239 -0.01944983 -0.7440653 0.6678238 -0.01945006 -0.7440653 0.6664612 -0.0236786 -0.7451636 0.6684737 -0.02503454 -0.7433143 0.6684548 0.02951157 -0.7431671 0.6683123 0.02937227 -0.7433007 0.6668499 0.03125911 -0.7445362 0.6621461 0.08460497 -0.7445835 0.6639438 0.08573114 -0.7428518 0.663944 0.08573114 -0.7428518 0.6639438 0.08573114 -0.7428517 0.6503172 0.1629543 -0.7419795 0.6503172 0.1629546 -0.7419794 0.6503173 0.162954 -0.7419795 0.6516468 0.1408822 -0.7453246 0.6531296 0.1404712 -0.7441033 0.6390943 0.194333 -0.7441728 0.6465548 0.1929478 -0.7380638 0.6410499 0.1962806 -0.7419764 0.623565 0.2464464 -0.7419103 0.6237794 0.246397 -0.7417465 0.601118 0.2975748 -0.7416917 0.5996288 0.2953857 -0.7437692 0.5725613 0.3448895 -0.7437908 0.5727364 0.3453239 -0.7434545 0.5721138 0.3455756 -0.7438168 0.5416303 0.3916118 -0.7438259 0.5417116 0.3914716 -0.7438405 0.5444067 0.3888468 -0.7432494 0.5444067 0.3888463 -0.7432497 0.5444066 0.3888455 -0.74325 0.5095128 0.4336649 -0.7431901 0.5106087 0.4364125 -0.7408259 0.4711028 0.4790133 -0.7406811 0.4717732 0.4747437 -0.7429997 0.4696135 0.4745427 -0.7444948 0.4272914 0.5127174 -0.7446764 0.4273262 0.5128493 -0.7445656 0.4321203 0.5104518 -0.7434455 0.3877342 0.5452487 -0.7432134 0.3880095 0.5479017 -0.7411157 0.3352448 0.5819506 -0.7409079 0.3391022 0.5749606 -0.7446007 0.3399842 0.5754997 -0.7437814 0.2918606 0.6013195 -0.7437958 0.2903155 0.6001555 -0.7453391 0.2869926 0.6006708 -0.7462103 0.2383723 0.6214975 -0.7462705 0.2381079 0.6232566 -0.7448865 0.1952478 0.6377807 -0.7450599 0.1894788 0.6423889 -0.7425863 0.1890603 0.6421726 -0.7428799 0.1329787 0.6560849 -0.742879 0.1306574 0.653176 -0.7458484 0.1369317 0.6552052 -0.7429374 0.07894295 0.664971 -0.7426854 0.07961553 0.6633591 -0.7440539 0.01979744 0.6676948 -0.7441719 0.01979738 0.6676949 -0.7441718 0.01979738 0.6676949 -0.7441718 0.02349513 0.6663284 -0.7452882 0.02501761 0.6688866 -0.7429434 -0.02955472 0.6680412 -0.7435372 -0.02947592 0.6684282 -0.7431924 -0.03139865 0.666759 -0.7446117 -0.08465743 0.6621544 -0.7445701 -0.0854935 0.6632172 -0.743528 -0.1532666 0.6509699 -0.74347 -0.14151 0.6515629 -0.745279 -0.1410757 0.653096 -0.7440184 -0.1943659 0.638995 -0.7442496 -0.1928221 0.646353 -0.7382734 -0.1962349 0.6412225 -0.7418394 -0.2463802 0.623623 -0.7418836 -0.2448028 0.6222583 -0.7435497 -0.2963744 0.5987972 -0.7440458 -0.2988302 0.6005294 -0.7416637 -0.3457558 0.5743973 -0.7419708 -0.3464354 0.574361 -0.7416819 -0.3454416 0.5776307 -0.7396032 -0.3957677 0.5442008 -0.7397388 -0.3879777 0.5408327 -0.7463065 -0.3870692 0.5417079 -0.7461435 -0.3870692 0.5417081 -0.7461434 -0.3870691 0.5417076 -0.7461437 -0.4313313 0.5067121 -0.7464557 -0.4340082 0.5078083 -0.7441557 -0.4761862 0.4684108 -0.744203 -0.4744474 0.4684511 -0.7452874 -0.4745285 0.4697476 -0.7444192 -0.511795 0.4294556 -0.7440657 -0.5118437 0.4295647 -0.7439692 -0.5109695 0.4318355 -0.7432553 -0.5465915 0.3856379 -0.7433177 -0.5493343 0.3860466 -0.7410803 -0.577349 0.3426469 -0.7411217 -0.5765286 0.3428894 -0.741648 -0.5730984 0.334478 -0.7481194 -0.5981044 0.2872654 -0.7481643 -0.6003505 0.2901818 -0.7452341 -0.5999106 0.2999861 -0.7416979 -0.6263537 0.2402805 -0.7415837 -0.6280301 0.2399197 -0.7402815 -0.6463755 0.1847782 -0.7403078 -0.6425221 0.1894831 -0.74247 -0.6421325 0.1890723 -0.7429116 -0.6559833 0.1329849 -0.7429677 -0.6600875 0.1364278 -0.7386962 -0.6571792 0.1276085 -0.7428538 -0.6649445 0.07891345 -0.7427123 -0.6633345 0.07964891 -0.7440722 -0.6664459 0.03905582 -0.7445299 -0.6710125 0.02659064 -0.7409691 -0.6684346 0.02487277 -0.743355 -0.6684345 0.02487283 -0.743355 -0.6684345 0.02487283 -0.743355 -0.6681186 -0.03248232 -0.7433455 -0.6645548 -0.03422057 -0.7464556 -0.6667323 -0.03125363 -0.7446417 -0.6620459 -0.08477473 -0.7446534 -0.6632716 -0.08551543 -0.743477 -0.6510382 -0.1529991 -0.7434652 -0.6510384 -0.1529993 -0.743465 -0.6510384 -0.1529992 -0.7434651 -0.6517075 -0.1415304 -0.7451487 -0.6529257 -0.1411356 -0.7441564 -0.6398879 -0.1916437 -0.7441883 -0.6413612 -0.1913668 -0.7429903 -0.6413611 -0.1913668 -0.7429904 -0.6360882 -0.1946493 -0.7466616 -0.6360883 -0.1946492 -0.7466616 -0.6360882 -0.1946491 -0.7466617 -0.619146 -0.2434214 -0.7465952 -0.6230885 -0.2479797 -0.7417998 -0.6010935 -0.297471 -0.7417531 -0.5995733 -0.2954475 -0.7437894 -0.5709368 -0.3476581 -0.7437506 -0.5703135 -0.3439451 -0.745952 -0.5736511 -0.3431105 -0.7437739 -0.5405893 -0.3932278 -0.7437306 -0.814231 -0.3233597 -0.4821478 -0.7861075 -0.3873237 -0.4816797 -0.7863306 -0.3874854 -0.4811853 -0.7505216 -0.4527232 -0.4814137 -0.7508779 -0.4535813 -0.4800483 -0.7109382 -0.51381 -0.480173 -0.710722 -0.5130214 -0.4813351 -0.6662566 -0.5693692 -0.4815818 -0.6664824 -0.5707642 -0.4796139 -0.6167025 -0.6245745 -0.4791501 -0.6167034 -0.6243394 -0.4794551 -0.5640726 -0.6724389 -0.479216 -0.5640726 -0.672439 -0.479216 -0.5640727 -0.6724389 -0.479216 -0.5639981 -0.6707988 -0.4815964 -0.5066255 -0.7155241 -0.4809947 -0.5065777 -0.7159824 -0.4803627 -0.4457068 -0.7556909 -0.4798718 -0.4458684 -0.7545163 -0.4815669 -0.3796058 -0.7902776 -0.4809998 -0.37973 -0.7897707 -0.4817339 -0.3140082 -0.8179796 -0.4819838 -0.3148175 -0.8154852 -0.4856684 -0.2461115 -0.838358 -0.4864 -0.2448065 -0.8415836 -0.4814634 -0.1741628 -0.8591653 -0.4811468 -0.1746715 -0.858179 -0.4827202 -0.1043412 -0.8695284 -0.4827351 -0.1064304 -0.8663878 -0.4878984 -0.0347343 -0.8722764 -0.487778 -0.03039008 -0.8780099 -0.4776766 0.04249066 -0.8772932 -0.4780704 0.03809344 -0.8724129 -0.4872829 0.1121806 -0.8663356 -0.4867014 0.1136507 -0.8676475 -0.4840158 0.1812024 -0.8558304 -0.4844792 0.1828938 -0.8571953 -0.481421 0.2550143 -0.8385602 -0.4814402 0.2554111 -0.8388014 -0.4808093 0.3257677 -0.814249 -0.4804935 0.3227686 -0.8126976 -0.4851217 0.3864103 -0.7843686 -0.4852352 0.3889656 -0.7854729 -0.481392 0.4509431 -0.7516717 -0.48129 0.4547824 -0.7529361 -0.4756683 0.5173312 -0.7117531 -0.475159 0.5083383 -0.7094565 -0.4881227 0.5671424 -0.663484 -0.4879944 0.569024 -0.6639082 -0.4852191 0.6201875 -0.6163282 -0.4852908 0.6243368 -0.6168049 -0.479328 0.6722245 -0.5640186 -0.4795804 0.6707356 -0.5640262 -0.4816517 0.7172837 -0.5039962 -0.481136 0.7129487 -0.5042986 -0.4872238 0.7521386 -0.4437147 -0.4872422 0.751073 -0.443807 -0.4887993 0.7848171 -0.3809174 -0.4888396 0.7898665 -0.3796573 -0.481634 0.8180819 -0.3139634 -0.4818392 0.8188007 -0.3137897 -0.4807301 0.841369 -0.2471085 -0.4806616 0.8407949 -0.2471871 -0.481625 0.8591335 -0.1741574 -0.4812057 0.8581591 -0.1747289 -0.4827347 0.8695487 -0.1043156 -0.4827044 0.8713663 -0.1031596 -0.4796657 0.8771573 -0.03101813 -0.4792006 0.873054 -0.03418254 -0.4864239 0.8729147 0.03834843 -0.4863635 0.8768324 0.04196941 -0.4789608 0.87085 0.1127288 -0.4784482 0.868242 0.1099383 -0.4838072 0.8551637 0.1849793 -0.484229 0.8564692 0.18647 -0.4813416 0.8385512 0.2550652 -0.4814288 0.8387975 0.2554382 -0.4808017 0.8155872 0.3223707 -0.4805149 0.813984 0.3195855 -0.4850726 0.7843301 0.3862103 -0.4854567 0.78433 0.3862103 -0.4854567 0.78433 0.3862103 -0.4854567 0.7854654 0.3888292 -0.4815142 0.750562 0.4527488 -0.4813266 0.750562 0.4527488 -0.4813266 0.7508635 0.4535925 -0.4800602 0.7109057 0.5138756 -0.4801511 0.7106751 0.5130751 -0.481347 0.6662227 0.5694295 -0.4815573 0.6657794 0.5668151 -0.4852407 0.616352 0.6201559 -0.4853008 0.616671 0.6243066 -0.4795396 0.5616532 0.6741445 -0.4796614 0.5616533 0.6741445 -0.4796613 0.5616533 0.6741444 -0.4796614 0.561652 0.668015 -0.4881631 0.5043616 0.7123268 -0.4880676 0.5044426 0.7129648 -0.4870514 0.443637 0.752058 -0.4874371 0.443637 0.752058 -0.4874371 0.4436371 0.752058 -0.4874372 0.4433993 0.7539943 -0.4846544 0.3817328 0.7867557 -0.4850727 0.381196 0.7890754 -0.4817153 0.3127598 0.8184643 -0.4819727 0.3124406 0.819246 -0.4808502 0.3124407 0.819246 -0.4808502 0.3124407 0.819246 -0.4808502 0.2480657 0.8411816 -0.4804966 0.2476987 0.8420785 -0.4791131 0.2476987 0.8420785 -0.4791131 0.2476987 0.8420785 -0.4791131 0.1743446 0.8600487 -0.4795001 0.1754106 0.858034 -0.48271 0.1043493 0.8695068 -0.4827725 0.1027798 0.8719385 -0.4787063 0.03092992 0.8774212 -0.4787229 0.03416472 0.8730443 -0.4864428 -0.03862035 0.8729633 -0.4862547 -0.04191541 0.8766122 -0.4793685 -0.1121946 0.8703638 -0.4794573 -0.1148608 0.8727962 -0.4743773 -0.1868584 0.8603966 -0.4741327 -0.1828726 0.8572502 -0.4813312 -0.255033 0.8385016 -0.4815323 -0.2550331 0.8385016 -0.4815322 -0.2550331 0.8385016 -0.4815322 -0.255446 0.838817 -0.4807634 -0.3210747 0.8160966 -0.4805179 -0.3201255 0.81561 -0.4819753 -0.3904207 0.784703 -0.4814697 -0.3855359 0.7824323 -0.4890419 -0.4504982 0.747065 -0.4888203 -0.4515137 0.7473917 -0.4873819 -0.5091774 0.7096742 -0.4869301 -0.5091775 0.7096742 -0.48693 -0.5163956 0.7115763 -0.4764398 -0.5713669 0.6685156 -0.4760533 -0.5733681 0.6688854 -0.4731189 -0.626856 0.6190317 -0.4731293 -0.6224603 0.6187525 -0.4792584 -0.6723852 0.5640458 -0.4793232 -0.6707962 0.5640494 -0.4815399 -0.7173454 0.5040395 -0.4809988 -0.7130639 0.5040711 -0.4872908 -0.7130638 0.5040712 -0.4872908 -0.7130638 0.5040712 -0.4872907 -0.75049 0.4463894 -0.4873409 -0.757535 0.4453856 -0.4772552 -0.7920447 0.3804694 -0.4773974 -0.7889941 0.3812491 -0.4818065 -0.8184965 0.312727 -0.4819393 -0.8140104 0.3140838 -0.4886087 -0.8367561 0.2468883 -0.488759 -0.8430165 0.2441459 -0.4792869 -0.8600541 0.174344 -0.4794907 -0.858002 0.175387 -0.4827754 -0.8695487 0.1043156 -0.4827044 -0.8669121 0.1059331 -0.4870746 -0.8724923 0.03461194 -0.4874006 -0.8778424 0.03059017 -0.477972 -0.8774595 -0.0426535 -0.4777505 -0.8766298 -0.04204678 -0.4793248 -0.8703898 -0.1121646 -0.4794171 -0.8687226 -0.1104816 -0.4828197 -0.8559308 -0.1858906 -0.4825217 -0.8563788 -0.1864503 -0.4815099 -0.8395203 -0.2515353 -0.481597 -0.8399031 -0.2519074 -0.4807344 -0.8147948 -0.3243526 -0.4805257 -0.9165591 -0.3606936 -0.172684 -0.883383 -0.4354149 -0.173345 -0.8831652 -0.4394934 -0.1639042 -0.8444406 -0.5099734 -0.1638511 -0.8446992 -0.5077332 -0.1693826 -0.7991913 -0.5768415 -0.1689596 -0.7989354 -0.577942 -0.1663888 -0.7490113 -0.6414372 -0.1659527 -0.749674 -0.6390954 -0.1718898 -0.6920865 -0.7009126 -0.1724467 -0.6920865 -0.7009126 -0.1724468 -0.6920865 -0.7009126 -0.1724468 -0.692192 -0.7007421 -0.1727159 -0.692192 -0.7007421 -0.1727159 -0.692192 -0.7007421 -0.1727159 -0.633838 -0.7538706 -0.1729993 -0.6324494 -0.7565758 -0.1661349 -0.569527 -0.804935 -0.1664899 -0.5700741 -0.8040551 -0.1688517 -0.5014061 -0.8484979 -0.1692436 -0.4999473 -0.850429 -0.1637781 -0.4274429 -0.8890882 -0.1637518 -0.4289255 -0.8874467 -0.1687046 -0.3549638 -0.9195303 -0.1687147 -0.3537497 -0.9207378 -0.1646301 -0.2755058 -0.9470771 -0.1647473 -0.2769992 -0.9458905 -0.1690055 -0.1965633 -0.9657052 -0.1696367 -0.1957846 -0.9662348 -0.1675073 -0.1201876 -0.9784493 -0.1679047 -0.119678 -0.9787548 -0.1664816 -0.03410035 -0.985445 -0.1665393 -0.03399354 -0.985474 -0.16639 0.04300838 -0.985127 -0.166359 0.04266941 -0.9850056 -0.1671626 0.1280245 -0.9774916 -0.1676898 0.1280449 -0.9774622 -0.1678457 0.2057009 -0.9641548 -0.1676089 0.205702 -0.9641546 -0.1676089 0.205702 -0.9641546 -0.1676089 0.2082277 -0.9646742 -0.1613849 0.2875039 -0.9440214 -0.1617569 0.2861548 -0.9439482 -0.1645517 0.3641061 -0.9166638 -0.1647856 0.3624151 -0.9165979 -0.1688303 0.4374385 -0.8833233 -0.168486 0.4373604 -0.8833558 -0.1685184 0.509581 -0.8435653 -0.1694842 0.507137 -0.8439729 -0.1747049 0.5735742 -0.8002403 -0.1750087 0.5807494 -0.7986514 -0.1577533 0.6426483 -0.7497345 -0.1578019 0.6397091 -0.7506819 -0.1650726 0.6397091 -0.7506819 -0.1650726 0.7017392 -0.6931146 -0.1647855 0.6986235 -0.6943951 -0.1724547 0.7539374 -0.6341288 -0.1716372 0.7561302 -0.6329931 -0.1660933 0.8050572 -0.5694046 -0.1663173 0.8072589 -0.5680935 -0.1600092 0.8072589 -0.5680935 -0.1600092 0.8072589 -0.5680935 -0.1600092 0.8498153 -0.502202 -0.160023 0.8485638 -0.5031362 -0.1636872 0.888965 -0.427574 -0.1640783 0.8889651 -0.427574 -0.1640783 0.8889651 -0.427574 -0.1640783 0.8875282 -0.4287502 -0.1687215 0.9203838 -0.3526355 -0.1689438 0.9203838 -0.3526354 -0.1689437 0.9203838 -0.3526355 -0.1689438 0.9196211 -0.353539 -0.1711937 0.9450728 -0.2779214 -0.1720382 0.9458633 -0.277081 -0.1690233 0.9656721 -0.1967259 -0.1696363 0.9656721 -0.1967259 -0.1696363 0.9656721 -0.1967259 -0.1696363 0.9657029 -0.196561 -0.1696519 0.9787481 -0.1159503 -0.1691381 0.9792765 -0.115172 -0.1665921 0.9792766 -0.1151721 -0.1665921 0.9792765 -0.1151721 -0.1665922 0.9852453 -0.03856915 -0.1667459 0.9853214 -0.03840553 -0.1663333 0.9849609 0.04697066 -0.1662706 0.9848266 0.04673385 -0.1671301 0.9780358 0.1237625 -0.167717 0.9780358 0.1237625 -0.167717 0.9780358 0.1237624 -0.167717 0.979225 0.1281037 -0.1571875 0.96503 0.2101116 -0.1567499 0.9640005 0.2047742 -0.1696195 0.9428936 0.2871392 -0.168828 0.9425661 0.2844423 -0.1751049 0.9164557 0.3598343 -0.1750095 0.9166074 0.3623872 -0.1688385 0.8833379 0.4373147 -0.1687311 0.8832708 0.4393717 -0.163662 0.8443921 0.5101394 -0.1635849 0.8444671 0.5093893 -0.1655232 0.7995663 0.5771121 -0.166239 0.7994697 0.5772144 -0.1663494 0.7506629 0.6394069 -0.1663258 0.7506629 0.6394068 -0.1663258 0.750663 0.6394068 -0.1663258 0.7506852 0.6397759 -0.164799 0.6930935 0.7018048 -0.1645949 0.6931431 0.7016931 -0.1648617 0.6348242 0.7548679 -0.1648421 0.6351112 0.7543244 -0.1662186 0.5694466 0.8049966 -0.1664664 0.5680714 0.8072449 -0.1601586 0.5002564 0.8509456 -0.16011 0.5013718 0.8496047 -0.1637023 0.4291077 0.8882678 -0.1638501 0.42772 0.8898311 -0.1589218 0.3518423 0.9225282 -0.1585842 0.3537567 0.9206709 -0.1649888 0.2783427 0.9462819 -0.1645479 0.277349 0.9470897 -0.1615505 0.1976937 0.9669623 -0.1609385 0.1976936 0.9669623 -0.1609384 0.1976937 0.9669623 -0.1609384 0.1998972 0.9653971 -0.1674807 0.1153936 0.9790474 -0.1677817 0.1149837 0.9793124 -0.1665111 0.0385456 0.9852264 -0.1668627 0.03839313 0.9853439 -0.1662026 -0.0471003 0.9849704 -0.1661776 -0.04691469 0.9848838 -0.1667423 -0.1286509 0.9776363 -0.1663613 -0.128045 0.9774738 -0.1677781 -0.2056679 0.9641845 -0.1674783 -0.2038434 0.9638392 -0.1716447 -0.2870199 0.9423345 -0.1721199 -0.2870199 0.9423345 -0.1721198 -0.2856144 0.9421793 -0.1752791 -0.3597395 0.9165092 -0.1749237 -0.3666992 0.9166717 -0.1588863 -0.4363793 0.8856059 -0.1589818 -0.4342877 0.8857507 -0.1638292 -0.510097 0.8443651 -0.1638556 -0.511635 0.8441999 -0.1598634 -0.5798149 0.7989265 -0.1597853 -0.5745127 0.8000964 -0.1725719 -0.641007 0.7478323 -0.1727919 -0.6415029 0.7476252 -0.1718451 -0.6986757 0.6943448 -0.1724459 -0.7017006 0.6931049 -0.1649911 -0.7549042 0.6347388 -0.165004 -0.7543463 0.6350588 -0.1663192 -0.8049651 0.5695146 -0.1663858 -0.8040629 0.5700457 -0.1689112 -0.8496214 0.499564 -0.1690549 -0.8514879 0.4981502 -0.1637523 -0.8883308 0.4290719 -0.1636023 -0.8867443 0.4304157 -0.1686036 -0.8867442 0.4304157 -0.1686037 -0.8867442 0.4304158 -0.1686037 -0.9195948 0.3548231 -0.1686591 -0.9207552 0.3536167 -0.1648187 -0.9207552 0.3536167 -0.1648188 -0.9207552 0.3536167 -0.1648188 -0.9474732 0.2742409 -0.1645796 -0.9454398 0.2767834 -0.1718567 -0.9651584 0.1974995 -0.171649 -0.9662889 0.1956458 -0.1673573 -0.9785521 0.1196193 -0.1677118 -0.9788098 0.1193091 -0.1664231 -0.9854348 0.03419286 -0.1665807 -0.9855006 0.03422135 -0.1661852 -0.9849815 -0.04714691 -0.1660988 -0.9848662 -0.04711222 -0.1667903 -0.9781932 -0.1241369 -0.1665182 -0.9778075 -0.1235353 -0.1692086 -0.9629544 -0.2096596 -0.1695931 -0.9627793 -0.2086937 -0.1717647 -0.9435936 -0.282964 -0.1719375 -0.9439404 -0.2861627 -0.1645829 -0.9166568 -0.3641207 -0.1647922 -0.1463237 0.4780053 -0.8660835 -0.1054881 0.4882007 -0.8663328 0.01870352 0.4998845 -0.8658902 0.2156921 0.4509243 -0.8661087 0.3229833 0.381612 -0.8660566 0.3229834 0.3816121 -0.8660567 0.3229834 0.3816121 -0.8660565 0.4060932 0.2901427 -0.8665481 0.4060932 0.2901428 -0.866548 0.4060932 0.2901428 -0.866548 0.4283251 0.2585678 -0.8658409 0.4465349 0.2210049 -0.8670429 0.4780456 0.1465525 -0.8660224 0.4883223 0.1049541 -0.866329 0.4999932 -0.01885193 -0.8658242 0.4794147 -0.1411545 -0.8661623 0.3882824 -0.313296 -0.8666501 0.2897943 -0.4059723 -0.8667214 0.2897943 -0.4059723 -0.8667213 0.2897943 -0.4059723 -0.8667214 0.2568537 -0.4295686 -0.8657349 0.2210263 -0.4465852 -0.8670116 0.1465654 -0.4789953 -0.8654953 0.1030896 -0.4884181 -0.866499 -0.01866567 -0.4990544 -0.8663697 -0.2241201 -0.4480744 -0.8654475 -0.322846 -0.3814658 -0.8661723 -0.4213076 -0.2707445 -0.8655619 -0.4294575 -0.2568544 -0.8657899 -0.4461877 -0.2207551 -0.8672853 -0.478985 -0.1466613 -0.8654848 -0.4882285 -0.1054593 -0.8663207 -0.4989558 0.01881355 -0.8664233 -0.4792777 0.1409671 -0.8662685 -0.4792778 0.140967 -0.8662686 -0.4792778 0.140967 -0.8662686 -0.3813895 0.3227214 -0.8662523 -0.2904425 0.4066318 -0.866195 -0.2568696 0.4294517 -0.8657884 -0.2210412 0.4465386 -0.8670318 -0.1563377 0.08463668 -0.9840708 -0.0441032 0.2271185 -0.972868 -0.0441032 0.2271186 -0.972868 -0.0441032 0.2271186 -0.972868 0.03056102 -0.2318254 -0.9722772 0.03056097 -0.2318256 -0.9722772 0.03056097 -0.2318257 -0.9722772 0.162918 -0.1702558 -0.9718389 0.1726216 -0.3135226 -0.9337588 0.1726216 -0.3135226 -0.9337587 0.1726216 -0.3135226 -0.9337588 0.146484 -0.1803749 -0.9726292 0.1592661 -0.2499237 -0.9550772 -0.00199753 -0.2617426 -0.9651356 0.1477671 -0.1805828 -0.9723964 0.147767 -0.1805828 -0.9723965 0.1477671 -0.1805829 -0.9723964 -0.00161314 -0.2121971 -0.9772256 -0.02965039 -0.1769157 -0.9837793 -0.04361885 -0.1722339 -0.9840899 -0.03257548 -0.1741943 -0.9841724 -0.1707366 -0.1619533 -0.9719157 -0.306101 -0.1732547 -0.936101 -0.306101 -0.1732546 -0.936101 -0.306101 -0.1732546 -0.936101 -0.1798823 -0.1466868 -0.9726898 -0.2500058 -0.1593203 -0.9550467 -0.2616876 0.001932859 -0.9651508 -0.1800004 -0.150326 -0.9721122 -0.1800004 -0.150326 -0.9721122 -0.1800004 -0.150326 -0.9721121 -0.2121918 0.001647412 -0.9772267 -0.1767674 0.02969032 -0.9838048 -0.1725677 0.04372638 -0.9840266 -0.1768656 0.02099281 -0.9840112 -0.1768656 0.02099281 -0.9840112 -0.1768656 0.02099281 -0.9840111 -0.1629611 0.1702402 -0.9718344 -0.1757593 0.2956672 -0.9389833 -0.1470035 0.1839296 -0.9718848 -0.159102 0.2499237 -0.9551046 0 0.2615692 -0.9651848 -0.1344295 0.183517 -0.9737814 -0.1344295 0.1835169 -0.9737814 -0.1344296 0.1835171 -0.9737815 0 0.2119117 -0.9772889 0.02803647 0.1770424 -0.9838039 0.04358124 0.1722406 -0.9840903 0.03273272 0.1740862 -0.9841862 0.1736114 0.1634532 -0.9711551 0.2953312 0.1757835 -0.9390845 0.1806865 0.1463571 -0.9725903 0.249283 0.1589542 -0.9552966 0.249283 0.1589542 -0.9552966 0.2492829 0.1589542 -0.9552966 0.261002 0 -0.9653384 0.1804429 0.1564925 -0.9710564 0.2142005 0 -0.9767898 0.1768127 -0.02947109 -0.9838033 0.1725487 -0.04147541 -0.9841274 0.1744093 -0.03285223 -0.9841251 -0.2581499 0.4286842 -0.8657878 -0.2275206 0.4390652 -0.8691698 -0.1945304 0.3753731 -0.9062301 -0.1484485 0.3959487 -0.9061941 -0.1203549 0.3209587 -0.9394149 -0.0809068 0.3330561 -0.9394296 -0.2937886 0.4039561 -0.8663185 -0.2784481 0.4079591 -0.8695033 -0.2382657 0.3490923 -0.9062914 -0.1947751 0.3749665 -0.9063459 -0.1584028 0.3049716 -0.9390959 -0.118813 0.3225449 -0.9390679 -0.3559737 0.3523799 -0.8655121 -0.3571677 0.3511788 -0.8655083 -0.3204213 0.3765106 -0.8692353 -0.328254 0.3748332 -0.8670348 -0.2782152 0.3176808 -0.9064631 -0.2385231 0.3486326 -0.9064007 -0.1941077 0.283672 -0.93907 -0.1582455 0.3051852 -0.9390529 -0.3823913 0.3208919 -0.8664903 -0.3693332 0.3284776 -0.8693075 -0.3152753 0.2804106 -0.9066265 -0.2785452 0.3168132 -0.9066655 -0.2268202 0.2579233 -0.9391636 -0.1944175 0.2831161 -0.9391736 -0.4317068 0.2517724 -0.8661639 -0.4297599 0.2550538 -0.8661721 -0.4045342 0.2853825 -0.8688549 -0.4072833 0.2840246 -0.8680152 -0.3466804 0.2417936 -0.9062829 -0.3149046 0.2819468 -0.9062787 -0.2561021 0.2292758 -0.9390656 -0.2265897 0.2584731 -0.9390681 -0.1836519 0.2094728 -0.960413 -0.157444 0.2292224 -0.9605565 -0.1415374 0.2264823 -0.9636768 -0.1230457 0.2373092 -0.96361 -0.1468854 0.2425718 -0.9589492 -0.09748589 0.2646593 -0.959402 -0.07475626 0.2572149 -0.9634584 -0.06335628 0.2608177 -0.9633069 -0.0785591 0.2681689 -0.9601635 -0.07900607 0.2681853 -0.9601223 -0.2016025 0.1672098 -0.9650894 -0.1951748 0.1736882 -0.9652665 -0.2564132 0.228208 -0.9392409 -0.2819675 0.1958575 -0.93922 -0.3467926 0.2409279 -0.9064704 -0.3730472 0.1979309 -0.9064542 -0.4365311 0.2317181 -0.8693374 -0.4626387 0.1773953 -0.8686175 -0.4474229 0.2239624 -0.8658254 -0.4501175 0.2175434 -0.8660654 -0.4804954 0.1372933 -0.8661841 -0.462731 0.1779816 -0.8684484 -0.3947903 0.1518964 -0.9061282 -0.3730444 0.199332 -0.9061483 -0.3032424 0.1620125 -0.93904 -0.2817133 0.1972193 -0.9390113 -0.2144004 0.1500954 -0.9651445 -0.1946345 0.1749358 -0.9651502 -0.1356027 0.1218948 -0.9832363 -0.04396897 0.2269498 -0.9729135 -0.1506815 0.09737902 -0.9837746 -0.1472675 0.1022624 -0.9837961 -0.2146899 0.1491135 -0.9652324 -0.231145 0.1220079 -0.9652389 -0.3033419 0.1601147 -0.9393333 -0.320018 0.1235846 -0.9393165 -0.394877 0.1523441 -0.9060152 -0.410431 0.1034181 -0.9060084 -0.4786369 0.1204659 -0.8697096 -0.4918812 0.05844873 -0.8686984 -0.4903721 0.09547638 -0.8662676 -0.4892109 0.1010951 -0.8662866 -0.498274 0.0294069 -0.8665208 -0.498274 0.02940636 -0.8665208 -0.4982741 0.02940654 -0.8665208 -0.4934999 0.06254678 -0.867494 -0.419306 0.05314218 -0.9062882 -0.4101032 0.1020128 -0.9063162 -0.333166 0.08292788 -0.9392144 -0.3200823 0.1242277 -0.9392098 -0.2441837 0.09476286 -0.9650878 -0.2307879 0.124299 -0.9650321 -0.1564376 0.08425623 -0.9840875 -0.14801 0.09806007 -0.9841125 -0.1621145 0.09265768 -0.9824121 -0.1621146 0.09265756 -0.982412 -0.1621146 0.09265762 -0.982412 -0.1668335 0.06142556 -0.9840698 -0.1660773 0.06297165 -0.9841001 -0.2442913 0.09258311 -0.9652721 -0.253589 0.06304657 -0.9652554 -0.3331901 0.08287966 -0.93921 -0.3405861 0.04306352 -0.9392266 -0.4192809 0.05315148 -0.9062993 -0.4226003 0.001528024 -0.9063149 -0.4935473 0.001814126 -0.8697172 -0.4906285 -0.06272774 -0.8691082 -0.4998505 -0.0234344 -0.8657947 -0.4997866 -0.02591049 -0.8657609 -0.4868046 -0.1141048 -0.8660263 -0.4945861 -0.05737602 -0.8672328 -0.4199035 -0.04869282 -0.9062616 -0.4227715 0.001839637 -0.9062346 -0.3433326 0.001508057 -0.9392127 -0.3406616 0.04331701 -0.9391877 -0.2592992 0.0329163 -0.965236 -0.2536387 0.06343328 -0.9652169 -0.1725499 0.0431354 -0.9840558 -0.1655873 0.06533098 -0.9840288 -0.4799708 -0.1431314 -0.8655296 -0.4813442 -0.1159213 -0.8688327 -0.4104724 -0.09884089 -0.9065003 -0.4193604 -0.04947996 -0.9064705 -0.3411473 -0.04022181 -0.939149 -0.3435295 0.001915276 -0.93914 -0.2615432 0.001447796 -0.9651907 -0.2594323 0.03347152 -0.9651812 -0.1776169 0.02285236 -0.9838344 -0.1757176 0.02596604 -0.9840982 -0.4633955 -0.1822823 -0.8672012 -0.4632197 -0.1745885 -0.8688766 -0.395278 -0.1490277 -0.9063918 -0.4107451 -0.09850245 -0.9064137 -0.3343997 -0.08018213 -0.9390143 -0.341593 -0.03952819 -0.9390164 -0.2883689 -0.0332576 -0.9569417 -0.254766 0.02173262 -0.9667586 -0.4274029 -0.2601644 -0.8658182 -0.427403 -0.2601644 -0.8658183 -0.427403 -0.2601645 -0.8658183 -0.4386709 -0.2272791 -0.8694321 -0.3758142 -0.1950702 -0.9059312 -0.3758141 -0.1950702 -0.9059312 -0.3758141 -0.1950703 -0.9059312 -0.3964537 -0.1480199 -0.9060434 -0.3217765 -0.1201114 -0.9391663 -0.3337389 -0.0811029 -0.9391703 -0.4039481 -0.2937785 -0.8663257 -0.407929 -0.278442 -0.8695195 -0.3497037 -0.2386684 -0.9059497 -0.3760775 -0.1945803 -0.9059273 -0.3048954 -0.1576455 -0.939248 -0.3215365 -0.120334 -0.9392199 -0.354204 -0.354149 -0.8655161 -0.3512996 -0.3568611 -0.8655859 -0.3512996 -0.356861 -0.8655859 -0.3512996 -0.3568611 -0.8655859 -0.3754919 -0.3217982 -0.8691673 -0.3743078 -0.3277633 -0.8674474 -0.3181765 -0.2786306 -0.9061616 -0.3487399 -0.2391737 -0.9061879 -0.2829791 -0.1940684 -0.9392871 -0.3045648 -0.1579617 -0.9393021 -0.319991 -0.3840085 -0.8661081 -0.3291391 -0.3682115 -0.8695332 -0.2815451 -0.3150129 -0.9063659 -0.3173804 -0.2788293 -0.9063796 -0.2580332 -0.2267584 -0.9391483 -0.2837809 -0.1935242 -0.9391576 -0.254257 -0.4302501 -0.8661629 -0.2549679 -0.4297265 -0.866214 -0.2854176 -0.4045613 -0.8688308 -0.2834932 -0.4082904 -0.8677158 -0.2407916 -0.346827 -0.9064935 -0.28064 -0.3152047 -0.90658 -0.2285937 -0.2567318 -0.9390601 -0.258556 -0.2265219 -0.9390616 -0.2087598 -0.1828768 -0.9607161 -0.2290794 -0.1562199 -0.9607903 -0.2264683 -0.1415321 -0.9636809 -0.2373253 -0.1230887 -0.9636005 -0.2429426 -0.1487324 -0.9585707 -0.2652271 -0.09920895 -0.9590684 -0.2565938 -0.07274985 -0.9637776 -0.2595633 -0.06304031 -0.9636664 -0.2670734 -0.07862812 -0.9604631 -0.2674232 -0.07682234 -0.960512 -0.2156673 -0.4520793 -0.8655125 -0.2328045 -0.4354251 -0.8696017 -0.199302 -0.3726666 -0.9063103 -0.2420774 -0.3466624 -0.9062141 -0.1968018 -0.2817859 -0.9390771 -0.2284585 -0.2568231 -0.939068 -0.1736581 -0.195208 -0.9652651 -0.1672398 -0.2015606 -0.9650929 -0.2312821 -0.03238165 -0.9723477 -0.2312821 -0.03238165 -0.9723477 -0.2312821 -0.03238177 -0.9723477 -0.1411389 -0.4793905 -0.8661782 -0.1373218 -0.480496 -0.8661792 -0.1775257 -0.462891 -0.8684564 -0.1766337 -0.4639332 -0.8680821 -0.150366 -0.3948693 -0.906349 -0.1991395 -0.372807 -0.9062883 -0.1620343 -0.3032833 -0.939023 -0.1972038 -0.2816699 -0.9390276 -0.1500886 -0.2144338 -0.9651381 -0.1749705 -0.1946265 -0.9651455 -0.1200706 -0.133552 -0.9837413 -0.2317683 -0.03268438 -0.9722219 -0.0981298 -0.1501408 -0.9837827 -0.1025527 -0.1470753 -0.9837946 -0.1496049 -0.2144958 -0.9651995 -0.1221352 -0.2312999 -0.9651857 -0.1601673 -0.3033595 -0.9393187 -0.1230492 -0.3202674 -0.9393018 -0.1518145 -0.3950818 -0.9060148 -0.1037201 -0.4103115 -0.906028 -0.1209859 -0.4786857 -0.8696105 -0.06065034 -0.4919742 -0.8684947 -0.09518718 -0.4905254 -0.8662126 -0.1011656 -0.4892783 -0.8662403 -0.01462709 -0.4990718 -0.8664372 -0.0624814 -0.4926467 -0.8679835 -0.05317431 -0.4193173 -0.9062812 -0.1025016 -0.4100064 -0.9063047 -0.08327567 -0.3330844 -0.9392125 -0.1236334 -0.3202951 -0.9392156 -0.09426182 -0.2442175 -0.9651282 -0.1225439 -0.2312605 -0.9651434 -0.08304005 -0.1567102 -0.9841476 -0.09751582 -0.1479551 -0.9841748 -0.09232497 -0.1615691 -0.9825333 -0.09232497 -0.1615691 -0.9825332 -0.09232497 -0.1615691 -0.9825333 -0.08469682 -0.1563594 -0.9840621 -0.06299936 -0.1661927 -0.9840788 -0.09257668 -0.2443321 -0.9652624 -0.06303578 -0.2535402 -0.9652688 -0.0827732 -0.3329321 -0.9393109 -0.0431292 -0.3405444 -0.9392388 -0.05310565 -0.4192504 -0.9063162 -0.001524031 -0.4226123 -0.9063094 -0.001787722 -0.4935244 -0.8697302 0.06271082 -0.4904721 -0.8691976 0.02352601 -0.4999439 -0.8657382 0.02570658 -0.4997578 -0.8657838 0.1144256 -0.4862024 -0.8663221 0.05733019 -0.4944618 -0.8673067 0.04869586 -0.4199762 -0.9062278 -0.001822531 -0.4227665 -0.906237 -0.001478731 -0.3433302 -0.9392136 -0.04327082 -0.3405331 -0.9392364 -0.03302705 -0.2598768 -0.9650768 -0.06543654 -0.2539162 -0.9650103 -0.04438054 -0.1721184 -0.9840761 -0.06338864 -0.1661959 -0.9840533 0.147014 -0.4788284 -0.8655115 0.1152456 -0.4804269 -0.8694301 0.09854292 -0.4107956 -0.9063864 0.04946172 -0.4194465 -0.9064316 0.04022032 -0.3411542 -0.9391465 -0.00188595 -0.3435608 -0.9391286 -0.001435875 -0.2615027 -0.9652017 -0.03145033 -0.2595275 -0.9652236 -0.02156674 -0.1779105 -0.9838104 -0.02440065 -0.1760708 -0.984075 0.1831034 -0.4633795 -0.8670368 0.174611 -0.4632423 -0.86886 0.1489749 -0.3952901 -0.9063953 0.09856659 -0.4106873 -0.9064329 0.08021241 -0.3342115 -0.9390787 0.03961437 -0.3414298 -0.9390721 0.03343951 -0.2882692 -0.9569655 -0.02185672 -0.2548158 -0.9667426 0.2581683 -0.4285488 -0.8658493 0.2275386 -0.4390394 -0.8691782 0.194525 -0.3753627 -0.9062355 0.1484528 -0.3958866 -0.9062206 0.1206018 -0.3215925 -0.9391665 0.08064639 -0.333935 -0.9391399 0.2917218 -0.4045559 -0.866737 0.278455 -0.4079087 -0.8695247 0.2384107 -0.3493047 -0.9061714 0.1942825 -0.3756694 -0.9061605 0.1578319 -0.3052362 -0.9391061 0.1204391 -0.321823 -0.9391083 0.3573725 -0.3499998 -0.8659013 0.3536746 -0.3535836 -0.8659636 0.3218657 -0.3755036 -0.8691372 0.3277429 -0.3743106 -0.8674539 0.2781966 -0.3177819 -0.9064332 0.2388967 -0.3482261 -0.9064585 0.1943288 -0.2832742 -0.9391443 0.38112 -0.3224577 -0.8664691 0.3688414 -0.3296831 -0.8690599 0.3150096 -0.2815246 -0.9063735 0.2779925 -0.3182625 -0.9063274 0.2259407 -0.2586067 -0.9391877 0.1943955 -0.283203 -0.939152 0.4305477 -0.2563709 -0.8653916 0.4343262 -0.2502371 -0.8652988 0.404621 -0.2861568 -0.8685598 0.4079511 -0.2844902 -0.867549 0.3467047 -0.2417494 -0.9062853 0.3149046 -0.2819468 -0.9062787 0.2556554 -0.2289495 -0.939267 0.2261937 -0.2581606 -0.9392494 0.1828467 -0.2087175 -0.9607311 0.1569475 -0.2285844 -0.9607897 0.1412375 -0.2258564 -0.9638677 0.122801 -0.2367568 -0.9637771 0.1495493 -0.2425071 -0.9585537 0.09925037 -0.2652068 -0.9590697 0.07211875 -0.2563906 -0.963879 0.06264638 -0.259427 -0.9637287 0.07860857 -0.267021 -0.9604794 0.07690095 -0.2673197 -0.9605345 0.2026669 -0.1667119 -0.9649525 0.1947766 -0.1747302 -0.9651588 0.255523 -0.2292291 -0.9392349 0.2819696 -0.1958222 -0.9392268 0.3467926 -0.2409279 -0.9064704 0.3733965 -0.1973741 -0.9064318 0.4367586 -0.2308354 -0.8694579 0.4628325 -0.1788231 -0.8682215 0.4491143 -0.2195975 -0.8660677 0.4506181 -0.2165743 -0.8660479 0.4804954 -0.1372933 -0.8661841 0.4627066 -0.1779722 -0.8684633 0.3943613 -0.1516094 -0.9063631 0.3734051 -0.1976845 -0.9063606 0.3033353 -0.1605902 -0.9392542 0.2819886 -0.195551 -0.9392775 0.2147147 -0.1489197 -0.9652568 0.1952558 -0.1735073 -0.9652826 0.1341795 -0.1192237 -0.983759 0.03140693 -0.2332326 -0.9719137 0.1511389 -0.09764963 -0.9836776 0.1474883 -0.1028568 -0.9837011 0.2145523 -0.1496264 -0.9651836 0.2306672 -0.1231994 -0.9652019 0.3032463 -0.1620219 -0.9390371 0.3209096 -0.1233189 -0.9390471 0.3943307 -0.1515774 -0.9063817 0.4094654 -0.1035569 -0.9064294 0.4786227 -0.1210306 -0.869639 0.4919196 -0.05811131 -0.8686993 0.4899155 -0.1039102 -0.8655551 0.4909712 -0.09811478 -0.8656332 0.5001098 -0.01453083 -0.8658402 0.4936168 -0.06262445 -0.8674218 0.4193199 -0.05314534 -0.9062818 0.4096496 -0.1041938 -0.906273 0.3326618 -0.0846039 -0.9392435 0.3208328 -0.121934 -0.9392542 0.2442642 -0.09284853 -0.9652534 0.230832 -0.122279 -0.9652795 0.1570568 -0.08321571 -0.9840774 0.148449 -0.09728521 -0.9841232 0.1501983 -0.09661549 -0.9839237 0.1571043 -0.08291238 -0.9840954 0.1655095 -0.06465107 -0.9840869 0.2441786 -0.09529078 -0.9650371 0.2538 -0.06491017 -0.9650763 0.3327479 -0.08511084 -0.9391672 0.3405844 -0.04317373 -0.9392222 0.4192528 -0.05314791 -0.9063127 0.4226098 -0.001528024 -0.9063106 0.4945454 -0.001757204 -0.8691501 0.4904437 0.06277829 -0.8692088 0.4998626 0.02343499 -0.8657876 0.4999684 0.02203941 -0.8657633 0.4851679 0.1214628 -0.865944 0.4851679 0.1214631 -0.8659439 0.4851679 0.121463 -0.8659439 0.4944813 0.05736386 -0.8672933 0.4199047 0.04863178 -0.9062643 0.4227715 -0.001766085 -0.9062347 0.3433324 -0.001508057 -0.9392129 0.3405938 -0.04302465 -0.9392256 0.2592826 -0.03277981 -0.9652451 0.2535384 -0.06285309 -0.9652812 0.1725599 -0.04280501 -0.9840686 0.165405 -0.06526422 -0.9840639 0.4790467 0.1428452 -0.8660886 0.4803362 0.1170022 -0.8692455 0.4105079 0.1000694 -0.9063496 0.4194714 0.04920452 -0.9064341 0.341253 0.0400601 -0.9391176 0.3435296 -0.001868546 -0.93914 0.2614938 -0.001400828 -0.9652042 0.2594881 -0.03373414 -0.965157 0.177614 -0.02302515 -0.9838309 0.1757062 -0.02605253 -0.9840978 0.4634242 0.1831044 -0.8670126 0.4632196 0.1727679 -0.8692405 0.3965138 0.1478993 -0.9060369 0.411536 0.09876567 -0.9060263 0.3335221 0.0800451 -0.939338 0.3403862 0.04137456 -0.9393751 0.2892662 0.03519058 -0.9566017 0.2542619 -0.02280849 -0.9668664 0.4287233 0.2582146 -0.8657491 0.4390458 0.2275339 -0.8691762 0.3753589 0.1945546 -0.9062309 0.3958511 0.1484004 -0.9062446 0.321632 0.1206454 -0.9391474 0.3343908 0.07884973 -0.9391303 0.4043623 0.2922317 -0.8666555 0.4076693 0.279536 -0.8692902 0.3481991 0.2386756 -0.9065271 0.3742105 0.195383 -0.9065275 0.3046917 0.1590151 -0.9390832 0.3217791 0.1204292 -0.9391246 0.3518499 0.3555243 -0.8659124 0.3507215 0.3566046 -0.8659259 0.3759492 0.3200548 -0.8696132 0.3743945 0.3277782 -0.8674043 0.3181642 0.2785587 -0.906188 0.349615 0.2380201 -0.9061545 0.284108 0.1933765 -0.939089 0.3047383 0.1590325 -0.9390652 0.3200373 0.3839936 -0.8660976 0.3292374 0.3682135 -0.8694951 0.2816669 0.3149811 -0.9063392 0.3172455 0.2789253 -0.9063974 0.2579688 0.226774 -0.9391623 0.2838101 0.1935946 -0.9391341 0.2546855 0.4309753 -0.8656765 0.2499307 0.433947 -0.8655777 0.2868185 0.4032995 -0.8689562 0.2844922 0.4079617 -0.8675433 0.2417665 0.3467028 -0.9062815 0.2819656 0.3148738 -0.9062837 0.2288951 0.255693 -0.9392701 0.2571812 0.2271445 -0.9392887 0.2080465 0.1837768 -0.9606992 0.2290667 0.1562112 -0.9607948 0.2264438 0.1415168 -0.9636889 0.2369711 0.1236645 -0.9636139 0.2421916 0.1477568 -0.9589115 0.2640542 0.09877473 -0.9594368 0.255934 0.0736404 -0.9638854 0.2597615 0.06132942 -0.9637234 0.2684778 0.07924258 -0.960021 0.2688608 0.07746934 -0.9600585 0.2177045 0.4501009 -0.8660334 0.2316489 0.4365841 -0.8693292 0.198126 0.3734332 -0.9062527 0.2420932 0.3466587 -0.9062112 0.1965546 0.2814687 -0.939224 0.2292367 0.2555677 -0.9392208 0.1747297 0.1947906 -0.9651561 0.1680371 0.201397 -0.9649885 0.2279618 0.04198575 -0.9727645 0.2279618 0.0419858 -0.9727645 0.2279617 0.04198586 -0.9727645 0.141142 0.4794009 -0.866172 0.1462402 0.4779453 -0.8661305 0.1778702 0.4637249 -0.8679409 0.1782288 0.4633782 -0.8680525 0.1515609 0.3940264 -0.9065167 0.1967239 0.37338 -0.9065799 0.1600018 0.3036603 -0.9392497 0.1964337 0.2814343 -0.9392597 0.1497045 0.2145453 -0.9651731 0.1748337 0.1946722 -0.9651612 0.1197906 0.1334308 -0.9837919 0.2276743 0.04179465 -0.97284 0.09691786 0.1509177 -0.983784 0.1025419 0.1471093 -0.9837906 0.1495937 0.2145436 -0.9651905 0.1226364 0.2309978 -0.9651945 0.1611785 0.3036758 -0.9390434 0.1237993 0.3206693 -0.9390661 0.152148 0.3941069 -0.9063833 0.1031584 0.4095838 -0.9064214 0.1205468 0.4786397 -0.8696969 0.05840063 0.491916 -0.8686817 0.1023766 0.4900002 -0.8656899 0.09816861 0.4907029 -0.8657792 0.0147615 0.5003816 -0.8656792 0.0147615 0.5003816 -0.8656792 0.0147615 0.5003817 -0.8656791 0.06281602 0.4935715 -0.8674339 0.05336844 0.4194056 -0.9062288 0.1043043 0.4098601 -0.9061653 0.08465164 0.3326346 -0.9392489 0.122593 0.320583 -0.9392537 0.09338933 0.2442759 -0.9651982 0.122432 0.2310492 -0.9652082 0.08321845 0.1570468 -0.9840788 0.09840267 0.1477378 -0.9841192 0.09724295 0.1512496 -0.9837009 0.09724289 0.1512496 -0.9837009 0.09724295 0.1512497 -0.9837009 0.08295077 0.157159 -0.9840835 0.06414192 0.1656873 -0.9840903 0.09454083 0.2441292 -0.9651233 0.06450015 0.2537375 -0.9651203 0.08456039 0.3326837 -0.9392396 0.04293578 0.3405187 -0.939257 0.05284762 0.419227 -0.906342 0.001524209 0.4225972 -0.9063164 0.001787483 0.4945648 -0.8691391 -0.06271082 0.4904721 -0.8691976 -0.02352833 0.4997937 -0.8658249 -0.02204549 0.4999912 -0.8657498 -0.1145586 0.4867673 -0.8659873 -0.05713164 0.4946342 -0.8672214 -0.04851913 0.4200978 -0.9061809 0.001830518 0.4227035 -0.9062663 0.001485109 0.3434123 -0.9391837 0.04328477 0.3405962 -0.9392128 0.03294736 0.2593422 -0.9652234 0.06341284 0.2536514 -0.9652149 0.04304289 0.1721394 -0.9841318 0.06326222 0.1658123 -0.9841262 -0.1428731 0.4790046 -0.8661074 -0.1174297 0.4803084 -0.8692032 -0.1002815 0.4101976 -0.9064665 -0.04945176 0.4193625 -0.906471 -0.0401321 0.3403688 -0.9394353 0 0.3426521 -0.9394624 0 0.2616164 -0.9651719 0.03339481 0.2593669 -0.9652013 0.02287906 0.1776638 -0.9838253 0.02581173 0.1757714 -0.9840926 -0.1830892 0.4634206 -0.8670178 -0.1728134 0.4632025 -0.8692405 -0.1479191 0.3964643 -0.9060552 -0.09878635 0.4115295 -0.9060269 -0.0800876 0.3336548 -0.9392872 -0.03932249 0.3408609 -0.939291 -0.03346467 0.2900639 -0.956422 0.02395933 0.2548295 -0.9666892 0.9131424 0.4076339 0.002416551 0.9147719 0.4039694 0.001124858 0.9137852 0.4061978 -4.15592e-4 0.9137883 0.4061911 -2.83514e-5 0.9128226 0.4082482 -0.009400904 0.9128226 0.4082482 -0.009400904 0.9128226 0.4082482 -0.009400904 0.916161 0.4003501 0.01920795 0.9161607 0.4003506 0.01921105 0.9161607 0.4003506 0.01921105 0.9134719 0.4069015 -4.48277e-4 0.9132959 0.4072965 -5.77056e-4 -0.9551132 -0.2962414 0 -0.8599948 -0.510303 0 -0.8599948 -0.5103029 0 -0.7213413 -0.6925798 0 -0.7213415 -0.6925796 0 -0.5400387 -0.8416402 0 -0.5400005 -0.8416647 0 -0.3325091 -0.9431002 0 -0.3325356 -0.9430908 0 -0.1034985 -0.9946297 0 -0.1034898 -0.9946306 0 0.126159 -0.9920101 0 0.3530211 -0.9356154 0 0.3529932 -0.9356259 0 0.5573786 -0.8302585 0 0.5573395 -0.8302847 0 0.7352268 -0.6778212 0 0.735269 -0.6777755 0 0.871541 -0.4903227 0 0.8716133 -0.4901942 0 0.961314 -0.2754551 0 0.9612916 -0.2755332 0 0.9989382 -0.04607093 0 0.9830272 0.18346 0 0.9830425 0.1833783 0 0.9141712 0.4053285 0 0.9141399 0.4053992 0 0.7955146 0.6059346 0 0.7955146 0.6059346 0 0.6333578 0.7738592 0 0.6334407 0.7737913 0 0.4391252 0.8984259 0 0.4391588 0.8984095 0 0.2187743 0.9757755 0 0.2187743 0.9757755 0 -0.008602797 0.9999631 0 -0.008602797 0.9999631 0 -0.2411867 0.9704788 0 -0.2411669 0.9704837 0 -0.4598318 0.8880061 0 -0.4597974 0.8880239 0 -0.6519923 0.7582257 0 -0.6519507 0.7582615 0 -0.8088524 0.5880118 0 -0.8088526 0.5880117 0 -0.9218456 0.3875573 0 -0.9217852 0.387701 0 -0.9870086 0.1606676 0 -0.9870086 0.1606675 0 -0.9976186 -0.06897276 0 -0.9550892 -0.2963188 0 -0.7751018 -0.4476776 -0.4458724 -0.7749044 -0.4479581 -0.4459334 -0.780413 -0.4364617 -0.4477241 -0.7733517 -0.4465132 -0.4500592 -0.7746457 -0.4484446 -0.4458942 -0.775202 -0.4475989 -0.4457771 -0.775202 -0.4475991 -0.445777 -0.7752021 -0.4475989 -0.445777 -0.7736619 -0.449928 -0.4461078 -0.7746239 -0.4484072 -0.4459697 -0.776986 -0.4441561 -0.4461147 -0.7743015 -0.4485521 -0.4463835 -0.7758144 -0.4457716 -0.4465421 0.06263518 0.9953842 -0.07271301 0.134178 0.9885122 -0.06956988 0.2491815 0.9659622 -0.06946611 0.2491815 0.9659623 -0.06946611 0.2491815 0.9659623 -0.06946617 0.2707117 0.9601833 -0.06901711 0.2419479 0.9678338 -0.06898707 0.2864536 0.9555276 -0.07008153 0.3811947 0.9218336 -0.07009553 0.4216113 0.9039199 -0.07192212 0.4216113 0.9039199 -0.07192218 0.4216114 0.9039199 -0.07192218 0.5028291 -0.8643857 6.45064e-4 0.5003209 -0.8658401 -2.90941e-4 0.5002525 -0.8658797 -2.19793e-4 0.5002108 -0.8659034 7.94329e-4 0.5006107 -0.8656715 -0.001429498 0.5006107 -0.8656714 -0.001429438 0.5006107 -0.8656715 -0.001429438 0.4978236 -0.8672304 0.009111583 0.5006181 -0.8656679 8.12495e-4 0.5015905 -0.8651052 -3.12359e-4 0.8212741 0.5704942 0.006744921 0.7974006 0.6034504 0 0.7451171 0.6669337 0 0.7451171 0.6669337 1.60833e-7 0.7451171 0.6669337 0 0.7168268 0.6972178 0.006837666 0.6872656 0.7264062 0 0.6252533 0.7804218 0 0.5920364 0.8058813 0.006957292 0.5576377 0.8300845 0 0.4882431 0.8727076 0 0.4523817 0.891799 0.006732463 0.4157796 0.9094654 0 0.3368375 0.9415629 0 0.2980298 0.9545325 0.006790578 0.1777466 0.9840763 0 0.1383938 0.9903555 0.006573855 0.09907829 0.9950796 0 0.01296502 0.999916 0 -0.02812987 0.9995813 0.006786167 -0.06908392 0.9976109 0 -0.1510715 0.9885228 0 -0.1923668 0.9812984 0.006959676 -0.2333549 0.9723917 0 -0.3110043 0.9504085 0 -0.350426 0.936565 0.006908357 -0.3892426 0.9211353 0 -0.4627283 0.8865002 0 -0.5000683 0.8659573 0.007060647 -0.5366264 0.84382 0 -0.6034728 0.7973837 0 -0.6356496 0.7719476 0.0068264 -0.6671074 0.7449616 0 -0.7262707 0.6874089 0 -0.754051 0.6567804 0.006838619 -0.7804245 0.6252501 0 -0.8520848 0.5233605 0.006752133 -0.8727316 0.4882004 0 -0.9263365 0.3766363 0.006768703 -0.9410149 0.3383653 0 -0.9659711 0.2586501 0 -0.9759116 0.218056 0.006943583 -0.9842022 0.1770486 0 -0.9950338 0.09953802 0 -0.9983918 0.0562371 0.007167935 -0.9999157 0.01299011 0 -0.9976206 -0.06894385 0 -0.9938825 -0.1102299 0.006844282 -0.9885133 -0.1511343 0 -0.9724099 -0.2332789 0 -0.9621278 -0.2725168 0.006688416 -0.9211608 -0.3891825 0 -0.9045306 -0.4263558 0.006727993 -0.8865184 -0.4626935 0 -0.8450701 -0.5346555 0 -0.8212294 -0.5705535 0.007144272 -0.7959123 -0.6054119 0 -0.7468982 -0.6649386 0 -0.7178292 -0.6961833 0.007074475 -0.6873556 -0.7263211 0 -0.6225327 -0.7825938 0 -0.5919957 -0.8059159 0.0063771 -0.5606843 -0.8280298 0 -0.4882431 -0.8727076 0 -0.4506959 -0.8926498 0.007044374 -0.4121255 -0.9111271 0 -0.340709 -0.9401689 0 -0.2980284 -0.9545279 0.007471263 -0.2546719 -0.9670276 0 -0.1811933 -0.9834475 0 -0.1383808 -0.9903531 0.00719285 -0.09522575 -0.9954558 0 -0.01296502 -0.999916 0 0.02812987 -0.9995813 0.006786167 0.06908392 -0.9976109 0 0.1902879 -0.9817063 0.006590783 0.2292692 -0.9733631 0 0.3148918 -0.9491276 0 0.3522893 -0.9358682 0.006576001 0.3892426 -0.9211353 0 0.4627283 -0.8865002 0 0.4991715 -0.8664759 0.006884694 0.5345906 -0.8451112 0 0.6028072 -0.7978869 0 0.6356934 -0.7719106 0.006922602 0.6672632 -0.744822 0 0.7263606 -0.6873139 0 0.7550759 -0.6555989 0.007101535 0.7825305 -0.6226123 0 0.8286958 -0.5596994 0 0.8514904 -0.5243245 0.006942331 0.8727316 -0.4882004 0 0.9266725 -0.3758063 0.006918609 0.9415076 -0.336992 0 0.965636 -0.2598985 0 0.9753664 -0.2204898 0.006686031 0.9834414 -0.1812267 0 0.9954926 -0.09483951 0 0.99852 -0.05396074 0.006797254 0.9999133 -0.01317089 0 0.9938826 0.1102299 0.006840109 0.9885133 0.1511343 0 0.9724099 0.2332789 0 0.9621514 0.2724334 0.006694197 0.9210961 0.3893353 0 0.9045653 0.426282 0.00672543 0.8865184 0.4626935 0 0.8438329 0.5366061 0 0.4975116 0.447328 -0.7432225 0.5133042 0.4341687 -0.7402813 0.5133046 0.4341678 -0.7402816 0.5133048 0.4341673 -0.7402817 0.4628667 0.4872596 -0.7404949 0.4626353 0.4863637 -0.741228 0.4166728 0.5266483 -0.7409626 0.4180353 0.5211834 -0.7440527 0.4178597 0.521047 -0.7442469 0.3721985 0.5547462 -0.744127 0.3722404 0.5553119 -0.7436839 0.3759661 0.554354 -0.7425236 0.327018 0.5843207 -0.742717 0.3270537 0.5833951 -0.7434286 0.2751728 0.6093649 -0.7436091 0.2769178 0.6068359 -0.745028 0.2802271 0.6086649 -0.7422937 0.2242241 0.6313852 -0.7423452 0.2231529 0.6302735 -0.7436116 0.2232137 0.6305771 -0.7433359 0.1728581 0.6459565 -0.7435458 0.173803 0.6421655 -0.746603 0.1304115 0.6523373 -0.7466251 0.1184585 0.6603239 -0.7415794 0.117805 0.6597231 -0.742218 0.06498265 0.6675016 -0.7417675 0.06599748 0.6689288 -0.7403909 0.0587002 0.6656262 -0.7439732 0.009080648 0.6683619 -0.7437809 0.008887112 0.6687228 -0.7434588 -0.04043287 0.6676323 -0.7433924 -0.04043281 0.6676325 -0.7433924 -0.04043287 0.6676325 -0.7433922 -0.04440325 0.6686503 -0.7422501 -0.04624617 0.6653843 -0.7450672 -0.1030029 0.6592184 -0.7448635 -0.1026473 0.6601306 -0.7441043 -0.09534591 0.667092 -0.7388488 -0.1585198 0.655335 -0.7385171 -0.1526877 0.6489037 -0.7453929 -0.1988136 0.6360685 -0.7455803 -0.2095212 0.6344517 -0.7440242 -0.2094455 0.6348996 -0.7436633 -0.2595459 0.6164401 -0.7433961 -0.2596641 0.6153044 -0.7442951 -0.2607823 0.6129166 -0.7458726 -0.3074302 0.5907173 -0.746016 -0.3092467 0.5920006 -0.7442458 -0.3562274 0.5645688 -0.7445564 -0.3584825 0.5658362 -0.7425091 -0.4072296 0.5321344 -0.7422919 -0.4024789 0.531621 -0.7452448 -0.4025388 0.531093 -0.745589 -0.4443981 0.4966664 -0.7455421 -0.4433754 0.4961173 -0.7465159 -0.4433754 0.4961174 -0.7465159 -0.4433753 0.4961172 -0.7465159 -0.4318643 0.5106483 -0.7434591 -0.4318644 0.5106484 -0.7434591 -0.4318643 0.5106483 -0.7434592 -0.4857267 0.4585205 -0.7441966 -0.4890983 0.459462 -0.7414025 -0.5233033 0.4203062 -0.7412803 -0.523777 0.4201738 -0.7410208 -0.5238914 0.4199821 -0.7410485 -0.5583869 0.372339 -0.7413284 -0.5554004 0.3722162 -0.7436299 -0.5542084 0.3760513 -0.7425891 -0.5542084 0.3760513 -0.7425891 -0.5542083 0.3760513 -0.7425892 -0.5844529 0.3269801 -0.7426297 -0.5801743 0.3269815 -0.7459765 -0.6072406 0.2743437 -0.7456504 -0.6059077 0.2751435 -0.7464395 -0.6086219 0.2799492 -0.7424338 -0.6308394 0.225105 -0.7425426 -0.6303172 0.2246387 -0.743127 -0.6304416 0.2232318 -0.7434453 -0.6452618 0.1757519 -0.7434707 -0.6488956 0.174854 -0.7405138 -0.6615304 0.1166852 -0.7407848 -0.6603941 0.1184463 -0.7415187 -0.6606851 0.1185883 -0.7412369 -0.6679343 0.06532603 -0.7413477 -0.6690136 0.06603276 -0.7403111 -0.6655067 0.05834561 -0.7441079 -0.6655067 0.05834567 -0.7441079 -0.6655067 0.05834567 -0.744108 -0.6682948 0.009036839 -0.7438417 -0.6688712 0.008894622 -0.7433251 -0.6677422 -0.03913068 -0.7433634 -0.6687035 -0.04447823 -0.7421976 -0.6649258 -0.04640114 -0.7454668 -0.6588 -0.09996414 -0.7456472 -0.6633865 -0.09835088 -0.7417854 -0.6596468 -0.1021719 -0.7445986 -0.6487811 -0.1568607 -0.7446328 -0.6479415 -0.1561096 -0.7455211 -0.6359152 -0.1991147 -0.7456308 -0.6345859 -0.2086759 -0.7441473 -0.6392657 -0.2075888 -0.7404366 -0.6187 -0.2616299 -0.7407835 -0.6136603 -0.2622033 -0.744762 -0.6220201 -0.2580686 -0.7392508 -0.5955135 -0.3146387 -0.7391659 -0.5920012 -0.3092244 -0.7442546 -0.564692 -0.3562326 -0.7444605 -0.565849 -0.358502 -0.7424899 -0.5343344 -0.4040303 -0.7424597 -0.5343117 -0.404468 -0.7422376 -0.5289723 -0.4051581 -0.7456777 -0.496697 -0.44438 -0.7455325 -0.4962974 -0.4434826 -0.7463325 -0.5102443 -0.4324229 -0.743412 -0.4585627 -0.4856669 -0.7442097 -0.4583798 -0.484817 -0.7448762 -0.4175492 -0.5198335 -0.745269 -0.4167892 -0.5232115 -0.743328 -0.4199659 -0.5236733 -0.7412118 -0.3763376 -0.5556818 -0.7413419 -0.3762767 -0.5539376 -0.7426769 -0.365258 -0.5576614 -0.7453861 -0.325672 -0.5820067 -0.7451215 -0.3257631 -0.5863355 -0.74168 -0.279998 -0.6100677 -0.7412278 -0.2790002 -0.6113994 -0.7405064 -0.2738481 -0.6087665 -0.7445875 -0.2261509 -0.6283645 -0.7443211 -0.2228949 -0.625587 -0.7476355 -0.2347882 -0.6266271 -0.7431104 -0.1728748 -0.6459546 -0.7435436 -0.1720135 -0.6495344 -0.7406191 -0.1190331 -0.6611259 -0.7407724 -0.1212673 -0.6596159 -0.7417554 -0.1170573 -0.6553771 -0.746176 -0.06478279 -0.6625158 -0.7462413 -0.06546783 -0.6635599 -0.7452532 -0.06839567 -0.6649212 -0.7437754 -0.009080111 -0.6684124 -0.7437355 -0.008850932 -0.6688476 -0.7433469 0.05873173 -0.6666775 -0.7430288 0.05873191 -0.6666779 -0.7430285 0.05873191 -0.6666779 -0.7430284 0.0470187 -0.6638822 -0.7463576 0.04645621 -0.6650522 -0.7453506 0.09998077 -0.6587674 -0.7456739 0.09833663 -0.6635717 -0.7416215 0.1021021 -0.6595223 -0.7447185 0.1540565 -0.6496357 -0.744473 0.1573551 -0.6531006 -0.7407423 0.2362464 -0.6301391 -0.7396704 0.2067274 -0.6349254 -0.7444015 0.2064958 -0.6358929 -0.7436395 0.2595258 -0.6163032 -0.7435165 0.2591903 -0.6197946 -0.740726 0.2631641 -0.6116567 -0.7460703 0.2631641 -0.6116567 -0.7460702 0.3098727 -0.5895504 -0.7459285 0.3114886 -0.5907562 -0.7442997 0.3562757 -0.5646454 -0.7444751 0.3585202 -0.5657709 -0.7425407 0.4072296 -0.5321344 -0.7422919 0.4024224 -0.531753 -0.7451812 0.4017176 -0.5373458 -0.7415406 0.4470853 -0.4997413 -0.7418717 0.4462814 -0.4994195 -0.742572 0.4531376 -0.4906386 -0.7442715 0.4531368 -0.4906378 -0.7442726 0.4531368 -0.4906377 -0.7442726 0.4842457 -0.4600117 -0.7442415 0.4877347 -0.4610537 -0.7413126 0.5266062 -0.4164208 -0.7411341 0.5210648 -0.418016 -0.7441466 0.5211197 -0.4179049 -0.7441706 0.5529838 -0.374552 -0.7442579 0.5545872 -0.3747002 -0.7429891 0.5540837 -0.3757486 -0.7428354 0.5856299 -0.3247991 -0.7426596 0.5844784 -0.3246017 -0.7436523 0.6053941 -0.2832356 -0.7438251 0.6113728 -0.2789779 -0.7405368 0.6100957 -0.2765198 -0.7425093 0.6299296 -0.227637 -0.742543 0.6255209 -0.2229293 -0.7476806 0.6264409 -0.2348168 -0.7432584 0.6462359 -0.1721047 -0.7434778 0.6481142 -0.1716088 -0.7419558 0.6600921 -0.119154 -0.7416743 0.6585577 -0.1210546 -0.7427299 0.6552779 -0.1177362 -0.7461563 0.6628636 -0.06162256 -0.7462002 0.6688361 -0.06545186 -0.740523 0.6658702 -0.05969798 -0.7436754 0.6684191 -0.01214307 -0.7436858 0.6687769 -0.01179099 -0.7433697 0.6665757 0.05858218 -0.7431319 0.6639386 0.04699897 -0.7463088 0.6653316 0.04618304 -0.7451182 0.659589 0.1001761 -0.7449209 0.6627502 0.09898424 -0.7422698 0.6596781 0.1021682 -0.7445713 0.6495254 0.1539345 -0.7445945 0.6518573 0.1563307 -0.7420532 0.6518573 0.1563306 -0.7420532 0.6323566 0.222863 -0.7419281 0.6323568 0.2228628 -0.7419281 0.6323568 0.2228627 -0.7419281 0.6349927 0.2067459 -0.7443389 0.635879 0.2064931 -0.7436522 0.6153473 0.2620825 -0.7434114 0.6089617 0.2629319 -0.7483533 0.6089616 0.262932 -0.7483533 0.6089617 0.2629319 -0.7483533 0.6200361 0.2574627 -0.7411262 0.5938706 0.3121459 -0.7415409 0.5936158 0.3115151 -0.7420099 0.5671246 0.3578659 -0.7418233 0.5667054 0.3571818 -0.742473 0.5320494 0.4070611 -0.7424452 0.5317025 0.4024761 -0.7451882 0.5373865 0.4018098 -0.7414612 0.4981142 0.4488135 -0.7419223 0.7741538 0.4061543 -0.4855148 0.7395564 0.4660914 -0.485608 0.7398167 0.4665956 -0.4847264 0.6973197 0.527928 -0.4848065 0.6979317 0.5301095 -0.4815344 0.6520808 0.5860738 -0.4809452 0.6515746 0.583404 -0.4848613 0.6026646 0.633494 -0.4852635 0.6028915 0.6372342 -0.4800568 0.548748 0.6841522 -0.4804284 0.5488615 0.6859205 -0.4777699 0.4889966 0.7296402 -0.4780247 0.4893283 0.7262735 -0.4827883 0.4282826 0.7639288 -0.4826871 0.4285401 0.7623537 -0.4849436 0.3630509 0.7957099 -0.4848092 0.3619313 0.8000279 -0.4784988 0.2938595 0.8273323 -0.4787147 0.2955856 0.8224194 -0.4860614 0.2283074 0.8436396 -0.4859507 0.2256721 0.8491177 -0.4775682 0.1551294 0.86484 -0.4774795 0.1564407 0.8624121 -0.481427 0.08493441 0.8722998 -0.4815387 0.083925 0.8738158 -0.4789597 0.01166546 0.8780273 -0.4784685 0.01513367 0.8736875 -0.4862521 -0.05786466 0.8715464 -0.4868865 -0.06112456 0.8750741 -0.4801138 -0.06112462 0.8750742 -0.4801138 -0.06112462 0.8750742 -0.4801138 -0.1353771 0.8665383 -0.4804004 -0.1326522 0.8640735 -0.4855722 -0.2002183 0.8507715 -0.4859018 -0.2014989 0.8516845 -0.4837683 -0.2744151 0.8309842 -0.4839025 -0.2744997 0.8312398 -0.4834155 -0.3396875 0.8070021 -0.4830737 -0.3396875 0.8070021 -0.4830736 -0.3396875 0.8070021 -0.4830736 -0.3433346 0.8087117 -0.4776055 -0.4068562 0.7787972 -0.4774338 -0.4041572 0.7774867 -0.4818417 -0.4041573 0.7774868 -0.4818416 -0.4041573 0.7774868 -0.4818418 -0.4692106 0.7405732 -0.4810332 -0.4713845 0.741389 -0.477639 -0.53022 0.7003197 -0.4779323 -0.5276265 0.6997009 -0.4816938 -0.5840294 0.6537318 -0.4811908 -0.5855074 0.6540398 -0.4789709 -0.6399114 0.6009455 -0.4789342 -0.6349323 0.6007587 -0.4857468 -0.6818678 0.5469759 -0.4856684 -0.6836658 0.546983 -0.483126 -0.7274403 0.4875519 -0.4828288 -0.7274446 0.4876211 -0.4827527 -0.7629868 0.4298693 -0.4827667 -0.7643737 0.4296783 -0.4807386 -0.7981376 0.3624932 -0.4812225 -0.7975834 0.3625367 -0.4821078 -0.8255029 0.2945435 -0.4814448 -0.822448 0.2954787 -0.4860777 -0.8437547 0.2273319 -0.4862082 -0.8481032 0.2254225 -0.4794847 -0.864028 0.155007 -0.4789869 -0.8625147 0.1557622 -0.4814627 -0.8723063 0.0852707 -0.4814671 -0.8693641 0.08734589 -0.4863918 -0.8734517 0.01152074 -0.4867747 -0.8735831 0.01154673 -0.4865379 -0.8717618 -0.05800932 -0.4864836 -0.8750232 -0.06080842 -0.4802465 -0.8670637 -0.1316765 -0.4804812 -0.8692944 -0.133975 -0.4757922 -0.8551912 -0.2060033 -0.475616 -0.8517996 -0.2016057 -0.483521 -0.8314934 -0.2733373 -0.4836378 -0.8315078 -0.2733486 -0.4836067 -0.8062224 -0.3410924 -0.4833853 -0.8070327 -0.3426319 -0.4809384 -0.7769387 -0.4057793 -0.4813621 -0.775756 -0.4031413 -0.4854686 -0.7384446 -0.4678248 -0.4856331 -0.7402595 -0.4730683 -0.4777261 -0.7002766 -0.5299935 -0.4782465 -0.7002766 -0.5299936 -0.4782465 -0.7002765 -0.5299935 -0.4782465 -0.698879 -0.5240609 -0.4867529 -0.6513609 -0.582035 -0.4867897 -0.6522576 -0.5873615 -0.4791309 -0.603061 -0.6377391 -0.4791724 -0.6030068 -0.6374498 -0.4796256 -0.546926 -0.6866083 -0.4789999 -0.5469793 -0.6837432 -0.4830205 -0.4920094 -0.724402 -0.4828752 -0.4916459 -0.7279775 -0.4778422 -0.4264766 -0.7677249 -0.4782431 -0.4268187 -0.7658294 -0.4809691 -0.363864 -0.7974917 -0.4812588 -0.3633563 -0.7993019 -0.478632 -0.297276 -0.8261089 -0.4787181 -0.2970942 -0.8266091 -0.477967 -0.2248823 -0.8492057 -0.4777843 -0.2277682 -0.8428231 -0.4876177 -0.1578965 -0.8587454 -0.487468 -0.1557854 -0.8624749 -0.4815269 -0.08529323 -0.8723245 -0.4814302 -0.08396089 -0.8741893 -0.4782714 -0.01161527 -0.8780814 -0.4783704 -0.01146209 -0.8782325 -0.4780966 0.06205385 -0.8761832 -0.4779669 0.06113898 -0.8752343 -0.4798197 0.1316884 -0.8677493 -0.4792382 0.1290712 -0.8653593 -0.4842458 0.2049717 -0.8508371 -0.4838006 0.2051215 -0.8509296 -0.4835742 0.2709611 -0.8322177 -0.4837293 0.2743221 -0.8343828 -0.478072 0.3406434 -0.8090656 -0.4789311 0.3394523 -0.8084666 -0.4807847 0.4089244 -0.7754892 -0.4810379 0.4060437 -0.7741991 -0.485535 0.4679037 -0.7384579 -0.4855369 0.4682811 -0.7386444 -0.4848889 0.5277746 -0.6973111 -0.4849857 0.5265473 -0.69693 -0.4868639 0.5265473 -0.6969301 -0.4868639 0.5265473 -0.6969301 -0.4868639 0.5820394 -0.6513266 -0.4868304 0.5873675 -0.6522523 -0.4791309 0.6379297 -0.6029129 -0.4791052 0.6373471 -0.6028625 -0.4799433 0.6840175 -0.5488962 -0.480451 0.6822231 -0.5488859 -0.4830073 0.7256126 -0.4901494 -0.4829491 0.7257508 -0.4902516 -0.4826378 0.7656978 -0.4251811 -0.482626 0.7639195 -0.4256653 -0.4850116 0.7957004 -0.3631438 -0.4847552 0.8000582 -0.3619298 -0.4784493 0.825744 -0.2985579 -0.4785498 0.8261345 -0.2982679 -0.4780567 0.8490951 -0.2250263 -0.4779132 0.8442925 -0.2269796 -0.4854383 0.8595883 -0.1581087 -0.4859112 0.8623933 -0.1564306 -0.4814637 0.872758 -0.08102339 -0.4813821 0.8691651 -0.08348113 -0.487425 0.8732176 -0.0155729 -0.4870817 0.878346 -0.01143378 -0.4778888 0.876271 0.06214904 -0.4777935 0.8750095 0.06071984 -0.4802827 0.8670637 0.1316765 -0.4804812 0.8686349 0.133374 -0.4771633 0.8542855 0.2048575 -0.4777339 0.8517425 0.2015047 -0.4836637 0.832203 0.2709084 -0.483784 0.8353586 0.2759648 -0.4754149 0.8094472 0.3447493 -0.4753348 0.8061133 0.3383854 -0.4854657 0.7744431 0.4067237 -0.4845759 0.7744431 0.4067237 -0.4845759 0.7744432 0.4067236 -0.4845759 0.8738179 0.4559991 -0.1688409 0.8335308 0.5258535 -0.1694242 0.832931 0.5296979 -0.160144 0.7860932 0.5970445 -0.1599854 0.7865383 0.595243 -0.1644487 0.7348758 0.6578081 -0.165064 0.7347979 0.6579364 -0.1648993 0.6778444 0.7165608 -0.1645227 0.6779741 0.7163189 -0.165041 0.6779741 0.7163189 -0.165041 0.6779741 0.7163188 -0.165041 0.6162799 0.7701255 -0.164639 0.6165279 0.7695939 -0.1661888 0.616528 0.7695939 -0.1661887 0.616528 0.7695938 -0.1661888 0.5509181 0.8178614 -0.1661088 0.5502501 0.8189098 -0.1631306 0.4834326 0.8599027 -0.163891 0.4820778 0.8616856 -0.1584264 0.4820778 0.8616856 -0.1584263 0.4068699 0.8995155 -0.1591504 0.4098016 0.8964045 -0.1688838 0.3334369 0.9275962 -0.1684789 0.3322658 0.928635 -0.1650353 0.3322658 0.928635 -0.1650353 0.3322657 0.928635 -0.1650354 0.2533813 0.9533062 -0.1643328 0.2550123 0.9520092 -0.1692553 0.1759184 0.9696791 -0.1696323 0.1752177 0.9701666 -0.1675577 0.09425747 0.9813258 -0.167676 0.09751307 0.9794961 -0.1762919 0.01704448 0.9840379 -0.1771407 0.01278388 0.9859618 -0.1664814 -0.06871235 0.9837665 -0.1657776 -0.06811106 0.9835225 -0.167465 -0.1495906 0.9744162 -0.1677374 -0.1489003 0.9742458 -0.1693336 -0.2269194 0.9590888 -0.1692818 -0.2302742 0.95961 -0.1616249 -0.3095377 0.9370695 -0.1615151 -0.3066337 0.9368223 -0.1683447 -0.3851162 0.9072965 -0.1688156 -0.3833823 0.9072375 -0.1730271 -0.4540753 0.8739635 -0.1732148 -0.4559292 0.8739063 -0.1685717 -0.4559292 0.8739064 -0.1685717 -0.4559292 0.8739063 -0.1685717 -0.5288431 0.8316968 -0.169132 -0.5289012 0.8316223 -0.169316 -0.5934469 0.7870533 -0.168428 -0.5952445 0.7865384 -0.1644422 -0.6578676 0.7348273 -0.1650432 -0.657889 0.7348254 -0.1649664 -0.7165068 0.6779434 -0.1643499 -0.7164285 0.6778544 -0.1650568 -0.7701744 0.6162271 -0.1646074 -0.7695873 0.6165344 -0.166195 -0.8191884 0.548905 -0.1662337 -0.8180303 0.5497785 -0.1690268 -0.8590606 0.4831234 -0.1691356 -0.8590605 0.4831233 -0.1691356 -0.8590606 0.4831234 -0.1691356 -0.8608464 0.4817205 -0.1639781 -0.898128 0.408186 -0.1635558 -0.8978314 0.408553 -0.1642658 -0.9282182 0.3334916 -0.1649076 -0.9280859 0.3337993 -0.1650289 -0.9532701 0.2534145 -0.1644909 -0.9520575 0.2548292 -0.1692592 -0.9698801 0.1750978 -0.1693322 -0.9698801 0.1750978 -0.1693322 -0.9698802 0.1750978 -0.1693322 -0.9702624 0.1745164 -0.1677348 -0.9808888 0.09851837 -0.1677836 -0.9811094 0.09811568 -0.1667268 -0.985944 0.01280701 -0.1665846 -0.985998 0.01275211 -0.1662691 -0.9837656 -0.06844496 -0.1658937 -0.9836434 -0.06796646 -0.166812 -0.9745586 -0.1504051 -0.1661748 -0.9742301 -0.1488656 -0.1694543 -0.9590477 -0.2269106 -0.1695259 -0.9596258 -0.2302324 -0.1615903 -0.9375545 -0.3080542 -0.1615373 -0.9375545 -0.3080542 -0.1615373 -0.9375545 -0.3080541 -0.1615373 -0.9374271 -0.3067524 -0.1647225 -0.907938 -0.3854354 -0.1645856 -0.9079282 -0.3836281 -0.1688077 -0.8747023 -0.4545047 -0.1682896 -0.8744962 -0.4565291 -0.1638223 -0.8312542 -0.5313503 -0.1633507 -0.8321062 -0.5263041 -0.1749387 -0.787661 -0.5907294 -0.1750114 -0.7858443 -0.5979447 -0.1578322 -0.733763 -0.6608489 -0.1577045 -0.735787 -0.6550205 -0.1719472 -0.6770288 -0.7155233 -0.1722166 -0.6770646 -0.7153803 -0.1726693 -0.6152042 -0.769131 -0.1730937 -0.6139566 -0.7716238 -0.1662952 -0.5518694 -0.8171725 -0.1663411 -0.5526182 -0.8161211 -0.1689958 -0.4797619 -0.8609352 -0.1691717 -0.4808079 -0.8595365 -0.1732655 -0.4075481 -0.8966256 -0.17311 -0.4062731 -0.8980178 -0.1688377 -0.3334665 -0.9275336 -0.1687646 -0.3334667 -0.9275336 -0.1687646 -0.3334666 -0.9275336 -0.1687646 -0.3354735 -0.9256368 -0.175083 -0.2568864 -0.9505158 -0.1747264 -0.2568864 -0.9505158 -0.1747263 -0.2568864 -0.9505158 -0.1747264 -0.2515021 -0.9546974 -0.1590586 -0.2515021 -0.9546974 -0.1590586 -0.2515021 -0.9546974 -0.1590586 -0.1754996 -0.9715447 -0.1590628 -0.1785982 -0.9695728 -0.1674258 -0.09426021 -0.9813547 -0.1675056 -0.09388637 -0.9814875 -0.1669365 -0.01287114 -0.9859592 -0.1664902 -0.01278203 -0.9859952 -0.166283 0.06870961 -0.9837061 -0.166137 0.06870967 -0.9837061 -0.166137 0.06870961 -0.9837061 -0.166137 0.06811207 -0.9835366 -0.1673817 0.1454229 -0.975058 -0.1676728 0.1491656 -0.9759811 -0.1587784 0.2313818 -0.9597444 -0.1592267 0.2258408 -0.9588903 -0.1718291 0.307653 -0.9358621 -0.1717904 0.307653 -0.9358621 -0.1717904 0.307653 -0.9358621 -0.1717904 0.3106104 -0.9361615 -0.1646902 0.3818185 -0.9094471 -0.1646836 0.3842464 -0.9094538 -0.1588978 0.4586155 -0.8742758 -0.1591027 0.4564486 -0.8745203 -0.163918 0.5282937 -0.8331765 -0.1634713 0.5271673 -0.8334142 -0.1658781 0.5944268 -0.786735 -0.1664482 0.5943486 -0.7867947 -0.1664457 0.659855 -0.7328507 -0.1658954 0.6573767 -0.7336811 -0.1719537 0.7155343 -0.6770232 -0.1721929 0.7154446 -0.6769235 -0.1729562 0.7673575 -0.6173949 -0.1731653 0.7725916 -0.6145718 -0.1593859 0.8179094 -0.5525974 -0.1601884 0.8180237 -0.5524775 -0.1600182 0.8624003 -0.4804331 -0.1595298 0.8609464 -0.4816021 -0.1638009 0.8988708 -0.4065929 -0.163443 0.8971359 -0.4082279 -0.1688116 0.9270657 -0.3347914 -0.168713 0.9292718 -0.3323464 -0.1612447 0.95293 -0.2565631 -0.1615543 0.9529539 -0.2563858 -0.1616948 0.9711061 -0.176205 -0.1609497 0.9695594 -0.1785669 -0.167537 0.9813464 -0.09417974 -0.1675988 0.9817231 -0.09357404 -0.1657221 0.9859688 -0.0128073 -0.166438 0.9859916 -0.01292699 -0.1662931 0.9836116 0.06843423 -0.1668086 0.9835335 0.06813293 -0.1673918 0.9744285 0.1495521 -0.1676995 0.9742247 0.1490389 -0.1693337 0.9590762 0.2269173 -0.1693556 0.9596207 0.2302311 -0.1616221 0.9370883 0.3094454 -0.1615836 0.9367907 0.3067175 -0.1683678 0.908744 0.3816778 -0.1688382 0.908744 0.3816778 -0.1688382 0.908744 0.3816778 -0.1688382 0.9088166 0.3840023 -0.1630787 0.8735768 0.4583014 -0.1637792 0.1976645 -0.4595724 -0.8658648 0.1543 -0.4751735 -0.8662574 0.03487819 -0.4987909 -0.8660203 0.03487819 -0.4987909 -0.8660203 0.03487825 -0.498791 -0.8660203 -0.1755781 -0.4686514 -0.8657588 -0.2733954 -0.4175827 -0.8665332 -0.3814868 -0.3233941 -0.8659585 -0.3814868 -0.3233942 -0.8659585 -0.3814868 -0.3233942 -0.8659585 -0.3975628 -0.3045583 -0.8655566 -0.4219548 -0.2662343 -0.866645 -0.462242 -0.1917786 -0.8657675 -0.4751411 -0.1542525 -0.8662837 -0.4986406 -0.03488165 -0.8661068 -0.4917695 0.08836823 -0.8662298 -0.4135798 0.2806365 -0.866138 -0.4135798 0.2806364 -0.8661381 -0.4135798 0.2806364 -0.866138 -0.3225406 0.3809352 -0.8665194 -0.3225406 0.3809352 -0.8665195 -0.3225405 0.3809353 -0.8665194 -0.3025032 0.3991161 -0.8655624 -0.265965 0.421498 -0.8669499 -0.1959111 0.4603342 -0.8658587 -0.1562212 0.4735174 -0.8668196 -0.03467273 0.498625 -0.8661242 0.1669694 0.4713447 -0.8659997 0.2806146 0.4136872 -0.8660937 0.2806147 0.4136873 -0.8660937 0.2806146 0.4136874 -0.8660936 0.3818728 0.3229968 -0.8659366 0.3818727 0.3229972 -0.8659366 0.3818726 0.3229977 -0.8659364 0.4011156 0.2998793 -0.8655511 0.4214702 0.265864 -0.8669944 0.4621503 0.1917536 -0.865822 0.4748592 0.1542448 -0.8664394 0.4986268 0.03460502 -0.8661258 0.4917267 -0.08836054 -0.8662547 0.413124 -0.2804312 -0.8664219 0.3383899 -0.3663665 -0.8667572 0.3383899 -0.3663664 -0.8667572 0.3383899 -0.3663665 -0.8667572 0.2997968 -0.4012872 -0.8655003 0.2659741 -0.4215891 -0.8669028 -0.06800013 -0.1645118 -0.9840284 0.06061673 -0.2240234 -0.9726969 -0.05860215 0.2260154 -0.9723595 -0.1798125 0.1530055 -0.9717288 -0.2064685 0.2741736 -0.9392548 -0.1683713 0.1619641 -0.9723265 -0.1894234 0.2314116 -0.9542366 -0.02567136 0.2605644 -0.9651152 -0.1724721 0.1613407 -0.9717112 -0.02072077 0.2103244 -0.9774121 0.01003378 0.1788997 -0.9838162 0.02609795 0.1760834 -0.9840292 0.01107317 0.1772826 -0.9840977 0.1562428 0.1807482 -0.9710398 0.2794297 0.2042802 -0.9381837 0.1619148 0.1683486 -0.9723387 0.1619148 0.1683484 -0.9723386 0.1619147 0.1683486 -0.9723386 0.2307086 0.1892005 -0.954451 0.2307085 0.1892004 -0.9544511 0.2307085 0.1892003 -0.9544511 0.2600705 0.0256136 -0.96525 0.1614359 0.1717034 -0.9718315 0.2124134 0.02090382 -0.9769563 0.1795605 -0.01122486 -0.983683 0.1758514 -0.02423495 -0.9841184 0.176823 -0.01032322 -0.9841886 0.1768231 -0.01032328 -0.9841886 0.1768231 -0.01032328 -0.9841886 0.1817325 -0.155477 -0.970979 0.2044078 -0.2916956 -0.9344149 0.2044078 -0.2916957 -0.9344149 0.2044078 -0.2916957 -0.9344149 0.1613481 -0.1662248 -0.9727982 0.1613481 -0.1662249 -0.9727982 0.1613481 -0.1662248 -0.9727981 0.1798689 -0.2321712 -0.9558994 0.02755028 -0.2596616 -0.9653067 0.1644899 -0.166386 -0.9722443 0.02251267 -0.212107 -0.9769871 -0.01003265 -0.1790059 -0.9837968 -0.02388972 -0.1758492 -0.9841273 -0.01110929 -0.1771004 -0.9841301 -0.1531386 -0.1798948 -0.9716926 -0.2797278 -0.204661 -0.938012 -0.2797279 -0.2046609 -0.938012 -0.2797278 -0.2046609 -0.938012 -0.1661942 -0.1608733 -0.972882 -0.1661942 -0.1608732 -0.972882 -0.1661942 -0.1608732 -0.972882 -0.2327573 -0.1800513 -0.9557225 -0.2605896 -0.02566432 -0.9651086 -0.1667785 -0.1566878 -0.973465 -0.210301 -0.02069592 -0.9774176 -0.1795653 0.009500324 -0.9837002 -0.1760758 0.02604603 -0.984032 -0.177316 0.01106792 -0.9840918 -0.177316 0.01106786 -0.9840918 -0.177316 0.01106792 -0.9840918 0.3044044 -0.3976645 -0.8655641 0.2721312 -0.4125788 -0.8693236 0.2330432 -0.3533695 -0.9059917 0.1886013 -0.3790248 -0.9059635 0.1528066 -0.3071004 -0.9393293 0.1168901 -0.3223766 -0.9393669 0.3326382 -0.3718091 -0.866666 0.319759 -0.3765509 -0.8694618 0.2736442 -0.3223155 -0.9062183 0.2336313 -0.3522633 -0.906271 0.1898421 -0.2862246 -0.9391674 0.152116 -0.3079849 -0.9391518 0.3909558 -0.313575 -0.8653464 0.3930671 -0.3107516 -0.8654084 0.3584712 -0.3405089 -0.8692251 0.3652361 -0.3383923 -0.8672332 0.3103188 -0.2875208 -0.9061094 0.2733818 -0.3229069 -0.906087 0.2218375 -0.2620506 -0.9392112 0.1900173 -0.2859717 -0.9392091 0.4131041 -0.2797867 -0.8666398 0.4018658 -0.2880607 -0.8692093 0.3435754 -0.2462776 -0.9062578 0.3104972 -0.2867714 -0.9062857 0.252063 -0.2327525 -0.9393032 0.2220683 -0.2616 -0.9392822 0.4547168 -0.2060335 -0.8664773 0.452262 -0.2117671 -0.8663798 0.4522621 -0.211767 -0.8663797 0.4522621 -0.211767 -0.8663797 0.4330786 -0.2401522 -0.868775 0.4349452 -0.2388622 -0.8681979 0.3707848 -0.203647 -0.9061163 0.3435394 -0.2466373 -0.9061737 0.2788709 -0.2002089 -0.9392271 0.2519735 -0.2331986 -0.9392166 0.2036523 -0.1885128 -0.960723 0.1794354 -0.2113745 -0.9607933 0.1641684 -0.2102954 -0.9637556 0.1477963 -0.2223974 -0.9636886 0.1730583 -0.2251465 -0.9588326 0.1250787 -0.2531855 -0.959298 0.1008906 -0.2480404 -0.9634818 0.09142369 -0.2521947 -0.9633482 0.1058105 -0.2573265 -0.9605141 0.1073237 -0.2566061 -0.9605389 0.2183877 -0.1448232 -0.9650561 0.2124339 -0.1521225 -0.965262 0.278957 -0.1998351 -0.9392811 0.3007391 -0.1652546 -0.93928 0.3707787 -0.2037023 -0.9061062 0.3923503 -0.1581829 -0.9061123 0.4575843 -0.1844987 -0.8698143 0.4786683 -0.1275369 -0.8686836 0.468066 -0.1755568 -0.8660798 0.4680659 -0.1755568 -0.8660798 0.468066 -0.1755567 -0.8660798 0.4707401 -0.1677561 -0.8661766 0.4915831 -0.08855491 -0.8663164 0.4915831 -0.08855485 -0.8663164 0.4915831 -0.08855485 -0.8663164 0.4789348 -0.1286787 -0.8683682 0.4088044 -0.1098445 -0.9059874 0.3924263 -0.1588107 -0.9059696 0.3181533 -0.1287234 -0.9392597 0.300679 -0.1654278 -0.9392688 0.2291199 -0.1260259 -0.9652055 0.2122434 -0.1527237 -0.965209 0.1461095 -0.1051492 -0.9836644 0.06102281 -0.2244207 -0.9725799 0.1608898 -0.07976132 -0.9837443 0.1570096 -0.08658969 -0.9837939 0.2290912 -0.1264371 -0.9651585 0.2426785 -0.09758263 -0.9651864 0.3181006 -0.1280077 -0.9393754 0.3314382 -0.08768647 -0.9393933 0.4083788 -0.1080168 -0.906399 0.4183429 -0.05933046 -0.9063494 0.489029 -0.06935453 -0.8695061 0.4956043 -0.00893706 -0.8685026 0.4978075 -0.04453986 -0.8661432 0.4974722 -0.04853451 -0.8661212 0.4974722 -0.04853451 -0.8661212 0.4974722 -0.04853445 -0.8661212 0.4982494 0.04391986 -0.8659207 0.4965462 -0.01070785 -0.8679443 0.4229309 -0.009175539 -0.9061155 0.4187188 -0.06028497 -0.9061129 0.3402797 -0.04905557 -0.9390439 0.3318728 -0.08997654 -0.9390233 0.2526762 -0.06852626 -0.9651212 0.2426198 -0.09866315 -0.9650913 0.1646593 -0.06697946 -0.9840738 0.1573342 -0.08240473 -0.9841014 0.1609993 -0.08045333 -0.9836699 0.1609992 -0.08045315 -0.9836699 0.1609993 -0.08045327 -0.98367 0.1646202 -0.06713801 -0.9840695 0.1718344 -0.04562056 -0.9840691 0.2525662 -0.06714147 -0.9652473 0.2588617 -0.03594195 -0.9652456 0.3397322 -0.04713046 -0.9393406 0.3430173 -0.005953371 -0.9393103 0.4220031 -0.007271885 -0.9065653 0.4200379 0.0424965 -0.906511 0.4919571 0.04978752 -0.8691947 0.4811379 0.1141079 -0.8691869 0.4945153 0.07679611 -0.8657696 0.4945154 0.07679605 -0.8657696 0.4945154 0.07679611 -0.8657696 0.4947816 0.07382732 -0.8658757 0.4711917 0.1660459 -0.8662605 0.4711918 0.1660459 -0.8662605 0.4711918 0.1660459 -0.8662605 0.4855296 0.1092973 -0.8673611 0.412134 0.09276068 -0.906389 0.4203664 0.04196083 -0.9063838 0.3420363 0.03415316 -0.9390659 0.343689 -0.007483005 -0.9390538 0.2617517 -0.005764067 -0.9651181 0.2592407 -0.03749459 -0.9650847 0.1759787 -0.02547538 -0.9840643 0.1718267 -0.04571849 -0.9840658 0.4594692 0.1982819 -0.8657785 0.4645456 0.1666266 -0.8697316 0.3974187 0.142594 -0.9064907 0.4116688 0.09335374 -0.9065396 0.3352563 0.07596254 -0.9390596 0.3421331 0.03405481 -0.9390342 0.2599394 0.02585649 -0.9652788 0.2611607 -0.003956615 -0.9652873 0.1797056 -0.002769351 -0.9837166 0.177266 -0.007523655 -0.9841343 0.4411742 0.2319143 -0.8669378 0.4421986 0.2201806 -0.8694716 0.3788827 0.1886775 -0.9060071 0.3991811 0.1409935 -0.9059665 0.324335 0.1145467 -0.9389813 0.3357067 0.07547533 -0.938938 0.2822529 0.06336832 -0.9572449 0.2551837 0.005682945 -0.966876 0.3976839 0.304355 -0.8655723 0.4126634 0.2721578 -0.8692752 0.3534097 0.2331194 -0.9059564 0.379047 0.188548 -0.9059653 0.3071102 0.1528093 -0.9393256 0.3226869 0.1163024 -0.9393333 0.3710534 0.3345164 -0.8662669 0.3766226 0.3197451 -0.8694357 0.3222847 0.2736528 -0.9062266 0.3522841 0.233535 -0.9062876 0.2858905 0.1896435 -0.9393093 0.3072628 0.1526925 -0.9392948 0.3126022 0.3898484 -0.8661975 0.3099956 0.391909 -0.8662045 0.3395698 0.3574026 -0.8700321 0.3365491 0.3670141 -0.8671998 0.2855913 0.3113819 -0.9063549 0.3214446 0.2740527 -0.9064043 0.2613831 0.2227931 -0.939171 0.2865902 0.1891286 -0.9391999 0.2784388 0.4149126 -0.8662098 0.2896005 0.3997704 -0.869664 0.2482501 0.3426705 -0.9060623 0.2870717 0.3109797 -0.9060252 0.2330796 0.2525056 -0.9391033 0.2620083 0.222421 -0.939085 0.2091412 0.4542489 -0.8659781 0.2058324 0.4557511 -0.8659815 0.2058324 0.4557511 -0.8659816 0.2058324 0.455751 -0.8659815 0.2417376 0.4319667 -0.8688888 0.2393063 0.4356666 -0.8677138 0.2032575 0.3700747 -0.906494 0.2462468 0.3429614 -0.9064988 0.2002528 0.2788488 -0.9392243 0.2320744 0.252807 -0.9392711 0.1869319 0.2036929 -0.9610233 0.2105888 0.1787579 -0.9610921 0.2096513 0.1649826 -0.9637567 0.2228863 0.1470791 -0.9636854 0.2258783 0.1734985 -0.9585809 0.2533799 0.125952 -0.9591323 0.2480928 0.1008512 -0.9634724 0.2523394 0.09094762 -0.9633554 0.257492 0.105206 -0.9605361 0.2585904 0.1019236 -0.960595 0.1668821 0.4714313 -0.8659694 0.1844545 0.4575549 -0.8698392 0.1581593 0.3923679 -0.9061087 0.2051972 0.3700824 -0.9060536 0.1666787 0.3005898 -0.9390761 0.2014222 0.2786576 -0.939031 0.153325 0.2120866 -0.965148 0.1465954 0.2175409 -0.9649798 0.226143 0.05855047 -0.9723328 0.0878337 0.4918787 -0.866222 0.09784233 0.4900693 -0.866175 0.09784233 0.4900692 -0.866175 0.09784233 0.4900692 -0.8661751 0.1284409 0.4799707 -0.8678313 0.1288509 0.4796965 -0.8679221 0.109599 0.4078844 -0.9064318 0.1568622 0.3922381 -0.9063905 0.1274732 0.318761 -0.9392242 0.16539 0.3007092 -0.9392657 0.1260204 0.2291195 -0.9652063 0.1527447 0.2122341 -0.9652077 0.1032921 0.1435288 -0.984241 0.225878 0.05798918 -0.9724282 0.225878 0.05798918 -0.9724282 0.225878 0.05798918 -0.9724281 0.08108389 0.1600989 -0.9837651 0.08606761 0.1573457 -0.9837859 0.1253684 0.2292652 -0.9652566 0.09756475 0.2424548 -0.9652444 0.1282644 0.3187153 -0.939132 0.08925849 0.331742 -0.939138 0.1097681 0.4080479 -0.9063377 0.05912679 0.4183714 -0.9063495 0.06912529 0.4891029 -0.8694828 0.006734132 0.4955108 -0.8685758 0.04389691 0.4979145 -0.8661145 0.04908359 0.4974126 -0.8661245 -0.03019374 0.4988623 -0.8661552 -0.03019374 0.4988623 -0.8661552 -0.0301938 0.4988626 -0.8661549 0.01073628 0.4974818 -0.867408 0.00910294 0.4220482 -0.9065276 0.05844521 0.4181556 -0.9064933 0.0474981 0.3398088 -0.9392944 0.08802735 0.3315281 -0.9393298 0.06707543 0.252533 -0.9652606 0.0973773 0.2424904 -0.9652544 0.06631338 0.1651077 -0.9840437 0.08225548 0.1576309 -0.9840664 0.08051723 0.1610345 -0.983659 0.06523716 0.1652969 -0.984084 0.04687207 0.1714106 -0.9840841 0.06911015 0.2528265 -0.9650402 0.0374372 0.2591593 -0.9651088 0.04915744 0.3403417 -0.9390161 0.00742799 0.343622 -0.9390788 0.009118854 0.4220573 -0.9065233 -0.04260367 0.4199343 -0.906554 -0.04990363 0.4920318 -0.8691459 -0.116135 0.4801142 -0.8694844 -0.07087427 0.496212 -0.8653037 -0.07702034 0.4950419 -0.8654487 -0.1486351 0.4758813 -0.8668591 -0.1486351 0.4758812 -0.8668592 -0.1486351 0.4758821 -0.8668587 -0.1106218 0.4851937 -0.8673811 -0.09390616 0.4119038 -0.9063757 -0.04203051 0.4203786 -0.9063748 -0.03420358 0.3420085 -0.9390743 0.007512032 0.3437068 -0.939047 0.005716025 0.2611524 -0.9652807 0.03528529 0.2587113 -0.96531 0.02398717 0.1758691 -0.9841213 0.04557979 0.1714724 -0.984134 -0.1945464 0.4609762 -0.8658249 -0.1658955 0.4656089 -0.8693026 -0.1418873 0.3982523 -0.9062357 -0.09346395 0.412358 -0.9062149 -0.07583087 0.3345444 -0.9393241 -0.03580492 0.341097 -0.939346 -0.02727907 0.259901 -0.96525 0.005941152 0.261251 -0.9652526 0.004070699 0.1791111 -0.9838204 0.006524264 0.1778238 -0.9840408 -0.230132 0.442167 -0.866907 -0.2205871 0.4430072 -0.8689569 -0.1883337 0.3782552 -0.9063407 -0.1423115 0.3976781 -0.9064214 -0.1156787 0.3233169 -0.9391937 -0.07527583 0.3349631 -0.9392195 -0.06388306 0.2843112 -0.9566014 -0.004264771 0.256002 -0.9666669 -0.3044686 0.3975812 -0.8655796 -0.2721176 0.4126793 -0.86928 -0.2326393 0.3527629 -0.9063318 -0.1882371 0.3782929 -0.9063451 -0.1531023 0.3076946 -0.9390867 -0.1148998 0.3239897 -0.9390574 -0.3326479 0.37176 -0.8666833 -0.321103 0.3760905 -0.8691655 -0.2745555 0.321593 -0.9061994 -0.2324169 0.3531886 -0.906223 -0.188539 0.286526 -0.9393381 -0.1541573 0.3064537 -0.9393198 -0.3904617 0.3130532 -0.8657583 -0.3902385 0.3135881 -0.8656653 -0.3596292 0.3395531 -0.8691205 -0.3647471 0.3379463 -0.8676128 -0.3102967 0.2874497 -0.9061395 -0.2744326 0.3219921 -0.9060949 -0.2227461 0.2613765 -0.939184 -0.1879205 0.2875488 -0.9391494 -0.4157586 0.2771497 -0.8662176 -0.4013727 0.2877678 -0.8695341 -0.3429483 0.2458282 -0.9066174 -0.3109024 0.2853807 -0.9065857 -0.2532491 0.2323731 -0.9390782 -0.2224407 0.261992 -0.9390848 -0.4546643 0.2093523 -0.865709 -0.4560916 0.20621 -0.8657124 -0.4324287 0.2419261 -0.8686065 -0.4353348 0.2400605 -0.8676719 -0.3700754 0.2040306 -0.9063199 -0.3427777 0.2474886 -0.9062301 -0.2783226 0.200923 -0.9392371 -0.2536448 0.2311013 -0.9392851 -0.2052429 0.1870119 -0.9606778 -0.1794376 0.2113189 -0.9608051 -0.1641841 0.2103065 -0.9637503 -0.1461296 0.2235953 -0.9636656 -0.1722635 0.2265368 -0.9586482 -0.1271278 0.2527657 -0.9591392 -0.1003374 0.2469756 -0.963813 -0.0892775 0.2517144 -0.963675 -0.1051729 0.2575026 -0.960537 -0.1096034 0.2561544 -0.960402 -0.2183158 0.1461768 -0.9648682 -0.2123444 0.1535527 -0.9650552 -0.2782677 0.201247 -0.9391841 -0.3006952 0.1658785 -0.9391841 -0.3701029 0.2041568 -0.9062802 -0.392047 0.1580602 -0.906265 -0.4579263 0.1845761 -0.8696178 -0.4792823 0.1305224 -0.8679012 -0.4712339 0.1668781 -0.8660777 -0.4711084 0.1677882 -0.86597 -0.4920282 0.08675599 -0.8662458 -0.4788137 0.1281697 -0.8685103 -0.4080799 0.1092422 -0.9063869 -0.3920174 0.1574712 -0.9063802 -0.3187506 0.1280918 -0.9391436 -0.3006328 0.1663466 -0.9391213 -0.2287709 0.1266247 -0.9652099 -0.2128362 0.1517971 -0.9652246 -0.1439886 0.1026573 -0.9842403 -0.05827355 0.2259292 -0.9723992 -0.1602123 0.08154928 -0.9837082 -0.15732 0.08675873 -0.9837294 -0.2288113 0.1261546 -0.9652619 -0.242715 0.09711635 -0.9652243 -0.3187003 0.1274963 -0.9392417 -0.3315544 0.08922576 -0.9392074 -0.4082393 0.1098936 -0.9062364 -0.4184372 0.05928266 -0.906309 -0.489029 0.06935453 -0.8695061 -0.4954811 0.006796598 -0.8685922 -0.4977867 0.04388403 -0.8661887 -0.4973661 0.04904067 -0.8661536 -0.4986537 -0.02897709 -0.8663169 -0.4975183 0.0106678 -0.867388 -0.422955 0.009114861 -0.9061049 -0.418845 0.06037867 -0.9060482 -0.3395431 0.04891437 -0.9393178 -0.3314181 0.08849853 -0.9393243 -0.2530189 0.06760716 -0.9650963 -0.2426214 0.09859967 -0.9650974 -0.1646603 0.06688386 -0.9840801 -0.1575989 0.08177584 -0.9841115 -0.1660404 0.07753008 -0.9830665 -0.1647973 0.06594783 -0.9841203 -0.1715715 0.04555147 -0.9841181 -0.2529774 0.0671218 -0.965141 -0.2591201 0.03722047 -0.9651277 -0.3395034 0.04878652 -0.9393388 -0.3430038 0.005916178 -0.9393154 -0.4220418 0.007345795 -0.9065467 -0.4200052 -0.04243063 -0.9065293 -0.4920212 -0.0496717 -0.8691651 -0.4804072 -0.1161429 -0.8693215 -0.4943143 -0.07657116 -0.8659044 -0.4949203 -0.07342731 -0.8658304 -0.476642 -0.1491269 -0.8663566 -0.4865078 -0.1095175 -0.8667849 -0.4119537 -0.09265899 -0.9064815 -0.4202517 -0.04209631 -0.9064306 -0.3420119 -0.03422433 -0.9390723 -0.3436711 0.007570743 -0.9390596 -0.2611846 0.005736768 -0.9652719 -0.2587457 0.03562539 -0.9652884 -0.1758933 0.02421104 -0.9841116 -0.1715473 0.04559189 -0.9841204 -0.4601269 -0.1964775 -0.8658405 -0.4648662 -0.1668679 -0.869514 -0.3974091 -0.1425946 -0.9064948 -0.4117804 -0.09296786 -0.9065285 -0.3347915 -0.0754857 -0.9392639 -0.3412154 -0.03563469 -0.9393095 -0.2598753 -0.02714794 -0.9652606 -0.2612324 0.005917072 -0.9652578 -0.1796944 0.004085481 -0.9837141 -0.1776592 0.008063375 -0.984059 -0.4411134 -0.2329322 -0.8666958 -0.4421928 -0.2202382 -0.8694601 -0.3785695 -0.1885206 -0.9061706 -0.3986554 -0.1414552 -0.906126 -0.3235419 -0.1148288 -0.9392205 -0.3349703 -0.0752567 -0.9392185 -0.2838771 -0.06379085 -0.9567364 -0.2559176 -0.004312813 -0.966689 -0.3994156 -0.3017264 -0.8656954 -0.3994156 -0.3017264 -0.8656954 -0.4130843 -0.2724379 -0.8689873 -0.3523357 -0.2324097 -0.9065568 -0.377155 -0.1894451 -0.9065675 -0.3068804 -0.1541694 -0.9391786 -0.3235856 -0.1148167 -0.9392068 -0.3723662 -0.3331131 -0.8662443 -0.376775 -0.3213881 -0.8687637 -0.3212718 -0.2740181 -0.906476 -0.3527711 -0.2321614 -0.9064512 -0.287392 -0.1890826 -0.9389643 -0.3081915 -0.1531482 -0.9389162 -0.3130706 -0.3904424 -0.8657608 -0.3133348 -0.3900373 -0.8658477 -0.3133348 -0.3900373 -0.8658478 -0.3133347 -0.3900373 -0.8658477 -0.3395111 -0.3595647 -0.8691636 -0.3375249 -0.366073 -0.8672183 -0.286352 -0.3105593 -0.9063971 -0.3214457 -0.2739802 -0.9064258 -0.2613715 -0.2226729 -0.9392027 -0.2859563 -0.1901021 -0.9391967 -0.2798365 -0.4130386 -0.8666549 -0.2887116 -0.4009994 -0.8693936 -0.2469796 -0.3429549 -0.9063019 -0.2867316 -0.3105617 -0.9062761 -0.2331444 -0.2524533 -0.9391013 -0.2620285 -0.2224848 -0.9390643 -0.2052236 -0.4561944 -0.8658927 -0.208625 -0.4545589 -0.8659399 -0.241962 -0.4323676 -0.8686269 -0.2404879 -0.434647 -0.8678985 -0.2047538 -0.3701051 -0.9061446 -0.2475665 -0.3429304 -0.9061509 -0.2011951 -0.2787098 -0.9390642 -0.2335146 -0.2523198 -0.9390451 -0.1884956 -0.2036815 -0.9607202 -0.2113407 -0.1794544 -0.9607973 -0.2102653 -0.1641191 -0.9637705 -0.2224088 -0.1478375 -0.9636797 -0.2253039 -0.1743536 -0.9585609 -0.253381 -0.1258982 -0.9591391 -0.2474767 -0.09809106 -0.9639157 -0.2513477 -0.08919095 -0.9637786 -0.2580615 -0.1080296 -0.9600698 -0.2598755 -0.1026582 -0.9601698 -0.1678162 -0.4710913 -0.8659738 -0.1832458 -0.4589309 -0.8693696 -0.1564386 -0.3918866 -0.9066157 -0.2023719 -0.3700516 -0.9067015 -0.1646448 -0.3010879 -0.9392753 -0.1997864 -0.2789454 -0.9392949 -0.1521523 -0.2123939 -0.9652661 -0.145718 -0.2176408 -0.96509 -0.2244001 -0.06121563 -0.9725725 -0.08780711 -0.49173 -0.8663091 -0.08850216 -0.4913399 -0.8664597 -0.1281523 -0.4788208 -0.8685089 -0.1281588 -0.4787748 -0.8685334 -0.1094605 -0.4089768 -0.9059561 -0.1594523 -0.392192 -0.9059584 -0.1293514 -0.3181263 -0.9391826 -0.1655463 -0.3010865 -0.9391173 -0.1261223 -0.2293154 -0.9651465 -0.1532105 -0.2121856 -0.9651445 -0.105434 -0.1459693 -0.9836548 -0.22426 -0.06104195 -0.9726158 -0.08070755 -0.1599459 -0.9838209 -0.08546197 -0.1573941 -0.983831 -0.124678 -0.2295958 -0.9652674 -0.09828078 -0.2421606 -0.9652457 -0.1291388 -0.3181546 -0.9392023 -0.08782917 -0.3319752 -0.9391905 -0.1080991 -0.4085649 -0.9063053 -0.05934989 -0.4184204 -0.9063124 -0.06935942 -0.489003 -0.8695203 -0.006720781 -0.4944525 -0.8691787 -0.05116975 -0.4970175 -0.8662305 -0.04907906 -0.4972653 -0.8662093 -0.04907906 -0.4972653 -0.8662093 -0.04907906 -0.4972653 -0.8662093 0.04396635 -0.4984102 -0.8658257 -0.01071149 -0.496569 -0.8679312 -0.009122252 -0.4229432 -0.9061103 -0.06035494 -0.4188631 -0.9060414 -0.04903149 -0.3402925 -0.9390404 -0.0886895 -0.3321071 -0.939063 -0.0674178 -0.2524453 -0.9652597 -0.0984168 -0.2420599 -0.9652571 -0.06692695 -0.1646325 -0.9840819 -0.08174681 -0.1576882 -0.9840996 -0.07747066 -0.1660086 -0.9830765 -0.04317814 -0.1728159 -0.9840073 -0.04560375 -0.1716679 -0.9840989 -0.06704807 -0.2524879 -0.9652743 -0.03575593 -0.2588137 -0.9652652 -0.04692226 -0.3396657 -0.9393751 -0.007420659 -0.3428956 -0.9393443 -0.009156525 -0.4230224 -0.906073 0.04270619 -0.4207704 -0.9061614 0.04991811 -0.4920249 -0.8691489 0.1140592 -0.4808428 -0.8693565 0.07650709 -0.4940803 -0.8660435 0.07329815 -0.4947506 -0.8659384 0.1758903 -0.4683752 -0.8658449 0.1088947 -0.4857367 -0.8672958 0.09242534 -0.412201 -0.9063928 0.04382693 -0.4201219 -0.9064088 0.03560537 -0.3412758 -0.9392886 -0.007536709 -0.3429237 -0.9393331 -0.005754709 -0.261784 -0.9651094 -0.03759193 -0.2591971 -0.9650927 -0.02552998 -0.1760269 -0.9840543 -0.04833406 -0.1713759 -0.9840194 0.1930449 -0.4617068 -0.8657717 0.165426 -0.4659557 -0.8692064 0.1415014 -0.3986663 -0.906114 0.09140121 -0.4130674 -0.9061023 0.07428193 -0.335767 -0.9390116 0.03384977 -0.3421861 -0.9390223 0.02576678 -0.260564 -0.9651128 -0.005955398 -0.2617487 -0.9651177 -0.004071176 -0.1790325 -0.9838348 -0.007621943 -0.1773056 -0.9841264 0.2318626 -0.4411829 -0.8669472 0.2227619 -0.4419879 -0.8689211 0.1900188 -0.3770046 -0.9065101 0.1427721 -0.3971991 -0.9065589 0.1161509 -0.3231993 -0.9391759 0.07528364 -0.3349511 -0.9392232 0.06379812 -0.2839332 -0.9567193 0.003315329 -0.2554643 -0.9668129 0.9182922 0.3959035 0 0.8016615 0.5977784 0 0.8017427 0.5976694 0 0.6427393 0.766085 0 0.6427395 0.7660849 0 0.4483737 0.8938462 0 0.4483398 0.8938633 0 0.2323709 0.9726272 0 0.2323901 0.9726227 0 -0.2323901 0.9726227 0 -0.4483737 0.8938462 0 -0.6427393 0.766085 0 -0.6426979 0.7661198 0 -0.801702 0.5977239 0 -0.8017427 0.5976694 0 -0.9182306 0.3960463 0 -0.9182614 0.3959748 0 -0.9850402 0.1723248 0 -0.9850402 0.1723247 0 -0.9983508 -0.05740958 0 -0.9983556 -0.0573253 0 -0.9577468 -0.2876129 0 -0.8664683 -0.4992322 0 -0.8664683 -0.4992321 0 -0.7269464 -0.6866943 0 -0.7269042 -0.6867389 0 -0.5507524 -0.8346688 0 -0.5507135 -0.8346944 0 -0.3419534 -0.939717 0 -0.3419806 -0.9397071 0 -0.1148468 -0.9933833 0 -0.1148565 -0.9933821 0 0.1148468 -0.9933833 0 0.1148468 -0.9933833 0 0.3419534 -0.939717 0 0.3419806 -0.9397071 0 0.5507524 -0.8346688 0 0.5507135 -0.8346944 0 0.7269041 -0.6867391 0 0.7269887 -0.6866494 0 0.8664317 -0.4992957 0 0.8665049 -0.4991686 0 0.9577234 -0.2876906 0 0.9577702 -0.2875351 0 0.9981819 -0.06027412 0 0.998187 -0.06018984 0 0.9845626 0.175033 0 0.984548 0.1751149 0 0.9182306 0.3960463 0 -0.866912 0.49846 0.001202166 -0.8670786 0.4981697 0.001318812 -0.8655163 0.5008804 -6.99543e-4 -0.865354 0.5011382 -0.00481373 -0.8669737 0.4983441 0.003135859 -0.8646503 0.5023722 -0.001526415 -0.8650894 0.5016179 3.68145e-4 -0.870069 0.491398 0.03883111 0.8670164 -0.4982764 0.001834452 0.8653249 -0.5012108 8.5339e-4 0.8661202 -0.4998358 -1.09807e-4 0.8661519 -0.4997782 -0.001672148 0.865562 -0.5007944 0.002753496 0.865562 -0.5007944 0.002753496 0.865562 -0.5007944 0.002753496 0.8656595 -0.5006263 0.002619326 0.8665772 -0.4990372 -0.002429664 0.8668979 -0.4984761 -0.003135681 0.9046095 -0.4261878 0.006756365 0.9212924 -0.3888706 0 0.9503751 -0.3111064 0 0.9621514 -0.2724334 0.006701231 0.9724345 -0.2331768 0 0.9884831 -0.1513318 0 0.993872 -0.1103252 0.006847739 0.9976062 -0.06915181 0 0.999916 0.01296794 0 0.9985111 0.05412101 0.006813704 0.9954534 0.09525042 0 0.9834744 0.1810471 0 0.975433 0.2201977 0.006598651 0.9659689 0.2586582 0 0.9410187 0.338355 0 0.9263702 0.3765535 0.006777286 0.9102327 0.414097 0 0.8727316 0.4882004 0 0.8520801 0.523368 0.006755053 0.8300356 0.5577104 0 0.7825433 0.6225962 0 0.7551203 0.6555477 0.007107615 0.7262557 0.6874247 0 0.6648686 0.7469604 0 0.6356957 0.7719134 0.006376266 0.6055529 0.7958052 0 0.5345906 0.8451112 0 0.4991447 0.8664915 0.006861627 0.4627532 0.8864873 0 0.3892151 0.9211469 0 0.3504118 0.9365704 0.006908416 0.3110575 0.9503911 0 0.2333446 0.9723941 0 0.192384 0.9812952 0.006954669 0.1510401 0.9885277 0 0.06911605 0.9976087 0 0.02812981 0.9995812 0.006803095 -0.01299726 0.9999155 0 -0.09948712 0.9950389 0 -0.1383938 0.9903562 0.006483733 -0.1769912 0.9842125 0 -0.2587401 0.965947 0 -0.2980298 0.9545325 0.006790578 -0.3368946 0.9415424 0 -0.4157796 0.9094654 0 -0.4523686 0.8918058 0.006715595 -0.4881412 0.8727647 0 -0.5577211 0.8300284 0 -0.592047 0.8058735 0.00695163 -0.6251849 0.7804768 0 -0.6874456 0.7262359 0 -0.7167364 0.6973107 0.006836771 -0.744983 0.6670835 0 -0.7974753 0.6033517 0 -0.8212317 0.5705549 0.006753027 -0.843842 0.5365918 0 -0.8865115 0.4627068 0 -0.9045655 0.4262818 0.006728291 -0.9211009 0.3893243 0 -0.9504189 0.3109729 0 -0.9621514 0.2724334 0.006687164 -0.9723691 0.2334493 0 -0.9885393 0.1509636 0 -0.9938852 0.1102068 0.006845355 -0.9976103 0.06909191 0 -0.999916 -0.01296794 0 -0.9983966 -0.05615288 0.007164835 -0.9950465 -0.09941065 0 -0.9841627 -0.1772676 0 -0.9758403 -0.2183746 0.006955146 -0.9658097 -0.2592524 0 -0.9414088 -0.3372679 0 -0.9264905 -0.3762546 0.006935298 -0.90994 -0.4147402 0 -0.8727316 -0.4882004 0 -0.8520801 -0.523368 0.006749391 -0.8300356 -0.5577104 0 -0.7798456 -0.6259721 0 -0.753684 -0.6572027 0.006722927 -0.7265584 -0.6871048 0 -0.6680553 -0.7441117 0 -0.6356928 -0.77191 0.007052183 -0.6023021 -0.7982683 0 -0.5362461 -0.8440617 0 -0.5004346 -0.8657465 0.006946861 -0.4637401 -0.8859714 0 -0.3895977 -0.9209852 0 -0.3507637 -0.9364386 0.006906747 -0.3114352 -0.9502674 0 -0.2321674 -0.9726759 0 -0.1915279 -0.9814631 0.006881356 -0.1506584 -0.9885859 0 -0.06911605 -0.9976087 0 -0.02769488 -0.9995928 0.006876468 0.01386785 -0.9999039 0 0.0960896 -0.9953727 0 0.1373345 -0.9905007 0.006901621 0.178591 -0.9839235 0 0.2583205 -0.9660594 0 0.2981948 -0.9544803 0.00688517 0.3376644 -0.9412665 0 0.4150587 -0.9097948 0 0.4520351 -0.8919745 0.006784498 0.4882431 -0.8727076 0 0.5582367 -0.8296818 0 0.5919013 -0.8059818 0.006800532 0.6243813 -0.7811198 0 0.6873556 -0.7263211 0 0.7172044 -0.6968284 0.006940066 0.7458465 -0.6661179 0 0.796756 -0.6043012 0 0.821299 -0.5704559 0.006937623 0.8444625 -0.5356147 0 0.8865184 -0.4626935 0 0.634818 -0.2064883 -0.7445594 0.6302238 -0.2344531 -0.7401687 0.6302233 -0.2344548 -0.7401686 0.6302235 -0.2344542 -0.7401686 0.6534775 -0.1550601 -0.7408938 0.6493065 -0.1561565 -0.7443227 0.6599441 -0.1018441 -0.74438 0.6614671 -0.1004562 -0.7432159 0.6596123 -0.09807336 -0.74518 0.6652213 -0.04638105 -0.7452044 0.6640097 -0.04709446 -0.7462394 0.6666713 -0.05868035 -0.7430384 0.6666712 -0.05868071 -0.7430385 0.6666712 -0.05868065 -0.7430385 0.668841 0.01205897 -0.7433077 0.6683634 0.01175242 -0.7437421 0.6657816 0.0588873 -0.7438193 0.6657816 0.05888736 -0.7438193 0.6657817 0.05888718 -0.7438193 0.6672399 0.06215929 -0.7422447 0.662365 0.06529384 -0.7463306 0.6547773 0.1203597 -0.7461771 0.6602604 0.1186287 -0.7416087 0.6616438 0.1167817 -0.7406684 0.6616438 0.1167817 -0.7406684 0.6616437 0.1167816 -0.7406685 0.6490584 0.1736648 -0.740651 0.646536 0.1711869 -0.7434288 0.6264569 0.2351891 -0.7431271 0.6264569 0.2351891 -0.7431271 0.6257801 0.2263188 -0.7464443 0.6310019 0.2246552 -0.7425407 0.6099047 0.2770475 -0.7424695 0.6109876 0.2769089 -0.7416304 0.6032496 0.2822753 -0.7459294 0.5824479 0.3228521 -0.7460034 0.5847172 0.3265709 -0.7426018 0.5542066 0.375832 -0.7427014 0.5546202 0.3746372 -0.7429963 0.5567314 0.3746824 -0.7413929 0.5236105 0.4201385 -0.7411583 0.5239063 0.4201545 -0.7409402 0.5235062 0.4204581 -0.7410508 0.5235062 0.4204581 -0.7410508 0.4880657 0.4608416 -0.7412266 0.4869343 0.4574239 -0.7440822 0.4320113 0.510335 -0.7435889 0.4320113 0.5103352 -0.7435888 0.4320113 0.5103352 -0.7435889 0.4434979 0.4963045 -0.7463186 0.444348 0.4964488 -0.7457168 0.444348 0.4964488 -0.7457168 0.444348 0.4964488 -0.7457168 0.4022616 0.5313412 -0.7455617 0.4031326 0.5315948 -0.7449102 0.4031326 0.5315949 -0.7449101 0.4031326 0.5315948 -0.7449101 0.4071609 0.5319274 -0.7424778 0.3574483 0.5664857 -0.7425124 0.3573527 0.5641332 -0.7443473 0.308346 0.5924295 -0.7442783 0.3083472 0.5903671 -0.7459147 0.2632082 0.611947 -0.7458166 0.2601597 0.6178152 -0.7420386 0.258026 0.6170105 -0.7434519 0.2094586 0.6348406 -0.7437099 0.209518 0.6345443 -0.7439461 0.1988451 0.6360644 -0.7455755 0.1566575 0.6477301 -0.7455899 0.1547846 0.6548555 -0.7397338 0.09518212 0.6664171 -0.7394787 0.1029643 0.6589182 -0.7451343 0.1024288 0.6583712 -0.7456915 0.04647403 0.6650045 -0.745392 0.04438084 0.6688225 -0.7420963 0.03919726 0.667465 -0.7436088 -0.009065747 0.6688262 -0.7433635 -0.008839666 0.6684166 -0.7437346 -0.05879837 0.6657968 -0.7438129 -0.06536257 0.6687031 -0.740651 -0.06591665 0.6679348 -0.7412949 -0.1185056 0.6605866 -0.7413379 -0.1181324 0.6617019 -0.7404023 -0.1306435 0.6531191 -0.7459006 -0.1723635 0.6440228 -0.7453359 -0.1739187 0.6456453 -0.7435688 -0.2232754 0.6303374 -0.7435206 -0.2238826 0.6303306 -0.7433438 -0.2241765 0.6292466 -0.7441732 -0.2771205 0.6073752 -0.744513 -0.2772379 0.6064697 -0.7452071 -0.277893 0.6054813 -0.7457666 -0.3251866 0.581139 -0.7460102 -0.3261179 0.5816966 -0.7451686 -0.3651069 0.5575387 -0.7455519 -0.3651069 0.5575388 -0.7455518 -0.3651069 0.5575389 -0.7455518 -0.3738735 0.5548529 -0.7432072 -0.3738669 0.5572531 -0.7414125 -0.4201341 0.5237108 -0.7410901 -0.4201728 0.524034 -0.7408396 -0.4203444 0.5230833 -0.7414138 -0.4606852 0.4881221 -0.7412868 -0.4616687 0.4883103 -0.7405505 -0.5133136 0.4341683 -0.740275 -0.5133138 0.4341683 -0.7402749 -0.5133137 0.4341684 -0.740275 -0.4975683 0.4471801 -0.7432737 -0.4966604 0.4443473 -0.7455763 -0.5313867 0.4023424 -0.7454856 -0.5317552 0.4028134 -0.7449684 -0.5320178 0.4070857 -0.7424543 -0.5320178 0.4070858 -0.7424542 -0.5320178 0.4070857 -0.7424542 -0.5664658 0.3573443 -0.7425777 -0.5673037 0.3575606 -0.7418336 -0.5934076 0.3118412 -0.7420395 -0.5940012 0.3118011 -0.7415812 -0.619983 0.2574148 -0.7411875 -0.6158967 0.2593038 -0.7439307 -0.6189174 0.2667168 -0.7387852 -0.6409233 0.208123 -0.7388519 -0.6344054 0.2095818 -0.7440466 -0.6377981 0.1872968 -0.7470833 -0.6377982 0.1872968 -0.7470833 -0.637798 0.1872963 -0.7470836 -0.6465063 0.1563162 -0.7467229 -0.6490656 0.1556732 -0.744634 -0.6596897 0.1019421 -0.7445921 -0.6614233 0.1004496 -0.7432558 -0.6597907 0.09838938 -0.7449804 -0.6653263 0.04639023 -0.74511 -0.6688554 0.04445838 -0.7420619 -0.6675962 0.03930932 -0.743485 -0.6675963 0.03930926 -0.743485 -0.6675962 0.03930932 -0.7434852 -0.6688659 -0.009040236 -0.7433282 -0.6684367 -0.008815586 -0.7437168 -0.665808 -0.05908226 -0.7437803 -0.6686597 -0.06524926 -0.7407002 -0.6677396 -0.06590712 -0.7414716 -0.6605145 -0.1184679 -0.7414081 -0.6605082 -0.118348 -0.741433 -0.6606635 -0.1183837 -0.7412888 -0.6475869 -0.1758883 -0.7414138 -0.6456543 -0.1741415 -0.7435088 -0.6303719 -0.2232071 -0.7435118 -0.630446 -0.2245571 -0.7430424 -0.6307171 -0.2246434 -0.7427861 -0.6092026 -0.2777129 -0.7427973 -0.60464 -0.2779803 -0.7464165 -0.6085996 -0.2749103 -0.7443326 -0.6085996 -0.2749103 -0.7443326 -0.5828116 -0.326153 -0.7442815 -0.5837655 -0.3274701 -0.7429544 -0.555141 -0.3743775 -0.7427383 -0.5555922 -0.3725518 -0.7433186 -0.5555785 -0.3726204 -0.7432944 -0.5216556 -0.418713 -0.7433403 -0.5236275 -0.4189764 -0.741804 -0.5247852 -0.4187446 -0.7411164 -0.5247852 -0.4187445 -0.7411164 -0.5247852 -0.4187445 -0.7411164 -0.4872988 -0.4614537 -0.7413504 -0.4860891 -0.45775 -0.7444342 -0.4407361 -0.5018852 -0.7442198 -0.4444906 -0.4970552 -0.7452277 -0.4453403 -0.4974319 -0.7444687 -0.4024205 -0.5328285 -0.7444136 -0.4028228 -0.5331313 -0.743979 -0.4048549 -0.5331824 -0.7428385 -0.3580571 -0.5655515 -0.7429311 -0.3579319 -0.5636239 -0.7444548 -0.3095601 -0.5918284 -0.7442525 -0.3094406 -0.5919184 -0.7442307 -0.259924 -0.6153181 -0.744193 -0.2598628 -0.6157736 -0.7438375 -0.2618771 -0.6165781 -0.7424635 -0.2082971 -0.636272 -0.7428125 -0.2085586 -0.6351615 -0.743689 -0.2104434 -0.6348279 -0.7434428 -0.2104433 -0.6348277 -0.743443 -0.2104434 -0.6348273 -0.7434433 -0.1554539 -0.6502924 -0.7436087 -0.1550993 -0.651682 -0.7424654 -0.1008652 -0.6617726 -0.7428885 -0.1010255 -0.6616509 -0.7429751 -0.1004033 -0.6611765 -0.7434817 -0.04600542 -0.6669823 -0.7436519 -0.04603821 -0.666959 -0.7436708 -0.04653221 -0.6670133 -0.7435913 0.009076416 -0.6681401 -0.7439801 0.009481608 -0.6689186 -0.7432752 0.06454068 -0.6657069 -0.743417 0.06420737 -0.6655879 -0.7435525 0.06437331 -0.6653771 -0.7437267 0.118802 -0.6572362 -0.7442626 0.1186109 -0.657963 -0.7436506 0.1197419 -0.6570172 -0.7443053 0.1732062 -0.6449002 -0.7443812 0.1732062 -0.6449003 -0.7443812 0.1732062 -0.6449003 -0.7443812 0.1738587 -0.6457228 -0.7435155 0.2256261 -0.6294989 -0.7435213 0.2250398 -0.6294571 -0.7437344 0.2247655 -0.6303836 -0.7430323 0.2776227 -0.6091178 -0.7429006 0.2776597 -0.6088137 -0.7431361 0.2771143 -0.6095885 -0.7427042 0.3267767 -0.5844612 -0.7427127 0.3259289 -0.5839798 -0.7434635 0.3756895 -0.5533218 -0.7434329 0.3731678 -0.5542352 -0.7440223 0.3731725 -0.554047 -0.7441601 0.4172949 -0.521552 -0.7442101 0.4169058 -0.5200055 -0.7455091 0.4159275 -0.5237207 -0.7434521 0.4604357 -0.4849461 -0.743523 0.4605072 -0.4851279 -0.7433599 0.5059351 -0.4379935 -0.7430958 0.505935 -0.4379938 -0.7430957 0.5059352 -0.4379939 -0.7430956 0.4974321 -0.4449392 -0.7447083 0.4989481 -0.449763 -0.7407861 0.5353834 -0.4058583 -0.7407049 0.5316902 -0.3979537 -0.7476219 0.5321476 -0.4053518 -0.7433094 0.5655446 -0.3573328 -0.7432851 0.5652847 -0.3575029 -0.7434009 0.5919043 -0.3113569 -0.7434421 0.5954282 -0.31122 -0.7406804 0.6209094 -0.2573117 -0.7404474 0.6209094 -0.2573118 -0.7404474 0.6130194 -0.2613823 -0.745578 0.6137956 -0.2632274 -0.7442892 0.6350327 -0.2063226 -0.7444223 0.739376 -0.4677514 -0.4842848 0.7752807 -0.4053912 -0.4843531 0.773338 -0.4057442 -0.4871551 0.8031924 -0.3424968 -0.4874198 0.810646 -0.3403779 -0.476441 0.8362765 -0.2719599 -0.4761086 0.8316321 -0.2736507 -0.483222 0.851199 -0.2046667 -0.4832926 0.8556205 -0.2025071 -0.4763451 0.8693594 -0.1319324 -0.4762438 0.8669756 -0.1333217 -0.4801862 0.8749791 -0.06197142 -0.4801785 0.8762335 -0.06108474 -0.4779995 0.8782341 0.01544201 -0.4779816 0.8733692 0.01144671 -0.4869243 0.8696537 0.08102416 -0.4869678 0.8725131 0.08387511 -0.4813379 0.86213 0.1584912 -0.4812613 0.8592692 0.1552704 -0.4873887 0.8439321 0.2234747 -0.4876861 0.8480028 0.2292638 -0.4778382 0.8261046 0.2986152 -0.4778915 0.8247737 0.296387 -0.4815633 0.797788 0.3622456 -0.4819881 0.7979906 0.362499 -0.481462 0.7979906 0.3624989 -0.481462 0.7979906 0.3624989 -0.4814621 0.7655689 0.4274923 -0.4807856 0.7655689 0.4274922 -0.4807855 0.7655689 0.4274922 -0.4807855 0.7650897 0.426405 -0.4825109 0.7258005 0.4900984 -0.4827185 0.7256512 0.4901843 -0.482856 0.683026 0.5480117 -0.4828653 0.6825061 0.5460376 -0.4858276 0.6370221 0.5983211 -0.4860192 0.6376782 0.6032924 -0.4789622 0.5848298 0.6546276 -0.4789958 0.5846119 0.6490715 -0.48676 0.5271998 0.6965223 -0.4867413 0.5269181 0.7025428 -0.4783209 0.470123 0.7421748 -0.477662 0.4708208 0.7364882 -0.4857088 0.4047132 0.7748727 -0.4855715 0.4041392 0.7777317 -0.4814613 0.3402311 0.8079974 -0.4810229 0.3413775 0.8041727 -0.4865878 0.2739894 0.829717 -0.4863123 0.2733837 0.8315165 -0.483572 0.2013298 0.8517785 -0.4836732 0.2014653 0.8515027 -0.4841023 0.1350705 0.86438 -0.4843585 0.1331729 0.8675917 -0.4791135 0.05809819 0.8755521 -0.4796177 0.06091594 0.8716107 -0.4863992 -0.01155567 0.8736093 -0.4864909 -0.01527136 0.8779457 -0.4785167 -0.0854426 0.8741238 -0.4781287 -0.08382302 0.8724399 -0.4814794 -0.1547703 0.8627485 -0.4813641 -0.1560228 0.8637169 -0.4792183 -0.228272 0.8473951 -0.4793886 -0.2244838 0.8446362 -0.486001 -0.2924974 0.8235132 -0.4860775 -0.296983 0.8262922 -0.4785839 -0.3645137 0.7988265 -0.4785457 -0.3627021 0.7981052 -0.4811187 -0.4288076 0.764816 -0.4808126 -0.430305 0.7653568 -0.478609 -0.430305 0.7653568 -0.478609 -0.430305 0.7653568 -0.478609 -0.4908488 0.7284063 -0.4780082 -0.4874975 0.7275074 -0.4827828 -0.5480023 0.6829558 -0.4829752 -0.5460134 0.6825666 -0.4857698 -0.6004777 0.6351311 -0.4858345 -0.6009395 0.6352384 -0.4851226 -0.650589 0.5845346 -0.484823 -0.6530429 0.5848355 -0.4811469 -0.698782 0.5288741 -0.4816595 -0.70117 0.5289364 -0.4781077 -0.743334 0.4682939 -0.4776561 -0.7376988 0.4691064 -0.4855304 -0.7738927 0.4062598 -0.4858428 -0.7738927 0.4062598 -0.4858428 -0.7738927 0.4062598 -0.4858428 -0.7797451 0.4051048 -0.4773758 -0.8098313 0.3409065 -0.4774475 -0.8058064 0.3421112 -0.4833591 -0.8311145 0.2745602 -0.4835964 -0.83107 0.2744602 -0.4837296 -0.8511071 0.2041788 -0.4836607 -0.8549718 0.2021867 -0.4776442 -0.8689429 0.1318691 -0.4770207 -0.8668749 0.1330999 -0.4804293 -0.8752135 0.05805134 -0.480241 -0.8715538 0.06087344 -0.4865066 -0.8735875 -0.01154273 -0.4865303 -0.8733504 -0.01135915 -0.48696 -0.8693381 -0.08487844 -0.4868746 -0.8721802 -0.08763146 -0.4812718 -0.8721802 -0.0876314 -0.4812718 -0.8721802 -0.08763146 -0.4812718 -0.8626667 -0.1548519 -0.4814842 -0.8641117 -0.1564003 -0.4783828 -0.8478184 -0.2287977 -0.4783887 -0.8478184 -0.2287977 -0.4783887 -0.8478184 -0.2287977 -0.4783887 -0.8447123 -0.2242053 -0.4859971 -0.8234192 -0.2931174 -0.4858633 -0.8234192 -0.2931174 -0.4858633 -0.8234192 -0.2931174 -0.4858633 -0.8256886 -0.2971057 -0.4795482 -0.7984071 -0.3640331 -0.4796105 -0.7971969 -0.3615934 -0.4834537 -0.7634802 -0.4284707 -0.4832296 -0.7639865 -0.4296899 -0.4813429 -0.7280341 -0.4881299 -0.4813478 -0.7278028 -0.4879315 -0.4818982 -0.6833307 -0.5483816 -0.4820135 -0.6830705 -0.5473297 -0.4835752 -0.6371369 -0.5999187 -0.483895 -0.6371369 -0.5999186 -0.4838949 -0.6371369 -0.5999186 -0.4838949 -0.6376136 -0.6030061 -0.4794088 -0.6376136 -0.6030061 -0.4794088 -0.6376135 -0.6030061 -0.4794088 -0.5848279 -0.6540874 -0.4797354 -0.5848715 -0.6549224 -0.4785415 -0.5290372 -0.7005994 -0.478832 -0.5291725 -0.6972239 -0.4835861 -0.4693247 -0.7388899 -0.4835041 -0.4688932 -0.7421694 -0.4788776 -0.4066584 -0.7777827 -0.4792525 -0.4067061 -0.7776119 -0.4794893 -0.3411486 -0.8082362 -0.4799709 -0.3412602 -0.8075355 -0.4810696 -0.2734983 -0.8328347 -0.481233 -0.2737277 -0.832172 -0.482248 -0.2737276 -0.832172 -0.482248 -0.2737276 -0.832172 -0.482248 -0.202889 -0.8523525 -0.4820078 -0.2031194 -0.8519618 -0.4826009 -0.1322349 -0.8660562 -0.4821417 -0.1321576 -0.8661389 -0.4820145 -0.06034755 -0.8741145 -0.4819567 -0.06032937 -0.8742255 -0.4817574 0.01242339 -0.8764933 -0.481254 0.01174718 -0.8756973 -0.4827176 0.08407819 -0.8714599 -0.4832068 0.08455401 -0.872114 -0.4819418 0.08455401 -0.872114 -0.4819418 0.08455401 -0.872114 -0.4819418 0.1557924 -0.8620984 -0.4821982 0.1564986 -0.8626589 -0.4809655 0.227988 -0.8468047 -0.4805657 0.2271878 -0.8462524 -0.4819157 0.2949352 -0.8250594 -0.4819653 0.2955824 -0.8253815 -0.4810162 0.3636696 -0.7978721 -0.4807748 0.3620721 -0.7971114 -0.4832362 0.4265757 -0.7642643 -0.4836665 0.4271411 -0.7645742 -0.4826769 0.4891116 -0.7264157 -0.4827941 0.491814 -0.7271336 -0.4789527 0.5485219 -0.6856385 -0.4785641 0.5481241 -0.6856644 -0.4789825 0.604557 -0.6366158 -0.4787809 0.6029843 -0.6366083 -0.48077 0.6535653 -0.5845237 -0.4808165 0.6508283 -0.5845546 -0.4844776 0.6969905 -0.5283923 -0.4847741 0.6979277 -0.5284277 -0.4833853 0.7398071 -0.4678112 -0.4835681 0.8327786 -0.5280482 -0.1662681 0.8731245 -0.4582824 -0.1662259 0.8749728 -0.4566053 -0.1610412 0.9100427 -0.3821125 -0.1606629 0.9085682 -0.3835362 -0.1655406 0.9367839 -0.3082237 -0.165633 0.9378507 -0.3070322 -0.1617636 0.9602708 -0.2274793 -0.1616578 0.9584297 -0.2298372 -0.169078 0.9741329 -0.1498363 -0.1691572 0.9745278 -0.1492815 -0.167364 0.9835039 -0.06870633 -0.1673308 0.9835039 -0.06870633 -0.1673308 0.9835039 -0.06870639 -0.1673308 0.9836919 -0.06834805 -0.1663695 0.985979 0.01263618 -0.1663906 0.985979 0.01263618 -0.1663907 0.985979 0.01263612 -0.1663907 0.9859791 0.01272994 -0.1663829 0.9815316 0.09445738 -0.1663538 0.9813541 0.0937736 -0.1677818 0.9701355 0.1752593 -0.1676945 0.9709378 0.1789883 -0.1588804 0.9531229 0.2575924 -0.158755 0.9527874 0.2552102 -0.1645113 0.9281913 0.3334819 -0.1650779 0.9281727 0.3336451 -0.1648532 0.8980687 0.4080489 -0.1642217 0.8980688 0.4080489 -0.1642217 0.8980687 0.4080489 -0.1642216 0.8980211 0.4084592 -0.1634598 0.861719 0.4802229 -0.1637881 0.8615284 0.4819341 -0.1597138 0.8179886 0.5524756 -0.1602039 0.8184908 0.5499396 -0.1662511 0.7699536 0.6160241 -0.1663913 0.7708122 0.6131411 -0.1729361 0.7154533 0.6769777 -0.1727073 0.7154838 0.6769967 -0.1725065 0.6591506 0.732032 -0.1721913 0.656606 0.737571 -0.1576629 0.5924934 0.7900059 -0.1576146 0.5961681 0.783586 -0.1748624 0.5303484 0.8295131 -0.1750397 0.5273265 0.8338475 -0.1631722 0.4549805 0.8753544 -0.163547 0.4560632 0.8739015 -0.1682336 0.385138 0.9072502 -0.1690147 0.3839145 0.908555 -0.1647345 0.3080558 0.9369606 -0.1649442 0.3069408 0.9379269 -0.1614951 0.2272599 0.960389 -0.1612639 0.2300658 0.9583423 -0.1692627 0.2300658 0.9583423 -0.1692626 0.2300658 0.9583423 -0.1692627 0.1495453 0.974124 -0.1694661 0.1489592 0.974542 -0.1675688 0.1489593 0.9745419 -0.1675688 0.1489592 0.9745419 -0.1675688 0.0687285 0.9834982 -0.1673553 0.0687285 0.9834982 -0.1673552 0.0687285 0.9834982 -0.1673552 0.06814837 0.9837834 -0.16591 -0.01279228 0.9840882 -0.1772199 -0.09412634 0.9796333 -0.177367 -0.09807723 0.9809604 -0.1676236 -0.1752264 0.9701331 -0.1677424 -0.1752264 0.9701331 -0.1677423 -0.1752264 0.9701331 -0.1677423 -0.174425 0.9699716 -0.1695023 -0.253166 0.9524964 -0.1692858 -0.2551963 0.9527685 -0.1646423 -0.2551963 0.9527685 -0.1646423 -0.2551963 0.9527685 -0.1646423 -0.333587 0.9281889 -0.1648791 -0.3320908 0.9280372 -0.1687088 -0.4077579 0.8973473 -0.1688235 -0.4101758 0.8972111 -0.1636096 -0.4834578 0.8598891 -0.1638884 -0.4812225 0.8601448 -0.1690441 -0.5486797 0.8187489 -0.169118 -0.5499548 0.8184795 -0.1662564 -0.6159148 0.7700604 -0.1663008 -0.6167441 0.7697534 -0.1646409 -0.677823 0.7165033 -0.1648607 -0.6780159 0.7163832 -0.1645892 -0.734887 0.6578376 -0.1648966 -0.7348113 0.6579508 -0.1647827 -0.7875796 0.5939211 -0.1642442 -0.7859958 0.5948475 -0.1684256 -0.8317281 0.5287588 -0.1692412 -0.8315694 0.5289797 -0.169331 -0.874617 0.454449 -0.168883 -0.8730906 0.4556423 -0.1735022 -0.9066458 0.3846997 -0.1732037 -0.9066459 0.3846997 -0.1732037 -0.9066459 0.3846997 -0.1732038 -0.9080099 0.3834657 -0.1687366 -0.936036 0.3090979 -0.1682115 -0.9378991 0.3070755 -0.1614 -0.9604054 0.2270667 -0.1614384 -0.9583035 0.2300888 -0.1694508 -0.9741002 0.1496699 -0.1694933 -0.9744983 0.1489123 -0.1678637 -0.9834724 0.06857556 -0.1675695 -0.9837086 0.06811445 -0.1663666 -0.9859764 -0.01279634 -0.1663936 -0.9859769 -0.01290428 -0.1663825 -0.9811407 -0.09850406 -0.1663132 -0.9809434 -0.09796959 -0.167786 -0.9700959 -0.1754648 -0.1677082 -0.9698677 -0.1746652 -0.1698496 -0.9524946 -0.2528646 -0.1697454 -0.9529031 -0.2556912 -0.1630882 -0.9282282 -0.3343007 -0.163204 -0.9282079 -0.3322663 -0.1674194 -0.8978497 -0.4072684 -0.1673273 -0.8977875 -0.4092934 -0.1626552 -0.859946 -0.4836834 -0.1629212 -0.8602605 -0.481226 -0.1684443 -0.8188403 -0.548638 -0.1688106 -0.8188403 -0.548638 -0.1688106 -0.8188403 -0.548638 -0.1688106 -0.8186603 -0.5498809 -0.1656099 -0.769519 -0.6167281 -0.1657927 -0.7693205 -0.6176694 -0.1631885 -0.7168127 -0.6778383 -0.1634466 -0.7168724 -0.6778823 -0.163002 -0.6570534 -0.7359751 -0.1631609 -0.6584544 -0.7332306 -0.1697373 -0.5957664 -0.7850511 -0.1695795 -0.5943081 -0.7876939 -0.1622843 -0.5270437 -0.8340609 -0.1629955 -0.5286644 -0.8317356 -0.1694992 -0.5286645 -0.8317356 -0.1694992 -0.4569216 -0.8733147 -0.1689495 -0.4569194 -0.8731705 -0.1696996 -0.3837686 -0.9078364 -0.1689813 -0.3838976 -0.9076382 -0.1697517 -0.3078855 -0.9362171 -0.1694224 -0.3070956 -0.9369564 -0.1667482 -0.2286867 -0.9591282 -0.1666601 -0.2288711 -0.9589469 -0.1674488 -0.1487352 -0.974631 -0.1672495 -0.1485321 -0.9747481 -0.1667469 -0.06788772 -0.9837018 -0.1664996 -0.06813257 -0.983555 -0.1672653 0.0132274 -0.9857835 -0.1674993 0.0136767 -0.9859788 -0.1663097 0.09515982 -0.9815935 -0.1655868 0.09475058 -0.981459 -0.1666151 0.1760094 -0.9701657 -0.1667307 0.1761191 -0.970223 -0.1662814 0.2556297 -0.9523436 -0.1664187 0.2546275 -0.9522269 -0.168609 0.3322744 -0.9279075 -0.1690604 0.3328594 -0.9279671 -0.1675756 0.4077378 -0.897525 -0.1679251 0.4093646 -0.8975154 -0.1639721 0.4812242 -0.861258 -0.1632725 0.481839 -0.8611981 -0.1617691 0.5529032 -0.8174294 -0.1615778 0.5529031 -0.8174294 -0.1615777 0.5504789 -0.8179812 -0.1669725 0.6155849 -0.7701677 -0.1670243 0.6157546 -0.7699576 -0.1673669 0.6779771 -0.7157856 -0.1673265 0.6774951 -0.7160087 -0.1683213 0.7334758 -0.6584839 -0.1685593 0.7359211 -0.6574004 -0.1620025 0.7868384 -0.5956207 -0.1616209 0.7859736 -0.5961365 -0.1639114 0.8336026 -0.5275388 -0.1637371 -0.3026694 -0.398488 -0.8657936 -0.3329232 -0.37186 -0.8665346 -0.4150124 -0.2782585 -0.8662199 -0.4919433 -0.08811765 -0.8661565 -0.4988622 0.02955222 -0.8661774 -0.4988622 0.0295521 -0.8661774 -0.4988622 0.02955216 -0.8661774 -0.4785597 0.1409299 -0.8666715 -0.4594705 0.1980088 -0.8658402 -0.441186 0.2318603 -0.8669463 -0.3977026 0.3041866 -0.865623 -0.3977027 0.3041866 -0.8656231 -0.3977026 0.3041866 -0.8656231 -0.3723402 0.3331755 -0.8662315 -0.2784314 0.4149313 -0.8662033 -0.1678065 0.4711343 -0.8659524 0.02929836 0.4990075 -0.8661024 0.02929449 0.4990075 -0.8661023 0.02929848 0.4990078 -0.8661022 0.148662 0.4756625 -0.8669745 0.148662 0.4756625 -0.8669745 0.148662 0.4756629 -0.8669744 0.1930389 0.4616925 -0.8657807 0.2301096 0.4420841 -0.8669552 0.3043664 0.3976695 -0.8655751 0.3326382 0.3718091 -0.866666 0.4138956 0.2785267 -0.8666681 0.4921722 0.08678048 -0.8661615 0.4981753 -0.04342418 -0.8659883 0.4689406 -0.1744894 -0.8658223 0.4689406 -0.174489 -0.8658224 0.4689406 -0.1744894 -0.8658223 0.459977 -0.1972785 -0.8657382 0.4411867 -0.2320901 -0.8668844 0.3984414 -0.3034632 -0.8655372 0.3710526 -0.3344302 -0.8663005 0.2790883 -0.414373 -0.8662591 0.1678911 -0.4710392 -0.8659878 -0.03477305 -0.4987779 -0.8660321 -0.1570675 -0.4737422 -0.8665438 -0.1570675 -0.4737423 -0.8665437 -0.1570675 -0.4737427 -0.8665436 -0.1956154 -0.4605255 -0.8658239 -0.2309949 -0.4416005 -0.8669663 -0.1683787 -0.1616474 -0.972378 0.1611238 0.166833 -0.9727312 0.0420348 0.2318266 -0.9718486 0.143355 0.3196604 -0.9366251 0.06090301 0.2245556 -0.9725562 0.1099818 0.2743442 -0.9553216 0.2130907 0.151903 -0.9651518 0.06436377 0.2195656 -0.9734724 0.1730064 0.1233483 -0.9771663 0.1608704 0.07968771 -0.9837533 0.164353 0.06756585 -0.9840849 0.1607981 0.07507997 -0.9841276 0.2361414 -0.04411739 -0.9707167 0.3139163 -0.1335322 -0.9400137 0.2247424 -0.06000643 -0.9725688 0.2757188 -0.1082215 -0.9551269 0.2757188 -0.1082216 -0.9551268 0.2757188 -0.1082215 -0.9551268 0.1532061 -0.2117802 -0.9652342 0.2290073 -0.0567277 -0.9717704 0.1248139 -0.1725162 -0.9770669 0.08067834 -0.1603367 -0.9837597 0.06623589 -0.1650316 -0.9840618 0.08033156 -0.1582871 -0.98412 -0.04363548 -0.2341256 -0.9712267 -0.1443201 -0.3203128 -0.936254 -0.1443203 -0.3203127 -0.936254 -0.1443203 -0.3203126 -0.936254 -0.0592575 -0.225117 -0.9725281 -0.05925744 -0.2251168 -0.9725282 -0.0592575 -0.2251169 -0.9725282 -0.1072605 -0.2770361 -0.954854 -0.2128476 -0.152435 -0.9651215 -0.05900049 -0.2253633 -0.9724867 -0.05900049 -0.2253631 -0.9724868 -0.05900049 -0.2253636 -0.9724867 -0.1719206 -0.1231448 -0.9773836 -0.1602073 -0.08109825 -0.9837462 -0.1653354 -0.06549954 -0.9840601 -0.1600447 -0.07679128 -0.9841183 -0.231854 0.04207211 -0.9718403 -0.3147345 0.1327619 -0.9398492 -0.2260954 0.05797815 -0.9723783 -0.2783216 0.1060681 -0.9546134 -0.1519678 0.2131542 -0.9651275 -0.2210216 0.06164729 -0.9733186 -0.2210217 0.06164729 -0.9733186 -0.2210216 0.06164723 -0.9733186 -0.1222717 0.1714945 -0.977568 -0.08146971 0.1602212 -0.9837134 -0.06603842 0.1650303 -0.9840752 -0.07498097 0.1609891 -0.9841039 -0.1946754 -0.4608651 -0.8658551 -0.220741 -0.4426474 -0.8691011 -0.1887093 -0.3783274 -0.9062324 -0.2329072 -0.3528342 -0.9062352 -0.1891797 -0.2866131 -0.9391826 -0.2225612 -0.2614725 -0.9392012 -0.1552658 -0.4743807 -0.8665192 -0.1663317 -0.465249 -0.869412 -0.1423157 -0.3980914 -0.9062392 -0.1888031 -0.3783228 -0.9062148 -0.1532592 -0.3071335 -0.9392448 -0.1885065 -0.2866783 -0.9392982 -0.07510858 -0.4944956 -0.8659288 -0.07536125 -0.4945121 -0.8658975 -0.11486 -0.480508 -0.8694363 -0.1091243 -0.4858013 -0.8672307 -0.09261888 -0.4122998 -0.9063282 -0.1416641 -0.3980064 -0.9063786 -0.1151344 -0.3234505 -0.9392145 -0.1535445 -0.3070657 -0.9392204 -0.03437471 -0.4983369 -0.8663018 -0.04986763 -0.4916392 -0.86937 -0.04265934 -0.4205443 -0.9062685 -0.09292215 -0.4123651 -0.9062674 -0.07548248 -0.3349987 -0.9391902 -0.1152717 -0.3234497 -0.939198 0.04816979 -0.4979311 -0.8658778 0.04828262 -0.497761 -0.8659694 0.006726682 -0.4953137 -0.8686882 0.01001614 -0.4969121 -0.867743 0.008518159 -0.4226253 -0.9062646 -0.04259437 -0.4204764 -0.9063031 -0.03460764 -0.3416741 -0.9391811 -0.07546985 -0.3349922 -0.9391936 -0.06107872 -0.2711175 -0.9606065 -0.09321582 -0.261543 -0.96068 -0.09998661 -0.2477281 -0.9636563 -0.1195864 -0.2391602 -0.9635878 -0.1090798 -0.2630704 -0.9585905 -0.1555008 -0.2365275 -0.9591009 -0.1639003 -0.2105563 -0.9637442 -0.1732851 -0.2035751 -0.9636024 -0.1701843 -0.2208589 -0.960343 -0.1726399 -0.2185961 -0.9604225 -0.01672667 -0.2616497 -0.965018 -0.02632027 -0.2601314 -0.9652144 -0.0345593 -0.3415989 -0.9392103 0.006987869 -0.3433642 -0.9391763 0.008595943 -0.4224614 -0.9063402 0.05928957 -0.4184718 -0.9062926 0.0693053 -0.4891483 -0.8694427 0.1287086 -0.4792883 -0.8681687 0.08957368 -0.4915803 -0.8662133 0.0887041 -0.4920012 -0.8660638 0.1687039 -0.4706424 -0.8660455 0.1286177 -0.4794194 -0.8681098 0.1094955 -0.408177 -0.9063125 0.0593757 -0.4184399 -0.9063016 0.04826211 -0.3400168 -0.9391801 0.006946861 -0.3432926 -0.9392029 0.00528711 -0.2613965 -0.9652171 -0.02620494 -0.2602402 -0.9651883 -0.01795798 -0.1782217 -0.9838265 -0.1696062 -0.1656939 -0.9714831 -0.1696062 -0.1656938 -0.9714831 -0.1696062 -0.1656938 -0.9714831 0.01025754 -0.1792771 -0.9837452 0.003667771 -0.1793875 -0.9837718 0.005342006 -0.2614366 -0.9652059 0.03680777 -0.258852 -0.9652155 0.04834318 -0.3399621 -0.9391958 0.08893668 -0.3316206 -0.9392114 0.1094624 -0.4081321 -0.9063367 0.157874 -0.392081 -0.9062827 0.184426 -0.4579061 -0.8696603 0.2415658 -0.4321532 -0.8688438 0.2069746 -0.4550043 -0.866102 0.2074558 -0.454874 -0.8660553 0.2805005 -0.4133956 -0.86627 0.2393476 -0.4354304 -0.8678209 0.2037106 -0.3705744 -0.906188 0.1575404 -0.3924611 -0.9061763 0.1279801 -0.3188194 -0.9391355 0.08851915 -0.3320065 -0.9391146 0.06739461 -0.2527793 -0.965174 0.03650957 -0.258979 -0.9651927 0.0248028 -0.175947 -0.9840872 0.007845699 -0.177302 -0.9841253 0.0124247 -0.1803345 -0.983527 0.0124247 -0.1803343 -0.983527 0.0124247 -0.1803345 -0.983527 0.02475643 -0.1760227 -0.9840748 0.04598408 -0.1715928 -0.9840943 0.06766766 -0.2524593 -0.9652385 0.09785807 -0.2425673 -0.9651865 0.1284713 -0.3182882 -0.9392486 0.1658815 -0.3005132 -0.9392419 0.204163 -0.3698936 -0.9063643 0.2473928 -0.3425354 -0.9063478 0.2892465 -0.4005109 -0.869441 0.3399025 -0.3579998 -0.8696566 0.3110961 -0.3918169 -0.8658515 0.3129519 -0.3902822 -0.8658759 0.3779636 -0.327353 -0.866016 0.3372172 -0.3665195 -0.8671494 0.2864957 -0.3114427 -0.9060485 0.2467953 -0.3437637 -0.9060456 0.2003588 -0.2790268 -0.9391489 0.1655572 -0.3010598 -0.939124 0.1259638 -0.2290167 -0.9652382 0.09810775 -0.2422159 -0.9652494 0.066693 -0.1647188 -0.9840833 0.04585492 -0.1716215 -0.9840953 0.4009758 -0.3000774 -0.8655472 0.3764456 -0.3199606 -0.8694332 0.3217222 -0.2734377 -0.9064915 0.2871381 -0.3093977 -0.9065455 0.2334795 -0.2516145 -0.939243 0.2007097 -0.2784326 -0.9392503 0.1529582 -0.2121672 -0.9651886 0.1255401 -0.2295008 -0.9651783 0.08607035 -0.1573015 -0.9837928 0.08215159 -0.1576806 -0.9840671 0.4213998 -0.2663101 -0.8668917 0.41281 -0.2722988 -0.8691614 0.3526694 -0.2326595 -0.9063631 0.3215766 -0.2740996 -0.9063432 0.2615599 -0.2229555 -0.9390833 0.2331046 -0.2524972 -0.9390993 0.1968311 -0.2132639 -0.9569619 0.1320065 -0.2187563 -0.9668092 0.4622467 -0.1917958 -0.8657612 0.4421753 -0.2204132 -0.8694245 0.3787551 -0.1888324 -0.9060282 0.3525595 -0.2340311 -0.9060527 0.2860233 -0.18985 -0.9392272 0.2617688 -0.2222606 -0.9391898 0.475039 -0.154379 -0.866317 0.4647924 -0.1668392 -0.8695589 0.3982434 -0.142942 -0.9060739 0.3787919 -0.188606 -0.9060599 0.3072639 -0.1530344 -0.9392388 0.2860587 -0.1898704 -0.9392123 0.4947471 -0.07360148 -0.8659147 0.4943424 -0.07647418 -0.8658968 0.4810277 -0.1140863 -0.8692507 0.4855522 -0.1091824 -0.8673629 0.4118472 -0.092655 -0.9065302 0.3979277 -0.1407423 -0.9065568 0.3234691 -0.1143608 -0.9393026 0.3073286 -0.1523929 -0.9393219 0.4986586 -0.03468054 -0.8661044 0.4919861 -0.04986268 -0.8691741 0.4202314 -0.04251706 -0.9064204 0.4119784 -0.09318435 -0.9064164 0.3355336 -0.07592606 -0.9389636 0.3236927 -0.1167834 -0.9389274 0.4974216 0.04909485 -0.8661186 0.4978298 0.04383093 -0.8661665 0.4956031 0.009013473 -0.8685025 0.496531 0.01064634 -0.8679538 0.4220759 0.009156703 -0.9065143 0.4200032 -0.04199779 -0.9065504 0.3421521 -0.03416502 -0.9390233 0.3353833 -0.07540267 -0.9390594 0.2707286 -0.06081026 -0.9607331 0.2609184 -0.09416341 -0.9607574 0.2482649 -0.1002085 -0.9634952 0.2400857 -0.1190845 -0.9634198 0.2627142 -0.1090811 -0.958688 0.2356161 -0.1563627 -0.959185 0.2100305 -0.1646266 -0.9637351 0.2038035 -0.1730324 -0.9635995 0.2199131 -0.1700923 -0.9605762 0.2198683 -0.1699577 -0.9606105 0.4917434 0.08835959 -0.8662455 0.489029 0.06935453 -0.8695061 0.4188761 0.05940622 -0.9060981 0.4231057 0.007287859 -0.906051 0.3436185 0.005961298 -0.9390904 0.3420328 -0.0339514 -0.9390745 0.2599757 -0.02578896 -0.9652708 0.2611868 -0.01814645 -0.9651177 0.1649914 -0.1643207 -0.9725105 0.4711118 0.1677973 -0.8659664 0.468381 0.1754803 -0.865925 0.4788317 0.1281842 -0.8684982 0.4788048 0.1281703 -0.868515 0.4083654 0.1093211 -0.9062487 0.4182678 0.06024056 -0.906324 0.3395584 0.04890877 -0.9393125 0.342891 0.007486104 -0.9393454 0.2612024 0.005721271 -0.9652672 0.2600052 -0.02564465 -0.9652667 0.1779682 -0.01753371 -0.9838801 0.1649492 -0.1640301 -0.9725667 0.1649493 -0.1640301 -0.9725667 0.1649492 -0.16403 -0.9725667 0.1795589 0.01117819 -0.9836837 0.1797147 0.002732217 -0.983715 0.261875 0.003985285 -0.9650936 0.2593119 0.03588539 -0.9651267 0.3406356 0.04710012 -0.939015 0.3322994 0.08795428 -0.9390641 0.4092972 0.1081902 -0.905964 0.3926151 0.1582285 -0.9059897 0.4579223 0.1846344 -0.8696076 0.4334998 0.2403832 -0.868501 0.452522 0.2115804 -0.8662896 0.4550821 0.206188 -0.8662489 0.4127645 0.2801871 -0.8666721 0.4345753 0.2396417 -0.8681683 0.3701354 0.2040647 -0.9062877 0.3914751 0.1592397 -0.9063058 0.317412 0.1290598 -0.9394644 0.3305079 0.09011048 -0.9394917 0.2521396 0.0687201 -0.9652478 0.2585065 0.03746122 -0.965283 0.1757395 0.02546757 -0.9841072 0.1771656 0.007885336 -0.9841495 0.1791916 0.01099801 -0.9837527 0.1763231 0.02403658 -0.9840389 0.1718707 0.04573565 -0.9840574 0.2530757 0.06738173 -0.9650972 0.2431085 0.09722709 -0.9651141 0.3190087 0.1276186 -0.9391204 0.3013792 0.1647869 -0.9391571 0.3715708 0.2031989 -0.9058949 0.3441325 0.2467382 -0.9059212 0.4013798 0.2877123 -0.8695493 0.3596034 0.3396227 -0.8691041 0.3902491 0.313166 -0.8658133 0.3904285 0.3131489 -0.8657387 0.3226293 0.3811002 -0.8664139 0.3226292 0.3811003 -0.8664139 0.3226292 0.3811004 -0.8664138 0.3647789 0.3379043 -0.8676157 0.310061 0.2872819 -0.9062734 0.3427078 0.2472926 -0.90631 0.2778996 0.2005825 -0.9394353 0.2998649 0.1659771 -0.9394321 0.2286553 0.1266139 -0.9652387 0.2420889 0.09838038 -0.9652535 0.1647959 0.06699812 -0.9840497 0.171857 0.04573982 -0.9840595 0.302522 0.3991408 -0.8655445 0.3211097 0.3761116 -0.8691539 0.2746739 0.3217451 -0.9061095 0.310764 0.2870146 -0.9061172 0.2521761 0.2329346 -0.9392278 0.2791334 0.1999128 -0.9392122 0.2125664 0.1522641 -0.9652105 0.2289482 0.126241 -0.9652181 0.1570297 0.08665585 -0.9837847 0.1572605 0.083346 -0.9840338 0.2659629 0.421468 -0.8669652 0.2721371 0.4126887 -0.8692696 0.2327556 0.3528548 -0.9062662 0.2742747 0.3218696 -0.9061863 0.2229284 0.2615743 -0.9390856 0.2531182 0.2324643 -0.9390909 0.2140745 0.1966875 -0.9568105 0.219388 0.1317325 -0.9667034 0.1977093 0.4596031 -0.8658384 0.2214437 0.4429634 -0.8687614 0.188959 0.3779715 -0.906329 0.2322461 0.3529604 -0.9063558 0.1887708 0.2868695 -0.9391867 0.2222155 0.2617837 -0.9391962 0.1562235 0.4736075 -0.86677 0.1654199 0.4659703 -0.8691997 0.1412289 0.3978086 -0.9065334 0.1880393 0.3778769 -0.9065597 0.1530093 0.3074707 -0.9391752 0.1887349 0.2868799 -0.9391908 0.07704025 0.4950814 -0.8654243 0.07084751 0.4961701 -0.86533 0.1161286 0.4801468 -0.8694673 0.1105967 0.4852553 -0.8673499 0.09399431 0.4124015 -0.9061403 0.1431089 0.398197 -0.9060679 0.1162584 0.3234744 -0.9390679 0.1537364 0.3074265 -0.9390709 0.03485459 0.4985002 -0.8661887 0.04990297 0.4920253 -0.8691495 0.04263329 0.4202877 -0.9063889 0.09300178 0.4120786 -0.9063895 0.07557421 0.3348994 -0.9392184 0.1153444 0.3233714 -0.939216 -0.04907536 0.4974275 -0.8661165 -0.0439707 0.4978063 -0.8661729 -0.006715297 0.4954532 -0.8686087 -0.01073658 0.4974949 -0.8674005 -0.009103834 0.4220905 -0.906508 0.04199683 0.4199684 -0.9065665 0.03414076 0.341417 -0.9392917 0.07524842 0.3348358 -0.9392672 0.0608533 0.2707633 -0.9607206 0.09315609 0.2611368 -0.9607964 0.1000154 0.2471966 -0.9637899 0.119377 0.2386854 -0.9637316 0.1090681 0.2624364 -0.9587656 0.1551162 0.2357583 -0.9593524 0.16319 0.2109705 -0.9637741 0.1729596 0.2037673 -0.9636203 0.1699778 0.2201794 -0.9605356 0.1698954 0.2200527 -0.9605792 0.01692998 0.2619666 -0.9649285 0.02717095 0.2603209 -0.9651399 0.03570061 0.3419172 -0.9390517 -0.007447004 0.3437225 -0.9390417 -0.009145736 0.4221 -0.9065032 -0.05928468 0.4180148 -0.9065037 -0.0693472 0.4889969 -0.8695246 -0.1283909 0.4797301 -0.8679717 -0.09795296 0.4894711 -0.8665007 -0.08778196 0.4917419 -0.8663051 -0.1669633 0.4713276 -0.8660102 -0.1284072 0.4797493 -0.8679587 -0.1093021 0.4083381 -0.9062634 -0.05848324 0.4186578 -0.9062591 -0.04755151 0.3403551 -0.939094 -0.00755167 0.3435597 -0.9391006 -0.005749583 0.2611939 -0.9652692 0.02560794 0.2599674 -0.9652778 0.01755499 0.1782096 -0.9838359 0.1609326 0.1662638 -0.9728602 -0.00941956 0.1796236 -0.9836904 -0.004085302 0.1796555 -0.9837212 -0.005939602 0.2612461 -0.965254 -0.03714811 0.258638 -0.9652598 -0.04876524 0.33961 -0.9393014 -0.08914089 0.3312683 -0.9393165 -0.1097558 0.4079115 -0.9064005 -0.1579706 0.3918385 -0.9063708 -0.1845935 0.4578394 -0.86966 -0.24197 0.4323819 -0.8686176 -0.2086078 0.4545215 -0.8659636 -0.207917 0.4549022 -0.8659299 -0.2737739 0.4182077 -0.8661121 -0.2395339 0.4361417 -0.8674123 -0.2034469 0.3704336 -0.9063048 -0.1576202 0.3922567 -0.9062508 -0.1280149 0.3185339 -0.9392275 -0.08860057 0.3317552 -0.9391957 -0.0675525 0.252906 -0.9651296 -0.03562992 0.2594253 -0.9651058 -0.02420341 0.176253 -0.9840473 -0.008489131 0.1775817 -0.9840695 -0.01120591 0.1789082 -0.983802 -0.02601963 0.1755033 -0.984135 -0.04683417 0.171272 -0.98411 -0.06890004 0.2519939 -0.965273 -0.09703683 0.2426241 -0.9652552 -0.1275905 0.3189879 -0.9391312 -0.1659846 0.30085 -0.9391158 -0.2039486 0.3696609 -0.9065075 -0.247722 0.34196 -0.9064751 -0.2895981 0.3997879 -0.8696566 -0.3390194 0.3591337 -0.8695337 -0.3128936 0.3896781 -0.866169 -0.3125912 0.3898029 -0.8662219 -0.3816931 0.3230048 -0.8660129 -0.3365574 0.3669613 -0.8672189 -0.2856095 0.3114629 -0.9063212 -0.2473874 0.3426951 -0.9062889 -0.2012236 0.2787685 -0.9390407 -0.1656755 0.3012282 -0.9390492 -0.1259271 0.2290536 -0.9652341 -0.09676074 0.2427562 -0.9652497 -0.06583064 0.1652353 -0.9840547 -0.04569447 0.1719528 -0.9840449 -0.399129 0.3023675 -0.8656038 -0.377198 0.3202337 -0.8690065 -0.3219726 0.2733878 -0.9064176 -0.2856861 0.3113195 -0.9063463 -0.2324035 0.2532479 -0.9390709 -0.2013707 0.2785035 -0.9390876 -0.1530531 0.2116864 -0.9652791 -0.1261561 0.228641 -0.965302 -0.08678537 0.1573179 -0.9837273 -0.08259183 0.1575429 -0.9840523 -0.4215176 0.2659599 -0.8669419 -0.4126386 0.2721352 -0.8692939 -0.3529155 0.2327821 -0.9062357 -0.3218426 0.2741832 -0.9062235 -0.2615509 0.2229478 -0.9390876 -0.2324163 0.2531731 -0.939088 -0.1957184 0.2131988 -0.9572046 -0.1321619 0.2186925 -0.9668024 -0.4621307 0.1918978 -0.8658005 -0.442188 0.2201819 -0.8694767 -0.3782514 0.1883059 -0.9063481 -0.3529783 0.2323011 -0.9063347 -0.2868737 0.1887785 -0.9391839 -0.2617863 0.2221921 -0.9392011 -0.4748724 0.1542436 -0.8664324 -0.4645395 0.1666854 -0.8697237 -0.3984078 0.1430094 -0.905991 -0.378277 0.1900839 -0.9059662 -0.3071347 0.1543327 -0.9390686 -0.2867873 0.1893142 -0.9391024 -0.4948266 0.07395601 -0.865839 -0.4945394 0.07675915 -0.8657592 -0.4945394 0.07675909 -0.8657591 -0.4945394 0.07675904 -0.8657591 -0.4803645 0.116136 -0.869346 -0.4865351 0.1095232 -0.8667689 -0.4118601 0.09269905 -0.9065198 -0.3980283 0.1405081 -0.906549 -0.3235196 0.1142538 -0.9392982 -0.3071387 0.1526251 -0.9393463 -0.4986421 0.0347718 -0.8661103 -0.4919347 0.04981434 -0.8692058 -0.420274 0.04253613 -0.9063997 -0.4120516 0.09344106 -0.9063566 -0.3347694 0.07585221 -0.9392423 -0.3235574 0.1148067 -0.9392178 -0.4974088 -0.0490576 -0.8661282 -0.4979333 -0.04384452 -0.8661063 -0.4954594 -0.006793081 -0.8686045 -0.4974757 -0.01072758 -0.8674117 -0.4220757 -0.009156703 -0.9065144 -0.4200394 0.04203969 -0.9065317 -0.3413721 0.03409463 -0.9393097 -0.3346748 0.07527989 -0.939322 -0.272228 0.06127077 -0.9602801 -0.2626689 0.09316331 -0.9603779 -0.2468028 0.1008798 -0.9638007 -0.2390192 0.1187738 -0.9637234 -0.2636089 0.1078596 -0.9585806 -0.2361765 0.1559135 -0.9591203 -0.2101984 0.1642605 -0.9637609 -0.2037636 0.1729589 -0.9636212 -0.2185894 0.1702054 -0.9608584 -0.2193855 0.1695252 -0.9607973 -0.4917086 -0.08819991 -0.8662813 -0.489048 -0.06922161 -0.869506 -0.4189033 -0.05928456 -0.9060935 -0.4231106 -0.007364392 -0.9060481 -0.3436215 -0.005926787 -0.9390896 -0.3419604 0.03579038 -0.9390325 -0.2603533 0.0272569 -0.9651287 -0.2620031 0.01702278 -0.964917 -0.1648879 0.1650984 -0.9723963 -0.4710644 -0.167671 -0.8660167 -0.4712848 -0.1668943 -0.8660467 -0.4792886 -0.1302182 -0.8679434 -0.4789441 -0.1283961 -0.8684049 -0.4081574 -0.1094267 -0.9063296 -0.4181956 -0.06031084 -0.9063528 -0.3395805 -0.04897695 -0.939301 -0.3428663 -0.007536411 -0.9393541 -0.261205 -0.005724549 -0.9652664 -0.2599878 0.02562439 -0.965272 -0.177977 0.01755827 -0.9838781 -0.164563 0.1649937 -0.9724692 -0.1795894 -0.009391009 -0.9836968 -0.1796963 -0.004122793 -0.9837135 -0.2611909 -0.005962371 -0.9652689 -0.2585984 -0.03720796 -0.9652681 -0.339558 -0.04883068 -0.9393168 -0.3313832 -0.0891 -0.9392797 -0.4079234 -0.1096362 -0.9064096 -0.3917999 -0.1579594 -0.9063894 -0.4578007 -0.184586 -0.869682 -0.4322019 -0.2418782 -0.8687327 -0.4558227 -0.206153 -0.8658677 -0.4545889 -0.209015 -0.86583 -0.4144746 -0.279362 -0.8661223 -0.4355947 -0.2396494 -0.8676552 -0.370399 -0.2038508 -0.9062281 -0.3924577 -0.1573584 -0.9062094 -0.3187472 -0.1278916 -0.939172 -0.3318772 -0.08841979 -0.9391696 -0.2529761 -0.0674315 -0.9651197 -0.2594554 -0.03560632 -0.9650985 -0.1762566 -0.0241931 -0.9840469 -0.17751 -0.008456587 -0.9840826 -0.1791916 -0.01099801 -0.9837527 -0.1754835 -0.02605432 -0.9841377 -0.1715099 -0.0455982 -0.9841267 -0.2530989 -0.06728309 -0.965098 -0.2429469 -0.09762209 -0.965115 -0.3185549 -0.1280369 -0.9392174 -0.3004169 -0.1662146 -0.9392138 -0.3694846 -0.2044154 -0.9064742 -0.3429996 -0.2463588 -0.9064539 -0.4014137 -0.2882498 -0.8693556 -0.3589639 -0.3399949 -0.8692229 -0.3912352 -0.3122782 -0.865689 -0.3908302 -0.3128803 -0.8656545 -0.3292436 -0.3751959 -0.8665026 -0.3292436 -0.375196 -0.8665025 -0.3292436 -0.3751962 -0.8665024 -0.3654233 -0.3378384 -0.8673703 -0.3099558 -0.286616 -0.9065201 -0.3425626 -0.2464798 -0.9065862 -0.278945 -0.2007347 -0.9390928 -0.3011527 -0.1657015 -0.9390687 -0.2290974 -0.1260983 -0.9652014 -0.2421699 -0.09849458 -0.9652215 -0.1643654 -0.06688165 -0.9841295 -0.1714307 -0.04568535 -0.9841364 -0.3017497 -0.3992432 -0.8657667 -0.3201044 -0.3765997 -0.8693135 -0.2738302 -0.3221182 -0.9062323 -0.3113967 -0.2861045 -0.9061879 -0.2528265 -0.2322969 -0.9392108 -0.2782191 -0.2012119 -0.9392061 -0.2118514 -0.1531941 -0.9652205 -0.228869 -0.126257 -0.9652349 -0.1571361 -0.08666586 -0.9837669 -0.1573969 -0.0828765 -0.9840517 -0.2666101 -0.4210882 -0.8669509 -0.2725923 -0.4125983 -0.8691699 -0.2331376 -0.352823 -0.9061804 -0.2741418 -0.3221346 -0.9061322 -0.2225764 -0.261554 -0.9391748 -0.2531201 -0.2320646 -0.9391893 -0.2138356 -0.1960833 -0.9569878 -0.2192049 -0.1317108 -0.9667479 -0.502138 -0.864787 -0.001017808 -0.4970799 -0.8677025 0.002054452 -0.5005058 -0.8657332 -3.80685e-4 -0.5005075 -0.8657321 -3.4037e-4 -0.4992306 -0.8664679 0.00151205 -0.499574 -0.8662706 0.001078546 -0.5031489 -0.8641406 -0.0101093 -0.4998413 -0.8661139 0.002357482 -0.4998414 -0.8661139 0.002357661 -0.4998413 -0.8661139 0.002357542 0.802155 -0.5971159 0 0.91814 -0.3962563 0 0.9845395 -0.1751629 0 0.9845541 -0.1750808 0 0.9981838 0.06024259 0 0.9981787 0.06032687 0 0.9579609 0.2868991 0 0.9579143 0.2870544 0 0.8657831 0.5004197 0 0.8657097 0.5005466 0 0.7283049 0.6852533 0 0.7283051 0.6852531 0 0.5486987 0.8360202 0 0.3419806 0.9397071 0 0.117674 0.9930524 0 -0.117674 0.9930524 0 -0.3419806 0.9397071 0 -0.5486987 0.8360202 0 -0.7283049 0.6852533 0 -0.7283051 0.6852531 0 -0.8657096 0.5005467 0 -0.8657831 0.5004195 0 -0.9579144 0.2870544 0 -0.9579608 0.2868992 0 -0.9983478 0.05745989 0 -0.9983527 0.05737549 0 -0.9850463 -0.1722899 0 -0.9850175 -0.1724541 0 -0.9181708 -0.3961849 0 -0.91814 -0.3962563 0 -0.802155 -0.5971159 0 -0.6425636 -0.7662324 0 -0.642522 -0.7662674 0 -0.4491088 -0.8934771 0 -0.4490408 -0.8935112 0 -0.2304688 -0.9730798 0 -0.2304878 -0.9730752 0 0.2304877 -0.9730752 0 0.2304688 -0.9730797 0 0.4490749 -0.8934943 0 0.642522 -0.7662674 0 0.6425636 -0.7662324 0 2.73801e-6 0 1 7.44358e-6 0 1 5.95749e-6 0 1 -4.19419e-6 0 1 9.85144e-6 0 1 -3.21709e-5 0 1 -8.85459e-7 0 1 -5.47972e-7 0 1 -3.7634e-6 0 1 2.20653e-5 0 1 -5.69126e-6 0 1 -3.52993e-6 0 1 -9.86738e-6 0 1 -1.106e-5 0 1 -7.68457e-6 0 1 1.18844e-5 0 1 -4.89417e-6 0 1 5.5054e-6 0 1 -5.22141e-6 0 1 4.40442e-6 0 1 1.51684e-5 0 1 9.77693e-6 0 1 -1.18197e-5 0 1 1.40583e-5 0 1 -1.57659e-5 0 1 5.06005e-6 0 1 -4.61939e-6 0 1 3.44847e-6 0 1 1.01158e-5 0 1 -2.10051e-5 0 1 1.73357e-5 0 1 -1.56453e-5 0 1 -3.31225e-5 0 1 -2.02179e-5 0 1 2.06785e-5 0 1 -0.08542734 0.2250682 -0.9705909 -0.2241989 -0.08950459 -0.9704246 -0.1494353 -0.1104052 -0.9825884 0.1079141 -0.1496774 -0.9828283 0.2247212 -0.06577289 -0.9722008 0.2014871 0.02309089 -0.979219 0.2249473 0.06583952 -0.972144 0.1499162 0.1029462 -0.9833246 0.2249717 0.06584769 -0.9721378 0.1505455 0.08738118 -0.9847338 0.1502491 0.0878008 -0.9847417 0.1983496 0.04607379 -0.9790479 0.2332767 -0.02673894 -0.9720427 0.2327696 -0.03699535 -0.971828 0.2780907 0 -0.9605549 0.2326731 0.03696078 -0.9718525 0.2327427 0.03676158 -0.9718433 0.2322237 -0.08272784 -0.969138 0.2236913 -0.1060161 -0.9688771 0.277817 -0.06453299 -0.958464 0.199633 -0.03638243 -0.9791951 0.1996383 -0.03644871 -0.9791916 0.1503514 -0.08726847 -0.9847734 0.1562542 -0.07702589 -0.984709 0.1503529 -0.07717621 -0.9856155 0.1417134 -0.09076666 -0.9857377 0.1502394 -0.08521729 -0.9849702 -0.119756 -0.2240867 -0.9671834 -0.1197559 -0.2240867 -0.9671834 -0.1197561 -0.2240867 -0.9671834 -0.1309294 -0.1963673 -0.9717497 -0.1309294 -0.1963669 -0.9717497 -0.1309294 -0.1963676 -0.9717496 0.02560937 -0.05697506 -0.9980472 0.02560937 -0.05697506 -0.9980472 0.02560937 -0.05697512 -0.9980472 -0.03742909 -0.2931287 -0.9553401 -0.007147371 -0.2239872 -0.974566 -0.03148448 -0.2223008 -0.9744697 -0.08647394 -0.221894 -0.9712288 -0.07899886 -0.2247527 -0.9712082 -0.07630938 -0.2895506 -0.9541161 -0.07630932 -0.2895506 -0.954116 -0.07630926 -0.2895506 -0.9541161 -0.03699231 -0.1993749 -0.9792248 -0.03702527 -0.1992447 -0.9792501 -0.09507775 -0.1394385 -0.9856557 -0.07837182 -0.1502032 -0.985544 -0.07830709 -0.1504413 -0.9855129 -0.07810509 -0.1505224 -0.9855164 -0.08186256 -0.2166221 -0.9728173 -0.2243438 -0.08952742 -0.9703889 -0.150501 -0.07574313 -0.9857041 -0.1503735 -0.07589131 -0.9857121 -0.2978046 0.08719915 -0.950636 -0.2245705 0.07869607 -0.971275 -0.2190139 0.09292811 -0.9712865 -0.2242494 0.08886826 -0.9704714 -0.1379368 0.1000406 -0.9853758 -0.1503175 0.08092403 -0.9853203 -0.1462036 0.08270424 -0.9857913 -0.150501 0.07574313 -0.9857041 -0.1073839 0.1513413 -0.9826315 -0.08892011 0.1434406 -0.9856562 -0.07822442 0.1502866 -0.985543 -0.0819469 0.2168481 -0.9727598 -0.08194696 0.2168482 -0.9727599 -0.0819469 0.2168481 -0.9727598 -0.07816457 0.1505216 -0.9855118 -0.07869631 0.15015 -0.9855262 -0.008788466 0.2764093 -0.9609999 0.03927236 0.2475435 -0.9680806 0.02222096 0.2479648 -0.9685143 0.03709924 0.2026596 -0.9785463 0.04073452 0.2021031 -0.9785168 0.03586703 0.2366562 -0.9709312 0.03586703 0.236656 -0.9709313 0.03586709 0.2366562 -0.9709312 0.04205578 0.2353116 -0.9710097 0.08814126 0.2740592 -0.9576653 0.0881412 0.2740591 -0.9576653 0.08814126 0.2740591 -0.9576653 0.07908946 0.2249999 -0.9711437 0.09963703 0.1381057 -0.985393 0.08340996 0.1500288 -0.985157 0.08711481 0.1434483 -0.9858163 0.07505124 0.150951 -0.9856882 0.08473157 0.1883881 -0.9784327 -0.1573027 0.2198448 -0.962769 -0.1073153 -0.1512446 -0.9826538 -0.09142309 -0.1445366 -0.9852671 -0.1123555 -0.1283399 -0.9853453 -0.111707 -0.1286833 -0.9853742 -0.1257586 -0.1150686 -0.9853649 -0.1260449 -0.1148762 -0.9853508 -0.1387277 -0.09941995 -0.9853276 -0.1378727 -0.09999614 -0.9853892 -0.1484186 -0.08396279 -0.9853539 0.09312444 -0.2212136 -0.970769 0.09312444 -0.2212136 -0.970769 0.09312438 -0.2212136 -0.9707691 0.07505124 -0.150951 -0.9856882 0.08709645 -0.1434485 -0.9858179 0.08422255 -0.1485596 -0.9853105 0.1044569 -0.1347508 -0.9853584 0.1040949 -0.1352257 -0.9853316 0.1183534 -0.1228996 -0.9853366 0.1181098 -0.1231911 -0.9853294 0.1321972 -0.1078715 -0.9853363 0.1322661 -0.1075679 -0.9853603 0.1402683 -0.09644246 -0.9854054 0.1402683 -0.09644252 -0.9854054 0.1402683 -0.09644252 -0.9854054 0.1039511 0.1350497 -0.9853709 0.1045284 0.1348429 -0.9853382 0.1180902 0.123175 -0.9853338 0.1183915 0.122942 -0.9853268 0.1323834 0.10768 -0.9853323 0.1321992 0.1078621 -0.9853371 0.1470925 0.08725386 -0.9852668 0.141725 0.0907886 -0.985734 0.1517974 0.07482022 -0.9855758 -0.1497365 0.1106277 -0.9825174 -0.1386585 0.09937036 -0.9853422 -0.1258976 0.1151882 -0.9853333 -0.1259858 0.1148273 -0.9853641 -0.1122471 0.1282067 -0.9853748 -0.1118068 0.1288044 -0.985347 -0.09608244 0.1409299 -0.9853461 -0.08542501 -0.2250664 -0.9705914 -0.08506113 -0.2250109 -0.9706363 -0.1109727 -0.2131699 -0.9706924 -0.1121429 -0.2130416 -0.9705861 -0.1355982 -0.1988797 -0.9705978 -0.1365274 -0.1986811 -0.9705082 -0.1580241 -0.1820412 -0.9705099 -0.1580697 -0.1820187 -0.9705066 -0.1781644 -0.1623876 -0.970509 -0.1768122 -0.1631175 -0.9706339 -0.1947264 -0.1412336 -0.9706362 -0.1946185 -0.141286 -0.9706503 -0.2094209 -0.1184685 -0.9706226 -0.209659 -0.1181436 -0.9706107 -0.2239831 -0.08906686 -0.9705147 -0.2189884 -0.09292441 -0.9712925 -0.224617 -0.07871419 -0.9712628 -0.2980653 -0.08723533 -0.950551 -0.2980653 -0.08723533 -0.950551 -0.2980653 -0.08723527 -0.950551 -0.2096583 -0.03687983 -0.977079 -0.2095817 -0.03634119 -0.9771156 -0.2103027 -0.03660172 -0.976951 -0.2125748 -0.01218593 -0.9770689 -0.2686419 -0.037023 -0.9625284 -0.2686767 0.01540154 -0.9631073 -0.2103047 0.03650027 -0.9769544 -0.2103102 0.03645575 -0.9769548 -0.209599 0.03660082 -0.9771023 -0.209645 0.03688341 -0.9770817 0.2244536 -0.06569343 -0.9722679 0.2259541 -0.08267414 -0.9706234 0.2158717 -0.1064212 -0.970605 0.2159641 -0.1060416 -0.970626 0.2025482 -0.1297284 -0.9706414 0.2024314 -0.1300837 -0.9706183 0.1865069 -0.1521686 -0.9705977 0.186187 -0.1528506 -0.970552 0.1671953 -0.1736244 -0.9705155 0.1679734 -0.1718223 -0.9707018 0.1471628 -0.1898328 -0.9707248 0.1462921 -0.1913145 -0.9705656 0.1250308 -0.205927 -0.970547 0.1244938 -0.2064936 -0.9704956 0.09897869 -0.2200189 -0.9704612 0.1008574 -0.218114 -0.9706978 0.07936197 -0.2264738 -0.9707787 0.08814007 -0.2740527 -0.9576672 0.08814001 -0.2740527 -0.9576672 0.08814001 -0.2740527 -0.9576672 0.04218482 -0.2352217 -0.9710259 0.04726403 -0.23434 -0.9710051 0.03570455 -0.2026703 -0.978596 0.01831907 -0.2047542 -0.9786421 0.03760308 -0.2475791 -0.9681378 0.03929883 -0.2474129 -0.9681128 -0.1317238 0.1971208 -0.9714898 -0.1317235 0.1971207 -0.9714899 -0.1317238 0.1971207 -0.9714897 -0.0939033 0.2890012 -0.9527122 -0.09390318 0.2890012 -0.9527122 -0.0939033 0.2890011 -0.9527122 0.09853595 0.2190346 -0.9707289 0.101188 0.218829 -0.9705024 0.1251897 0.2061169 -0.9704862 0.1243601 0.2062852 -0.970557 0.1476094 0.1904088 -0.9705442 0.145954 0.1909042 -0.9706972 0.1666191 0.1730347 -0.9707199 0.1684147 0.1722675 -0.9705464 0.1866904 0.1523228 -0.9705383 0.1859909 0.1526862 -0.9706155 0.2026851 0.1298333 -0.9705989 0.2023908 0.130046 -0.9706318 0.215718 0.1063279 -0.9706494 0.2160661 0.1060937 -0.9705976 0.2259142 0.08265954 -0.9706339 0.2321611 0.0827105 -0.9691544 0.2238828 0.1060424 -0.9688301 0.223882 0.106042 -0.9688302 0.2238824 0.1060422 -0.9688302 0.3121342 0.03727436 -0.9493066 -0.2242239 0.08948016 -0.970421 -0.2238144 0.08932262 -0.9705301 -0.2095611 0.1185486 -0.9705825 -0.2095443 0.1180767 -0.9706436 -0.1946936 0.1412098 -0.9706463 -0.1946771 0.1413491 -0.9706294 -0.1776962 0.161951 -0.9706678 -0.1771891 0.163469 -0.970506 -0.1580107 0.1820259 -0.970515 -0.1580498 0.1819958 -0.9705142 -0.1358222 0.1992191 -0.9704969 -0.136345 0.1983781 -0.9705958 -0.1111826 0.2135943 -0.970575 -0.1119512 0.2127469 -0.9706729 -0.085074 0.2250106 -0.9706352 -0.08649057 0.2218777 -0.971231 -0.07904076 0.2247045 -0.971216 -0.07641911 0.2899474 -0.9539867 -0.07641899 0.2899473 -0.9539868 -0.07641899 0.2899473 -0.9539867 -0.03695446 0.199278 -0.979246 -0.02839148 0.2004127 -0.9793002 -0.03730374 0.2216385 -0.9744151 -0.03684383 0.2216604 -0.9744277 -0.3050422 0.05288767 -0.9508692 -0.3049337 0.0527687 -0.9509106 -0.2970492 0.08695495 -0.9508946 -0.2970137 0.08705401 -0.9508967 -0.2850039 0.1209245 -0.9508681 -0.2849732 0.120631 -0.9509146 -0.2695338 0.1518854 -0.9509376 -0.2695953 0.151664 -0.9509555 -0.2503196 0.1817451 -0.9509516 -0.2501646 0.1822443 -0.9508969 -0.2275509 0.2099254 -0.9508691 -0.2277871 0.2092927 -0.9509519 -0.2027557 0.2334712 -0.9509897 -0.202556 0.2340503 -0.9508898 -0.1753414 0.2551088 -0.9508811 -0.1752367 0.2550856 -0.9509068 -0.1441684 0.2739799 -0.9508684 -0.1440267 0.2740124 -0.9508805 -0.1124638 0.2884948 -0.9508537 -0.1123859 0.2885343 -0.9508509 -0.07891255 0.2994242 -0.9508512 -0.07905685 0.2993549 -0.950861 -0.04343962 0.3065569 -0.9508606 -0.04424834 0.305987 -0.9510068 -0.00984019 0.3089728 -0.9510201 -0.007903397 0.3099035 -0.9507352 0.02767467 0.3089132 -0.9506876 0.02528405 0.3080375 -0.9510383 0.0610519 0.3028832 -0.9510703 0.06160956 0.3030321 -0.9509868 0.09466612 0.2943463 -0.9509988 0.09653419 0.2945773 -0.9507395 0.1301547 0.2814604 -0.950705 0.1280423 0.2814196 -0.9510038 0.1596438 0.2647989 -0.9509971 0.1595669 0.2647766 -0.9510162 0.1877439 0.2455675 -0.9510253 0.1898034 0.2451272 -0.9507299 0.2167105 0.2216879 -0.9507319 0.2153344 0.2222145 -0.9509216 0.2390965 0.1962824 -0.9509502 0.2391776 0.196209 -0.9509449 0.2603219 0.1672587 -0.9509244 0.2605247 0.16707 -0.950902 0.2779096 0.1364508 -0.9508666 0.2779259 0.1363602 -0.9508749 0.2916221 0.1039064 -0.9508734 0.2913252 0.1041325 -0.9509396 0.3014281 0.07001489 -0.9509149 0.3014718 0.0699675 -0.9509046 0.3074886 0.03524309 -0.950899 0.3074173 0.03535288 -0.9509179 0.3094355 0 -0.9509205 0.3094831 0 -0.9509051 0.3074126 -0.03523641 -0.9509237 0.3074211 -0.03535169 -0.9509167 0.3013986 -0.07001358 -0.9509243 0.3014748 -0.06996905 -0.9509035 0.2914405 -0.1038284 -0.9509376 0.2914957 -0.1041946 -0.9508806 0.2779042 -0.1364551 -0.9508677 0.2778436 -0.1363165 -0.9509053 0.2604485 -0.1673676 -0.9508706 0.2602909 -0.1679332 -0.950814 0.2395116 -0.1966232 -0.9507753 0.2398495 -0.1954861 -0.9509246 0.216238 -0.2211922 -0.9509549 0.2157055 -0.2226042 -0.9507464 0.1883721 -0.2463357 -0.9507023 0.1893468 -0.2445459 -0.9509707 0.1596349 -0.2647909 -0.9510008 0.1595701 -0.2647764 -0.9510157 0.1297181 -0.2805122 -0.9510448 0.128392 -0.2821769 -0.9507323 0.09495663 -0.2952455 -0.950691 0.09632426 -0.2938803 -0.9509764 0.06113278 -0.3031596 -0.9509769 0.06156075 -0.3027952 -0.9510654 0.02754122 -0.3076908 -0.9510878 0.02535277 -0.3089578 -0.9507378 -0.009888112 -0.3099674 -0.9506958 -0.00791496 -0.3091058 -0.9509947 -0.04334563 -0.3060652 -0.9510233 -0.04425704 -0.3063514 -0.9508892 -0.07888019 -0.2993282 -0.9508842 -0.0790897 -0.2993869 -0.9508483 -0.1124502 -0.2885223 -0.9508469 -0.1123684 -0.2885059 -0.9508616 -0.1442377 -0.273976 -0.950859 -0.1440203 -0.2739601 -0.9508964 -0.175306 -0.2551105 -0.9508872 -0.175235 -0.2551116 -0.9509 -0.2029767 -0.2337386 -0.9508768 -0.202419 -0.2338817 -0.9509605 -0.2273095 -0.2097046 -0.9509755 -0.22797 -0.2094367 -0.9508765 -0.2505355 -0.1818823 -0.9508685 -0.2499757 -0.1821058 -0.950973 -0.2695003 -0.1518628 -0.9509508 -0.2697074 -0.1517431 -0.9509112 -0.2848319 -0.1208617 -0.9509277 -0.2850437 -0.1206641 -0.9508892 -0.2971154 -0.08696484 -0.950873 -0.2969549 -0.08703678 -0.9509167 -0.3049592 -0.05287468 -0.9508966 -0.3050159 -0.05278235 -0.9508835 -0.3089292 -0.01770657 -0.9509202 -0.3089751 -0.01775103 -0.9509045 -0.3089079 0.01770591 -0.9509271 -0.3089479 0.01774489 -0.9509134 -0.371151 0.06422638 -0.9263488 -0.3712213 0.06424069 -0.9263197 -0.3614447 0.1059378 -0.9263558 -0.3615599 0.1062128 -0.9262793 -0.3470661 0.1469166 -0.9262617 -0.3469991 0.1467016 -0.9263209 -0.3283311 0.184705 -0.9263277 -0.3283554 0.1847816 -0.9263037 -0.3045122 0.2218353 -0.926316 -0.3046303 0.2211347 -0.9264447 -0.2771822 0.2546774 -0.9264499 -0.2771954 0.2544876 -0.9264981 -0.246296 0.2845823 -0.9264726 -0.2463436 0.2841716 -0.9265859 -0.2128793 0.3098871 -0.926635 -0.2119111 0.3118936 -0.9261836 -0.1755565 0.3339865 -0.9260848 -0.1759034 0.3332408 -0.9262875 -0.1367791 0.3511719 -0.9262667 -0.1370323 0.3508216 -0.9263619 -0.09614664 0.364055 -0.9264016 -0.0953443 0.3649277 -0.9261411 -0.05397945 0.3732867 -0.9261443 -0.05483061 0.3726627 -0.9263456 -0.009604811 0.3765805 -0.9263342 -0.009658515 0.3764742 -0.9263768 0.03080159 0.3753599 -0.9263673 0.03232347 0.3760325 -0.9260425 0.07518833 0.3698271 -0.9260532 0.07428354 0.369579 -0.9262254 0.1173925 0.3582328 -0.9262226 0.1160628 0.3579887 -0.9264845 0.1558401 0.342502 -0.9265022 0.1564072 0.3425444 -0.926391 0.1943819 0.3225397 -0.9263821 0.1951486 0.3224619 -0.926248 0.2308137 0.298098 -0.9262088 0.2290993 0.2983614 -0.9265494 0.2617337 0.2700992 -0.9265754 0.2627202 0.2699062 -0.9263524 0.2911769 0.2388589 -0.9263707 0.2920395 0.2385223 -0.9261859 0.3173962 0.2035352 -0.9261929 0.3166211 0.2039396 -0.9263691 0.3381201 0.1658918 -0.9263665 0.3381635 0.1659086 -0.9263476 0.3546791 0.1267782 -0.9263532 0.354897 0.1265864 -0.9262958 0.3669677 0.08516955 -0.9263266 0.3667885 0.08546423 -0.9263705 0.3741685 0.04302847 -0.926362 0.3742873 0.04294329 -0.926318 0.3766561 0 -0.9263533 0.3767323 0 -0.9263222 0.3741685 -0.04302847 -0.926362 0.3742609 -0.04294276 -0.9263286 0.3667585 -0.08512026 -0.9264139 0.3669905 -0.08550494 -0.9262866 0.3548534 -0.1268393 -0.926278 0.3547393 -0.1265301 -0.926364 0.3380861 -0.165876 -0.9263817 0.3381522 -0.1659018 -0.9263529 0.316461 -0.2041745 -0.9263721 0.3165271 -0.2038887 -0.9264124 0.2917945 -0.2378225 -0.926443 0.2917056 -0.2382291 -0.9263664 0.2621314 -0.2705094 -0.9263433 0.2623813 -0.2695526 -0.9265515 0.2302083 -0.2973204 -0.9266093 0.2295476 -0.2989416 -0.9262515 0.194634 -0.3229495 -0.9261864 0.1949645 -0.3222056 -0.926376 0.1559567 -0.3427582 -0.9263878 0.1562882 -0.3422389 -0.9265239 0.1171872 -0.3575069 -0.9265291 0.1162412 -0.3585393 -0.9262493 0.07509416 -0.3693574 -0.9262484 0.07436168 -0.369973 -0.9260618 0.03087663 -0.3761948 -0.9260261 0.03225785 -0.3753333 -0.9263285 -0.009635508 -0.3765077 -0.9263635 -0.009685158 -0.3765046 -0.9263641 -0.05384409 -0.3727173 -0.9263815 -0.05489629 -0.3731406 -0.9261493 -0.09635537 -0.364722 -0.9261175 -0.09519517 -0.3644562 -0.926342 -0.1366933 -0.3509515 -0.9263628 -0.1371099 -0.3510202 -0.9262752 -0.1753475 -0.3335332 -0.9262877 -0.1760432 -0.3335108 -0.9261638 -0.213549 -0.3109093 -0.9261384 -0.2113796 -0.3111113 -0.9265682 -0.2461237 -0.284379 -0.9265807 -0.246478 -0.2843301 -0.9265015 -0.277126 -0.2546018 -0.9264876 -0.2772853 -0.2545477 -0.9264547 -0.3042145 -0.2216214 -0.926465 -0.3048692 -0.2213239 -0.9263209 -0.3283646 -0.1847363 -0.9263095 -0.3283239 -0.1847555 -0.9263201 -0.3470004 -0.1468881 -0.9262908 -0.3471227 -0.146762 -0.926265 -0.361619 -0.1059889 -0.9262819 -0.361433 -0.1061739 -0.9263333 -0.3712224 -0.06424528 -0.9263188 -0.3711388 -0.06422096 -0.9263541 -0.3761547 -0.02160584 -0.9263049 -0.3760966 -0.02162897 -0.926328 -0.3761073 0.02159816 -0.9263244 -0.3760896 0.02162975 -0.9263309 -0.4354318 0.07534742 -0.897063 -0.4353289 0.07528203 -0.8971185 -0.4238465 0.1245067 -0.8971356 -0.423847 0.1245383 -0.897131 -0.4069187 0.1720346 -0.8971183 -0.4068952 0.1719098 -0.8971529 -0.3848474 0.216574 -0.8972113 -0.3849294 0.2175215 -0.896947 -0.3577843 0.2597118 -0.8969616 -0.3578565 0.2594907 -0.8969969 -0.3255915 0.2989181 -0.8970164 -0.3255554 0.2989051 -0.8970338 -0.2894925 0.3339426 -0.8970376 -0.289552 0.3338649 -0.8970474 -0.2484213 0.36562 -0.897 -0.2486805 0.3648591 -0.8972379 -0.2061194 0.3904861 -0.8972377 -0.2060413 0.390653 -0.897183 -0.1606626 0.4113119 -0.8972235 -0.1603319 0.4118329 -0.8970437 -0.1117343 0.4276346 -0.8970195 -0.1126673 0.4265841 -0.897403 -0.06420195 0.4364064 -0.8974562 -0.06225878 0.4380772 -0.8967789 -0.01135641 0.4424677 -0.8967127 -0.01307761 0.4412574 -0.8972853 0.03780144 0.4398124 -0.8972938 0.03756773 0.4397235 -0.8973472 0.08694761 0.4325884 -0.8973892 0.08835959 0.433182 -0.896965 0.1363506 0.4205527 -0.8969637 0.1358144 0.4203794 -0.8971263 0.1834798 0.4018319 -0.8971435 0.1849234 0.4020804 -0.8967357 0.2291633 0.3786649 -0.8967147 0.2274957 0.3785996 -0.8971668 0.268983 0.3502961 -0.897185 0.2701081 0.3501778 -0.8968931 0.3084566 0.3168939 -0.8969019 0.3076927 0.3170666 -0.8971032 0.342215 0.2794908 -0.8970919 0.3417548 0.2795962 -0.8972346 0.3713134 0.2391633 -0.8971774 0.3724733 0.2385784 -0.8968523 0.3970664 0.1948072 -0.8968771 0.3963967 0.1952396 -0.8970792 0.4162238 0.1484565 -0.897061 0.4159771 0.1486688 -0.8971404 0.4302293 0.1002458 -0.8971363 0.4307174 0.09982019 -0.8969496 0.4391345 0.05038243 -0.8970077 0.4390786 0.05044251 -0.8970315 0.442017 0 -0.8970067 0.4419505 0 -0.8970395 0.4391081 -0.05038315 -0.8970205 0.4391265 -0.05045074 -0.8970077 0.4306209 -0.1003313 -0.8969389 0.4303806 -0.09973669 -0.8971205 0.4160566 -0.1483961 -0.8971486 0.4160615 -0.1487013 -0.8970957 0.3967251 -0.1946371 -0.8970649 0.3967596 -0.1954206 -0.8968794 0.3719571 -0.2395955 -0.8967953 0.3718989 -0.2382099 -0.8971886 0.3420593 -0.2793443 -0.8971969 0.3419165 -0.2797308 -0.8971309 0.3081879 -0.3166123 -0.8970936 0.3079614 -0.3173483 -0.8969114 0.2693462 -0.3507692 -0.8968911 0.2697792 -0.3497513 -0.8971584 0.2286561 -0.3778709 -0.897179 0.2278965 -0.3792714 -0.8967812 0.1838659 -0.4026176 -0.896712 0.1846007 -0.4014298 -0.8970935 0.1362438 -0.4202234 -0.8971343 0.1359064 -0.4206642 -0.8969789 0.08714389 -0.4335378 -0.8969119 0.08819365 -0.4323916 -0.8973626 0.03778666 -0.4396382 -0.8973799 0.0376017 -0.439844 -0.8972867 -0.01135259 -0.441254 -0.8973105 -0.013103 -0.4422762 -0.8967832 -0.06441903 -0.4378365 -0.8967438 -0.06207758 -0.4368094 -0.8974096 -0.1114923 -0.4268335 -0.8974313 -0.1128118 -0.4272204 -0.897082 -0.1607794 -0.411618 -0.8970622 -0.1602378 -0.4115247 -0.8972019 -0.2061865 -0.3906082 -0.8971691 -0.2059972 -0.3905739 -0.8972275 -0.2481316 -0.3651937 -0.8972538 -0.2489387 -0.3652031 -0.8970264 -0.2894578 -0.3339046 -0.897063 -0.2895498 -0.3338919 -0.897038 -0.3255977 -0.2989043 -0.8970186 -0.3256226 -0.2989431 -0.8969966 -0.3576503 -0.2596379 -0.8970366 -0.3579332 -0.2595587 -0.8969466 -0.3853195 -0.2168259 -0.8969479 -0.3844733 -0.2172638 -0.8972049 -0.4068347 -0.1720067 -0.8971619 -0.4069187 -0.1719241 -0.8971396 -0.4239152 -0.124526 -0.8971006 -0.4238326 -0.1245341 -0.8971383 -0.4353295 -0.07532972 -0.897114 -0.4353289 -0.07528203 -0.8971185 -0.4411858 -0.02537435 -0.8970569 -0.4413284 -0.02517247 -0.8969926 -0.441277 0.02537804 -0.8970121 -0.4412075 0.02516424 -0.8970524 0.04304647 -0.5036432 -0.8628387 0.006594657 -0.504899 -0.8631533 -0.01485598 -0.5013701 -0.8651055 -0.01980632 -0.5036693 -0.8636695 -0.07095146 -0.4992398 -0.863554 -0.07279062 -0.5001576 -0.8628696 -0.129069 -0.4887561 -0.8628203 -0.1272853 -0.4880989 -0.8634571 -0.1830266 -0.4700461 -0.863457 -0.1833704 -0.4701606 -0.8633217 -0.2354027 -0.446306 -0.8633635 -0.2363715 -0.4464915 -0.8630029 -0.2844936 -0.4173665 -0.8630578 -0.2848971 -0.417393 -0.8629117 -0.3310643 -0.3817707 -0.8629297 -0.3308703 -0.38181 -0.8629867 -0.3720974 -0.3416114 -0.8630442 -0.3721627 -0.3415745 -0.8630306 -0.4089883 -0.296585 -0.8629983 -0.4083794 -0.2967723 -0.8632223 -0.4395589 -0.2483928 -0.8631854 -0.4398809 -0.2482174 -0.8630719 -0.465188 -0.1965333 -0.8631193 -0.4649859 -0.1967519 -0.8631784 -0.4843776 -0.1423243 -0.8632045 -0.4845471 -0.1422188 -0.8631269 -0.4976016 -0.08605116 -0.8631268 -0.497535 -0.08612143 -0.8631582 -0.5041524 -0.02875387 -0.8631359 -0.5040756 -0.02876055 -0.8631806 -0.5041078 0.02875447 -0.8631619 -0.504087 0.0287556 -0.863174 -0.4976338 0.08606147 -0.8631072 -0.4976083 0.08612632 -0.8631155 -0.4844723 0.1423522 -0.8631469 -0.4844387 0.1421858 -0.8631933 -0.4650647 0.1964868 -0.8631964 -0.4651442 0.1968235 -0.8630768 -0.4396573 0.2484497 -0.8631189 -0.4396816 0.2481026 -0.8632065 -0.4086937 0.29635 -0.8632186 -0.408662 0.2969776 -0.8630179 -0.3721567 0.341689 -0.8629878 -0.3721623 0.3415553 -0.8630383 -0.3310008 0.3816553 -0.8630051 -0.330901 0.3818833 -0.8629426 -0.2846275 0.4176011 -0.8629002 -0.2847985 0.4172486 -0.8630142 -0.235666 0.4468212 -0.8630251 -0.2361257 0.4459699 -0.8633399 -0.1830561 0.4702055 -0.8633639 -0.1832758 0.4699138 -0.8634762 -0.128777 0.4875789 -0.8635297 -0.1275302 0.4891142 -0.8628461 -0.07112264 0.5004774 -0.8628233 -0.07266831 0.4991204 -0.8634803 -0.01493436 0.5040169 -0.8635647 -0.01324653 0.5052581 -0.8628667 0.04302388 0.50358 -0.8628767 0.04304647 0.503674 -0.8628206 0.1010316 0.495311 -0.8628208 0.09915971 0.4945385 -0.8634808 0.1550291 0.4798505 -0.8635447 0.1571847 0.4805281 -0.862778 0.2112687 0.45937 -0.8627542 0.209941 0.4591485 -0.8631961 0.2599995 0.4326884 -0.8632387 0.2597926 0.4327148 -0.8632878 0.3082444 0.3996086 -0.8633067 0.3089675 0.3995408 -0.8630796 0.351793 0.3625206 -0.8630298 0.3524807 0.3623785 -0.8628089 0.391215 0.3200601 -0.8628513 0.3909191 0.3201782 -0.8629417 0.4254312 0.2724998 -0.8629902 0.4246934 0.2728129 -0.8632547 0.4528402 0.2230395 -0.8632434 0.4532326 0.2228538 -0.8630855 0.4754763 0.1699354 -0.8631594 0.4760358 0.1696222 -0.8629127 0.4921701 0.1140648 -0.8629935 0.4917049 0.1144937 -0.8632019 0.5016131 0.05762684 -0.8631706 0.501617 0.05762904 -0.8631682 0.5049563 0 -0.8631449 0.5049103 0 -0.8631719 0.5016538 -0.0576353 -0.8631465 0.5015441 -0.05762016 -0.863211 0.4918721 -0.1139868 -0.8631737 0.4920193 -0.1145749 -0.863012 0.4759094 -0.1700863 -0.862891 0.4756745 -0.1694872 -0.8631384 0.4531065 -0.2231659 -0.8630709 0.452987 -0.2227516 -0.8632407 0.4250594 -0.2722585 -0.8632496 0.4250604 -0.2730507 -0.862999 0.3910763 -0.3199452 -0.8629569 0.3910319 -0.3202706 -0.8628563 0.3520665 -0.3627968 -0.8628022 0.3522164 -0.3621089 -0.86303 0.3085445 -0.4000046 -0.863016 0.3087822 -0.3992628 -0.8632745 0.2599547 -0.4326201 -0.8632865 0.2598547 -0.4328127 -0.86322 0.2108799 -0.458581 -0.8632689 0.2102417 -0.4598107 -0.8627703 0.1554564 -0.4811656 -0.8627358 0.1567848 -0.4793123 -0.8635267 0.1007819 -0.4940869 -0.8635514 0.09935235 -0.4956242 -0.8628359 0.04305589 -0.503678 -0.8628179 -0.08217096 -0.9966183 0 0.08216983 -0.9966183 0 0.08216935 -0.9966185 0 0.2464425 -0.9691575 0 0.2464428 -0.9691574 0 0.4003388 -0.9163672 0 0.4003396 -0.9163669 0 0.5470319 -0.8371118 0 0.5470288 -0.8371138 0 0.6782088 -0.7348694 0 0.7891975 -0.6141397 0 0.8791244 -0.4765924 0 0.8791236 -0.476594 0 0.9459615 -0.3242793 0 0.9863526 -0.1646471 0 0.9863517 -0.1646528 0 0.9863508 0.1646578 0 0.9863517 0.1646525 0 0.9459615 0.3242793 0 0.8791233 0.4765947 0 0.8791247 0.4765919 0 0.7891975 0.6141397 0 0.6782088 0.7348694 0 0.5470515 0.837099 0 0.5470546 0.837097 0 0.4003127 0.9163787 0 0.4003117 0.9163791 0 0.2464425 0.9691575 0 0.2464428 0.9691574 0 0.08216935 0.9966185 0 0.08216983 0.9966183 0 -0.08217096 0.9966183 0 -0.08217144 0.9966183 0 -0.2464169 0.969164 0 -0.2464173 0.9691639 0 -0.4003055 0.9163818 0 -0.4003033 0.9163827 0 -0.5471006 0.837067 0 -0.5471023 0.8370658 0 -0.6782424 0.7348383 0 -0.789136 0.6142186 0 -0.7891305 0.6142256 0 -0.8791244 0.4765924 0 -0.8791247 0.4765919 0 -0.9459952 0.3241811 0 -0.9459934 0.3241861 0 -0.9863585 0.1646112 0 -0.9863586 0.1646114 0 -0.9863595 -0.1646059 0 -0.9863594 -0.1646062 0 -0.9459934 -0.3241861 0 -0.9459952 -0.3241811 0 -0.8791244 -0.4765924 0 -0.8791247 -0.4765919 0 -0.7891305 -0.6142256 0 -0.789136 -0.6142186 0 -0.6782424 -0.7348383 0 -0.5470796 -0.8370806 0 -0.5470778 -0.8370818 0 -0.4003306 -0.9163709 0 -0.4003323 -0.9163701 0 -0.2464169 -0.969164 0 -0.2464173 -0.9691639 0 -0.08217144 -0.9966183 0 -0.9182922 -0.3959035 0 -0.8016615 -0.5977784 0 -0.8017427 -0.5976694 0 -0.6427393 -0.766085 0 -0.6427395 -0.7660849 0 -0.4483737 -0.8938462 0 -0.4483398 -0.8938633 0 -0.2323709 -0.9726272 0 -0.2323901 -0.9726227 0 0.2323901 -0.9726227 0 0.4483737 -0.8938462 0 0.6427393 -0.766085 0 0.6426979 -0.7661198 0 0.801702 -0.5977239 0 0.8017427 -0.5976694 0 0.9182306 -0.3960463 0 0.9182614 -0.3959748 0 0.9850402 -0.1723248 0 0.9850402 -0.1723247 0 0.9983508 0.05740958 0 0.9983556 0.0573253 0 0.9577468 0.2876129 0 0.8664683 0.4992322 0 0.8664683 0.4992321 0 0.7269464 0.6866943 0 0.7269042 0.6867389 0 0.5507524 0.8346688 0 0.5507135 0.8346944 0 0.3419534 0.939717 0 0.1148468 0.9933833 0 0.1148565 0.9933821 0 -0.1148468 0.9933833 0 -0.1148468 0.9933833 0 -0.3419534 0.939717 0 -0.5507524 0.8346688 0 -0.5507135 0.8346944 0 -0.7269041 0.6867391 0 -0.7269887 0.6866494 0 -0.8664317 0.4992957 0 -0.8665049 0.4991686 0 -0.9577234 0.2876906 0 -0.9577702 0.2875351 0 -0.9981819 0.06027412 0 -0.998187 0.06018984 0 -0.9845626 -0.175033 0 -0.984548 -0.1751149 0 -0.9182306 -0.3960463 0 -1.76974e-6 0 1 -8.20856e-6 0 1 9.88693e-7 0 1 2.96325e-6 0 1 -1.09501e-6 0 1 -8.78673e-7 0 1 1.49343e-6 0 1 -2.46017e-6 0 1 0.7751018 0.4476776 -0.4458724 0.7749044 0.4479581 -0.4459334 0.780413 0.4364617 -0.4477241 0.7733517 0.4465132 -0.4500592 0.7746457 0.4484446 -0.4458942 0.775202 0.4475989 -0.4457771 0.775202 0.4475991 -0.445777 0.7752021 0.4475989 -0.445777 0.7736619 0.449928 -0.4461078 0.7746239 0.4484072 -0.4459697 0.776986 0.4441561 -0.4461147 0.7743015 0.4485521 -0.4463835 0.7758144 0.4457716 -0.4465421 0.445383 -0.7760707 -0.4464845 0.4516701 -0.7728042 -0.4458339 0.4507452 -0.7733201 -0.4458754 0.446517 -0.7733674 -0.4500286 0.4481167 -0.7744684 -0.4465315 0.4336231 -0.7843974 -0.4434996 0.4474547 -0.7752254 -0.4458812 0.4484388 -0.7745512 -0.446064 0.4438519 -0.7771505 -0.4461308 0.44858 -0.7743182 -0.4463265 0.4483073 -0.7744364 -0.4463954 -0.8212738 -0.5704945 0.006744921 -0.7974006 -0.6034504 0 -0.7451171 -0.6669337 0 -0.7451171 -0.6669337 1.60833e-7 -0.7451171 -0.6669337 0 -0.7168268 -0.6972178 0.006837666 -0.6872656 -0.7264062 0 -0.6252533 -0.7804218 0 -0.5920364 -0.8058813 0.006957292 -0.5576377 -0.8300845 0 -0.4523817 -0.891799 0.006732463 -0.4157796 -0.9094654 0 -0.3368375 -0.9415629 0 -0.2980298 -0.9545325 0.006790578 -0.2587401 -0.965947 0 -0.1777466 -0.9840763 0 -0.1383938 -0.9903555 0.006573855 -0.09907829 -0.9950796 0 0.1510715 -0.9885228 0 0.1923668 -0.9812984 0.006959676 0.2333549 -0.9723917 0 0.3110043 -0.9504085 0 0.350426 -0.936565 0.006908357 0.5000683 -0.8659573 0.007060647 0.5366264 -0.84382 0 0.6034728 -0.7973837 0 0.6356496 -0.7719476 0.0068264 0.6671074 -0.7449616 0 0.7262707 -0.6874089 0 0.754051 -0.6567804 0.006838619 0.7804245 -0.6252501 0 0.8520848 -0.5233605 0.006752133 0.9263365 -0.3766363 0.006768703 0.9410149 -0.3383653 0 0.9759116 -0.218056 0.006943583 0.9842022 -0.1770486 0 0.9950338 -0.09953802 0 0.9983918 -0.0562371 0.007167935 0.9999157 -0.01299011 0 0.9976206 0.06894385 0 0.9938825 0.1102299 0.006844282 0.9621278 0.2725168 0.006688416 0.9045306 0.4263558 0.006727993 0.8450701 0.5346555 0 0.8212294 0.5705535 0.007144272 0.7959123 0.6054119 0 0.7468982 0.6649386 0 0.7178292 0.6961833 0.007074475 0.6225327 0.7825938 0 0.5919957 0.8059159 0.0063771 0.5606843 0.8280298 0 0.4506959 0.8926498 0.007044374 0.4121255 0.9111271 0 0.340709 0.9401689 0 0.2980284 0.9545279 0.007471263 0.2546719 0.9670276 0 0.1811933 0.9834475 0 0.1383808 0.9903531 0.00719285 0.09522575 0.9954558 0 -0.1510984 0.9885188 0 -0.1902879 0.9817063 0.006590783 -0.2292692 0.9733631 0 -0.3148918 0.9491276 0 -0.3522893 0.9358682 0.006576001 -0.4991715 0.8664759 0.006884694 -0.5345906 0.8451112 0 -0.6028072 0.7978869 0 -0.6356934 0.7719106 0.006922602 -0.6672632 0.744822 0 -0.7263606 0.6873139 0 -0.7550759 0.6555989 0.007101535 -0.7825305 0.6226123 0 -0.8286958 0.5596994 0 -0.8514904 0.5243245 0.006942331 -0.9266725 0.3758063 0.006918609 -0.9415076 0.336992 0 -0.965636 0.2598985 0 -0.9753664 0.2204898 0.006686031 -0.9834414 0.1812267 0 -0.9954926 0.09483951 0 -0.99852 0.05396074 0.006797254 -0.9999133 0.01317089 0 -0.9938826 -0.1102299 0.006840109 -0.9621514 -0.2724334 0.006694197 -0.9210961 -0.3893353 0 -0.9045653 -0.426282 0.00672543 -0.8438329 -0.5366061 0 -0.4975116 -0.447328 -0.7432225 -0.5133042 -0.4341687 -0.7402813 -0.5133046 -0.4341678 -0.7402816 -0.5133048 -0.4341673 -0.7402817 -0.4628667 -0.4872596 -0.7404949 -0.4626353 -0.4863637 -0.741228 -0.4166728 -0.5266483 -0.7409626 -0.4180353 -0.5211834 -0.7440527 -0.4178597 -0.521047 -0.7442469 -0.3721985 -0.5547462 -0.744127 -0.3722404 -0.5553119 -0.7436839 -0.3759661 -0.554354 -0.7425236 -0.327018 -0.5843207 -0.742717 -0.3270537 -0.5833951 -0.7434286 -0.2751728 -0.6093649 -0.7436091 -0.2769178 -0.6068359 -0.745028 -0.2802271 -0.6086649 -0.7422937 -0.2242241 -0.6313852 -0.7423452 -0.2231529 -0.6302735 -0.7436116 -0.2232137 -0.6305771 -0.7433359 -0.1728581 -0.6459565 -0.7435458 -0.173803 -0.6421655 -0.746603 -0.1304115 -0.6523373 -0.7466251 -0.1184585 -0.6603239 -0.7415794 -0.117805 -0.6597231 -0.742218 -0.06498265 -0.6675016 -0.7417675 -0.06599748 -0.6689288 -0.7403909 -0.0587002 -0.6656262 -0.7439732 -0.009080648 -0.6683619 -0.7437809 -0.008887112 -0.6687228 -0.7434588 0.04043287 -0.6676323 -0.7433924 0.04043281 -0.6676325 -0.7433924 0.04043287 -0.6676325 -0.7433922 0.04440325 -0.6686503 -0.7422501 0.04624617 -0.6653843 -0.7450672 0.1030029 -0.6592184 -0.7448635 0.1026473 -0.6601306 -0.7441043 0.09534591 -0.667092 -0.7388488 0.1585198 -0.655335 -0.7385171 0.1526877 -0.6489037 -0.7453929 0.1988136 -0.6360685 -0.7455803 0.2095212 -0.6344517 -0.7440242 0.2094455 -0.6348996 -0.7436633 0.2595459 -0.6164401 -0.7433961 0.2596641 -0.6153044 -0.7442951 0.2607823 -0.6129166 -0.7458726 0.3074302 -0.5907173 -0.746016 0.3092467 -0.5920006 -0.7442458 0.3562274 -0.5645688 -0.7445564 0.3584825 -0.5658362 -0.7425091 0.4024789 -0.531621 -0.7452448 0.4025388 -0.531093 -0.745589 0.4443981 -0.4966664 -0.7455421 0.4433754 -0.4961173 -0.7465159 0.4433754 -0.4961174 -0.7465159 0.4433753 -0.4961172 -0.7465159 0.4318643 -0.5106483 -0.7434591 0.4318644 -0.5106484 -0.7434591 0.4318643 -0.5106483 -0.7434592 0.4857267 -0.4585205 -0.7441966 0.4890983 -0.459462 -0.7414025 0.5233033 -0.4203062 -0.7412803 0.523777 -0.4201738 -0.7410208 0.5238914 -0.4199821 -0.7410485 0.5583869 -0.372339 -0.7413284 0.5554004 -0.3722162 -0.7436299 0.5542084 -0.3760513 -0.7425891 0.5542084 -0.3760513 -0.7425891 0.5542083 -0.3760513 -0.7425892 0.5844529 -0.3269801 -0.7426297 0.5801743 -0.3269815 -0.7459765 0.6072406 -0.2743437 -0.7456504 0.6059077 -0.2751435 -0.7464395 0.6086219 -0.2799492 -0.7424338 0.6308394 -0.225105 -0.7425426 0.6303172 -0.2246387 -0.743127 0.6304416 -0.2232318 -0.7434453 0.6452618 -0.1757519 -0.7434707 0.6488956 -0.174854 -0.7405138 0.6615304 -0.1166852 -0.7407848 0.6603941 -0.1184463 -0.7415187 0.6606851 -0.1185883 -0.7412369 0.6679343 -0.06532603 -0.7413477 0.6690136 -0.06603276 -0.7403111 0.6655067 -0.05834561 -0.7441079 0.6655067 -0.05834567 -0.7441079 0.6655067 -0.05834567 -0.744108 0.6682948 -0.009036839 -0.7438417 0.6688712 -0.008894622 -0.7433251 0.6677422 0.03913068 -0.7433634 0.6687035 0.04447823 -0.7421976 0.6649258 0.04640114 -0.7454668 0.6588 0.09996414 -0.7456472 0.6633865 0.09835088 -0.7417854 0.6596468 0.1021719 -0.7445986 0.6487811 0.1568607 -0.7446328 0.6479415 0.1561096 -0.7455211 0.6359152 0.1991147 -0.7456308 0.6345859 0.2086759 -0.7441473 0.6392657 0.2075888 -0.7404366 0.6187 0.2616299 -0.7407835 0.6136603 0.2622033 -0.744762 0.6220201 0.2580686 -0.7392508 0.5955135 0.3146387 -0.7391659 0.5920012 0.3092244 -0.7442546 0.564692 0.3562326 -0.7444605 0.565849 0.358502 -0.7424899 0.5343344 0.4040303 -0.7424597 0.5343117 0.404468 -0.7422376 0.5289723 0.4051581 -0.7456777 0.496697 0.44438 -0.7455325 0.4962974 0.4434826 -0.7463325 0.5102443 0.4324229 -0.743412 0.4585627 0.4856669 -0.7442097 0.4583798 0.484817 -0.7448762 0.4175492 0.5198335 -0.745269 0.4167892 0.5232115 -0.743328 0.4199659 0.5236733 -0.7412118 0.3763376 0.5556818 -0.7413419 0.3762767 0.5539376 -0.7426769 0.365258 0.5576614 -0.7453861 0.325672 0.5820067 -0.7451215 0.3257631 0.5863355 -0.74168 0.279998 0.6100677 -0.7412278 0.2790002 0.6113994 -0.7405064 0.2738481 0.6087665 -0.7445875 0.2261509 0.6283645 -0.7443211 0.2228949 0.625587 -0.7476355 0.2347882 0.6266271 -0.7431104 0.1728748 0.6459546 -0.7435436 0.1720135 0.6495344 -0.7406191 0.1190331 0.6611259 -0.7407724 0.1212673 0.6596159 -0.7417554 0.1170573 0.6553771 -0.746176 0.06478279 0.6625158 -0.7462413 0.06546783 0.6635599 -0.7452532 0.06839567 0.6649212 -0.7437754 0.009080111 0.6684124 -0.7437355 0.008850932 0.6688476 -0.7433469 -0.05873173 0.6666775 -0.7430288 -0.05873191 0.6666779 -0.7430285 -0.05873191 0.6666779 -0.7430284 -0.0470187 0.6638822 -0.7463576 -0.04645621 0.6650522 -0.7453506 -0.09998077 0.6587674 -0.7456739 -0.09833663 0.6635717 -0.7416215 -0.1021021 0.6595223 -0.7447185 -0.1540565 0.6496357 -0.744473 -0.1573551 0.6531006 -0.7407423 -0.2362464 0.6301391 -0.7396704 -0.2067274 0.6349254 -0.7444015 -0.2064958 0.6358929 -0.7436395 -0.2595258 0.6163032 -0.7435165 -0.2591903 0.6197946 -0.740726 -0.2631641 0.6116567 -0.7460703 -0.2631641 0.6116567 -0.7460702 -0.3098727 0.5895504 -0.7459285 -0.3114886 0.5907562 -0.7442997 -0.3562757 0.5646454 -0.7444751 -0.3585202 0.5657709 -0.7425407 -0.4024224 0.531753 -0.7451812 -0.4017176 0.5373458 -0.7415406 -0.4470853 0.4997413 -0.7418717 -0.4462814 0.4994195 -0.742572 -0.4531376 0.4906386 -0.7442715 -0.4531368 0.4906378 -0.7442726 -0.4531368 0.4906377 -0.7442726 -0.4842457 0.4600117 -0.7442415 -0.4877347 0.4610537 -0.7413126 -0.5266062 0.4164208 -0.7411341 -0.5210648 0.418016 -0.7441466 -0.5211197 0.4179049 -0.7441706 -0.5529838 0.374552 -0.7442579 -0.5545872 0.3747002 -0.7429891 -0.5540837 0.3757486 -0.7428354 -0.5856299 0.3247991 -0.7426596 -0.5844784 0.3246017 -0.7436523 -0.6053941 0.2832356 -0.7438251 -0.6113728 0.2789779 -0.7405368 -0.6100957 0.2765198 -0.7425093 -0.6299296 0.227637 -0.742543 -0.6255209 0.2229293 -0.7476806 -0.6264409 0.2348168 -0.7432584 -0.6462359 0.1721047 -0.7434778 -0.6481142 0.1716088 -0.7419558 -0.6600921 0.119154 -0.7416743 -0.6585577 0.1210546 -0.7427299 -0.6552779 0.1177362 -0.7461563 -0.6628636 0.06162256 -0.7462002 -0.6688361 0.06545186 -0.740523 -0.6658702 0.05969798 -0.7436754 -0.6684191 0.01214307 -0.7436858 -0.6687769 0.01179099 -0.7433697 -0.6665757 -0.05858218 -0.7431319 -0.6639386 -0.04699897 -0.7463088 -0.6653316 -0.04618304 -0.7451182 -0.659589 -0.1001761 -0.7449209 -0.6627502 -0.09898424 -0.7422698 -0.6596781 -0.1021682 -0.7445713 -0.6495254 -0.1539345 -0.7445945 -0.6518573 -0.1563307 -0.7420532 -0.6518573 -0.1563306 -0.7420532 -0.6323566 -0.222863 -0.7419281 -0.6323568 -0.2228628 -0.7419281 -0.6323568 -0.2228627 -0.7419281 -0.6349927 -0.2067459 -0.7443389 -0.635879 -0.2064931 -0.7436522 -0.6153473 -0.2620825 -0.7434114 -0.6089617 -0.2629319 -0.7483533 -0.6089616 -0.262932 -0.7483533 -0.6089617 -0.2629319 -0.7483533 -0.6200361 -0.2574627 -0.7411262 -0.5938706 -0.3121459 -0.7415409 -0.5936158 -0.3115151 -0.7420099 -0.5671246 -0.3578659 -0.7418233 -0.5667054 -0.3571818 -0.742473 -0.5320494 -0.4070611 -0.7424452 -0.5317025 -0.4024761 -0.7451882 -0.5373865 -0.4018098 -0.7414612 -0.4981142 -0.4488135 -0.7419223 -0.7741538 -0.4061543 -0.4855148 -0.7395564 -0.4660914 -0.485608 -0.7398167 -0.4665956 -0.4847264 -0.6973197 -0.527928 -0.4848065 -0.6979317 -0.5301095 -0.4815344 -0.6520808 -0.5860738 -0.4809452 -0.6515746 -0.583404 -0.4848613 -0.6026646 -0.633494 -0.4852635 -0.6028915 -0.6372342 -0.4800568 -0.548748 -0.6841522 -0.4804284 -0.5488615 -0.6859205 -0.4777699 -0.4889966 -0.7296402 -0.4780247 -0.4893283 -0.7262735 -0.4827883 -0.4282826 -0.7639288 -0.4826871 -0.4285401 -0.7623537 -0.4849436 -0.3630509 -0.7957099 -0.4848092 -0.3619313 -0.8000279 -0.4784988 -0.2938595 -0.8273323 -0.4787147 -0.2955856 -0.8224194 -0.4860614 -0.2283074 -0.8436396 -0.4859507 -0.2256721 -0.8491177 -0.4775682 -0.1551294 -0.86484 -0.4774795 -0.1564407 -0.8624121 -0.481427 -0.08493441 -0.8722998 -0.4815387 -0.083925 -0.8738158 -0.4789597 -0.01166546 -0.8780273 -0.4784685 -0.01513367 -0.8736875 -0.4862521 0.05786466 -0.8715464 -0.4868865 0.06112456 -0.8750741 -0.4801138 0.06112462 -0.8750742 -0.4801138 0.06112462 -0.8750742 -0.4801138 0.1353771 -0.8665383 -0.4804004 0.1326522 -0.8640735 -0.4855722 0.2002183 -0.8507715 -0.4859018 0.2014989 -0.8516845 -0.4837683 0.2744151 -0.8309842 -0.4839025 0.2744997 -0.8312398 -0.4834155 0.3396875 -0.8070021 -0.4830737 0.3396875 -0.8070021 -0.4830736 0.3396875 -0.8070021 -0.4830736 0.3433346 -0.8087117 -0.4776055 0.4068562 -0.7787972 -0.4774338 0.4041572 -0.7774867 -0.4818417 0.4041573 -0.7774868 -0.4818416 0.4041573 -0.7774868 -0.4818418 0.4692106 -0.7405732 -0.4810332 0.4713845 -0.741389 -0.477639 0.53022 -0.7003197 -0.4779323 0.5276265 -0.6997009 -0.4816938 0.5840294 -0.6537318 -0.4811908 0.5855074 -0.6540398 -0.4789709 0.6399114 -0.6009455 -0.4789342 0.6349323 -0.6007587 -0.4857468 0.6818678 -0.5469759 -0.4856684 0.6836658 -0.546983 -0.483126 0.7274403 -0.4875519 -0.4828288 0.7274446 -0.4876211 -0.4827527 0.7629868 -0.4298693 -0.4827667 0.7643737 -0.4296783 -0.4807386 0.7981376 -0.3624932 -0.4812225 0.7975834 -0.3625367 -0.4821078 0.8255029 -0.2945435 -0.4814448 0.822448 -0.2954787 -0.4860777 0.8437547 -0.2273319 -0.4862082 0.8481032 -0.2254225 -0.4794847 0.864028 -0.155007 -0.4789869 0.8625147 -0.1557622 -0.4814627 0.8723063 -0.0852707 -0.4814671 0.8693641 -0.08734589 -0.4863918 0.8734517 -0.01152074 -0.4867747 0.8735831 -0.01154673 -0.4865379 0.8717618 0.05800932 -0.4864836 0.8750232 0.06080842 -0.4802465 0.8692944 0.133975 -0.4757922 0.8551912 0.2060033 -0.475616 0.8517996 0.2016057 -0.483521 0.8314934 0.2733373 -0.4836378 0.8315078 0.2733486 -0.4836067 0.8062224 0.3410924 -0.4833853 0.8070327 0.3426319 -0.4809384 0.7769387 0.4057793 -0.4813621 0.775756 0.4031413 -0.4854686 0.7384446 0.4678248 -0.4856331 0.7402595 0.4730683 -0.4777261 0.7002766 0.5299935 -0.4782465 0.7002766 0.5299936 -0.4782465 0.7002765 0.5299935 -0.4782465 0.698879 0.5240609 -0.4867529 0.6513609 0.582035 -0.4867897 0.6522576 0.5873615 -0.4791309 0.603061 0.6377391 -0.4791724 0.6030068 0.6374498 -0.4796256 0.546926 0.6866083 -0.4789999 0.5469793 0.6837432 -0.4830205 0.4920094 0.724402 -0.4828752 0.4916459 0.7279775 -0.4778422 0.4264766 0.7677249 -0.4782431 0.4268187 0.7658294 -0.4809691 0.363864 0.7974917 -0.4812588 0.3633563 0.7993019 -0.478632 0.297276 0.8261089 -0.4787181 0.2970942 0.8266091 -0.477967 0.2248823 0.8492057 -0.4777843 0.2277682 0.8428231 -0.4876177 0.1578965 0.8587454 -0.487468 0.1557854 0.8624749 -0.4815269 0.08529323 0.8723245 -0.4814302 0.08396089 0.8741893 -0.4782714 0.01161527 0.8780814 -0.4783704 0.01146209 0.8782325 -0.4780966 -0.06205385 0.8761832 -0.4779669 -0.06113898 0.8752343 -0.4798197 -0.1316884 0.8677493 -0.4792382 -0.1290712 0.8653593 -0.4842458 -0.2049717 0.8508371 -0.4838006 -0.2051215 0.8509296 -0.4835742 -0.2709611 0.8322177 -0.4837293 -0.2743221 0.8343828 -0.478072 -0.3406434 0.8090656 -0.4789311 -0.3394523 0.8084666 -0.4807847 -0.4089244 0.7754892 -0.4810379 -0.4060437 0.7741991 -0.485535 -0.4679037 0.7384579 -0.4855369 -0.4682811 0.7386444 -0.4848889 -0.5277746 0.6973111 -0.4849857 -0.5265473 0.69693 -0.4868639 -0.5265473 0.6969301 -0.4868639 -0.5265473 0.6969301 -0.4868639 -0.5820394 0.6513266 -0.4868304 -0.5873675 0.6522523 -0.4791309 -0.6379297 0.6029129 -0.4791052 -0.6373471 0.6028625 -0.4799433 -0.6840175 0.5488962 -0.480451 -0.6822231 0.5488859 -0.4830073 -0.7256126 0.4901494 -0.4829491 -0.7257508 0.4902516 -0.4826378 -0.7656978 0.4251811 -0.482626 -0.7639195 0.4256653 -0.4850116 -0.7957004 0.3631438 -0.4847552 -0.8000582 0.3619298 -0.4784493 -0.825744 0.2985579 -0.4785498 -0.8261345 0.2982679 -0.4780567 -0.8490951 0.2250263 -0.4779132 -0.8442925 0.2269796 -0.4854383 -0.8595883 0.1581087 -0.4859112 -0.8623933 0.1564306 -0.4814637 -0.872758 0.08102339 -0.4813821 -0.8691651 0.08348113 -0.487425 -0.8732176 0.0155729 -0.4870817 -0.878346 0.01143378 -0.4778888 -0.876271 -0.06214904 -0.4777935 -0.8750095 -0.06071984 -0.4802827 -0.8686349 -0.133374 -0.4771633 -0.8542855 -0.2048575 -0.4777339 -0.8517425 -0.2015047 -0.4836637 -0.832203 -0.2709084 -0.483784 -0.8353586 -0.2759648 -0.4754149 -0.8094472 -0.3447493 -0.4753348 -0.8061133 -0.3383854 -0.4854657 -0.7744431 -0.4067237 -0.4845759 -0.7744431 -0.4067237 -0.4845759 -0.7744432 -0.4067236 -0.4845759 -0.8738179 -0.4559991 -0.1688409 -0.8335308 -0.5258535 -0.1694242 -0.832931 -0.5296979 -0.160144 -0.7860932 -0.5970445 -0.1599854 -0.7865383 -0.595243 -0.1644487 -0.7348758 -0.6578081 -0.165064 -0.7347979 -0.6579364 -0.1648993 -0.6778444 -0.7165608 -0.1645227 -0.6779741 -0.7163189 -0.165041 -0.6779741 -0.7163189 -0.165041 -0.6779741 -0.7163188 -0.165041 -0.6162799 -0.7701255 -0.164639 -0.6165279 -0.7695939 -0.1661888 -0.616528 -0.7695939 -0.1661887 -0.616528 -0.7695938 -0.1661888 -0.5509181 -0.8178614 -0.1661088 -0.5502501 -0.8189098 -0.1631306 -0.4834326 -0.8599027 -0.163891 -0.4820778 -0.8616856 -0.1584264 -0.4820778 -0.8616856 -0.1584263 -0.4068699 -0.8995155 -0.1591504 -0.4098016 -0.8964045 -0.1688838 -0.3334369 -0.9275962 -0.1684789 -0.3322658 -0.928635 -0.1650353 -0.3322658 -0.928635 -0.1650353 -0.3322657 -0.928635 -0.1650354 -0.2533813 -0.9533062 -0.1643328 -0.2550123 -0.9520092 -0.1692553 -0.1759184 -0.9696791 -0.1696323 -0.1752177 -0.9701666 -0.1675577 -0.09425747 -0.9813258 -0.167676 -0.09751307 -0.9794961 -0.1762919 -0.01704448 -0.9840379 -0.1771407 -0.01278388 -0.9859618 -0.1664814 0.06871235 -0.9837665 -0.1657776 0.06811106 -0.9835225 -0.167465 0.1495906 -0.9744162 -0.1677374 0.1489003 -0.9742458 -0.1693336 0.2269194 -0.9590888 -0.1692818 0.2302742 -0.95961 -0.1616249 0.3095377 -0.9370695 -0.1615151 0.3066337 -0.9368223 -0.1683447 0.3851162 -0.9072965 -0.1688156 0.3833823 -0.9072375 -0.1730271 0.4540753 -0.8739635 -0.1732148 0.4559292 -0.8739063 -0.1685717 0.4559292 -0.8739064 -0.1685717 0.4559292 -0.8739063 -0.1685717 0.5288431 -0.8316968 -0.169132 0.5289012 -0.8316223 -0.169316 0.5934469 -0.7870533 -0.168428 0.5952445 -0.7865384 -0.1644422 0.6578676 -0.7348273 -0.1650432 0.657889 -0.7348254 -0.1649664 0.7165068 -0.6779434 -0.1643499 0.7164285 -0.6778544 -0.1650568 0.7701744 -0.6162271 -0.1646074 0.7695873 -0.6165344 -0.166195 0.8191884 -0.548905 -0.1662337 0.8180303 -0.5497785 -0.1690268 0.8590606 -0.4831234 -0.1691356 0.8590605 -0.4831233 -0.1691356 0.8590606 -0.4831234 -0.1691356 0.8608464 -0.4817205 -0.1639781 0.898128 -0.408186 -0.1635558 0.8978314 -0.408553 -0.1642658 0.9282182 -0.3334916 -0.1649076 0.9280859 -0.3337993 -0.1650289 0.9532701 -0.2534145 -0.1644909 0.9520575 -0.2548292 -0.1692592 0.9698801 -0.1750978 -0.1693322 0.9698801 -0.1750978 -0.1693322 0.9698802 -0.1750978 -0.1693322 0.9702624 -0.1745164 -0.1677348 0.9808888 -0.09851837 -0.1677836 0.9811094 -0.09811568 -0.1667268 0.985944 -0.01280701 -0.1665846 0.985998 -0.01275211 -0.1662691 0.9837656 0.06844496 -0.1658937 0.9836434 0.06796646 -0.166812 0.9745586 0.1504051 -0.1661748 0.9742301 0.1488656 -0.1694543 0.9590477 0.2269106 -0.1695259 0.9596258 0.2302324 -0.1615903 0.9375545 0.3080542 -0.1615373 0.9375545 0.3080542 -0.1615373 0.9375545 0.3080541 -0.1615373 0.9374271 0.3067524 -0.1647225 0.907938 0.3854354 -0.1645856 0.9079282 0.3836281 -0.1688077 0.8747023 0.4545047 -0.1682896 0.8744962 0.4565291 -0.1638223 0.8312542 0.5313503 -0.1633507 0.8321062 0.5263041 -0.1749387 0.787661 0.5907294 -0.1750114 0.7858443 0.5979447 -0.1578322 0.733763 0.6608489 -0.1577045 0.735787 0.6550205 -0.1719472 0.6770288 0.7155233 -0.1722166 0.6770646 0.7153803 -0.1726693 0.6152042 0.769131 -0.1730937 0.6139566 0.7716238 -0.1662952 0.5518694 0.8171725 -0.1663411 0.5526182 0.8161211 -0.1689958 0.4797619 0.8609352 -0.1691717 0.4808079 0.8595365 -0.1732655 0.4075481 0.8966256 -0.17311 0.4062731 0.8980178 -0.1688377 0.3334665 0.9275336 -0.1687646 0.3334667 0.9275336 -0.1687646 0.3334666 0.9275336 -0.1687646 0.3354735 0.9256368 -0.175083 0.2568864 0.9505158 -0.1747264 0.2568864 0.9505158 -0.1747263 0.2568864 0.9505158 -0.1747264 0.2515021 0.9546974 -0.1590586 0.2515021 0.9546974 -0.1590586 0.2515021 0.9546974 -0.1590586 0.1754996 0.9715447 -0.1590628 0.1785982 0.9695728 -0.1674258 0.09426021 0.9813547 -0.1675056 0.09388637 0.9814875 -0.1669365 0.01287114 0.9859592 -0.1664902 0.01278203 0.9859952 -0.166283 -0.06870961 0.9837061 -0.166137 -0.06870967 0.9837061 -0.166137 -0.06870961 0.9837061 -0.166137 -0.06811207 0.9835366 -0.1673817 -0.1454229 0.975058 -0.1676728 -0.1491656 0.9759811 -0.1587784 -0.2313818 0.9597444 -0.1592267 -0.2258408 0.9588903 -0.1718291 -0.307653 0.9358621 -0.1717904 -0.307653 0.9358621 -0.1717904 -0.307653 0.9358621 -0.1717904 -0.3106104 0.9361615 -0.1646902 -0.3818185 0.9094471 -0.1646836 -0.3842464 0.9094538 -0.1588978 -0.4586155 0.8742758 -0.1591027 -0.4564486 0.8745203 -0.163918 -0.5282937 0.8331765 -0.1634713 -0.5271673 0.8334142 -0.1658781 -0.5944268 0.786735 -0.1664482 -0.5943486 0.7867947 -0.1664457 -0.659855 0.7328507 -0.1658954 -0.6573767 0.7336811 -0.1719537 -0.7155343 0.6770232 -0.1721929 -0.7154446 0.6769235 -0.1729562 -0.7673575 0.6173949 -0.1731653 -0.7725916 0.6145718 -0.1593859 -0.8179094 0.5525974 -0.1601884 -0.8180237 0.5524775 -0.1600182 -0.8624003 0.4804331 -0.1595298 -0.8609464 0.4816021 -0.1638009 -0.8988708 0.4065929 -0.163443 -0.8971359 0.4082279 -0.1688116 -0.9270657 0.3347914 -0.168713 -0.9292718 0.3323464 -0.1612447 -0.95293 0.2565631 -0.1615543 -0.9529539 0.2563858 -0.1616948 -0.9711061 0.176205 -0.1609497 -0.9695594 0.1785669 -0.167537 -0.9813464 0.09417974 -0.1675988 -0.9817231 0.09357404 -0.1657221 -0.9859688 0.0128073 -0.166438 -0.9859916 0.01292699 -0.1662931 -0.9836116 -0.06843423 -0.1668086 -0.9835335 -0.06813293 -0.1673918 -0.9744285 -0.1495521 -0.1676995 -0.9742247 -0.1490389 -0.1693337 -0.9590762 -0.2269173 -0.1693556 -0.9596207 -0.2302311 -0.1616221 -0.9370883 -0.3094454 -0.1615836 -0.9367907 -0.3067175 -0.1683678 -0.908744 -0.3816778 -0.1688382 -0.908744 -0.3816778 -0.1688382 -0.908744 -0.3816778 -0.1688382 -0.9088166 -0.3840023 -0.1630787 -0.8735768 -0.4583014 -0.1637792 -0.1976645 0.4595724 -0.8658648 -0.1543 0.4751735 -0.8662574 -0.03487819 0.4987909 -0.8660203 -0.03487819 0.4987909 -0.8660203 -0.03487825 0.498791 -0.8660203 0.1755781 0.4686514 -0.8657588 0.2733954 0.4175827 -0.8665332 0.3814868 0.3233941 -0.8659585 0.3814868 0.3233942 -0.8659585 0.3814868 0.3233942 -0.8659585 0.3975628 0.3045583 -0.8655566 0.4219548 0.2662343 -0.866645 0.462242 0.1917786 -0.8657675 0.4751411 0.1542525 -0.8662837 0.4986406 0.03488165 -0.8661068 0.4712017 -0.1668658 -0.8660974 0.4135798 -0.2806365 -0.866138 0.4135798 -0.2806364 -0.8661381 0.4135798 -0.2806364 -0.866138 0.3225406 -0.3809352 -0.8665194 0.3225406 -0.3809352 -0.8665195 0.3225405 -0.3809353 -0.8665194 0.3025032 -0.3991161 -0.8655624 0.265965 -0.421498 -0.8669499 0.1959111 -0.4603342 -0.8658587 0.1562212 -0.4735174 -0.8668196 0.03467273 -0.498625 -0.8661242 -0.1669694 -0.4713447 -0.8659997 -0.2806146 -0.4136872 -0.8660937 -0.2806147 -0.4136873 -0.8660937 -0.2806146 -0.4136874 -0.8660936 -0.3818728 -0.3229968 -0.8659366 -0.3818727 -0.3229972 -0.8659366 -0.3818726 -0.3229977 -0.8659364 -0.4011156 -0.2998793 -0.8655511 -0.4214702 -0.265864 -0.8669944 -0.4621503 -0.1917536 -0.865822 -0.4748592 -0.1542448 -0.8664394 -0.4986268 -0.03460502 -0.8661258 -0.4681472 0.1750867 -0.866131 -0.413124 0.2804312 -0.8664219 -0.3383899 0.3663665 -0.8667572 -0.3383899 0.3663664 -0.8667572 -0.3383899 0.3663665 -0.8667572 -0.2997968 0.4012872 -0.8655003 -0.2659741 0.4215891 -0.8669028 0.1798125 -0.1530055 -0.9717288 0.2064685 -0.2741736 -0.9392548 0.1683713 -0.1619641 -0.9723265 0.1894234 -0.2314116 -0.9542366 0.02567136 -0.2605644 -0.9651152 0.1724721 -0.1613407 -0.9717112 0.02072077 -0.2103244 -0.9774121 -0.01003378 -0.1788997 -0.9838162 -0.02609795 -0.1760834 -0.9840292 -0.01107317 -0.1772826 -0.9840977 -0.1562428 -0.1807482 -0.9710398 -0.2794297 -0.2042802 -0.9381837 -0.1619148 -0.1683486 -0.9723387 -0.1619148 -0.1683484 -0.9723386 -0.1619147 -0.1683486 -0.9723386 -0.2307086 -0.1892005 -0.954451 -0.2307085 -0.1892004 -0.9544511 -0.2307085 -0.1892003 -0.9544511 -0.2600705 -0.0256136 -0.96525 -0.1614359 -0.1717034 -0.9718315 -0.2124134 -0.02090382 -0.9769563 -0.1795605 0.01122486 -0.983683 -0.1758514 0.02423495 -0.9841184 -0.176823 0.01032322 -0.9841886 -0.1768231 0.01032328 -0.9841886 -0.1768231 0.01032328 -0.9841886 -0.1817325 0.155477 -0.970979 -0.2044078 0.2916956 -0.9344149 -0.2044078 0.2916957 -0.9344149 -0.2044078 0.2916957 -0.9344149 -0.1613481 0.1662248 -0.9727982 -0.1613481 0.1662249 -0.9727982 -0.1613481 0.1662248 -0.9727981 -0.1798689 0.2321712 -0.9558994 -0.02755028 0.2596616 -0.9653067 -0.1644899 0.166386 -0.9722443 -0.02251267 0.212107 -0.9769871 0.01003265 0.1790059 -0.9837968 0.02388972 0.1758492 -0.9841273 0.01110929 0.1771004 -0.9841301 0.1531386 0.1798948 -0.9716926 0.2797278 0.204661 -0.938012 0.2797279 0.2046609 -0.938012 0.2797278 0.2046609 -0.938012 0.1661942 0.1608733 -0.972882 0.1661942 0.1608732 -0.972882 0.1661942 0.1608732 -0.972882 0.2327573 0.1800513 -0.9557225 0.2605896 0.02566432 -0.9651086 0.1667785 0.1566878 -0.973465 0.210301 0.02069592 -0.9774176 0.1795653 -0.009500324 -0.9837002 0.1760758 -0.02604603 -0.984032 0.177316 -0.01106792 -0.9840918 0.177316 -0.01106786 -0.9840918 0.177316 -0.01106792 -0.9840918 -0.3044044 0.3976645 -0.8655641 -0.2721312 0.4125788 -0.8693236 -0.2330432 0.3533695 -0.9059917 -0.1886013 0.3790248 -0.9059635 -0.1528066 0.3071004 -0.9393293 -0.1168901 0.3223766 -0.9393669 -0.3326382 0.3718091 -0.866666 -0.319759 0.3765509 -0.8694618 -0.2736442 0.3223155 -0.9062183 -0.2336313 0.3522633 -0.906271 -0.1898421 0.2862246 -0.9391674 -0.152116 0.3079849 -0.9391518 -0.3909558 0.313575 -0.8653464 -0.3930671 0.3107516 -0.8654084 -0.3584712 0.3405089 -0.8692251 -0.3652361 0.3383923 -0.8672332 -0.3103188 0.2875208 -0.9061094 -0.2733818 0.3229069 -0.906087 -0.2218375 0.2620506 -0.9392112 -0.1900173 0.2859717 -0.9392091 -0.4131041 0.2797867 -0.8666398 -0.4018658 0.2880607 -0.8692093 -0.3435754 0.2462776 -0.9062578 -0.3104972 0.2867714 -0.9062857 -0.252063 0.2327525 -0.9393032 -0.2220683 0.2616 -0.9392822 -0.4547168 0.2060335 -0.8664773 -0.452262 0.2117671 -0.8663798 -0.4522621 0.211767 -0.8663797 -0.4522621 0.211767 -0.8663797 -0.4330786 0.2401522 -0.868775 -0.4349452 0.2388622 -0.8681979 -0.3707848 0.203647 -0.9061163 -0.3435394 0.2466373 -0.9061737 -0.2788709 0.2002089 -0.9392271 -0.2519735 0.2331986 -0.9392166 -0.2036523 0.1885128 -0.960723 -0.1794354 0.2113745 -0.9607933 -0.1641684 0.2102954 -0.9637556 -0.1477963 0.2223974 -0.9636886 -0.1730583 0.2251465 -0.9588326 -0.1250787 0.2531855 -0.959298 -0.1008906 0.2480404 -0.9634818 -0.09142369 0.2521947 -0.9633482 -0.1058105 0.2573265 -0.9605141 -0.1073237 0.2566061 -0.9605389 -0.4707578 0.1677613 -0.8661658 -0.4575843 0.1844987 -0.8698143 -0.3923503 0.1581829 -0.9061123 -0.370754 0.2036886 -0.9061195 -0.3007169 0.1652432 -0.9392891 -0.278957 0.1998351 -0.9392811 -0.2124339 0.1521225 -0.965262 -0.2183848 0.1447881 -0.9650619 -0.06062275 0.2239699 -0.9727088 -0.4917267 0.08836054 -0.8662547 -0.4917961 0.08844757 -0.8662065 -0.4792391 0.127689 -0.8683464 -0.4784795 0.1285563 -0.8686373 -0.4088044 0.1098445 -0.9059874 -0.3924263 0.1588107 -0.9059696 -0.3181533 0.1287234 -0.9392597 -0.300679 0.1654278 -0.9392688 -0.2291199 0.1260259 -0.9652055 -0.2122434 0.1527237 -0.965209 -0.1461095 0.1051492 -0.9836644 -0.06102281 0.2244207 -0.9725799 -0.1608898 0.07976132 -0.9837443 -0.1570096 0.08658969 -0.9837939 -0.2290912 0.1264371 -0.9651585 -0.2426785 0.09758263 -0.9651864 -0.3181006 0.1280077 -0.9393754 -0.3314382 0.08768647 -0.9393933 -0.4083788 0.1080168 -0.906399 -0.4183429 0.05933046 -0.9063494 -0.4956043 0.00893706 -0.8685026 -0.4978075 0.04453986 -0.8661432 -0.4974722 0.04853451 -0.8661212 -0.4974722 0.04853451 -0.8661212 -0.4974722 0.04853445 -0.8661212 -0.4982494 -0.04391986 -0.8659207 -0.4965462 0.01070785 -0.8679443 -0.4229309 0.009175539 -0.9061155 -0.4187188 0.06028497 -0.9061129 -0.3402797 0.04905557 -0.9390439 -0.3318728 0.08997654 -0.9390233 -0.2526762 0.06852626 -0.9651212 -0.2426198 0.09866315 -0.9650913 -0.1646593 0.06697946 -0.9840738 -0.1573342 0.08240473 -0.9841014 -0.1609993 0.08045333 -0.9836699 -0.1609992 0.08045315 -0.9836699 -0.1609993 0.08045327 -0.98367 -0.1646202 0.06713801 -0.9840695 -0.1718344 0.04562056 -0.9840691 -0.2525662 0.06714147 -0.9652473 -0.2588617 0.03594195 -0.9652456 -0.3397322 0.04713046 -0.9393406 -0.3430173 0.005953371 -0.9393103 -0.4220031 0.007271885 -0.9065653 -0.4200379 -0.0424965 -0.906511 -0.4919571 -0.04978752 -0.8691947 -0.4811379 -0.1141079 -0.8691869 -0.4945153 -0.07679611 -0.8657696 -0.4945154 -0.07679605 -0.8657696 -0.4945154 -0.07679611 -0.8657696 -0.4947816 -0.07382732 -0.8658757 -0.4711917 -0.1660459 -0.8662605 -0.4711918 -0.1660459 -0.8662605 -0.4711918 -0.1660459 -0.8662605 -0.4855296 -0.1092973 -0.8673611 -0.412134 -0.09276068 -0.906389 -0.4203664 -0.04196083 -0.9063838 -0.3420363 -0.03415316 -0.9390659 -0.343689 0.007483005 -0.9390538 -0.2617517 0.005764067 -0.9651181 -0.2592407 0.03749459 -0.9650847 -0.1759787 0.02547538 -0.9840643 -0.1718267 0.04571849 -0.9840658 -0.4594692 -0.1982819 -0.8657785 -0.4645456 -0.1666266 -0.8697316 -0.3974187 -0.142594 -0.9064907 -0.4116688 -0.09335374 -0.9065396 -0.3352563 -0.07596254 -0.9390596 -0.3421331 -0.03405481 -0.9390342 -0.2599394 -0.02585649 -0.9652788 -0.2611607 0.003956615 -0.9652873 -0.1797056 0.002769351 -0.9837166 -0.177266 0.007523655 -0.9841343 -0.4411742 -0.2319143 -0.8669378 -0.4421986 -0.2201806 -0.8694716 -0.3788827 -0.1886775 -0.9060071 -0.3991811 -0.1409935 -0.9059665 -0.324335 -0.1145467 -0.9389813 -0.3357067 -0.07547533 -0.938938 -0.2822529 -0.06336832 -0.9572449 -0.2551837 -0.005682945 -0.966876 -0.3976839 -0.304355 -0.8655723 -0.4126634 -0.2721578 -0.8692752 -0.3534097 -0.2331194 -0.9059564 -0.379047 -0.188548 -0.9059653 -0.3071102 -0.1528093 -0.9393256 -0.3226869 -0.1163024 -0.9393333 -0.3710534 -0.3345164 -0.8662669 -0.3766226 -0.3197451 -0.8694357 -0.3222847 -0.2736528 -0.9062266 -0.3522841 -0.233535 -0.9062876 -0.2858905 -0.1896435 -0.9393093 -0.3072628 -0.1526925 -0.9392948 -0.3126022 -0.3898484 -0.8661975 -0.3099956 -0.391909 -0.8662045 -0.3395698 -0.3574026 -0.8700321 -0.3365491 -0.3670141 -0.8671998 -0.2855913 -0.3113819 -0.9063549 -0.3214446 -0.2740527 -0.9064043 -0.2613831 -0.2227931 -0.939171 -0.2865902 -0.1891286 -0.9391999 -0.2784388 -0.4149126 -0.8662098 -0.2896005 -0.3997704 -0.869664 -0.2482501 -0.3426705 -0.9060623 -0.2870717 -0.3109797 -0.9060252 -0.2330796 -0.2525056 -0.9391033 -0.2620083 -0.222421 -0.939085 -0.2091412 -0.4542489 -0.8659781 -0.2058324 -0.4557511 -0.8659815 -0.2058324 -0.4557511 -0.8659816 -0.2058324 -0.455751 -0.8659815 -0.2417376 -0.4319667 -0.8688888 -0.2393063 -0.4356666 -0.8677138 -0.2032575 -0.3700747 -0.906494 -0.2462468 -0.3429614 -0.9064988 -0.2002528 -0.2788488 -0.9392243 -0.2320744 -0.252807 -0.9392711 -0.1869319 -0.2036929 -0.9610233 -0.2105888 -0.1787579 -0.9610921 -0.2096513 -0.1649826 -0.9637567 -0.2228863 -0.1470791 -0.9636854 -0.2258783 -0.1734985 -0.9585809 -0.2533799 -0.125952 -0.9591323 -0.2480928 -0.1008512 -0.9634724 -0.2523394 -0.09094762 -0.9633554 -0.257492 -0.105206 -0.9605361 -0.2585904 -0.1019236 -0.960595 -0.1668821 -0.4714313 -0.8659694 -0.1844545 -0.4575549 -0.8698392 -0.1581593 -0.3923679 -0.9061087 -0.2051972 -0.3700824 -0.9060536 -0.1666787 -0.3005898 -0.9390761 -0.2014222 -0.2786576 -0.939031 -0.153325 -0.2120866 -0.965148 -0.1465954 -0.2175409 -0.9649798 -0.226143 -0.05855047 -0.9723328 -0.0878337 -0.4918787 -0.866222 -0.09784233 -0.4900693 -0.866175 -0.09784233 -0.4900692 -0.866175 -0.09784233 -0.4900692 -0.8661751 -0.1284409 -0.4799707 -0.8678313 -0.1288509 -0.4796965 -0.8679221 -0.109599 -0.4078844 -0.9064318 -0.1568622 -0.3922381 -0.9063905 -0.1274732 -0.318761 -0.9392242 -0.16539 -0.3007092 -0.9392657 -0.1260204 -0.2291195 -0.9652063 -0.1527447 -0.2122341 -0.9652077 -0.1032921 -0.1435288 -0.984241 -0.225878 -0.05798918 -0.9724282 -0.225878 -0.05798918 -0.9724282 -0.225878 -0.05798918 -0.9724281 -0.08108389 -0.1600989 -0.9837651 -0.08606761 -0.1573457 -0.9837859 -0.1253684 -0.2292652 -0.9652566 -0.09756475 -0.2424548 -0.9652444 -0.1282644 -0.3187153 -0.939132 -0.08925849 -0.331742 -0.939138 -0.1097681 -0.4080479 -0.9063377 -0.05912679 -0.4183714 -0.9063495 -0.06912529 -0.4891029 -0.8694828 -0.006734132 -0.4955108 -0.8685758 -0.04389691 -0.4979145 -0.8661145 -0.04908359 -0.4974126 -0.8661245 0.03019374 -0.4988623 -0.8661552 0.03019374 -0.4988623 -0.8661552 0.0301938 -0.4988626 -0.8661549 -0.01073628 -0.4974818 -0.867408 -0.00910294 -0.4220482 -0.9065276 -0.05844521 -0.4181556 -0.9064933 -0.0474981 -0.3398088 -0.9392944 -0.08802735 -0.3315281 -0.9393298 -0.06707543 -0.252533 -0.9652606 -0.0973773 -0.2424904 -0.9652544 -0.06631338 -0.1651077 -0.9840437 -0.08225548 -0.1576309 -0.9840664 -0.08051723 -0.1610345 -0.983659 -0.06523716 -0.1652969 -0.984084 -0.04687207 -0.1714106 -0.9840841 -0.06911015 -0.2528265 -0.9650402 -0.0374372 -0.2591593 -0.9651088 -0.04915744 -0.3403417 -0.9390161 -0.00742799 -0.343622 -0.9390788 -0.009118854 -0.4220573 -0.9065233 0.04260367 -0.4199343 -0.906554 0.04990363 -0.4920318 -0.8691459 0.116135 -0.4801142 -0.8694844 0.07087427 -0.496212 -0.8653037 0.07702034 -0.4950419 -0.8654487 0.1486351 -0.4758813 -0.8668591 0.1486351 -0.4758812 -0.8668592 0.1486351 -0.4758821 -0.8668587 0.1106218 -0.4851937 -0.8673811 0.09390616 -0.4119038 -0.9063757 0.04203051 -0.4203786 -0.9063748 0.03420358 -0.3420085 -0.9390743 -0.007512032 -0.3437068 -0.939047 -0.005716025 -0.2611524 -0.9652807 -0.03528529 -0.2587113 -0.96531 -0.02398717 -0.1758691 -0.9841213 -0.04557979 -0.1714724 -0.984134 0.1945464 -0.4609762 -0.8658249 0.1658955 -0.4656089 -0.8693026 0.1418873 -0.3982523 -0.9062357 0.09346395 -0.412358 -0.9062149 0.07583087 -0.3345444 -0.9393241 0.03580492 -0.341097 -0.939346 0.02727907 -0.259901 -0.96525 -0.005941152 -0.261251 -0.9652526 -0.004070699 -0.1791111 -0.9838204 -0.006524264 -0.1778238 -0.9840408 0.230132 -0.442167 -0.866907 0.2205871 -0.4430072 -0.8689569 0.1883337 -0.3782552 -0.9063407 0.1423115 -0.3976781 -0.9064214 0.1156787 -0.3233169 -0.9391937 0.07527583 -0.3349631 -0.9392195 0.06388306 -0.2843112 -0.9566014 0.004264771 -0.256002 -0.9666669 0.3044686 -0.3975812 -0.8655796 0.2721176 -0.4126793 -0.86928 0.2326393 -0.3527629 -0.9063318 0.1882371 -0.3782929 -0.9063451 0.1531023 -0.3076946 -0.9390867 0.1148998 -0.3239897 -0.9390574 0.3326479 -0.37176 -0.8666833 0.321103 -0.3760905 -0.8691655 0.2745555 -0.321593 -0.9061994 0.2324169 -0.3531886 -0.906223 0.188539 -0.286526 -0.9393381 0.1541573 -0.3064537 -0.9393198 0.3904617 -0.3130532 -0.8657583 0.3902385 -0.3135881 -0.8656653 0.3596292 -0.3395531 -0.8691205 0.3647471 -0.3379463 -0.8676128 0.3102967 -0.2874497 -0.9061395 0.2744326 -0.3219921 -0.9060949 0.2227461 -0.2613765 -0.939184 0.1879205 -0.2875488 -0.9391494 0.4157586 -0.2771497 -0.8662176 0.4013727 -0.2877678 -0.8695341 0.3429483 -0.2458282 -0.9066174 0.3109024 -0.2853807 -0.9065857 0.2532491 -0.2323731 -0.9390782 0.2224407 -0.261992 -0.9390848 0.4546643 -0.2093523 -0.865709 0.4560916 -0.20621 -0.8657124 0.4324287 -0.2419261 -0.8686065 0.4353348 -0.2400605 -0.8676719 0.3700754 -0.2040306 -0.9063199 0.3427777 -0.2474886 -0.9062301 0.2783226 -0.200923 -0.9392371 0.2536448 -0.2311013 -0.9392851 0.2052429 -0.1870119 -0.9606778 0.1794376 -0.2113189 -0.9608051 0.1641841 -0.2103065 -0.9637503 0.1461296 -0.2235953 -0.9636656 0.1722635 -0.2265368 -0.9586482 0.1271278 -0.2527657 -0.9591392 0.1003374 -0.2469756 -0.963813 0.0892775 -0.2517144 -0.963675 0.1051729 -0.2575026 -0.960537 0.1096034 -0.2561544 -0.960402 0.4710879 -0.1677809 -0.8659825 0.4579274 -0.184576 -0.8696173 0.3920462 -0.1580603 -0.9062653 0.3701029 -0.2041568 -0.9062802 0.3006939 -0.1658785 -0.9391844 0.2782664 -0.2012471 -0.9391844 0.2123472 -0.1535526 -0.9650546 0.2182966 -0.1461667 -0.964874 0.05859273 -0.2261533 -0.972328 0.4917695 -0.08836823 -0.8662298 0.4920083 -0.08675205 -0.8662574 0.4781351 -0.1302106 -0.8685805 0.4797242 -0.1284129 -0.8679717 0.4080799 -0.1092422 -0.9063869 0.3920174 -0.1574712 -0.9063802 0.3187506 -0.1280918 -0.9391436 0.3006328 -0.1663466 -0.9391213 0.2287709 -0.1266247 -0.9652099 0.2128362 -0.1517971 -0.9652246 0.1439886 -0.1026573 -0.9842403 0.05827355 -0.2259292 -0.9723992 0.1602123 -0.08154928 -0.9837082 0.15732 -0.08675873 -0.9837294 0.2288113 -0.1261546 -0.9652619 0.242715 -0.09711635 -0.9652243 0.3187003 -0.1274963 -0.9392417 0.3315544 -0.08922576 -0.9392074 0.4082393 -0.1098936 -0.9062364 0.4184372 -0.05928266 -0.906309 0.4954811 -0.006796598 -0.8685922 0.4977867 -0.04388403 -0.8661887 0.4973661 -0.04904067 -0.8661536 0.4986537 0.02897709 -0.8663169 0.4975183 -0.0106678 -0.867388 0.422955 -0.009114861 -0.9061049 0.418845 -0.06037867 -0.9060482 0.3395431 -0.04891437 -0.9393178 0.3314181 -0.08849853 -0.9393243 0.2530189 -0.06760716 -0.9650963 0.2426214 -0.09859967 -0.9650974 0.1646603 -0.06688386 -0.9840801 0.1575989 -0.08177584 -0.9841115 0.1660404 -0.07753008 -0.9830665 0.1647973 -0.06594783 -0.9841203 0.1715715 -0.04555147 -0.9841181 0.2529774 -0.0671218 -0.965141 0.2591201 -0.03722047 -0.9651277 0.3395034 -0.04878652 -0.9393388 0.3430038 -0.005916178 -0.9393154 0.4220418 -0.007345795 -0.9065467 0.4200052 0.04243063 -0.9065293 0.4920212 0.0496717 -0.8691651 0.4804072 0.1161429 -0.8693215 0.4943143 0.07657116 -0.8659044 0.4949203 0.07342731 -0.8658304 0.476642 0.1491269 -0.8663566 0.4865078 0.1095175 -0.8667849 0.4119537 0.09265899 -0.9064815 0.4202517 0.04209631 -0.9064306 0.3420119 0.03422433 -0.9390723 0.3436711 -0.007570743 -0.9390596 0.2611846 -0.005736768 -0.9652719 0.2587457 -0.03562539 -0.9652884 0.1758933 -0.02421104 -0.9841116 0.1715473 -0.04559189 -0.9841204 0.4601269 0.1964775 -0.8658405 0.4648662 0.1668679 -0.869514 0.3974091 0.1425946 -0.9064948 0.4117804 0.09296786 -0.9065285 0.3347915 0.0754857 -0.9392639 0.3412154 0.03563469 -0.9393095 0.2598753 0.02714794 -0.9652606 0.2612324 -0.005917072 -0.9652578 0.1796944 -0.004085481 -0.9837141 0.1776592 -0.008063375 -0.984059 0.4411134 0.2329322 -0.8666958 0.4421928 0.2202382 -0.8694601 0.3785695 0.1885206 -0.9061706 0.3986554 0.1414552 -0.906126 0.3235419 0.1148288 -0.9392205 0.3349703 0.0752567 -0.9392185 0.2838771 0.06379085 -0.9567364 0.2559176 0.004312813 -0.966689 0.3994156 0.3017264 -0.8656954 0.3994156 0.3017264 -0.8656954 0.4130843 0.2724379 -0.8689873 0.3523357 0.2324097 -0.9065568 0.377155 0.1894451 -0.9065675 0.3068804 0.1541694 -0.9391786 0.3235856 0.1148167 -0.9392068 0.3723662 0.3331131 -0.8662443 0.376775 0.3213881 -0.8687637 0.3212718 0.2740181 -0.906476 0.3527711 0.2321614 -0.9064512 0.287392 0.1890826 -0.9389643 0.3081915 0.1531482 -0.9389162 0.3130706 0.3904424 -0.8657608 0.3133348 0.3900373 -0.8658477 0.3133348 0.3900373 -0.8658478 0.3133347 0.3900373 -0.8658477 0.3395111 0.3595647 -0.8691636 0.3375249 0.366073 -0.8672183 0.286352 0.3105593 -0.9063971 0.3214457 0.2739802 -0.9064258 0.2613715 0.2226729 -0.9392027 0.2859563 0.1901021 -0.9391967 0.2798365 0.4130386 -0.8666549 0.2887116 0.4009994 -0.8693936 0.2469796 0.3429549 -0.9063019 0.2867316 0.3105617 -0.9062761 0.2331444 0.2524533 -0.9391013 0.2620285 0.2224848 -0.9390643 0.2052236 0.4561944 -0.8658927 0.208625 0.4545589 -0.8659399 0.241962 0.4323676 -0.8686269 0.2404879 0.434647 -0.8678985 0.2047538 0.3701051 -0.9061446 0.2475665 0.3429304 -0.9061509 0.2011951 0.2787098 -0.9390642 0.2335146 0.2523198 -0.9390451 0.1884956 0.2036815 -0.9607202 0.2113407 0.1794544 -0.9607973 0.2102653 0.1641191 -0.9637705 0.2224088 0.1478375 -0.9636797 0.2253039 0.1743536 -0.9585609 0.253381 0.1258982 -0.9591391 0.2474767 0.09809106 -0.9639157 0.2513477 0.08919095 -0.9637786 0.2580615 0.1080296 -0.9600698 0.2598755 0.1026582 -0.9601698 0.1678162 0.4710913 -0.8659738 0.1832458 0.4589309 -0.8693696 0.1564386 0.3918866 -0.9066157 0.2023719 0.3700516 -0.9067015 0.1646448 0.3010879 -0.9392753 0.1997864 0.2789454 -0.9392949 0.1521523 0.2123939 -0.9652661 0.145718 0.2176408 -0.96509 0.2244001 0.06121563 -0.9725725 0.08780711 0.49173 -0.8663091 0.08850216 0.4913399 -0.8664597 0.1281523 0.4788208 -0.8685089 0.1281588 0.4787748 -0.8685334 0.1094605 0.4089768 -0.9059561 0.1594523 0.392192 -0.9059584 0.1293514 0.3181263 -0.9391826 0.1655463 0.3010865 -0.9391173 0.1261223 0.2293154 -0.9651465 0.1532105 0.2121856 -0.9651445 0.105434 0.1459693 -0.9836548 0.22426 0.06104195 -0.9726158 0.08070755 0.1599459 -0.9838209 0.08546197 0.1573941 -0.983831 0.124678 0.2295958 -0.9652674 0.09828078 0.2421606 -0.9652457 0.1291388 0.3181546 -0.9392023 0.08782917 0.3319752 -0.9391905 0.1080991 0.4085649 -0.9063053 0.05934989 0.4184204 -0.9063124 0.06935942 0.489003 -0.8695203 0.006720781 0.4944525 -0.8691787 0.05116975 0.4970175 -0.8662305 0.04907906 0.4972653 -0.8662093 0.04907906 0.4972653 -0.8662093 0.04907906 0.4972653 -0.8662093 -0.04396635 0.4984102 -0.8658257 0.01071149 0.496569 -0.8679312 0.009122252 0.4229432 -0.9061103 0.06035494 0.4188631 -0.9060414 0.04903149 0.3402925 -0.9390404 0.0886895 0.3321071 -0.939063 0.0674178 0.2524453 -0.9652597 0.0984168 0.2420599 -0.9652571 0.06692695 0.1646325 -0.9840819 0.08174681 0.1576882 -0.9840996 0.07747066 0.1660086 -0.9830765 0.06800013 0.1645118 -0.9840284 0.04566651 0.1719039 -0.9840547 0.06704807 0.2524879 -0.9652743 0.03575593 0.2588137 -0.9652652 0.04692226 0.3396657 -0.9393751 0.007420659 0.3428956 -0.9393443 0.009156525 0.4230224 -0.906073 -0.04270619 0.4207704 -0.9061614 -0.04991811 0.4920249 -0.8691489 -0.1140592 0.4808428 -0.8693565 -0.07650709 0.4940803 -0.8660435 -0.07329815 0.4947506 -0.8659384 -0.1758903 0.4683752 -0.8658449 -0.1088947 0.4857367 -0.8672958 -0.09242534 0.412201 -0.9063928 -0.04382693 0.4201219 -0.9064088 -0.03560537 0.3412758 -0.9392886 0.007536709 0.3429237 -0.9393331 0.005754709 0.261784 -0.9651094 0.03759193 0.2591971 -0.9650927 0.02552998 0.1760269 -0.9840543 0.04569566 0.1719572 -0.9840441 -0.1930449 0.4617068 -0.8657717 -0.165426 0.4659557 -0.8692064 -0.1415014 0.3986663 -0.906114 -0.09140121 0.4130674 -0.9061023 -0.07428193 0.335767 -0.9390116 -0.03384977 0.3421861 -0.9390223 -0.02576678 0.260564 -0.9651128 0.005955398 0.2617487 -0.9651177 0.004071176 0.1790325 -0.9838348 0.007621943 0.1773056 -0.9841264 -0.2318626 0.4411829 -0.8669472 -0.2227619 0.4419879 -0.8689211 -0.1900188 0.3770046 -0.9065101 -0.1427721 0.3971991 -0.9065589 -0.1161509 0.3231993 -0.9391759 -0.07528364 0.3349511 -0.9392232 -0.06379812 0.2839332 -0.9567193 -0.003315329 0.2554643 -0.9668129 -0.4510113 0.7730137 -0.4461376 -0.4424318 0.7774328 -0.4470485 -0.45964 0.7692221 -0.4438788 -0.4491123 0.777755 -0.4397676 -0.4463486 0.7758413 -0.4459185 -0.455213 0.7697358 -0.4475355 -0.4473032 0.7750696 -0.4463039 -0.4473032 0.7750696 -0.4463039 -0.4473032 0.7750696 -0.4463038 -0.4440548 0.7770705 -0.4460682 -0.4498691 0.7737393 -0.4460331 -0.448741 0.7744474 -0.4459406 -0.44595 0.7759541 -0.4461207 5.07305e-6 0 1 -2.67136e-6 0 1 -3.20611e-6 0 1 -1.39863e-6 0 1 1.28931e-6 0 1 -1.26732e-6 0 1 -1.7623e-6 0 1 1.60511e-6 0 1 4.49608e-6 0 1 -3.93647e-6 0 1 4.72685e-6 0 1 1.57647e-6 0 1 -2.92589e-6 0 1 1.01825e-5 0 1 -6.85176e-6 0 1 1.01663e-5 0 1 -7.83012e-6 0 1 8.62783e-6 0 1 -1.64647e-5 0 1 2.47166e-5 0 1 -4.8962e-5 0 1 -2.02396e-5 0 1 2.47836e-5 0 1 -3.262e-5 0 1 0.9041571 0.4211102 -0.07187724 0.9041583 0.4211097 -0.07186406 0.9041582 0.4211101 -0.071864 0.9226933 0.3791374 -0.06994199 0.9567008 0.2825356 -0.06998008 0.9567008 0.2825356 -0.06998002 0.9567009 0.2825355 -0.06998002 0.9669187 0.2455577 -0.06906306 0.9608755 0.2682263 -0.06908696 0.9660234 0.2489213 -0.06954938 0.9660234 0.248921 -0.06954926 0.9660236 0.2489207 -0.06954932 0.988428 0.1347761 -0.06960916 0.9884281 0.1347762 -0.06960856 0.9884281 0.1347761 -0.06960922 0.9954907 0.06096631 -0.07267403 0.9954907 0.06096637 -0.07267409 0.9954907 0.06096625 -0.07267403 -0.7751758 0.4475275 -0.4458942 -0.7769686 0.4448294 -0.4454733 -0.7749793 0.4476189 -0.446144 -0.7773222 0.4482524 -0.4414068 -0.7748532 0.4480955 -0.4458847 -0.7803527 0.4360046 -0.4482742 -0.7737463 0.4500219 -0.4458667 -0.7767181 0.4445359 -0.4462028 -0.774156 0.4488326 -0.4463541 -0.7745016 0.4481396 -0.446451 -0.7735871 0.4496649 -0.4465027 -0.9046095 0.4261878 0.006759166 -0.9212924 0.3888706 0 -0.9503751 0.3111064 0 -0.9621514 0.2724334 0.006701231 -0.9724345 0.2331768 0 -0.9884831 0.1513318 0 -0.993872 0.1103252 0.006847739 -0.9976062 0.06915181 0 -0.9985111 -0.05412101 0.006813704 -0.9954534 -0.09525042 0 -0.9834744 -0.1810471 0 -0.975433 -0.2201977 0.006598651 -0.9659689 -0.2586582 0 -0.9410187 -0.338355 0 -0.9263702 -0.3765535 0.006777286 -0.9102327 -0.414097 0 -0.8520801 -0.523368 0.006755053 -0.7825433 -0.6225962 0 -0.7551203 -0.6555477 0.007107615 -0.7262557 -0.6874247 0 -0.6648686 -0.7469604 0 -0.6356957 -0.7719134 0.006376266 -0.6055529 -0.7958052 0 -0.5345906 -0.8451112 0 -0.4991447 -0.8664915 0.006861627 -0.4627532 -0.8864873 0 -0.3892151 -0.9211469 0 -0.3504118 -0.9365704 0.006908416 -0.3110575 -0.9503911 0 -0.2333446 -0.9723941 0 -0.192384 -0.9812952 0.006954669 -0.1510401 -0.9885277 0 -0.02812981 -0.9995812 0.006803095 0.01299726 -0.9999155 0 0.09948712 -0.9950389 0 0.1383938 -0.9903562 0.006483733 0.1769912 -0.9842125 0 0.2587401 -0.965947 0 0.2980298 -0.9545325 0.006790578 0.3368946 -0.9415424 0 0.4157796 -0.9094654 0 0.4523686 -0.8918058 0.006715595 0.4881412 -0.8727647 0 0.5577211 -0.8300284 0 0.592047 -0.8058735 0.00695163 0.6251849 -0.7804768 0 0.6874456 -0.7262359 0 0.7167364 -0.6973107 0.006836771 0.744983 -0.6670835 0 0.7974753 -0.6033517 0 0.8212317 -0.5705549 0.006753027 0.843842 -0.5365918 0 0.8865115 -0.4627068 0 0.9045655 -0.4262818 0.006728291 0.9211009 -0.3893243 0 0.9504189 -0.3109729 0 0.9621514 -0.2724334 0.006687164 0.9723691 -0.2334493 0 0.9885393 -0.1509636 0 0.9938852 -0.1102068 0.006845355 0.9976103 -0.06909191 0 0.9983966 0.05615288 0.007164835 0.9950465 0.09941065 0 0.9841627 0.1772676 0 0.9758403 0.2183746 0.006955146 0.9658097 0.2592524 0 0.9414088 0.3372679 0 0.9264905 0.3762546 0.006935298 0.90994 0.4147402 0 0.8520801 0.523368 0.006749391 0.7798456 0.6259721 0 0.753684 0.6572027 0.006722927 0.7265584 0.6871048 0 0.6680553 0.7441117 0 0.6356928 0.77191 0.007052183 0.6023021 0.7982683 0 0.5362461 0.8440617 0 0.5004346 0.8657465 0.006946861 0.4637401 0.8859714 0 0.3895977 0.9209852 0 0.3507637 0.9364386 0.006906747 0.3114352 0.9502674 0 0.2321674 0.9726759 0 0.1915279 0.9814631 0.006881356 0.1506584 0.9885859 0 0.02769488 0.9995928 0.006876468 -0.01386785 0.9999039 0 -0.0960896 0.9953727 0 -0.1373345 0.9905007 0.006901621 -0.178591 0.9839235 0 -0.2583205 0.9660594 0 -0.2981948 0.9544803 0.00688517 -0.3376644 0.9412665 0 -0.4150587 0.9097948 0 -0.4520351 0.8919745 0.006784498 -0.4882431 0.8727076 0 -0.5582367 0.8296818 0 -0.5919013 0.8059818 0.006800532 -0.6243813 0.7811198 0 -0.6873556 0.7263211 0 -0.7172044 0.6968284 0.006940066 -0.7458465 0.6661179 0 -0.796756 0.6043012 0 -0.821299 0.5704559 0.006937623 -0.8444625 0.5356147 0 -0.8865184 0.4626935 0 -0.634818 0.2064883 -0.7445594 -0.6302238 0.2344531 -0.7401687 -0.6302233 0.2344548 -0.7401686 -0.6302235 0.2344542 -0.7401686 -0.6534775 0.1550601 -0.7408938 -0.6493065 0.1561565 -0.7443227 -0.6599441 0.1018441 -0.74438 -0.6614671 0.1004562 -0.7432159 -0.6596123 0.09807336 -0.74518 -0.6652213 0.04638105 -0.7452044 -0.6640097 0.04709446 -0.7462394 -0.6666713 0.05868035 -0.7430384 -0.6666712 0.05868071 -0.7430385 -0.6666712 0.05868065 -0.7430385 -0.668841 -0.01205897 -0.7433077 -0.6683634 -0.01175242 -0.7437421 -0.6657816 -0.0588873 -0.7438193 -0.6657816 -0.05888736 -0.7438193 -0.6657817 -0.05888718 -0.7438193 -0.6672399 -0.06215929 -0.7422447 -0.662365 -0.06529384 -0.7463306 -0.6547773 -0.1203597 -0.7461771 -0.6602604 -0.1186287 -0.7416087 -0.6616438 -0.1167817 -0.7406684 -0.6616438 -0.1167817 -0.7406684 -0.6616437 -0.1167816 -0.7406685 -0.6490584 -0.1736648 -0.740651 -0.646536 -0.1711869 -0.7434288 -0.6264569 -0.2351891 -0.7431271 -0.6264569 -0.2351891 -0.7431271 -0.6257801 -0.2263188 -0.7464443 -0.6310019 -0.2246552 -0.7425407 -0.6099047 -0.2770475 -0.7424695 -0.6109876 -0.2769089 -0.7416304 -0.6032496 -0.2822753 -0.7459294 -0.5824479 -0.3228521 -0.7460034 -0.5847172 -0.3265709 -0.7426018 -0.5542066 -0.375832 -0.7427014 -0.5546202 -0.3746372 -0.7429963 -0.5567314 -0.3746824 -0.7413929 -0.5236105 -0.4201385 -0.7411583 -0.5239063 -0.4201545 -0.7409402 -0.5235062 -0.4204581 -0.7410508 -0.5235062 -0.4204581 -0.7410508 -0.4880657 -0.4608416 -0.7412266 -0.4869343 -0.4574239 -0.7440822 -0.4320113 -0.510335 -0.7435889 -0.4320113 -0.5103352 -0.7435888 -0.4320113 -0.5103352 -0.7435889 -0.4434979 -0.4963045 -0.7463186 -0.444348 -0.4964488 -0.7457168 -0.444348 -0.4964488 -0.7457168 -0.444348 -0.4964488 -0.7457168 -0.4022616 -0.5313412 -0.7455617 -0.4031326 -0.5315948 -0.7449102 -0.4031326 -0.5315949 -0.7449101 -0.4031326 -0.5315948 -0.7449101 -0.4071609 -0.5319274 -0.7424778 -0.3574483 -0.5664857 -0.7425124 -0.3573527 -0.5641332 -0.7443473 -0.308346 -0.5924295 -0.7442783 -0.3083472 -0.5903671 -0.7459147 -0.2632082 -0.611947 -0.7458166 -0.2601597 -0.6178152 -0.7420386 -0.258026 -0.6170105 -0.7434519 -0.2094586 -0.6348406 -0.7437099 -0.209518 -0.6345443 -0.7439461 -0.1988451 -0.6360644 -0.7455755 -0.1566575 -0.6477301 -0.7455899 -0.1547846 -0.6548555 -0.7397338 -0.09518212 -0.6664171 -0.7394787 -0.1029643 -0.6589182 -0.7451343 -0.1024288 -0.6583712 -0.7456915 -0.04647403 -0.6650045 -0.745392 -0.04438084 -0.6688225 -0.7420963 -0.03919726 -0.667465 -0.7436088 0.009065747 -0.6688262 -0.7433635 0.008839666 -0.6684166 -0.7437346 0.05879837 -0.6657968 -0.7438129 0.06536257 -0.6687031 -0.740651 0.06591665 -0.6679348 -0.7412949 0.1185056 -0.6605866 -0.7413379 0.1181324 -0.6617019 -0.7404023 0.1306435 -0.6531191 -0.7459006 0.1723635 -0.6440228 -0.7453359 0.1739187 -0.6456453 -0.7435688 0.2232754 -0.6303374 -0.7435206 0.2238826 -0.6303306 -0.7433438 0.2241765 -0.6292466 -0.7441732 0.2771205 -0.6073752 -0.744513 0.2772379 -0.6064697 -0.7452071 0.277893 -0.6054813 -0.7457666 0.3251866 -0.581139 -0.7460102 0.3261179 -0.5816966 -0.7451686 0.3651069 -0.5575387 -0.7455519 0.3651069 -0.5575388 -0.7455518 0.3651069 -0.5575389 -0.7455518 0.3738735 -0.5548529 -0.7432072 0.3738669 -0.5572531 -0.7414125 0.4201341 -0.5237108 -0.7410901 0.4201728 -0.524034 -0.7408396 0.4203444 -0.5230833 -0.7414138 0.4606852 -0.4881221 -0.7412868 0.4616687 -0.4883103 -0.7405505 0.5133136 -0.4341683 -0.740275 0.5133138 -0.4341683 -0.7402749 0.5133137 -0.4341684 -0.740275 0.4975683 -0.4471801 -0.7432737 0.4966604 -0.4443473 -0.7455763 0.5313867 -0.4023424 -0.7454856 0.5317552 -0.4028134 -0.7449684 0.5320178 -0.4070857 -0.7424543 0.5320178 -0.4070858 -0.7424542 0.5320178 -0.4070857 -0.7424542 0.5664658 -0.3573443 -0.7425777 0.5673037 -0.3575606 -0.7418336 0.5934076 -0.3118412 -0.7420395 0.5940012 -0.3118011 -0.7415812 0.619983 -0.2574148 -0.7411875 0.6158967 -0.2593038 -0.7439307 0.6189174 -0.2667168 -0.7387852 0.6409233 -0.208123 -0.7388519 0.6344054 -0.2095818 -0.7440466 0.6377981 -0.1872968 -0.7470833 0.6377982 -0.1872968 -0.7470833 0.637798 -0.1872963 -0.7470836 0.6465063 -0.1563162 -0.7467229 0.6490656 -0.1556732 -0.744634 0.6596897 -0.1019421 -0.7445921 0.6614233 -0.1004496 -0.7432558 0.6597907 -0.09838938 -0.7449804 0.6653263 -0.04639023 -0.74511 0.6688554 -0.04445838 -0.7420619 0.6675962 -0.03930932 -0.743485 0.6675963 -0.03930926 -0.743485 0.6675962 -0.03930932 -0.7434852 0.6688659 0.009040236 -0.7433282 0.6684367 0.008815586 -0.7437168 0.665808 0.05908226 -0.7437803 0.6686597 0.06524926 -0.7407002 0.6677396 0.06590712 -0.7414716 0.6605145 0.1184679 -0.7414081 0.6605082 0.118348 -0.741433 0.6606635 0.1183837 -0.7412888 0.6475869 0.1758883 -0.7414138 0.6456543 0.1741415 -0.7435088 0.6303719 0.2232071 -0.7435118 0.630446 0.2245571 -0.7430424 0.6307171 0.2246434 -0.7427861 0.6092026 0.2777129 -0.7427973 0.60464 0.2779803 -0.7464165 0.6085996 0.2749103 -0.7443326 0.6085996 0.2749103 -0.7443326 0.5828116 0.326153 -0.7442815 0.5837655 0.3274701 -0.7429544 0.555141 0.3743775 -0.7427383 0.5555922 0.3725518 -0.7433186 0.5555785 0.3726204 -0.7432944 0.5216556 0.418713 -0.7433403 0.5236275 0.4189764 -0.741804 0.5247852 0.4187446 -0.7411164 0.5247852 0.4187445 -0.7411164 0.5247852 0.4187445 -0.7411164 0.4872988 0.4614537 -0.7413504 0.4860891 0.45775 -0.7444342 0.4407361 0.5018852 -0.7442198 0.4444906 0.4970552 -0.7452277 0.4453403 0.4974319 -0.7444687 0.4024205 0.5328285 -0.7444136 0.4028228 0.5331313 -0.743979 0.4048549 0.5331824 -0.7428385 0.3580571 0.5655515 -0.7429311 0.3579319 0.5636239 -0.7444548 0.3095601 0.5918284 -0.7442525 0.3094406 0.5919184 -0.7442307 0.259924 0.6153181 -0.744193 0.2598628 0.6157736 -0.7438375 0.2618771 0.6165781 -0.7424635 0.2082971 0.636272 -0.7428125 0.2085586 0.6351615 -0.743689 0.2104434 0.6348279 -0.7434428 0.2104433 0.6348277 -0.743443 0.2104434 0.6348273 -0.7434433 0.1554539 0.6502924 -0.7436087 0.1550993 0.651682 -0.7424654 0.1008652 0.6617726 -0.7428885 0.1010255 0.6616509 -0.7429751 0.1004033 0.6611765 -0.7434817 0.04600542 0.6669823 -0.7436519 0.04603821 0.666959 -0.7436708 0.04653221 0.6670133 -0.7435913 -0.009076416 0.6681401 -0.7439801 -0.009481608 0.6689186 -0.7432752 -0.06454068 0.6657069 -0.743417 -0.06420737 0.6655879 -0.7435525 -0.06437331 0.6653771 -0.7437267 -0.118802 0.6572362 -0.7442626 -0.1186109 0.657963 -0.7436506 -0.1197419 0.6570172 -0.7443053 -0.1732062 0.6449002 -0.7443812 -0.1732062 0.6449003 -0.7443812 -0.1732062 0.6449003 -0.7443812 -0.1738587 0.6457228 -0.7435155 -0.2256261 0.6294989 -0.7435213 -0.2250398 0.6294571 -0.7437344 -0.2247655 0.6303836 -0.7430323 -0.2776227 0.6091178 -0.7429006 -0.2776597 0.6088137 -0.7431361 -0.2771143 0.6095885 -0.7427042 -0.3267767 0.5844612 -0.7427127 -0.3259289 0.5839798 -0.7434635 -0.3756895 0.5533218 -0.7434329 -0.3731678 0.5542352 -0.7440223 -0.3731725 0.554047 -0.7441601 -0.4172949 0.521552 -0.7442101 -0.4169058 0.5200055 -0.7455091 -0.4159275 0.5237207 -0.7434521 -0.4604357 0.4849461 -0.743523 -0.4605072 0.4851279 -0.7433599 -0.5059351 0.4379935 -0.7430958 -0.505935 0.4379938 -0.7430957 -0.5059352 0.4379939 -0.7430956 -0.4974321 0.4449392 -0.7447083 -0.4989481 0.449763 -0.7407861 -0.5353834 0.4058583 -0.7407049 -0.5316902 0.3979537 -0.7476219 -0.5321476 0.4053518 -0.7433094 -0.5655446 0.3573328 -0.7432851 -0.5652847 0.3575029 -0.7434009 -0.5919043 0.3113569 -0.7434421 -0.5954282 0.31122 -0.7406804 -0.6209094 0.2573117 -0.7404474 -0.6209094 0.2573118 -0.7404474 -0.6130194 0.2613823 -0.745578 -0.6137956 0.2632274 -0.7442892 -0.6350327 0.2063226 -0.7444223 -0.739376 0.4677514 -0.4842848 -0.7752807 0.4053912 -0.4843531 -0.773338 0.4057442 -0.4871551 -0.8031924 0.3424968 -0.4874198 -0.810646 0.3403779 -0.476441 -0.8362765 0.2719599 -0.4761086 -0.8316321 0.2736507 -0.483222 -0.851199 0.2046667 -0.4832926 -0.8556205 0.2025071 -0.4763451 -0.8693594 0.1319324 -0.4762438 -0.8669756 0.1333217 -0.4801862 -0.8749791 0.06197142 -0.4801785 -0.8762335 0.06108474 -0.4779995 -0.8782341 -0.01544201 -0.4779816 -0.8733692 -0.01144671 -0.4869243 -0.8696537 -0.08102416 -0.4869678 -0.8725131 -0.08387511 -0.4813379 -0.86213 -0.1584912 -0.4812613 -0.8592692 -0.1552704 -0.4873887 -0.8439321 -0.2234747 -0.4876861 -0.8480028 -0.2292638 -0.4778382 -0.8261046 -0.2986152 -0.4778915 -0.8247737 -0.296387 -0.4815633 -0.797788 -0.3622456 -0.4819881 -0.7979906 -0.362499 -0.481462 -0.7979906 -0.3624989 -0.481462 -0.7979906 -0.3624989 -0.4814621 -0.7655689 -0.4274923 -0.4807856 -0.7655689 -0.4274922 -0.4807855 -0.7655689 -0.4274922 -0.4807855 -0.7650897 -0.426405 -0.4825109 -0.7258005 -0.4900984 -0.4827185 -0.7256512 -0.4901843 -0.482856 -0.683026 -0.5480117 -0.4828653 -0.6825061 -0.5460376 -0.4858276 -0.6370221 -0.5983211 -0.4860192 -0.6376782 -0.6032924 -0.4789622 -0.5848298 -0.6546276 -0.4789958 -0.5846119 -0.6490715 -0.48676 -0.5271998 -0.6965223 -0.4867413 -0.5269181 -0.7025428 -0.4783209 -0.470123 -0.7421748 -0.477662 -0.4708208 -0.7364882 -0.4857088 -0.4047132 -0.7748727 -0.4855715 -0.4041392 -0.7777317 -0.4814613 -0.3402311 -0.8079974 -0.4810229 -0.3413775 -0.8041727 -0.4865878 -0.2739894 -0.829717 -0.4863123 -0.2733837 -0.8315165 -0.483572 -0.2013298 -0.8517785 -0.4836732 -0.2014653 -0.8515027 -0.4841023 -0.1350705 -0.86438 -0.4843585 -0.1331729 -0.8675917 -0.4791135 -0.05809819 -0.8755521 -0.4796177 -0.06091594 -0.8716107 -0.4863992 0.01155567 -0.8736093 -0.4864909 0.01527136 -0.8779457 -0.4785167 0.0854426 -0.8741238 -0.4781287 0.08382302 -0.8724399 -0.4814794 0.1547703 -0.8627485 -0.4813641 0.1560228 -0.8637169 -0.4792183 0.228272 -0.8473951 -0.4793886 0.2244838 -0.8446362 -0.486001 0.2924974 -0.8235132 -0.4860775 0.296983 -0.8262922 -0.4785839 0.3645137 -0.7988265 -0.4785457 0.3627021 -0.7981052 -0.4811187 0.4288076 -0.764816 -0.4808126 0.430305 -0.7653568 -0.478609 0.430305 -0.7653568 -0.478609 0.430305 -0.7653568 -0.478609 0.4908488 -0.7284063 -0.4780082 0.4874975 -0.7275074 -0.4827828 0.5480023 -0.6829558 -0.4829752 0.5460134 -0.6825666 -0.4857698 0.6004777 -0.6351311 -0.4858345 0.6009395 -0.6352384 -0.4851226 0.650589 -0.5845346 -0.484823 0.6530429 -0.5848355 -0.4811469 0.698782 -0.5288741 -0.4816595 0.70117 -0.5289364 -0.4781077 0.743334 -0.4682939 -0.4776561 0.7376988 -0.4691064 -0.4855304 0.7738927 -0.4062598 -0.4858428 0.7738927 -0.4062598 -0.4858428 0.7738927 -0.4062598 -0.4858428 0.7797451 -0.4051048 -0.4773758 0.8098313 -0.3409065 -0.4774475 0.8058064 -0.3421112 -0.4833591 0.8311145 -0.2745602 -0.4835964 0.83107 -0.2744602 -0.4837296 0.8511071 -0.2041788 -0.4836607 0.8549718 -0.2021867 -0.4776442 0.8689429 -0.1318691 -0.4770207 0.8668749 -0.1330999 -0.4804293 0.8752135 -0.05805134 -0.480241 0.8715538 -0.06087344 -0.4865066 0.8735875 0.01154273 -0.4865303 0.8733504 0.01135915 -0.48696 0.8693381 0.08487844 -0.4868746 0.8721802 0.08763146 -0.4812718 0.8721802 0.0876314 -0.4812718 0.8721802 0.08763146 -0.4812718 0.8626667 0.1548519 -0.4814842 0.8641117 0.1564003 -0.4783828 0.8478184 0.2287977 -0.4783887 0.8478184 0.2287977 -0.4783887 0.8478184 0.2287977 -0.4783887 0.8447123 0.2242053 -0.4859971 0.8234192 0.2931174 -0.4858633 0.8234192 0.2931174 -0.4858633 0.8234192 0.2931174 -0.4858633 0.8256886 0.2971057 -0.4795482 0.7984071 0.3640331 -0.4796105 0.7971969 0.3615934 -0.4834537 0.7634802 0.4284707 -0.4832296 0.7639865 0.4296899 -0.4813429 0.7280341 0.4881299 -0.4813478 0.7278028 0.4879315 -0.4818982 0.6833307 0.5483816 -0.4820135 0.6830705 0.5473297 -0.4835752 0.6371369 0.5999187 -0.483895 0.6371369 0.5999186 -0.4838949 0.6371369 0.5999186 -0.4838949 0.6376136 0.6030061 -0.4794088 0.6376136 0.6030061 -0.4794088 0.6376135 0.6030061 -0.4794088 0.5848279 0.6540874 -0.4797354 0.5848715 0.6549224 -0.4785415 0.5290372 0.7005994 -0.478832 0.5291725 0.6972239 -0.4835861 0.4693247 0.7388899 -0.4835041 0.4688932 0.7421694 -0.4788776 0.4066584 0.7777827 -0.4792525 0.4067061 0.7776119 -0.4794893 0.3411486 0.8082362 -0.4799709 0.3412602 0.8075355 -0.4810696 0.2734983 0.8328347 -0.481233 0.2737277 0.832172 -0.482248 0.2737276 0.832172 -0.482248 0.2737276 0.832172 -0.482248 0.202889 0.8523525 -0.4820078 0.2031194 0.8519618 -0.4826009 0.1322349 0.8660562 -0.4821417 0.1321576 0.8661389 -0.4820145 0.06034755 0.8741145 -0.4819567 0.06032937 0.8742255 -0.4817574 -0.01242339 0.8764933 -0.481254 -0.01174718 0.8756973 -0.4827176 -0.08407819 0.8714599 -0.4832068 -0.08455401 0.872114 -0.4819418 -0.08455401 0.872114 -0.4819418 -0.08455401 0.872114 -0.4819418 -0.1557924 0.8620984 -0.4821982 -0.1564986 0.8626589 -0.4809655 -0.227988 0.8468047 -0.4805657 -0.2271878 0.8462524 -0.4819157 -0.2949352 0.8250594 -0.4819653 -0.2955824 0.8253815 -0.4810162 -0.3636696 0.7978721 -0.4807748 -0.3620721 0.7971114 -0.4832362 -0.4265757 0.7642643 -0.4836665 -0.4271411 0.7645742 -0.4826769 -0.4891116 0.7264157 -0.4827941 -0.491814 0.7271336 -0.4789527 -0.5485219 0.6856385 -0.4785641 -0.5481241 0.6856644 -0.4789825 -0.604557 0.6366158 -0.4787809 -0.6029843 0.6366083 -0.48077 -0.6535653 0.5845237 -0.4808165 -0.6508283 0.5845546 -0.4844776 -0.6969905 0.5283923 -0.4847741 -0.6979277 0.5284277 -0.4833853 -0.7398071 0.4678112 -0.4835681 -0.8327786 0.5280482 -0.1662681 -0.8731245 0.4582824 -0.1662259 -0.8749728 0.4566053 -0.1610412 -0.9100427 0.3821125 -0.1606629 -0.9085682 0.3835362 -0.1655406 -0.9367839 0.3082237 -0.165633 -0.9378507 0.3070322 -0.1617636 -0.9602708 0.2274793 -0.1616578 -0.9584297 0.2298372 -0.169078 -0.9741329 0.1498363 -0.1691572 -0.9745278 0.1492815 -0.167364 -0.9835039 0.06870633 -0.1673308 -0.9835039 0.06870633 -0.1673308 -0.9835039 0.06870639 -0.1673308 -0.9836919 0.06834805 -0.1663695 -0.985979 -0.01263618 -0.1663906 -0.985979 -0.01263618 -0.1663907 -0.985979 -0.01263612 -0.1663907 -0.9859791 -0.01272994 -0.1663829 -0.9815316 -0.09445738 -0.1663538 -0.9813541 -0.0937736 -0.1677818 -0.9701355 -0.1752593 -0.1676945 -0.9709378 -0.1789883 -0.1588804 -0.9531229 -0.2575924 -0.158755 -0.9527874 -0.2552102 -0.1645113 -0.9281913 -0.3334819 -0.1650779 -0.9281727 -0.3336451 -0.1648532 -0.8980687 -0.4080489 -0.1642217 -0.8980688 -0.4080489 -0.1642217 -0.8980687 -0.4080489 -0.1642216 -0.8980211 -0.4084592 -0.1634598 -0.861719 -0.4802229 -0.1637881 -0.8615284 -0.4819341 -0.1597138 -0.8179886 -0.5524756 -0.1602039 -0.8184908 -0.5499396 -0.1662511 -0.7699536 -0.6160241 -0.1663913 -0.7708122 -0.6131411 -0.1729361 -0.7154533 -0.6769777 -0.1727073 -0.7154838 -0.6769967 -0.1725065 -0.6591506 -0.732032 -0.1721913 -0.656606 -0.737571 -0.1576629 -0.5924934 -0.7900059 -0.1576146 -0.5961681 -0.783586 -0.1748624 -0.5303484 -0.8295131 -0.1750397 -0.5273265 -0.8338475 -0.1631722 -0.4549805 -0.8753544 -0.163547 -0.4560632 -0.8739015 -0.1682336 -0.385138 -0.9072502 -0.1690147 -0.3839145 -0.908555 -0.1647345 -0.3080558 -0.9369606 -0.1649442 -0.3069408 -0.9379269 -0.1614951 -0.2272599 -0.960389 -0.1612639 -0.2300658 -0.9583423 -0.1692627 -0.2300658 -0.9583423 -0.1692626 -0.2300658 -0.9583423 -0.1692627 -0.1495453 -0.974124 -0.1694661 -0.1489592 -0.974542 -0.1675688 -0.1489593 -0.9745419 -0.1675688 -0.1489592 -0.9745419 -0.1675688 -0.0687285 -0.9834982 -0.1673553 -0.0687285 -0.9834982 -0.1673552 -0.0687285 -0.9834982 -0.1673552 -0.06814837 -0.9837834 -0.16591 0.01714944 -0.9859246 -0.1663089 0.01279228 -0.9840882 -0.1772199 0.09412634 -0.9796333 -0.177367 0.09807723 -0.9809604 -0.1676236 0.1752264 -0.9701331 -0.1677424 0.1752264 -0.9701331 -0.1677423 0.1752264 -0.9701331 -0.1677423 0.174425 -0.9699716 -0.1695023 0.253166 -0.9524964 -0.1692858 0.2551963 -0.9527685 -0.1646423 0.2551963 -0.9527685 -0.1646423 0.2551963 -0.9527685 -0.1646423 0.333587 -0.9281889 -0.1648791 0.3320908 -0.9280372 -0.1687088 0.4077579 -0.8973473 -0.1688235 0.4101758 -0.8972111 -0.1636096 0.4834578 -0.8598891 -0.1638884 0.4812225 -0.8601448 -0.1690441 0.5486797 -0.8187489 -0.169118 0.5499548 -0.8184795 -0.1662564 0.6159148 -0.7700604 -0.1663008 0.6167441 -0.7697534 -0.1646409 0.677823 -0.7165033 -0.1648607 0.6780159 -0.7163832 -0.1645892 0.734887 -0.6578376 -0.1648966 0.7348113 -0.6579508 -0.1647827 0.7875796 -0.5939211 -0.1642442 0.7859958 -0.5948475 -0.1684256 0.8317281 -0.5287588 -0.1692412 0.8315694 -0.5289797 -0.169331 0.874617 -0.454449 -0.168883 0.8730906 -0.4556423 -0.1735022 0.9066458 -0.3846997 -0.1732037 0.9066459 -0.3846997 -0.1732037 0.9066459 -0.3846997 -0.1732038 0.9080099 -0.3834657 -0.1687366 0.936036 -0.3090979 -0.1682115 0.9378991 -0.3070755 -0.1614 0.9604054 -0.2270667 -0.1614384 0.9583035 -0.2300888 -0.1694508 0.9741002 -0.1496699 -0.1694933 0.9744983 -0.1489123 -0.1678637 0.9834724 -0.06857556 -0.1675695 0.9837086 -0.06811445 -0.1663666 0.9859764 0.01279634 -0.1663936 0.9859769 0.01290428 -0.1663825 0.9811407 0.09850406 -0.1663132 0.9809434 0.09796959 -0.167786 0.9700959 0.1754648 -0.1677082 0.9698677 0.1746652 -0.1698496 0.9524946 0.2528646 -0.1697454 0.9529031 0.2556912 -0.1630882 0.9282282 0.3343007 -0.163204 0.9282079 0.3322663 -0.1674194 0.8978497 0.4072684 -0.1673273 0.8977875 0.4092934 -0.1626552 0.859946 0.4836834 -0.1629212 0.8602605 0.481226 -0.1684443 0.8188403 0.548638 -0.1688106 0.8188403 0.548638 -0.1688106 0.8188403 0.548638 -0.1688106 0.8186603 0.5498809 -0.1656099 0.769519 0.6167281 -0.1657927 0.7693205 0.6176694 -0.1631885 0.7168127 0.6778383 -0.1634466 0.7168724 0.6778823 -0.163002 0.6570534 0.7359751 -0.1631609 0.6584544 0.7332306 -0.1697373 0.5957664 0.7850511 -0.1695795 0.5943081 0.7876939 -0.1622843 0.5270437 0.8340609 -0.1629955 0.5286644 0.8317356 -0.1694992 0.5286645 0.8317356 -0.1694992 0.4569216 0.8733147 -0.1689495 0.4569194 0.8731705 -0.1696996 0.3837686 0.9078364 -0.1689813 0.3838976 0.9076382 -0.1697517 0.3078855 0.9362171 -0.1694224 0.3070956 0.9369564 -0.1667482 0.2286867 0.9591282 -0.1666601 0.2288711 0.9589469 -0.1674488 0.1487352 0.974631 -0.1672495 0.1485321 0.9747481 -0.1667469 0.06788772 0.9837018 -0.1664996 0.06813257 0.983555 -0.1672653 -0.0132274 0.9857835 -0.1674993 -0.0136767 0.9859788 -0.1663097 -0.09515982 0.9815935 -0.1655868 -0.09475058 0.981459 -0.1666151 -0.1760094 0.9701657 -0.1667307 -0.1761191 0.970223 -0.1662814 -0.2556297 0.9523436 -0.1664187 -0.2546275 0.9522269 -0.168609 -0.3322744 0.9279075 -0.1690604 -0.3328594 0.9279671 -0.1675756 -0.4077378 0.897525 -0.1679251 -0.4093646 0.8975154 -0.1639721 -0.4812242 0.861258 -0.1632725 -0.481839 0.8611981 -0.1617691 -0.5529032 0.8174294 -0.1615778 -0.5529031 0.8174294 -0.1615777 -0.5504789 0.8179812 -0.1669725 -0.6155849 0.7701677 -0.1670243 -0.6157546 0.7699576 -0.1673669 -0.6779771 0.7157856 -0.1673265 -0.6774951 0.7160087 -0.1683213 -0.7334758 0.6584839 -0.1685593 -0.7359211 0.6574004 -0.1620025 -0.7868384 0.5956207 -0.1616209 -0.7859736 0.5961365 -0.1639114 -0.8336026 0.5275388 -0.1637371 0.3026694 0.398488 -0.8657936 0.3329232 0.37186 -0.8665346 0.4150124 0.2782585 -0.8662199 0.4710644 0.167671 -0.8660167 0.4988622 -0.02955222 -0.8661774 0.4988622 -0.0295521 -0.8661774 0.4988622 -0.02955216 -0.8661774 0.4785597 -0.1409299 -0.8666715 0.4594705 -0.1980088 -0.8658402 0.441186 -0.2318603 -0.8669463 0.3977026 -0.3041866 -0.865623 0.3977027 -0.3041866 -0.8656231 0.3977026 -0.3041866 -0.8656231 0.3723402 -0.3331755 -0.8662315 0.2784314 -0.4149313 -0.8662033 0.1678065 -0.4711343 -0.8659524 -0.02929836 -0.4990075 -0.8661024 -0.02929449 -0.4990075 -0.8661023 -0.02929848 -0.4990078 -0.8661022 -0.148662 -0.4756625 -0.8669745 -0.148662 -0.4756625 -0.8669745 -0.148662 -0.4756629 -0.8669744 -0.1930389 -0.4616925 -0.8657807 -0.2301096 -0.4420841 -0.8669552 -0.3043664 -0.3976695 -0.8655751 -0.3326382 -0.3718091 -0.866666 -0.4138956 -0.2785267 -0.8666681 -0.4711118 -0.1677973 -0.8659664 -0.4981753 0.04342418 -0.8659883 -0.4689406 0.1744894 -0.8658223 -0.4689406 0.174489 -0.8658224 -0.4689406 0.1744894 -0.8658223 -0.459977 0.1972785 -0.8657382 -0.4411867 0.2320901 -0.8668844 -0.3984414 0.3034632 -0.8655372 -0.3710526 0.3344302 -0.8663005 -0.2790883 0.414373 -0.8662591 -0.1678911 0.4710392 -0.8659878 0.03477305 0.4987779 -0.8660321 0.1570675 0.4737422 -0.8665438 0.1570675 0.4737423 -0.8665437 0.1570675 0.4737427 -0.8665436 0.1956154 0.4605255 -0.8658239 0.2309949 0.4416005 -0.8669663 -0.1763231 -0.02403658 -0.9840389 0.1648787 -0.1651261 -0.9723932 0.1683787 0.1616474 -0.972378 -0.1650856 0.1639714 -0.9725534 -0.1650856 0.1639714 -0.9725535 -0.1650856 0.1639714 -0.9725535 -0.1611238 -0.166833 -0.9727312 -0.0420348 -0.2318266 -0.9718486 -0.143355 -0.3196604 -0.9366251 -0.06090301 -0.2245556 -0.9725562 -0.1099818 -0.2743442 -0.9553216 -0.2130907 -0.151903 -0.9651518 -0.06436377 -0.2195656 -0.9734724 -0.1730064 -0.1233483 -0.9771663 -0.1608704 -0.07968771 -0.9837533 -0.164353 -0.06756585 -0.9840849 -0.1607981 -0.07507997 -0.9841276 -0.2361414 0.04411739 -0.9707167 -0.3139163 0.1335322 -0.9400137 -0.2247424 0.06000643 -0.9725688 -0.2757188 0.1082215 -0.9551269 -0.2757188 0.1082216 -0.9551268 -0.2757188 0.1082215 -0.9551268 -0.1532061 0.2117802 -0.9652342 -0.2290073 0.0567277 -0.9717704 -0.1248139 0.1725162 -0.9770669 -0.08067834 0.1603367 -0.9837597 -0.06623589 0.1650316 -0.9840618 -0.08033156 0.1582871 -0.98412 0.04363548 0.2341256 -0.9712267 0.1443201 0.3203128 -0.936254 0.1443203 0.3203127 -0.936254 0.1443203 0.3203126 -0.936254 0.0592575 0.225117 -0.9725281 0.05925744 0.2251168 -0.9725282 0.0592575 0.2251169 -0.9725282 0.1072605 0.2770361 -0.954854 0.2128476 0.152435 -0.9651215 0.05900049 0.2253633 -0.9724867 0.05900049 0.2253631 -0.9724868 0.05900049 0.2253636 -0.9724867 0.1719206 0.1231448 -0.9773836 0.1602073 0.08109825 -0.9837462 0.1653354 0.06549954 -0.9840601 0.1600447 0.07679128 -0.9841183 0.231854 -0.04207211 -0.9718403 0.3147345 -0.1327619 -0.9398492 0.2260954 -0.05797815 -0.9723783 0.2783216 -0.1060681 -0.9546134 0.1519678 -0.2131542 -0.9651275 0.2210216 -0.06164729 -0.9733186 0.2210217 -0.06164729 -0.9733186 0.2210216 -0.06164723 -0.9733186 0.1222717 -0.1714945 -0.977568 0.08146971 -0.1602212 -0.9837134 0.06603842 -0.1650303 -0.9840752 0.07498097 -0.1609891 -0.9841039 0.1946754 0.4608651 -0.8658551 0.220741 0.4426474 -0.8691011 0.1887093 0.3783274 -0.9062324 0.2329072 0.3528342 -0.9062352 0.1891797 0.2866131 -0.9391826 0.2225612 0.2614725 -0.9392012 0.1552658 0.4743807 -0.8665192 0.1663317 0.465249 -0.869412 0.1423157 0.3980914 -0.9062392 0.1888031 0.3783228 -0.9062148 0.1532592 0.3071335 -0.9392448 0.1885065 0.2866783 -0.9392982 0.07510858 0.4944956 -0.8659288 0.07536125 0.4945121 -0.8658975 0.11486 0.480508 -0.8694363 0.1091243 0.4858013 -0.8672307 0.09261888 0.4122998 -0.9063282 0.1416641 0.3980064 -0.9063786 0.1151344 0.3234505 -0.9392145 0.1535445 0.3070657 -0.9392204 0.03437471 0.4983369 -0.8663018 0.04986763 0.4916392 -0.86937 0.04265934 0.4205443 -0.9062685 0.09292215 0.4123651 -0.9062674 0.07548248 0.3349987 -0.9391902 0.1152717 0.3234497 -0.939198 -0.04816979 0.4979311 -0.8658778 -0.04828262 0.497761 -0.8659694 -0.006726682 0.4953137 -0.8686882 -0.01001614 0.4969121 -0.867743 -0.008518159 0.4226253 -0.9062646 0.04259437 0.4204764 -0.9063031 0.03460764 0.3416741 -0.9391811 0.07546985 0.3349922 -0.9391936 0.06107872 0.2711175 -0.9606065 0.09321582 0.261543 -0.96068 0.09998661 0.2477281 -0.9636563 0.1195864 0.2391602 -0.9635878 0.1090798 0.2630704 -0.9585905 0.1555008 0.2365275 -0.9591009 0.1639003 0.2105563 -0.9637442 0.1732851 0.2035751 -0.9636024 0.1701843 0.2208589 -0.960343 0.1726399 0.2185961 -0.9604225 0.01672667 0.2616497 -0.965018 0.02632027 0.2601314 -0.9652144 0.0345593 0.3415989 -0.9392103 -0.006987869 0.3433642 -0.9391763 -0.008595943 0.4224614 -0.9063402 -0.05928957 0.4184718 -0.9062926 -0.0693053 0.4891483 -0.8694427 -0.1287086 0.4792883 -0.8681687 -0.08957368 0.4915803 -0.8662133 -0.0887041 0.4920012 -0.8660638 -0.1687039 0.4706424 -0.8660455 -0.1286177 0.4794194 -0.8681098 -0.1094955 0.408177 -0.9063125 -0.0593757 0.4184399 -0.9063016 -0.04826211 0.3400168 -0.9391801 -0.006946861 0.3432926 -0.9392029 -0.00528711 0.2613965 -0.9652171 0.02620494 0.2602402 -0.9651883 0.01795798 0.1782217 -0.9838265 0.1696062 0.1656939 -0.9714831 0.1696062 0.1656938 -0.9714831 0.1696062 0.1656938 -0.9714831 -0.01025754 0.1792771 -0.9837452 -0.003667771 0.1793875 -0.9837718 -0.005342006 0.2614366 -0.9652059 -0.03680777 0.258852 -0.9652155 -0.04834318 0.3399621 -0.9391958 -0.08893668 0.3316206 -0.9392114 -0.1094624 0.4081321 -0.9063367 -0.157874 0.392081 -0.9062827 -0.184426 0.4579061 -0.8696603 -0.2415658 0.4321532 -0.8688438 -0.2069746 0.4550043 -0.866102 -0.2074558 0.454874 -0.8660553 -0.2805005 0.4133956 -0.86627 -0.2393476 0.4354304 -0.8678209 -0.2037106 0.3705744 -0.906188 -0.1575404 0.3924611 -0.9061763 -0.1279801 0.3188194 -0.9391355 -0.08851915 0.3320065 -0.9391146 -0.06739461 0.2527793 -0.965174 -0.03650957 0.258979 -0.9651927 -0.0248028 0.175947 -0.9840872 -0.007845699 0.177302 -0.9841253 -0.0124247 0.1803345 -0.983527 -0.0124247 0.1803343 -0.983527 -0.0124247 0.1803345 -0.983527 -0.02475643 0.1760227 -0.9840748 -0.04598408 0.1715928 -0.9840943 -0.06766766 0.2524593 -0.9652385 -0.09785807 0.2425673 -0.9651865 -0.1284713 0.3182882 -0.9392486 -0.1658815 0.3005132 -0.9392419 -0.204163 0.3698936 -0.9063643 -0.2473928 0.3425354 -0.9063478 -0.2892465 0.4005109 -0.869441 -0.3399025 0.3579998 -0.8696566 -0.3110961 0.3918169 -0.8658515 -0.3129519 0.3902822 -0.8658759 -0.3779636 0.327353 -0.866016 -0.3372172 0.3665195 -0.8671494 -0.2864957 0.3114427 -0.9060485 -0.2467953 0.3437637 -0.9060456 -0.2003588 0.2790268 -0.9391489 -0.1655572 0.3010598 -0.939124 -0.1259638 0.2290167 -0.9652382 -0.09810775 0.2422159 -0.9652494 -0.066693 0.1647188 -0.9840833 -0.04585492 0.1716215 -0.9840953 -0.4009758 0.3000774 -0.8655472 -0.3764456 0.3199606 -0.8694332 -0.3217222 0.2734377 -0.9064915 -0.2871381 0.3093977 -0.9065455 -0.2334795 0.2516145 -0.939243 -0.2007097 0.2784326 -0.9392503 -0.1529582 0.2121672 -0.9651886 -0.1255401 0.2295008 -0.9651783 -0.08607035 0.1573015 -0.9837928 -0.08215159 0.1576806 -0.9840671 -0.4213998 0.2663101 -0.8668917 -0.41281 0.2722988 -0.8691614 -0.3526694 0.2326595 -0.9063631 -0.3215766 0.2740996 -0.9063432 -0.2615599 0.2229555 -0.9390833 -0.2331046 0.2524972 -0.9390993 -0.1968311 0.2132639 -0.9569619 -0.1320065 0.2187563 -0.9668092 -0.4622467 0.1917958 -0.8657612 -0.4421753 0.2204132 -0.8694245 -0.3787551 0.1888324 -0.9060282 -0.3525595 0.2340311 -0.9060527 -0.2860233 0.18985 -0.9392272 -0.2617688 0.2222606 -0.9391898 -0.475039 0.154379 -0.866317 -0.4647924 0.1668392 -0.8695589 -0.3982434 0.142942 -0.9060739 -0.3787919 0.188606 -0.9060599 -0.3072639 0.1530344 -0.9392388 -0.2860587 0.1898704 -0.9392123 -0.4947471 0.07360148 -0.8659147 -0.4943424 0.07647418 -0.8658968 -0.4810277 0.1140863 -0.8692507 -0.4855522 0.1091824 -0.8673629 -0.4118472 0.092655 -0.9065302 -0.3979277 0.1407423 -0.9065568 -0.3234691 0.1143608 -0.9393026 -0.3073286 0.1523929 -0.9393219 -0.4986586 0.03468054 -0.8661044 -0.4919861 0.04986268 -0.8691741 -0.4202314 0.04251706 -0.9064204 -0.4119784 0.09318435 -0.9064164 -0.3355336 0.07592606 -0.9389636 -0.3236927 0.1167834 -0.9389274 -0.4974216 -0.04909485 -0.8661186 -0.4978298 -0.04383093 -0.8661665 -0.4956031 -0.009013473 -0.8685025 -0.496531 -0.01064634 -0.8679538 -0.4220759 -0.009156703 -0.9065143 -0.4200032 0.04199779 -0.9065504 -0.3421521 0.03416502 -0.9390233 -0.3353833 0.07540267 -0.9390594 -0.2707286 0.06081026 -0.9607331 -0.2609184 0.09416341 -0.9607574 -0.2482649 0.1002085 -0.9634952 -0.2400857 0.1190845 -0.9634198 -0.2627142 0.1090811 -0.958688 -0.2356161 0.1563627 -0.959185 -0.2100305 0.1646266 -0.9637351 -0.2038035 0.1730324 -0.9635995 -0.2199131 0.1700923 -0.9605762 -0.2198683 0.1699577 -0.9606105 -0.2611867 0.01818251 -0.9651171 -0.2599757 0.02578896 -0.9652708 -0.3420338 0.0339514 -0.9390742 -0.3436193 -0.005961298 -0.9390901 -0.4231048 -0.007287859 -0.9060515 -0.4188753 -0.05940622 -0.9060985 -0.489029 -0.06935453 -0.8695061 -0.4788298 -0.1281844 -0.8684992 -0.4921265 -0.08677285 -0.8661883 -0.4917262 -0.08835679 -0.8662555 -0.4683552 -0.1758263 -0.8658686 -0.4683552 -0.1758263 -0.8658686 -0.4683552 -0.1758263 -0.8658686 -0.4788204 -0.1281735 -0.868506 -0.4083654 -0.1093211 -0.9062487 -0.4182678 -0.06024056 -0.906324 -0.3395584 -0.04890877 -0.9393125 -0.342891 -0.007486104 -0.9393454 -0.2612024 -0.005721271 -0.9652672 -0.2600052 0.02564465 -0.9652667 -0.1779682 0.01753371 -0.9838801 -0.1649492 0.1640301 -0.9725667 -0.1649493 0.1640301 -0.9725667 -0.1649492 0.16403 -0.9725667 -0.1795589 -0.01117819 -0.9836837 -0.1797147 -0.002732217 -0.983715 -0.261875 -0.003985285 -0.9650936 -0.2593119 -0.03588539 -0.9651267 -0.3406356 -0.04710012 -0.939015 -0.3322994 -0.08795428 -0.9390641 -0.4092972 -0.1081902 -0.905964 -0.3926151 -0.1582285 -0.9059897 -0.4579223 -0.1846344 -0.8696076 -0.4334998 -0.2403832 -0.868501 -0.452522 -0.2115804 -0.8662896 -0.4550821 -0.206188 -0.8662489 -0.4127645 -0.2801871 -0.8666721 -0.4345753 -0.2396417 -0.8681683 -0.3701354 -0.2040647 -0.9062877 -0.3914751 -0.1592397 -0.9063058 -0.317412 -0.1290598 -0.9394644 -0.3305079 -0.09011048 -0.9394917 -0.2521396 -0.0687201 -0.9652478 -0.2585065 -0.03746122 -0.965283 -0.1757395 -0.02546757 -0.9841072 -0.1771656 -0.007885336 -0.9841495 -0.1714424 -0.0478695 -0.9840306 -0.1716968 -0.0456894 -0.9840898 -0.2530757 -0.06738173 -0.9650972 -0.2431085 -0.09722709 -0.9651141 -0.3190087 -0.1276186 -0.9391204 -0.3013792 -0.1647869 -0.9391571 -0.3715708 -0.2031989 -0.9058949 -0.3441325 -0.2467382 -0.9059212 -0.4013798 -0.2877123 -0.8695493 -0.3596034 -0.3396227 -0.8691041 -0.3902491 -0.313166 -0.8658133 -0.3904285 -0.3131489 -0.8657387 -0.3226293 -0.3811002 -0.8664139 -0.3226292 -0.3811003 -0.8664139 -0.3226292 -0.3811004 -0.8664138 -0.3647789 -0.3379043 -0.8676157 -0.310061 -0.2872819 -0.9062734 -0.3427078 -0.2472926 -0.90631 -0.2778996 -0.2005825 -0.9394353 -0.2998649 -0.1659771 -0.9394321 -0.2286553 -0.1266139 -0.9652387 -0.2420889 -0.09838038 -0.9652535 -0.1647959 -0.06699812 -0.9840497 -0.1724953 -0.04365378 -0.9840426 -0.302522 -0.3991408 -0.8655445 -0.3211097 -0.3761116 -0.8691539 -0.2746739 -0.3217451 -0.9061095 -0.310764 -0.2870146 -0.9061172 -0.2521761 -0.2329346 -0.9392278 -0.2791334 -0.1999128 -0.9392122 -0.2125664 -0.1522641 -0.9652105 -0.2289482 -0.126241 -0.9652181 -0.1570297 -0.08665585 -0.9837847 -0.1572605 -0.083346 -0.9840338 -0.2659629 -0.421468 -0.8669652 -0.2721371 -0.4126887 -0.8692696 -0.2327556 -0.3528548 -0.9062662 -0.2742747 -0.3218696 -0.9061863 -0.2229284 -0.2615743 -0.9390856 -0.2531182 -0.2324643 -0.9390909 -0.2140745 -0.1966875 -0.9568105 -0.219388 -0.1317325 -0.9667034 -0.1977093 -0.4596031 -0.8658384 -0.2214437 -0.4429634 -0.8687614 -0.188959 -0.3779715 -0.906329 -0.2322461 -0.3529604 -0.9063558 -0.1887708 -0.2868695 -0.9391867 -0.2222155 -0.2617837 -0.9391962 -0.1562235 -0.4736075 -0.86677 -0.1654199 -0.4659703 -0.8691997 -0.1412289 -0.3978086 -0.9065334 -0.1880393 -0.3778769 -0.9065597 -0.1530093 -0.3074707 -0.9391752 -0.1887349 -0.2868799 -0.9391908 -0.07704025 -0.4950814 -0.8654243 -0.07084751 -0.4961701 -0.86533 -0.1161286 -0.4801468 -0.8694673 -0.1105967 -0.4852553 -0.8673499 -0.09399431 -0.4124015 -0.9061403 -0.1431089 -0.398197 -0.9060679 -0.1162584 -0.3234744 -0.9390679 -0.1537364 -0.3074265 -0.9390709 -0.03485459 -0.4985002 -0.8661887 -0.04990297 -0.4920253 -0.8691495 -0.04263329 -0.4202877 -0.9063889 -0.09300178 -0.4120786 -0.9063895 -0.07557421 -0.3348994 -0.9392184 -0.1153444 -0.3233714 -0.939216 0.04907536 -0.4974275 -0.8661165 0.0439707 -0.4978063 -0.8661729 0.006715297 -0.4954532 -0.8686087 0.01073658 -0.4974949 -0.8674005 0.009103834 -0.4220905 -0.906508 -0.04199683 -0.4199684 -0.9065665 -0.03414076 -0.341417 -0.9392917 -0.07524842 -0.3348358 -0.9392672 -0.0608533 -0.2707633 -0.9607206 -0.09315609 -0.2611368 -0.9607964 -0.1000154 -0.2471966 -0.9637899 -0.119377 -0.2386854 -0.9637316 -0.1090681 -0.2624364 -0.9587656 -0.1551162 -0.2357583 -0.9593524 -0.16319 -0.2109705 -0.9637741 -0.1729596 -0.2037673 -0.9636203 -0.1699778 -0.2201794 -0.9605356 -0.1698954 -0.2200527 -0.9605792 -0.01692998 -0.2619666 -0.9649285 -0.02717095 -0.2603209 -0.9651399 -0.03570061 -0.3419172 -0.9390517 0.007447004 -0.3437225 -0.9390417 0.009145736 -0.4221 -0.9065032 0.05928468 -0.4180148 -0.9065037 0.0693472 -0.4889969 -0.8695246 0.1283909 -0.4797301 -0.8679717 0.09795296 -0.4894711 -0.8665007 0.08778196 -0.4917419 -0.8663051 0.1669633 -0.4713276 -0.8660102 0.1284072 -0.4797493 -0.8679587 0.1093021 -0.4083381 -0.9062634 0.05848324 -0.4186578 -0.9062591 0.04755151 -0.3403551 -0.939094 0.00755167 -0.3435597 -0.9391006 0.005749583 -0.2611939 -0.9652692 -0.02560794 -0.2599674 -0.9652778 -0.01755499 -0.1782096 -0.9838359 -0.1609326 -0.1662638 -0.9728602 0.00941956 -0.1796236 -0.9836904 0.004085302 -0.1796555 -0.9837212 0.005939602 -0.2612461 -0.965254 0.03714811 -0.258638 -0.9652598 0.04876524 -0.33961 -0.9393014 0.08914089 -0.3312683 -0.9393165 0.1097558 -0.4079115 -0.9064005 0.1579706 -0.3918385 -0.9063708 0.1845935 -0.4578394 -0.86966 0.24197 -0.4323819 -0.8686176 0.2086078 -0.4545215 -0.8659636 0.207917 -0.4549022 -0.8659299 0.2737739 -0.4182077 -0.8661121 0.2395339 -0.4361417 -0.8674123 0.2034469 -0.3704336 -0.9063048 0.1576202 -0.3922567 -0.9062508 0.1280149 -0.3185339 -0.9392275 0.08860057 -0.3317552 -0.9391957 0.0675525 -0.252906 -0.9651296 0.03562992 -0.2594253 -0.9651058 0.02420341 -0.176253 -0.9840473 0.008489131 -0.1775817 -0.9840695 0.01120591 -0.1789082 -0.983802 0.02601963 -0.1755033 -0.984135 0.04683417 -0.171272 -0.98411 0.06890004 -0.2519939 -0.965273 0.09703683 -0.2426241 -0.9652552 0.1275905 -0.3189879 -0.9391312 0.1659846 -0.30085 -0.9391158 0.2039486 -0.3696609 -0.9065075 0.247722 -0.34196 -0.9064751 0.2895981 -0.3997879 -0.8696566 0.3390194 -0.3591337 -0.8695337 0.3128936 -0.3896781 -0.866169 0.3125912 -0.3898029 -0.8662219 0.3816931 -0.3230048 -0.8660129 0.3365574 -0.3669613 -0.8672189 0.2856095 -0.3114629 -0.9063212 0.2473874 -0.3426951 -0.9062889 0.2012236 -0.2787685 -0.9390407 0.1656755 -0.3012282 -0.9390492 0.1259271 -0.2290536 -0.9652341 0.09676074 -0.2427562 -0.9652497 0.06583064 -0.1652353 -0.9840547 0.04569447 -0.1719528 -0.9840449 0.399129 -0.3023675 -0.8656038 0.377198 -0.3202337 -0.8690065 0.3219726 -0.2733878 -0.9064176 0.2856861 -0.3113195 -0.9063463 0.2324035 -0.2532479 -0.9390709 0.2013707 -0.2785035 -0.9390876 0.1530531 -0.2116864 -0.9652791 0.1261561 -0.228641 -0.965302 0.08678537 -0.1573179 -0.9837273 0.08259183 -0.1575429 -0.9840523 0.4215176 -0.2659599 -0.8669419 0.4126386 -0.2721352 -0.8692939 0.3529155 -0.2327821 -0.9062357 0.3218426 -0.2741832 -0.9062235 0.2615509 -0.2229478 -0.9390876 0.2324163 -0.2531731 -0.939088 0.1957184 -0.2131988 -0.9572046 0.1321619 -0.2186925 -0.9668024 0.4621307 -0.1918978 -0.8658005 0.442188 -0.2201819 -0.8694767 0.3782514 -0.1883059 -0.9063481 0.3529783 -0.2323011 -0.9063347 0.2868737 -0.1887785 -0.9391839 0.2617863 -0.2221921 -0.9392011 0.4748724 -0.1542436 -0.8664324 0.4645395 -0.1666854 -0.8697237 0.3984078 -0.1430094 -0.905991 0.378277 -0.1900839 -0.9059662 0.3071347 -0.1543327 -0.9390686 0.2867873 -0.1893142 -0.9391024 0.4948266 -0.07395601 -0.865839 0.4945394 -0.07675915 -0.8657592 0.4945394 -0.07675909 -0.8657591 0.4945394 -0.07675904 -0.8657591 0.4803645 -0.116136 -0.869346 0.4865351 -0.1095232 -0.8667689 0.4118601 -0.09269905 -0.9065198 0.3980283 -0.1405081 -0.906549 0.3235196 -0.1142538 -0.9392982 0.3071387 -0.1526251 -0.9393463 0.4986421 -0.0347718 -0.8661103 0.4919347 -0.04981434 -0.8692058 0.420274 -0.04253613 -0.9063997 0.4120516 -0.09344106 -0.9063566 0.3347694 -0.07585221 -0.9392423 0.3235574 -0.1148067 -0.9392178 0.4974088 0.0490576 -0.8661282 0.4979333 0.04384452 -0.8661063 0.4954594 0.006793081 -0.8686045 0.4974757 0.01072758 -0.8674117 0.4220757 0.009156703 -0.9065144 0.4200394 -0.04203969 -0.9065317 0.3413721 -0.03409463 -0.9393097 0.3346748 -0.07527989 -0.939322 0.272228 -0.06127077 -0.9602801 0.2626689 -0.09316331 -0.9603779 0.2468028 -0.1008798 -0.9638007 0.2390192 -0.1187738 -0.9637234 0.2636089 -0.1078596 -0.9585806 0.2361765 -0.1559135 -0.9591203 0.2101984 -0.1642605 -0.9637609 0.2037636 -0.1729589 -0.9636212 0.2185894 -0.1702054 -0.9608584 0.2193855 -0.1695252 -0.9607973 0.2620031 -0.01702278 -0.964917 0.2603533 -0.0272569 -0.9651287 0.3419618 -0.03579038 -0.9390321 0.3436205 0.005926787 -0.93909 0.4231111 0.007364392 -0.9060479 0.4189037 0.0592845 -0.9060932 0.4890486 0.06922155 -0.8695055 0.4784292 0.1299854 -0.8684523 0.4918988 0.08810967 -0.8661825 0.4917154 0.0882014 -0.8662774 0.4713423 0.1669138 -0.8660117 0.4796285 0.1285791 -0.8680001 0.4081574 0.1094267 -0.9063296 0.4181956 0.06031084 -0.9063528 0.3395805 0.04897695 -0.939301 0.3428663 0.007536411 -0.9393541 0.261205 0.005724549 -0.9652664 0.2599878 -0.02562439 -0.965272 0.177977 -0.01755827 -0.9838781 0.164563 -0.1649937 -0.9724692 0.1795894 0.009391009 -0.9836968 0.1796963 0.004122793 -0.9837135 0.2611909 0.005962371 -0.9652689 0.2585984 0.03720796 -0.9652681 0.339558 0.04883068 -0.9393168 0.3313832 0.0891 -0.9392797 0.4079234 0.1096362 -0.9064096 0.3917999 0.1579594 -0.9063894 0.4578007 0.184586 -0.869682 0.4322019 0.2418782 -0.8687327 0.4558227 0.206153 -0.8658677 0.4545889 0.209015 -0.86583 0.4144746 0.279362 -0.8661223 0.4355947 0.2396494 -0.8676552 0.370399 0.2038508 -0.9062281 0.3924577 0.1573584 -0.9062094 0.3187472 0.1278916 -0.939172 0.3318772 0.08841979 -0.9391696 0.2529761 0.0674315 -0.9651197 0.2594554 0.03560632 -0.9650985 0.1762566 0.0241931 -0.9840469 0.17751 0.008456587 -0.9840826 0.1754835 0.02605432 -0.9841377 0.1715099 0.0455982 -0.9841267 0.2530989 0.06728309 -0.965098 0.2429469 0.09762209 -0.965115 0.3185549 0.1280369 -0.9392174 0.3004169 0.1662146 -0.9392138 0.3694846 0.2044154 -0.9064742 0.3429996 0.2463588 -0.9064539 0.4014137 0.2882498 -0.8693556 0.3589639 0.3399949 -0.8692229 0.3912352 0.3122782 -0.865689 0.3908302 0.3128803 -0.8656545 0.3292436 0.3751959 -0.8665026 0.3292436 0.375196 -0.8665025 0.3292436 0.3751962 -0.8665024 0.3654233 0.3378384 -0.8673703 0.3099558 0.286616 -0.9065201 0.3425626 0.2464798 -0.9065862 0.278945 0.2007347 -0.9390928 0.3011527 0.1657015 -0.9390687 0.2290974 0.1260983 -0.9652014 0.2421699 0.09849458 -0.9652215 0.1643654 0.06688165 -0.9841295 0.1714307 0.04568535 -0.9841364 0.3017497 0.3992432 -0.8657667 0.3201044 0.3765997 -0.8693135 0.2738302 0.3221182 -0.9062323 0.3113967 0.2861045 -0.9061879 0.2528265 0.2322969 -0.9392108 0.2782191 0.2012119 -0.9392061 0.2118514 0.1531941 -0.9652205 0.228869 0.126257 -0.9652349 0.1571361 0.08666586 -0.9837669 0.1573969 0.0828765 -0.9840517 0.2666101 0.4210882 -0.8669509 0.2725923 0.4125983 -0.8691699 0.2331376 0.352823 -0.9061804 0.2741418 0.3221346 -0.9061322 0.2225764 0.261554 -0.9391748 0.2531201 0.2320646 -0.9391893 0.2138356 0.1960833 -0.9569878 0.2192049 0.1317108 -0.9667479 -0.5014845 -0.8651656 -0.001394033 -0.4992854 -0.8664374 -6.23995e-4 -0.5003508 -0.8658228 2.98263e-4 -0.5003475 -0.8658248 -1.70192e-4 -0.5007303 -0.8656021 0.001472711 -0.5021559 -0.8647521 0.006581008 -0.4996201 -0.8662442 -8.9885e-4 -0.4992144 -0.8664771 -0.001564145 -0.06829434 0.9976653 0 0.06829434 0.9976653 0 -0.06829434 0.9976653 0 -0.2698075 0.9629144 0 -0.2698097 0.9629137 0 -0.5195422 0.8544449 0 -0.5195384 0.8544473 0 -0.7308545 0.6825334 0 -0.7308544 0.6825335 0 -0.8878435 0.4601458 0 -0.8878435 0.4601458 0 -0.9790888 0.2034336 0 -0.9790905 0.2034254 0 -0.9976645 -0.0683062 0 -0.9976645 -0.0683062 0 -0.9422729 -0.3348461 0 -0.8169763 -0.5766715 0 -0.8169761 -0.5766715 0 -0.6310515 -0.7757409 0 -0.6310515 -0.775741 0 -0.3984529 -0.9171888 0 -0.1361545 -0.9906876 0 -0.1361557 -0.9906876 0 0.1361545 -0.9906876 0 0.1361568 -0.9906873 0 0.3984498 -0.9171901 0 0.3984529 -0.9171888 0 0.6310515 -0.7757409 0 0.6310536 -0.7757393 0 0.8169742 -0.5766744 0 0.8169761 -0.5766715 0 0.9422702 -0.3348537 0 0.9422742 -0.3348423 0 0.9976648 -0.06830191 0 0.9976648 -0.06830197 0 0.9790896 0.2034295 0 0.9790905 0.2034254 0 0.8878435 0.4601458 0 0.8878417 0.4601492 0 0.7308545 0.6825334 0 0.7308544 0.6825335 0 0.5195422 0.8544449 0 0.5195403 0.8544461 0 0.2698075 0.9629144 0 0.2698097 0.9629137 0 0.06829434 0.9976653 0 -0.06828892 0.9976657 0 0.06828892 0.9976657 0 -0.2698097 0.9629137 0 -0.2698075 0.9629144 0 -0.5195403 0.8544461 0 -0.5195421 0.8544449 0 -0.8878417 0.4601491 0 -0.9790905 0.2034254 0 -0.9790896 0.2034295 0 -0.9976648 -0.06830173 0 -0.9976648 -0.06830173 0 -0.9422739 -0.3348432 0 -0.9422699 -0.3348546 0 -0.8169771 -0.5766702 0 -0.8169751 -0.576673 0 -0.6310536 -0.7757392 0 -0.3984498 -0.9171901 0 -0.1361569 -0.9906873 0 -0.1361545 -0.9906876 0 0.1361557 -0.9906876 0 0.1361545 -0.9906876 0 0.6310515 -0.775741 0 0.8169771 -0.5766702 0 0.8169772 -0.5766702 0 0.9422726 -0.334847 0 0.9422726 -0.3348469 0 0.9976644 -0.06830602 0 0.9976645 -0.06830602 0 0.9790905 0.2034254 0 0.9790889 0.2034336 0 0.8878435 0.4601458 0 0.5195384 0.8544471 0 0.5195421 0.8544449 0 0.2698097 0.9629137 0 0.2698075 0.9629144 0 -0.9976648 -0.06830191 0 -0.9976648 -0.06830197 0 -0.9422742 -0.3348423 0 -0.9422702 -0.3348537 0 -0.8169742 -0.5766744 0 0.8169763 -0.5766715 0 0.9422729 -0.3348461 0 0.9976645 -0.0683062 0 0.9976645 -0.0683062 0 2.52846e-7 0 -1 1.34262e-6 0 -1 3.35207e-7 0 -1 -2.22077e-7 0 -1 -3.3904e-7 0 -1 -6.77046e-7 0 -1 6.85382e-7 0 -1 -6.70098e-7 0 -1 2.25448e-7 0 -1 -3.35738e-7 0 -1 -1.6855e-7 0 -1 -1.34261e-6 0 -1 3.3904e-7 0 -1 -7.23627e-7 0 -1 3.35738e-7 0 -1 -2.25448e-7 0 -1 -1.26115e-7 0 -1 -2.23271e-7 0 -1 6.77046e-7 0 -1 -2.21336e-7 0 -1 -0.9976644 -0.06830602 0 -0.9976645 -0.06830602 0 -0.9422726 -0.334847 0 -0.9422726 -0.3348469 0 -0.8169772 -0.5766702 0 0.8169752 -0.576673 0 0.9422699 -0.3348546 0 0.9422739 -0.3348431 0 0.9976648 -0.06830173 0 0.9976648 -0.06830173 0 -0.05086886 0.9987054 0 0.05086886 0.9987054 0 -0.05086886 0.9987054 0 -0.201146 0.9795613 0 -0.3943669 0.9189531 0 -0.3943631 0.9189547 0 -0.5712323 0.8207884 0 -0.5712371 0.8207852 0 -0.7247976 0.6889619 0 -0.7247926 0.6889672 0 -0.8486946 0.5288833 0 -0.8486992 0.528876 0 -0.9377112 0.3474161 0 -0.9377112 0.3474161 0 -0.9884967 0.1512432 0 -0.9987162 -0.05065602 0 -0.9987167 -0.05064576 0 -0.9680868 -0.2506152 0 -0.9680868 -0.2506153 0 -0.8978154 -0.4403721 0 -0.8978154 -0.4403721 0 -0.7907661 -0.6121186 0 -0.790771 -0.6121122 0 -0.6513231 -0.7588006 0 -0.651318 -0.7588049 0 -0.4853455 -0.8743225 0 -0.4853455 -0.8743224 0 -0.2995126 -0.9540923 0 -0.2995126 -0.9540924 0 -0.1010609 -0.9948803 0 -0.1010599 -0.9948804 0 0.1010599 -0.9948804 0 0.2995126 -0.9540923 0 0.2995126 -0.9540924 0 0.4853455 -0.8743225 0 0.4853412 -0.8743249 0 0.6513231 -0.7588006 0 0.790771 -0.6121122 0 0.790771 -0.6121122 0 0.8978114 -0.4403803 0 0.8978154 -0.4403721 0 0.9680881 -0.2506104 0 0.9680868 -0.2506153 0 0.998717 -0.05064064 0 0.9987162 -0.05065602 0 0.9884598 0.1514841 0 0.9884606 0.1514791 0 0.9377931 0.3471947 0 0.9377914 0.3471993 0 0.8485839 0.529061 0 0.8485838 0.529061 0 0.7247976 0.6889619 0 0.7247926 0.6889672 0 0.5713528 0.8207046 0 0.5713527 0.8207047 0 0.3943632 0.9189547 0 0.3943669 0.9189532 0 0.2011439 0.9795618 0 0.201146 0.9795613 0 0.05086886 0.9987054 0 4.25684e-7 0 -1 1.41188e-7 0 -1 4.9517e-7 0 -1 8.45379e-7 0 -1 -5.65723e-7 0 -1 -5.67506e-7 0 -1 1.58896e-6 0 -1 -5.64309e-7 0 -1 8.09334e-7 0 -1 1.11627e-6 0 -1 -4.25684e-7 0 -1 5.66559e-7 0 -1 -1.12307e-6 0 -1 5.66863e-7 0 -1 7.9166e-7 0 -1 -3.96433e-7 0 -1 -2.01249e-7 0 -1 1.13422e-6 0 -1 -1.59341e-6 0 -1 3.16108e-7 0 -1 5.65723e-7 0 -1 -8.39888e-7 0 -1 -5.93685e-7 0 -1 5.6084e-7 0 -1 -1.13422e-6 0 -1 5.67514e-7 0 -1 -5.66827e-7 0 -1 1.59651e-6 0 -1 -5.66554e-7 0 -1 -0.05086779 0.9987055 0 -0.05086988 0.9987054 0 -0.2011439 0.9795618 0 -0.2011479 0.9795609 0 -0.3943632 0.9189547 0 -0.5712372 0.8207851 0 -0.7247925 0.6889672 0 -0.7247977 0.6889618 0 -0.8486946 0.5288834 0 -0.9377129 0.3474115 0 -0.9884974 0.1512382 0 -0.9884959 0.1512482 0 -0.9987164 -0.05065089 0 -0.9680881 -0.2506104 0 -0.8978134 -0.4403762 0 -0.790776 -0.6121057 0 -0.2995097 -0.9540933 0 0.1010609 -0.9948803 0 0.4853411 -0.874325 0 0.4853455 -0.8743224 0 0.6513282 -0.7587962 0 0.651318 -0.7588049 0 0.8978073 -0.4403886 0 0.9680893 -0.2506057 0 0.9680894 -0.2506057 0 0.9987162 -0.05065602 0 0.9377949 0.3471902 0 0.7247925 0.6889672 0 0.7247977 0.6889618 0 0.3943631 0.9189547 0 0.05086988 0.9987054 0 4.25691e-7 0 -1 1.41189e-7 0 -1 1.58904e-6 0 -1 5.66554e-7 0 -1 -2.0126e-7 0 -1 -5.66832e-7 0 -1 -5.66559e-7 0 -1 -0.2189296 0.06378948 0.9736534 -0.2188671 0.06377726 0.9736682 -0.6110416 0.1780562 0.7713134 -0.6111763 0.1780776 0.7712016 -0.8763335 0.2553348 0.4084651 -0.8763303 0.255334 0.4084726 -0.9593369 0.2795213 -0.03925156 -0.9593366 0.2795214 -0.03925937 -0.902821 0.3060221 -0.3021004 -0.5298122 0.6039028 -0.5954835 -0.7281227 0.4863727 -0.4829896 -0.8337199 0.3919966 -0.3889085 -0.7347316 0.4887156 -0.4704537 -0.8397459 0.3876509 -0.3802021 -0.5591438 0.5886733 -0.5837997 -0.1990976 0.6953358 -0.6905566 -0.19935 0.6953069 -0.6905128 0.1908754 0.6960885 -0.6921181 0.1910231 0.6960655 -0.6921005 -0.1749208 0.20567 0.9628617 -0.8470924 0.3420116 0.4067709 -0.9470926 0.3185586 -0.03919363 -0.5701885 0.2995643 0.7649487 -0.1593685 0.130602 0.9785423 -0.03004431 0.4801049 0.8766964 0.01452529 0.488267 0.8725735 0.01442342 0.4881924 0.872617 0.1991764 0.8081709 0.5542461 0.194332 0.8254356 0.5299918 0.1629762 0.8204426 0.5480079 0.3305162 0.9395601 0.08936351 0.3175953 0.9480582 0.01786369 0.1811681 0.8858926 -0.427051 0.3170362 0.8027296 -0.5050874 0.3319919 0.8402391 -0.4286953 0.2248951 0.9711434 0.07938981 -0.5645629 0.2475977 0.787378 -0.4283127 0.5838769 0.6896637 -0.4137716 0.564719 0.7140628 -0.2316484 0.8867177 0.4000886 -0.2489943 0.8937615 0.3730847 -0.1030117 0.9939343 -0.03851234 -0.1658269 0.9807954 -0.1026734 -0.08815127 0.8654691 -0.4931456 -0.1949898 0.8189452 -0.5397294 -0.8514612 0.3069896 0.4251719 -0.7532269 0.5479993 0.3637938 -0.7500364 0.538141 0.3845122 -0.6200078 0.7685403 0.1579119 -0.6260109 0.7678033 0.1363398 -0.5244392 0.8375781 -0.1530568 -0.5524253 0.8094029 -0.1992319 -0.500823 0.731907 -0.4620484 -0.5544307 0.6734814 -0.4889065 -0.9521023 0.303963 -0.03328305 -0.9188701 0.3909476 -0.05327081 -0.9208155 0.3872269 -0.04641181 -0.8750965 0.4672714 -0.1259515 -0.8739211 0.4671303 -0.1343557 -0.8398934 0.4904904 -0.2323755 -0.8410943 0.4791082 -0.2510297 -0.824624 0.4535793 -0.3380255 -0.8325086 0.428592 -0.3510529 -0.7771279 0.6293429 0 -0.7771241 0.6293475 0 -0.5446304 0.8386762 0 -0.5446302 0.8386763 0 -0.2587705 0.9659389 0 -0.2587704 0.9659389 0 0.05228555 0.9986322 0 0.05228579 0.9986322 0 0.3583686 0.9335802 0 0.3583685 0.9335803 0 -0.8660193 0.5000107 0 -0.8660194 0.5000107 0 -0.7973957 -0.1267454 -0.5899964 -0.6869524 -0.2667753 -0.6759641 -0.6699287 -0.2922728 -0.682475 -0.4423397 -0.4911991 -0.7503726 -0.2370933 -0.5908263 -0.7711751 -0.3471386 -0.5531045 -0.7573442 -0.04242527 -0.6922647 -0.7203955 0.07076907 -0.7140759 -0.6964822 0.1619079 -0.7408962 -0.6518118 0.2607244 -0.7524131 -0.6048946 0.2607244 -0.752413 -0.6048946 0.2607244 -0.752413 -0.6048946 0.4654169 -0.7446545 -0.4784108 0.4654826 -0.744657 -0.478343 0.7698808 -0.6147999 -0.1711857 0.7699489 -0.6147547 -0.1710425 0.8660224 -0.5000053 -3.82971e-6 0.8660154 -0.5000176 1.72341e-5 -0.8660231 0.5000042 -1.91484e-6 -0.8660144 0.500019 -1.14895e-5 -0.3784341 -0.6560596 0.6529728 -0.3789061 -0.6560749 0.6526837 -0.3788853 -0.6560879 0.6526827 -0.3787724 -0.6560802 0.652756 -0.3788265 -0.6561661 0.6526382 -0.3788167 -0.656047 0.6527636 -0.3786932 -0.6560994 0.6527826 -0.3787787 -0.6560676 0.6527649 -0.3787943 -0.6560609 0.6527627 -0.3789038 -0.6560739 0.652686 -0.3787013 -0.656296 0.6525802 -0.3786765 -0.6563585 0.6525316 -0.3806474 -0.656841 0.6508975 -0.3788183 -0.6560706 0.6527389 -0.3788262 -0.6560603 0.6527447 -0.3787544 -0.6561883 0.6526577 -0.3787914 -0.6560949 0.6527301 -0.378747 -0.6560331 0.652818 -0.3787993 -0.6560934 0.6527272 -0.3787912 -0.6560817 0.6527435 -0.3788512 -0.6561641 0.6526259 -0.3787791 -0.6560378 0.6527947 -0.3788033 -0.6561048 0.6527133 -0.3787822 -0.6560676 0.652763 -0.3788405 -0.655937 0.6528604 -0.3787818 -0.6560927 0.6527379 -0.3787575 -0.6561104 0.6527343 -0.3787708 -0.6561001 0.6527369 -0.3787831 -0.6560618 0.6527682 -0.3787947 -0.656082 0.6527412 -0.378811 -0.6561168 0.6526968 -0.378782 -0.6560668 0.6527638 0.4998815 0.8660939 1.37459e-4 0.5000088 0.8660205 -2.0055e-5 0.4999875 0.8660327 -4.7863e-5 0.5000129 0.8660181 1.29213e-4 0.4999035 0.8660811 1.54832e-4 0.5000075 0.8660212 0 0.5000002 0.8660253 -1.7621e-6 0.5000443 0.8659999 5.15496e-5 0.5000122 0.8660184 3.30779e-5 0.5000892 0.865974 -3.22568e-5 0.4999743 0.8660404 1.65584e-5 0.5000791 0.8659799 -3.52868e-5 0.4999762 0.8660392 -8.27922e-6 0.4999865 0.8660333 2.01619e-6 0.4999898 0.8660314 0 0.4994633 0.8663347 9.01691e-4 0.4998978 0.8660845 6.97457e-5 0.5000035 0.8660234 8.16947e-6 0.4999936 0.8660291 9.42193e-5 0.5001085 0.8659629 6.19236e-5 0.5001152 0.8659589 0 0.4999537 0.8660522 1.27398e-5 0.499967 0.8660445 8.13104e-6 -0.8555844 -0.02070629 -0.5172491 0.2494239 -0.7515445 -0.6107115 0.4098578 -0.751298 -0.5172697 0.4098523 -0.7513014 -0.5172693 0.3110719 -0.7545016 -0.5778943 0.3553482 -0.7509353 -0.5566185 0.4915151 -0.8089502 -0.3225098 0.7842015 0.1565873 0.6004238 0.8067039 0.1116316 0.5803165 0.6803252 0.2807824 0.6769926 0.6803597 0.2807525 0.6769703 0.5172983 0.4347605 0.7371472 0.5172988 0.4347626 0.7371456 0.3263556 0.5653228 0.7575634 0.3263915 0.5653039 0.7575619 0.1178823 0.6653739 0.7371441 0.1178373 0.6653844 0.7371419 -0.09701704 0.7295761 0.6769834 -0.09696745 0.7295701 0.676997 -0.3608869 0.7541755 0.5486166 -0.9136622 0.1650054 -0.3714764 -0.9146395 0.1695245 -0.3670099 -0.9146395 0.1695244 -0.3670098 -0.9146395 0.1695244 -0.3670099 -0.918574 0.1862329 -0.3486246 -0.9174299 0.1523836 -0.3675619 -0.9164324 0.1409823 -0.3745338 -0.9166617 0.1442409 -0.3727278 -0.9012567 0.101156 -0.4213123 -0.8555923 -0.02064907 -0.5172384 -0.9465711 0.02139967 -0.3217844 -0.7954178 -0.08564823 -0.5999793 -0.8316586 -0.06810426 -0.5510951 -0.7755978 -0.159767 -0.610674 -0.8539003 -0.02424609 -0.5198717 -0.829591 -0.05256366 -0.5558922 -0.8864887 0.04585498 -0.4604728 -0.9151013 0.1470077 -0.3754708 -0.8807181 0.07839107 -0.4671087 -0.9089719 0.148561 -0.3894867 -0.6028968 -0.3602079 -0.7118749 -0.5571012 -0.382331 -0.7371982 -0.6427491 -0.320999 -0.6955813 -0.7485888 -0.1975466 -0.6329219 -0.7134478 -0.2234387 -0.6641291 -0.7789363 -0.1548891 -0.607674 -0.219504 -0.6123816 -0.759478 -0.2755093 -0.5934146 -0.7562763 -0.4247325 -0.5034397 -0.7524299 -0.3687787 -0.5205287 -0.7700989 -0.471874 -0.4698458 -0.7460428 -0.006672322 -0.695558 -0.718439 -0.06428116 -0.6849606 -0.725739 -0.1710507 -0.6435333 -0.7460608 0.2065819 -0.7411835 -0.6387261 0.1502943 -0.7395637 -0.6560924 0.0433613 -0.7171313 -0.6955879 0.4088014 -0.7466036 -0.5248472 0.3568816 -0.7543096 -0.551047 0.2553776 -0.7520269 -0.6076496 0.6060522 -0.7112874 -0.3560492 0.5868276 -0.7156652 -0.3787568 0.5444484 -0.7382632 -0.3981751 0.5888622 -0.7191421 -0.3688849 0.6194357 -0.7028737 -0.3496684 0.6019433 -0.7081397 -0.3690564 0.5868971 -0.7120324 -0.385437 0.5752272 -0.7144811 -0.3982844 0.5891356 -0.7116316 -0.382753 0.5324736 -0.7313781 -0.4260963 0.4536612 -0.7463939 -0.4869166 0.6337147 -0.6978914 -0.3336966 0.7360181 -0.6411392 -0.2172968 0.7360183 -0.6411395 -0.2172956 0.8456105 -0.5319846 -0.04399192 0.8455982 -0.5320022 -0.04401737 0.909542 -0.3942506 0.1315292 0.9095447 -0.3942371 0.1315516 0.9244725 -0.2352336 0.3000267 0.9244719 -0.2352348 0.3000276 0.8895511 -0.06345939 0.4524069 0.8895508 -0.06345558 0.4524079 0.8336502 0.06445175 0.5485192 0.8336284 0.06447184 0.5485501 -0.2595748 0.7523183 0.6055065 -0.3050227 0.757222 0.5775605 -0.3609264 0.7541883 0.548573 -0.4997629 0.7386379 0.4523838 -0.4997999 0.7386282 0.4523587 -0.6659339 0.6830084 0.300053 -0.6659005 0.6830266 0.3000856 -0.7961844 0.590577 0.1315645 -0.7961834 0.5905787 0.1315634 -0.8835487 0.4662602 -0.04408013 -0.8835482 0.4662619 -0.0440756 -0.9232465 0.3168864 -0.2172533 -0.923249 0.3168841 -0.2172461 -0.92124 0.1998109 -0.3337552 -0.9190438 0.1694592 -0.3558683 -0.3787626 -0.6560688 0.652773 -0.378782 -0.6560689 0.6527618 -0.3787912 -0.6560693 0.652756 -0.3787815 -0.656071 0.65276 -0.378787 -0.6560499 0.6527779 -0.3787818 -0.6560794 0.6527513 -0.3787687 -0.6560813 0.652757 -0.3787739 -0.6560742 0.6527611 -0.3787624 -0.6560871 0.6527548 -0.378776 -0.656084 0.6527501 -0.3787779 -0.6560863 0.6527465 -0.3787701 -0.6560816 0.6527559 -0.378758 -0.656097 0.6527475 -0.3787738 -0.6560564 0.6527791 -0.3788021 -0.6560152 0.652804 -0.3788053 -0.6560212 0.652796 -0.3788424 -0.6560733 0.6527222 -0.3788408 -0.6560589 0.6527377 -0.3788186 -0.6560878 0.6527215 -0.3787698 -0.6560413 0.6527966 -0.3787761 -0.6560822 0.6527518 -0.3787633 -0.6560572 0.6527844 -0.3787648 -0.6560522 0.6527885 -0.3787858 -0.6560757 0.6527528 -0.3787794 -0.6560346 0.6527978 -0.3787773 -0.6560639 0.6527694 -0.3787521 -0.6560949 0.6527529 -0.3788115 -0.6560692 0.6527443 -0.3788096 -0.6560736 0.6527408 -0.3786621 -0.6561989 0.6527006 -0.3786267 -0.6561892 0.6527309 -0.378839 -0.6560475 0.6527502 -0.3787506 -0.6560776 0.6527711 -0.3787803 -0.6560977 0.6527338 -0.3788121 -0.656031 0.6527823 -0.3787304 -0.6560437 0.6528169 -0.3787334 -0.6560494 0.6528096 -0.3787899 -0.6560077 0.6528187 -0.3787618 -0.6561654 0.6526765 -0.378826 -0.6561014 0.6527037 -0.3787367 -0.6560842 0.6527725 -0.3788067 -0.6560581 0.6527583 -0.3787983 -0.656068 0.6527532 -0.3787333 -0.6560829 0.6527758 -0.3788334 -0.656059 0.6527419 -0.3788439 -0.6560825 0.6527122 -0.378807 -0.6560426 0.6527736 -0.3787921 -0.6560686 0.6527562 -0.3787814 -0.6560515 0.6527796 -0.378776 -0.656063 0.6527711 -0.3788707 -0.6560984 0.6526806 -0.3788559 -0.6560682 0.6527196 0.4971598 -0.8676497 0.00404644 -0.2896508 -0.733483 0.6149026 -0.3742458 -0.6605147 0.6508921 -0.09835273 -0.8495782 0.5182122 -0.09823495 -0.8496624 0.5180964 -0.2864513 -0.7418128 0.6063493 0.03383868 -0.9032566 0.4277645 -0.08343052 -0.8613279 0.5011523 0.03068947 -0.9048088 0.4247109 0.1634549 -0.9313765 0.3253006 0.4028296 -0.9091165 0.1059982 0.309754 -0.9304081 0.1959422 0.4081237 -0.9067987 0.1055988 0.1191015 -0.9269055 0.3558947 0.2930715 -0.9300218 0.22174 0.1622804 -0.9312818 0.3261583 0.6031321 -0.7859845 -0.1358679 0.4114985 -0.9048234 0.1093796 0.5148211 -0.8572339 -0.01045906 0.5148211 -0.8572339 -0.01045835 0.514821 -0.857234 -0.01045769 0.6827223 -0.6889723 -0.243326 0.6702398 -0.7079752 -0.2225983 0.6057503 -0.7849287 -0.1302054 0.5158138 -0.8566232 -0.01152431 0.8660238 -0.5000016 0.001108527 0.8660229 -0.5000045 1.4525e-5 0.8660178 -0.5000133 5.22091e-5 0.8660305 -0.4999911 -7.60664e-7 0.8660243 -0.5000019 -2.04416e-5 0.8660353 -0.499983 -2.21959e-5 0.8659055 -0.5002076 0 0.9910296 -0.1336423 0 0.9986132 -0.05228865 0.006145179 0.9586877 -0.2844609 0 0.9335771 -0.3583217 0.006290435 0.9025182 -0.4306519 0 0.999735 0.02302134 0 0.9659371 0.2587774 0 0.9659371 0.2587774 0 0.8386768 0.5446294 0 0.8386785 0.5446268 0 0.6292679 0.7771885 0 0.6292681 0.7771883 0 7.92488e-7 0 -1 2.51014e-6 0 -1 -3.03039e-7 0 -1 2.50932e-5 0 -1 1.13874e-6 0 -1 -2.87648e-6 0 -1 1.31793e-6 0 -1 -1.04102e-6 0 -1 -3.26768e-7 0 -1 0 0 -1 7.22635e-7 0 -1 -8.80917e-7 0 -1 0.2914924 0.4893648 -0.8219211 0.06276243 0.120964 -0.9906708 0.1124484 0.1921717 -0.9748977 0.008019208 0.01389211 -0.9998714 0.3241283 0.5842766 -0.7440173 0.4286843 0.7159414 -0.5510514 0.207368 0.3811899 -0.9009401 0.2861396 0.499026 -0.8179836 0.2129393 0.3721376 -0.9034217 0.1360844 0.2522199 -0.9580534 0.4998266 0.8657433 -0.02573096 0.4998266 0.8657433 -0.02573072 0.4998266 0.8657433 -0.02573114 0.4987008 0.8638874 -0.07068467 0.4849231 0.8475912 -0.2154965 0.4891846 0.8516107 -0.1883021 0.4496022 0.7754859 -0.4432601 0.4186297 0.7282286 -0.5426162 0.4475605 0.7782778 -0.440424 0.3934831 0.6910668 -0.6062986 0.547358 0.5182476 -0.6571291 0.3918511 0.2786526 -0.8768155 0.0977714 -0.1216971 -0.9877401 0.1431317 -0.08446806 -0.9860925 0.3265557 -0.3298923 -0.8857384 0.3265557 -0.3298922 -0.8857384 0.3563293 -0.3058373 -0.882889 0.5195924 -0.5047802 -0.6893627 0.5341377 -0.4927148 -0.686971 0.6539525 -0.6294971 -0.4196183 0.6539525 -0.6294972 -0.4196183 0.6583972 -0.6254987 -0.4186461 0.1670807 0.09306842 -0.9815408 0.2667177 0.05578327 -0.962159 0.3913199 -0.1634634 -0.9056206 0.4552353 -0.1903081 -0.8697953 0.5687915 -0.4048067 -0.7159664 0.5993893 -0.4181817 -0.682537 0.6739156 -0.5985802 -0.4330585 0.6809695 -0.6010729 -0.4183204 0.3430438 0.389273 -0.8548612 0.4389078 0.3596104 -0.823432 0.5581368 0.07769906 -0.826103 0.6236143 0.02840161 -0.7812162 0.6927198 -0.2511473 -0.6760653 0.7195382 -0.2807055 -0.6351923 0.7218647 -0.5478426 -0.4228238 0.7258569 -0.5558295 -0.4051979 0.4937815 0.6183329 -0.611428 0.5676586 0.6109291 -0.5518419 0.7165285 0.2751709 -0.6409898 0.7754058 0.2110617 -0.5951461 0.8176373 -0.1221107 -0.562635 0.835849 -0.163798 -0.5239531 0.7720431 -0.5045818 -0.3864542 0.7717235 -0.5174902 -0.3696578 0.6010619 0.7484453 -0.2802754 0.695772 0.6787703 -0.2348878 0.8440433 0.3948647 -0.3628675 0.8892024 0.3261991 -0.3208013 0.9246493 -0.04237651 -0.3784546 0.9330475 -0.08866602 -0.3486556 0.8167186 -0.4783204 -0.32277 0.8126057 -0.4929327 -0.3109488 0.7017702 0.1750864 -0.690553 0.5073876 0.5133063 -0.6921521 0.5072833 0.5135266 -0.6920652 0.7906187 -0.1891366 -0.5823654 0.7860546 -0.1545634 -0.5985218 0.7017507 0.1752017 -0.6905435 0.7162939 -0.6291124 -0.3018953 0.7493925 -0.5516175 -0.3662362 0.7587057 -0.5246958 -0.3860829 0.7776687 -0.440176 -0.4488615 0.7908677 -0.3313808 -0.5145047 0.6962921 -0.666655 -0.2659861 0.6962179 -0.6666796 -0.2661182 0.6962311 -0.6666676 -0.2661137 0.6962458 -0.6666952 -0.2660061 0.6970266 -0.6659771 -0.2657602 0.6962931 -0.6666495 -0.2659973 0.696324 -0.6665925 -0.2660589 0.6962791 -0.6666621 -0.2660021 0.6962317 -0.6667081 -0.2660107 0.6962759 -0.666671 -0.2659882 0.6964491 -0.6664801 -0.2660132 0.6962435 -0.6666964 -0.2660095 0.6964052 -0.6666678 -0.2656574 0.6962778 -0.6666567 -0.2660188 0.6962727 -0.6666427 -0.2660676 0.697067 -0.6659908 -0.2656197 0.696117 -0.6667282 -0.2662607 0.6962856 -0.6666172 -0.2660976 0.6963524 -0.6665643 -0.2660554 0.6033961 0.5661368 -0.5616068 0.8449092 -0.1545907 -0.5120843 0.7842151 -0.5088828 -0.355028 0.7794888 0.2224195 -0.5855997 0.4972177 0.5890809 -0.6369916 0.6882897 0.6585881 -0.3041694 0.6150159 0.7589756 -0.2138028 0.6151573 0.7587435 -0.2142195 0.7033019 0.6493923 0.2892339 0.6870222 0.6860396 0.2394793 0.6434224 0.7050006 0.2982982 0.5506513 0.4440299 0.7068384 0.5513784 0.4476673 0.7039716 0.3571977 0.057424 0.932262 0.2786146 0.05826431 0.9586341 0.3016905 0.09755015 0.9484022 0.5461522 0.4480483 0.7077928 0.7137993 0.2454878 -0.6559165 0.8971225 0.318755 -0.3058867 0.8323063 0.4113896 -0.3715171 0.9383947 0.3143721 0.1434768 0.9169824 0.3806349 0.1194171 0.8305563 0.1181834 0.5442509 0.8297725 0.1241105 0.5441269 0.5971513 -0.2129295 0.7733507 0.6024181 -0.2680524 0.7518248 0.809059 -0.1436376 -0.569905 0.9395293 -0.08592897 -0.3315134 0.9209132 -0.02507919 -0.3889602 0.9952003 -0.09487599 -0.02397924 0.9978215 -0.04970824 -0.04337334 0.9351398 -0.2396473 0.260927 0.9359742 -0.2362943 0.2609931 0.7698434 -0.4775722 0.4233982 0.7593027 -0.5105782 0.4034469 0.7729378 -0.5096721 -0.3778911 0.8220791 -0.4880383 -0.2932655 0.8209452 -0.4744112 -0.3177787 0.8462413 -0.4988798 -0.1870686 0.8509522 -0.4866851 -0.19753 0.8278755 -0.5536271 -0.09010654 0.8288211 -0.5521481 -0.09048837 0.7709224 -0.6359946 -0.03448855 0.7620043 -0.6463968 -0.03899741 0.05380767 0.09319704 0.9941927 0.1263452 0.2151935 0.968364 0.2224842 0.3876923 0.8945365 0.2224626 0.3876522 0.8945593 0.1212927 0.2185146 0.9682663 0.4128603 0.7067656 0.5744814 0.3403699 0.590936 0.731398 0.3401569 0.5905701 0.7317925 0.4078047 0.7098496 0.5742899 0.4762623 0.8212358 0.3142391 0.4971389 0.8615831 0.1026031 0.4743309 0.8219293 0.3153451 0.4956775 0.8624598 0.1023077 0.4912381 0.8466665 -0.2045505 0.4540446 0.7849321 -0.4215746 0.4540446 0.7849321 -0.4215746 0.4143901 0.7177124 -0.5596158 0.4075127 0.7028916 -0.5829896 0.4861934 0.849814 -0.2035492 0.4583554 0.7737872 -0.4372228 0.396516 0.6867731 -0.6091945 0.4017636 0.6966153 -0.5944015 0.4225516 0.7316721 -0.5348891 0.4225515 0.7316721 -0.5348891 0.4021672 0.6965584 -0.5941954 0.4479951 0.7882651 -0.4218276 0.4357068 0.7725135 -0.4619334 0.4812574 0.8319367 -0.276175 0.4435119 0.7573218 -0.4793338 0.4892773 0.8532269 -0.1805875 0.4346593 0.7531445 -0.4938064 0.3787363 0.6559776 -0.6528801 0.3787732 0.6560372 -0.6527987 0.3781798 0.654996 -0.6541868 0.3787954 0.6560953 -0.6527274 0.3787859 0.6560707 -0.6527576 0.3787705 0.6560943 -0.652743 0.3787725 0.6560981 -0.6527379 0.3787752 0.656069 -0.6527655 0.3787947 0.6560495 -0.6527738 0.3788711 0.6560572 -0.6527217 0.3787975 0.6560633 -0.6527584 0.3787943 0.6560676 -0.652756 0.3788126 0.6561273 -0.6526852 0.3787663 0.6560441 -0.6527957 0.3788238 0.6560679 -0.6527385 0.3786645 0.656109 -0.6527896 0.3787726 0.6560626 -0.6527735 0.3787986 0.6560797 -0.6527413 0.3787701 0.6560581 -0.6527795 0.3787919 0.6560611 -0.6527637 0.3787935 0.6560997 -0.6527241 0.378786 0.656093 -0.6527352 0.3787907 0.6560858 -0.6527397 0.3787485 0.6560569 -0.6527932 0.3787507 0.6560545 -0.6527944 0.3787754 0.6560776 -0.6527568 0.3787681 0.6560778 -0.6527609 0.3787767 0.6560434 -0.6527904 0.3787952 0.6560767 -0.6527462 0.3787589 0.6560451 -0.652799 0.3787832 0.6560688 -0.6527612 0.3786884 0.6561354 -0.6527491 0.3787162 0.6561329 -0.6527355 0.3788573 0.6560097 -0.6527774 0.3787695 0.6560686 -0.6527692 0.3787801 0.6560342 -0.6527977 0.3787187 0.6561049 -0.6527622 0.3794406 0.6575869 -0.6508489 0.3787896 0.6561041 -0.652722 0.3787939 0.6561115 -0.652712 0.3787537 0.6560181 -0.6528292 0.3787847 0.6560716 -0.6527575 0.3787849 0.6560728 -0.6527562 0.378769 0.656046 -0.6527922 0.3787816 0.6560648 -0.6527661 0.3787891 0.6560748 -0.6527518 0.3787848 0.6560707 -0.6527584 0.3787816 0.6560666 -0.6527643 0.3788046 0.6560612 -0.6527563 0.3787916 0.6560324 -0.6527928 0.3787302 0.6561504 -0.6527099 0.3787427 0.6561153 -0.6527379 0.3787807 0.6560612 -0.6527701 0.04753142 0.08235973 -0.9954686 0.008645713 0.01788294 -0.9998027 0.08127915 0.1199573 -0.9894463 0.1669843 0.3271196 -0.9301124 0.05388391 0.09531182 -0.9939881 0.256683 0.4450377 -0.8579366 0.1556391 0.2701909 -0.9501439 0.2533063 0.4381319 -0.8624828 0.2533063 0.4381319 -0.8624828 0.2533063 0.4381319 -0.8624828 0.1532942 0.2649251 -0.9520062 0.3394552 0.6051688 -0.7200979 0.2679123 0.4499776 -0.8519056 0.339983 0.5888702 -0.7332418 0.1413992 -0.7393543 -0.6583021 -0.3894063 -0.5276722 -0.7549336 -0.5065352 -0.4400168 -0.74149 -0.4551243 -0.487762 -0.7449497 -0.6133351 -0.3431239 -0.7113973 -0.541321 -0.4162999 -0.7305244 -0.7005603 -0.2584083 -0.6651619 -0.6552833 -0.307545 -0.689942 -0.6163609 -0.3491023 -0.7058519 -0.6061588 -0.3581422 -0.7101449 -0.6069337 -0.3574371 -0.7098383 -0.5222251 0.8178101 -0.2418007 -0.8067972 0.5901162 0.02900469 -0.8850459 0.4597634 -0.07287985 -0.8907397 0.4490501 -0.07026356 -0.8813852 0.4708499 -0.0382198 -0.8709744 0.4846729 -0.08059787 -0.8505899 0.517315 -0.09424442 -0.8841708 0.4624992 -0.06585305 -0.8593358 0.5111844 0.01524561 -0.8476185 0.5290989 0.0399664 0.8383169 -0.5420476 -0.05838859 0.8799607 -0.4639948 -0.1018741 0.8669289 -0.4904364 -0.08891808 0.8484792 -0.5278509 -0.03816735 0.8342472 -0.5468915 -0.07029438 0.8404933 -0.5369026 -0.07284754 0.852607 -0.516514 -0.07921427 0.9693859 -0.0434941 -0.2416597 0.9144662 -0.4036183 0.02905088 0.8820635 -0.4694271 0.04002946 0.1260616 -0.7366284 -0.6644449 0.1416539 -0.7387859 -0.6588851 0.06134647 -0.7212727 -0.6899293 0.005871176 -0.7083268 -0.7058603 -0.004767119 -0.7048022 -0.7093879 -0.4527111 -0.4846182 -0.7484638 -0.4008866 -0.5210755 -0.7535055 -0.389862 -0.5283249 -0.7542418 -0.3234158 -0.5645956 -0.7593643 -0.2625923 -0.6017643 -0.7542712 -0.2410544 -0.6123804 -0.7529163 -0.2625862 -0.6015017 -0.7544828 -0.1280153 -0.6591518 -0.7410338 -0.1864634 -0.6413456 -0.7442495 0.00909996 -0.7026386 -0.7114888 -0.08784317 -0.6775423 -0.7302192 -0.08843773 -0.6773045 -0.730368 -0.9229413 0.299012 -0.2424277 -0.910221 0.3931444 -0.1301362 -0.9102256 0.3931302 -0.130146 -0.9087648 0.2053028 -0.3633142 -0.9232713 0.3170647 -0.2168874 -0.920144 0.1908854 -0.3419033 -0.9146277 0.1672247 -0.3680924 -0.8963154 0.08076328 -0.436 -0.896312 0.08074039 -0.4360113 -0.8657451 0.007700264 -0.500426 -0.8519328 -0.02920097 -0.5228364 -0.710928 -0.2473034 -0.6583483 -0.7110012 -0.2472282 -0.6582975 -0.7778895 -0.1526742 -0.6095725 -0.7892538 -0.138521 -0.5982395 -0.8520033 -0.02903467 -0.5227306 0.2759093 -0.7506436 -0.6003402 0.2558997 -0.7514758 -0.6081116 0.4004829 -0.7523932 -0.5229895 0.4007589 -0.7523905 -0.5227819 0.4395276 -0.7459139 -0.500428 0.5180045 -0.7358727 -0.4360765 0.5180172 -0.7358648 -0.4360748 0.6021254 -0.70848 -0.3681048 0.6253893 -0.7014245 -0.3418945 0.7955192 -0.5917663 -0.1302386 0.7956258 -0.5916588 -0.130075 0.7375805 -0.6387014 -0.2191703 0.7186233 -0.6528946 -0.2393935 0.6247761 -0.7017583 -0.3423303 0.6247761 -0.7017583 -0.3423304 -0.9583293 0.2032739 0.2007111 -0.9583292 0.2032736 0.2007112 -0.9583292 0.2032738 0.2007111 -0.8942308 0.44735 -0.01514816 -0.08132195 -0.8336114 0.5463321 -0.2720232 -0.7156287 0.6433342 -0.3733263 -0.6593874 0.6525611 -0.3733261 -0.6593878 0.6525606 -0.3733263 -0.6593878 0.6525605 0.236892 -0.8652739 0.4417956 0.1008818 -0.8375781 0.5369225 0.1016266 -0.8377099 0.5365765 0.5234801 -0.8039129 0.2822991 0.4016993 -0.8275792 0.3921105 0.7498608 -0.6559935 0.08591377 0.6548395 -0.7285053 0.2011601 0.6536405 -0.7293316 0.2020637 0.6536405 -0.7293316 0.2020636 0.6536405 -0.7293316 0.2020635 -0.9441226 0.3189988 0.08290028 -0.9512851 0.0678696 0.3007499 -0.8553835 -0.1920644 0.4810721 -0.8553644 -0.1919625 0.4811468 0.8464832 0.5324154 -4.55976e-6 0.8464975 0.5323927 7.27177e-6 0.846483 0.5324158 -2.13043e-5 -0.3909457 0.9204137 -4.07244e-6 -0.3909457 0.9204137 -3.47197e-6 -0.3909667 0.9204048 2.49967e-6 -0.6860048 -0.5062445 0.522603 -0.7819409 -0.3497406 0.5159941 -0.3832299 -0.6533178 0.6529247 -0.9583426 0.2029224 0.2010028 -0.9416954 0.32671 0.08043885 -0.9658207 0.259204 -0.001967132 -0.9658556 0.2590754 -0.0017488 -0.9658487 0.2591009 -0.001786887 -0.9808297 0.1624616 -0.1076079 -0.9808344 0.1624422 -0.1075935 -0.9757392 0.05634588 -0.2115617 -0.976202 0.05970287 -0.2084833 -0.9761948 0.05973637 -0.2085074 -0.9521612 -0.04714047 -0.3019384 -0.9521632 -0.04733437 -0.301902 -0.9522011 -0.04734605 -0.3017807 -0.9091771 -0.156036 -0.3860695 -0.9091533 -0.1559027 -0.3861797 -0.9092972 -0.1557115 -0.385918 -0.8481481 -0.2640106 -0.4592858 -0.8481091 -0.2639867 -0.4593713 -0.7704495 -0.3689948 -0.5198564 -0.7704159 -0.3691481 -0.5197972 -0.7704032 -0.3691477 -0.5198163 -0.6776457 -0.4690085 -0.5664163 -0.6776562 -0.4688946 -0.5664981 -0.6779938 -0.4687064 -0.5662499 -0.5719054 -0.5615532 -0.5979819 -0.5718513 -0.5615208 -0.598064 -0.4553445 -0.6446628 -0.6140614 -0.4553529 -0.6446499 -0.6140687 -0.4554188 -0.6446714 -0.6139972 -0.3306243 -0.7167221 -0.6140009 -0.3305555 -0.7166799 -0.6140872 -0.330717 -0.7166689 -0.6140131 -0.2003816 -0.7760055 -0.5980491 -0.2002745 -0.775961 -0.5981427 -0.06731867 -0.8212721 -0.5665513 -0.06726258 -0.8213074 -0.5665068 -0.06729602 -0.8213238 -0.5664792 0.06558066 -0.8517151 -0.5198854 0.06559175 -0.8517075 -0.5198964 0.06571269 -0.8516798 -0.5199264 0.1955623 -0.8664411 -0.4593858 0.1954405 -0.8665099 -0.4593077 0.3192061 -0.8653834 -0.386289 0.3194189 -0.8654083 -0.3860571 0.3196996 -0.8652092 -0.3862709 0.435245 -0.8481215 -0.3020789 0.4351674 -0.848168 -0.3020602 0.4351503 -0.8481817 -0.3020467 0.5398235 -0.8155533 -0.2084789 0.5398002 -0.8155862 -0.2084105 0.5390166 -0.8158631 -0.2093525 0.6311179 -0.7681758 -0.1076845 0.8348217 -0.5503022 -0.01550143 0.7527807 -0.6535816 0.07843792 0.7073855 -0.7068251 -0.002029836 0.7074073 -0.7068032 -0.002035617 0.7073733 -0.7068381 -0.001728415 0.6310955 -0.7682014 -0.107635 0.5348226 -0.7897131 0.3005298 0.491669 -0.808506 0.3233878 0.452566 -0.8552113 0.2525823 0.452578 -0.8552064 0.2525774 0.387944 -0.9071843 0.1628378 0.3878665 -0.907213 0.162862 0.310377 -0.9474489 0.0775038 0.3104573 -0.9474258 0.07746392 0.22166 -0.9751222 -0.001934111 0.2214457 -0.9751711 -0.00179845 0.1234148 -0.9896475 -0.07325774 0.1236971 -0.9895965 -0.07346999 0.01841592 -0.9905984 -0.1355574 0.01821982 -0.9906338 -0.1353251 -0.0919376 -0.9781059 -0.1866987 -0.09193867 -0.9781121 -0.1866656 -0.2046491 -0.9523385 -0.2262084 -0.2046487 -0.9523435 -0.2261877 -0.3175626 -0.9138631 -0.2529987 -0.3173822 -0.9138395 -0.2533103 -0.4279691 -0.8634982 -0.2668583 -0.4280444 -0.8635044 -0.2667176 -0.5338273 -0.8024202 -0.2667402 -0.5338125 -0.8024271 -0.2667491 -0.6326791 -0.7318572 -0.2531843 -0.632699 -0.7318663 -0.2531086 -0.7224529 -0.653344 -0.2262817 -0.7224251 -0.6533285 -0.2264151 -0.8010886 -0.5686074 -0.1869295 -0.8011002 -0.5686141 -0.1868593 -0.8670637 -0.4794165 -0.1355016 -0.8670701 -0.4794284 -0.1354178 -0.9188251 -0.3877916 -0.07333683 -0.9188197 -0.3877941 -0.07339191 -0.9553079 -0.2956067 -0.001942873 -0.9553147 -0.2955837 -0.002036511 -0.9757375 -0.2048361 0.07732176 -0.9757254 -0.2048585 0.07741487 -0.9796169 -0.117608 0.1628472 -0.9796524 -0.1175221 0.1626961 -0.9669529 -0.03554499 0.2524654 -0.9669149 -0.03562086 0.2525998 -0.9484658 0.01597446 0.3164768 -0.9176256 -0.06575441 0.3919689 0.2605053 -0.8367376 0.4816712 0.1605211 -0.8339244 0.5280182 0.1283849 -0.873721 0.469179 0.1286165 -0.8737097 0.4691367 0.08533567 -0.9085146 0.4090465 0.08540058 -0.9085242 0.4090115 0.03359657 -0.93544 0.3518855 0.03330779 -0.9354028 0.352012 -0.02609503 -0.9539142 0.2989432 -0.025765 -0.9539775 0.2987695 -0.09138488 -0.9636756 0.2509546 -0.09151655 -0.9636518 0.2509977 -0.1619373 -0.9643037 0.2095103 -0.1618592 -0.9643386 0.2094108 -0.2355799 -0.9559591 0.1750559 -0.2355765 -0.9559631 0.175038 -0.3109978 -0.9387168 0.1486314 -0.3110657 -0.9386802 0.1487205 -0.3864772 -0.9129824 0.1307614 -0.3865568 -0.9129185 0.130972 -0.4605051 -0.8792476 0.1218963 -0.4604563 -0.8792977 0.1217201 -0.5312389 -0.8384272 0.1217585 -0.5312418 -0.8384382 0.1216703 -0.5974006 -0.7912059 0.1307891 -0.5974074 -0.791215 0.130704 -0.6574092 -0.7387155 0.1487036 -0.6574199 -0.7387158 0.1486544 -0.7100554 -0.6820329 0.1750787 -0.7100493 -0.6820185 0.1751592 -0.754183 -0.6223425 0.2095178 -0.7542238 -0.6223394 0.2093811 -0.7888545 -0.5610184 0.2509321 -0.7887964 -0.5610342 0.2510797 -0.8131703 -0.4994394 0.2988553 -0.8131345 -0.4994494 0.298936 -0.8267732 -0.4387804 0.3520196 -0.826774 -0.4387792 0.3520194 -0.8293773 -0.3804693 0.4091169 -0.829369 -0.3804627 0.4091399 -0.8208649 -0.3256095 0.4692113 -0.8208889 -0.3256015 0.4691751 -0.8009707 -0.2743329 0.5321535 -0.6666072 -0.4348955 0.6053932 -0.04345035 -0.7947309 0.605405 -0.2008234 -0.7403191 0.6415588 -0.2157144 -0.7588803 0.6144656 -0.2158252 -0.7588526 0.6144608 -0.2310109 -0.7710618 0.5933783 -0.2308859 -0.7710981 0.5933799 -0.2491308 -0.7805687 0.5732771 -0.249239 -0.7805263 0.5732876 -0.2700254 -0.7870024 0.5547194 -0.2700126 -0.7870192 0.5547018 -0.2931063 -0.7904248 0.5378825 -0.2931163 -0.7904214 0.5378817 -0.3178196 -0.790658 0.5233076 -0.3177627 -0.7907047 0.5232715 -0.3436941 -0.7877628 0.5111792 -0.3437333 -0.7877275 0.5112072 -0.3702296 -0.7816666 0.5019239 -0.37023 -0.7816263 0.5019862 -0.396723 -0.7726187 0.4956523 -0.3966724 -0.7727268 0.4955244 -0.4227058 -0.7609004 0.4922913 -0.4226714 -0.760917 0.4922949 -0.4475843 -0.7465463 0.4922772 -0.4476006 -0.7464579 0.4923965 -0.470803 -0.7298802 0.4956002 -0.4708103 -0.7299381 0.495508 -0.4919016 -0.7114704 0.5018394 -0.4919068 -0.7114737 0.5018296 -0.5104003 -0.691563 0.5111088 -0.5103453 -0.6914959 0.5112545 -0.5258325 -0.670587 0.5232717 -0.525797 -0.6705563 0.5233467 -0.5379651 -0.649021 0.537927 -0.5380069 -0.649033 0.5378707 -0.5465667 -0.627376 0.5546751 -0.5466473 -0.6274072 0.5545602 -0.5514544 -0.6060098 0.5732802 -0.5515331 -0.6060053 0.5732094 -0.5524492 -0.5855185 0.5932691 -0.5522821 -0.5855433 0.5934 -0.5492947 -0.5662854 0.6144886 -0.5494424 -0.5662314 0.6144063 -0.5486096 -0.5640388 0.6171612 -0.4837666 -0.5933678 0.6433386 -0.9780255 -0.1963347 0.07013553 0.8464713 0.5324343 -2.07126e-6 0.8464895 0.5324056 -3.07731e-6 0.846489 0.5324063 6.3628e-6 -0.9894083 -0.1000385 0.1051841 -0.9997274 0.02248305 -0.006312906 -0.9997273 0.02248281 -0.006312906 -0.9997273 0.02248293 -0.006312966 -0.9522391 -0.2153202 0.2165135 -0.8882015 -0.3253742 0.3243916 -0.829304 -0.3959195 0.3943384 -0.887852 -0.3221165 0.3285725 -0.7992772 -0.4245626 0.4253264 -0.6878299 -0.5148512 0.5116817 -0.5525516 -0.5913085 0.5874021 -0.9982845 0.05855101 9.28342e-6 -0.9982862 0.05852138 -7.10651e-6 -0.9982862 0.05852138 1.90139e-5 -0.686832 -0.509823 0.5180179 -0.4903997 -0.6175422 0.6149387 -0.3835694 -0.6545797 0.6514599 -0.9799309 -0.1403784 0.1415256 -0.9955731 0.06771874 -0.06518131 -0.9997622 0.01749753 -0.01301133 -0.9582203 0.2039088 -0.200587 -0.9382031 0.2474942 -0.2419122 -0.9826272 0.1319916 -0.1304688 0.8660197 -0.50001 0 0.8660189 -0.5000113 0 0.62927 0.7771869 0 0.6292661 0.77719 0 0.9659352 0.2587843 0 0.9986318 -0.0522933 0 0.9986322 -0.0522859 0 0.9335935 -0.358334 0 0.933596 -0.3583275 0 0.5000197 0.866014 0 0.5000116 0.8660188 0 -0.5816072 0.1694669 -0.7956219 -0.8488615 0.2473307 -0.4671849 -0.8898931 0.2493371 -0.3819964 -0.7952103 0.2317041 -0.560316 -0.6836577 0.1870933 -0.7054135 -0.5451495 0.1588514 -0.8231514 -0.2066449 0.06021356 -0.9765615 -0.3331598 0.08716076 -0.9388331 -0.1434862 0.04180824 -0.9887689 3.91268e-7 0 -1 -8.66183e-7 0 -1 -6.46396e-7 0 -1 1.33614e-6 0 -1 -1.47169e-6 0 -1 1.77895e-6 0 -1 -6.33971e-7 0 -1 -1.71599e-7 0 -1 -7.21101e-7 0 -1 0 0 -1 5.49217e-7 0 -1 1.72198e-7 0 -1 -0.8004649 0.5993797 0 -0.7771808 0.6292608 0.004565656 0.3583698 0.9335798 0 0.3583699 0.9335797 0 0.05229544 0.9986317 0 0.05229473 0.9986318 0 -0.2587793 0.9659366 0 -0.2587812 0.965936 0 -0.4799302 0.8773068 0 -0.5446133 0.8386648 0.006147503 -0.6113015 0.7913979 0 -0.6970165 0.7170551 0 -0.86602 0.5000095 -2.27242e-5 -0.8658052 0.5003815 0 -0.8659992 0.5000454 1.68191e-5 -0.8663815 0.4993826 -1.70351e-4 -0.8660209 0.5000078 1.02668e-4 -0.8660166 0.5000154 1.56505e-5 -0.866045 0.4999661 2.91804e-5 -0.925486 0.2696514 -0.2660149 -0.9254812 0.2696575 -0.2660256 -0.925484 0.2696679 -0.266005 -0.9254295 0.2699019 -0.2659572 -0.9254906 0.2696564 -0.2659938 -0.9254888 0.2696691 -0.2659871 -0.9254741 0.2696506 -0.2660571 -0.9255142 0.2697424 -0.2658244 -0.9254326 0.2695027 -0.266351 -0.9254699 0.2697072 -0.266014 -0.9254666 0.2697207 -0.2660118 -0.9254844 0.2696658 -0.2660058 -0.9254615 0.2696787 -0.2660727 -0.9255001 0.2696648 -0.2659522 -0.9254892 0.2696602 -0.2659946 -0.9254766 0.2696688 -0.26603 -0.9254766 0.2696688 -0.2660301 -0.9254766 0.2696688 -0.2660301 -0.9254638 0.2697142 -0.2660282 -0.9254428 0.2699642 -0.2658475 0.3011074 0.9516313 -0.06109386 0.3011061 0.9516323 -0.06108331 -0.1308193 0.9765658 -0.1708965 -0.1308081 0.9765697 -0.1708829 -0.5371361 0.8066095 -0.2467105 -0.5371258 0.8066161 -0.2467111 -0.8360877 0.4756955 -0.2732601 -0.8360981 0.4756832 -0.2732501 -7.5584e-6 0 -1 5.49982e-6 0 -1 -2.86867e-6 0 -1 -2.72765e-6 0 -1 7.57933e-6 0 -1 2.77216e-6 0 -1 3.36875e-6 0 -1 -3.18364e-6 0 -1 1.78577e-6 0 -1 2.97488e-6 0 -1 -1.24766e-6 0 -1 2.50025e-6 0 -1 -3.90509e-6 0 -1 -1.14657e-5 0 -1 1.01881e-5 0 -1 -8.18209e-6 0 -1 5.35714e-6 0 -1 3.75404e-5 0 -1 1.85261e-5 0 -1 -5.50661e-5 0 -1 0.3058424 -0.9520823 0 0.122552 -0.9924621 0 0.122552 -0.9924622 0 -0.1283078 -0.9917345 0 -0.1283078 -0.9917345 0 -0.3708516 -0.9286921 0 -0.3708516 -0.9286922 0 -0.5901313 -0.8073073 0 -0.772367 -0.6351767 0 -0.7723669 -0.6351768 0 -0.9060714 -0.423125 0 -0.9828433 -0.1844426 0 -0.9828433 -0.1844427 0 -0.9978371 0.06573563 0 -0.9978371 0.06573486 0 -0.9501399 0.311824 0 -0.9501396 0.3118249 0 -0.8426895 0.5384001 0 -0.8426893 0.5384003 0 -0.6823684 0.7310085 0 -0.6823683 0.7310085 0 -0.4793079 0.8776469 0 -0.4793079 0.8776469 0 -0.2457552 0.969332 0 -0.245755 0.969332 0 0.002877175 0.999996 0 0.002877175 0.999996 0 0.2514859 0.9678609 0 0.4844504 0.8748188 0 0.4844505 0.8748188 0 0.6867472 0.7268964 0 0.6867473 0.7268963 0 0.8458614 0.5334028 0 0.845862 0.533402 0 0.9519744 0.3061777 0 0.9519746 0.306177 0 0.9982063 0.05986756 0 0.9982063 0.05986762 0 0.9817301 -0.1902791 0 0.9817299 -0.1902798 0 0.9035527 -0.4284771 0 0.9035523 -0.4284779 0 0.7685725 -0.6397628 0 0.7685722 -0.6397631 0 0.5855563 -0.8106317 0 0.5855564 -0.8106317 0 0.4230119 -0.9061242 0 0.3651527 -0.9309468 -0.001293003 7.12427e-7 0 -1 -1.43419e-6 0 -1 2.26818e-6 0 -1 -2.77143e-6 0 -1 6.81712e-7 0 -1 2.74521e-6 0 -1 7.80713e-6 0 -1 -1.85737e-5 0 -1 1.48856e-6 0 -1 -1.9959e-6 0 -1 -3.63599e-6 0 -1 5.72907e-6 0 -1 -2.23095e-6 0 -1 2.2686e-6 0 -1 2.93005e-6 0 -1 1.43289e-6 0 -1 -5.70073e-6 0 -1 2.29274e-5 0 -1 8.92284e-7 0 -1 -1.11567e-6 0 -1 -2.49537e-7 0 -1 -8.41676e-7 0 -1 1.58486e-6 0 -1 1.4323e-6 0 -1 -3.9021e-6 0 -1 9.08982e-7 0 -1 -8.42493e-7 0 -1 3.16728e-6 0 -1 -1.51266e-6 0 -1 7.31258e-7 0 -1 2.54686e-6 0 -1 -1.48778e-6 0 -1 3.12487e-6 0 -1 -9.38861e-6 0 -1 -1.46338e-6 0 -1 3.58549e-6 0 -1 -2.86632e-6 0 -1 -3.90436e-6 0 -1 -7.12367e-7 0 -1 7.17064e-7 0 -1 -6.36508e-7 0 -1 -8.42588e-7 0 -1 -7.5572e-7 0 -1 -2.93202e-6 0 -1 2.86382e-6 0 -1 2.34645e-6 0 -1 9.09187e-7 0 -1 -1.14574e-5 0 -1 1.16307e-5 0 -1 -4.69095e-6 0 -1 2.92617e-6 0 -1 -1.51195e-6 0 -1 5.85663e-6 0 -1 -2.54537e-6 0 -1 2.23164e-6 0 -1 -0.4049467 0.5810933 -0.7059382 -0.404882 0.5811632 -0.7059179 -0.4928483 0.5087385 -0.7058936 -0.4930008 0.5083687 -0.7060536 -0.5681598 0.4227935 -0.706003 -0.5680428 0.4231894 -0.7058598 -0.6286341 0.3264404 -0.7058725 -0.628693 0.3260881 -0.7059828 -0.6726883 0.2214146 -0.7060214 -0.672716 0.221586 -0.7059412 -0.6996101 0.1102545 -0.7059673 -0.6996695 0.1104251 -0.7058817 -0.708351 -0.003183007 -0.7058532 -0.7082011 -0.003613889 -0.7060016 -0.6985508 -0.1165188 -0.7060101 -0.6985275 -0.1165948 -0.7060206 -0.6706851 -0.2274121 -0.7060208 -0.6707209 -0.2273584 -0.706004 -0.6255782 -0.332025 -0.7059826 -0.6258916 -0.331717 -0.7058495 -0.5644799 -0.4278876 -0.7058857 -0.5641822 -0.4280385 -0.7060322 -0.4881393 -0.5130959 -0.7060118 -0.4883063 -0.5130288 -0.7059451 -0.3997334 -0.5846835 -0.7059452 -0.3996663 -0.5847004 -0.705969 -0.3005901 -0.6412994 -0.7059609 -0.3007501 -0.6412792 -0.705911 -0.1943886 -0.6810742 -0.7059398 -0.1938924 -0.6810317 -0.7061172 -0.08202672 -0.7033966 -0.7060487 -0.08258587 -0.7034782 -0.7059023 0.03169095 -0.7075848 -0.7059175 0.03179848 -0.7075569 -0.7059406 0.1447309 -0.6933039 -0.7059623 0.144808 -0.6932726 -0.7059772 0.2541463 -0.6610533 -0.7059873 0.2539789 -0.6612029 -0.7059075 0.3570973 -0.6116866 -0.7059186 0.3569514 -0.6119088 -0.7057999 0.4503279 -0.5467734 -0.7058637 0.450401 -0.5467011 -0.7058731 0.5323714 -0.4672017 -0.705906 0.5323103 -0.4674063 -0.7058166 0.6003065 -0.3760214 -0.7058612 0.6003764 -0.3757489 -0.7059469 0.6528164 -0.2746394 -0.7059773 0.6528152 -0.2747161 -0.7059487 0.6883868 -0.1665547 -0.7059626 0.6884003 -0.1664701 -0.7059694 0.7062344 -0.05350542 -0.7059534 0.7062087 -0.05343091 -0.7059848 0.7057126 0.05985748 -0.7059652 0.7056316 0.06007426 -0.7060277 0.6867713 0.1727663 -0.7060433 0.6868518 0.172738 -0.7059718 0.6503729 0.2803095 -0.706004 0.6503228 0.2803593 -0.7060304 0.5967662 0.381318 -0.7060218 0.5968515 0.3812216 -0.7060017 0.527996 0.4720183 -0.7059879 0.5280596 0.4719983 -0.7059539 0.4453961 0.5506674 -0.7059658 0.445214 0.5507373 -0.7060263 0.3512914 0.6149146 -0.7060272 0.3515813 0.6149266 -0.7058725 0.248236 0.6633607 -0.705926 0.2482015 0.6633866 -0.7059138 0.1386933 0.6945152 -0.7059836 0.1386529 0.6945508 -0.7059566 0.02500265 0.7078074 -0.7059629 0.02518451 0.7078568 -0.7059069 -0.08837699 0.7027719 -0.7059046 -0.08830219 0.7027748 -0.705911 -0.2000631 0.6795184 -0.7058539 -0.2004909 0.6791271 -0.706109 -0.3065447 0.6384127 -0.7060167 -0.3064423 0.6385053 -0.7059774 -7.55608e-7 0 -1 7.43835e-7 0 -1 3.65685e-7 0 -1 -7.55841e-7 0 -1 -7.12468e-7 0 -1 1.58469e-6 0 -1 -8.42344e-7 0 -1 3.57291e-6 0 -1 -2.86421e-6 0 -1 -2.75149e-5 0 -1 -1.6738e-6 0 -1 8.92704e-7 0 -1 1.10777e-6 0 -1 -1.4323e-6 0 -1 -9.76562e-7 0 -1 5.73974e-6 0 -1 3.51782e-6 0 -1 -4.631e-6 0 -1 1.43375e-6 0 -1 3.56837e-6 0 -1 -9.98594e-7 0 -1 9.08909e-7 0 -1 -3.96111e-7 0 -1 -3.7911e-6 0 -1 1.27318e-6 0 -1 -8.93272e-6 0 -1 7.73836e-6 0 -1 -2.26777e-6 0 -1 7.31412e-7 0 -1 6.08569e-6 0 -1 -4.9844e-6 0 -1 1.87716e-5 0 -1 -5.5212e-5 0 -1 -2.29169e-5 0 -1 1.56165e-5 0 -1 -4.29637e-6 0 -1 4.46315e-6 0 -1 -1.38776e-5 0 -1 4.70296e-6 0 -1 0.674921 -0.7378901 0 0.5444045 -0.8388229 0 0.5444204 -0.8388125 0 0.398772 -0.9170501 0 0.3987847 -0.9170446 0 0.2424803 -0.9701563 0 0.2424727 -0.9701583 0 0.07939225 -0.9968435 0 0.07939487 -0.9968433 0 -0.08556789 -0.9963324 0 -0.08556807 -0.9963324 0 -0.2484205 -0.9686524 0 -0.2484123 -0.9686544 0 -0.4047518 -0.9144267 0 -0.4047393 -0.9144321 0 -0.5494469 -0.8355287 0 -0.5494788 -0.8355076 0 -0.6795343 -0.7336438 0 -0.6795522 -0.7336272 0 -0.7909869 -0.6118333 0 -0.7910206 -0.6117897 0 -0.880949 -0.4732114 0 -0.880978 -0.4731573 0 -0.9468027 -0.3218148 0 -0.9468134 -0.3217833 0 -0.98688 -0.1614553 0 -0.9868745 -0.1614894 0 -0.9999957 0.002958714 0 -0.9999957 0.002958714 0 -0.9858467 0.1676493 0 -0.9858525 0.1676152 0 -0.9447396 0.3278217 0 -0.9447396 0.3278221 0 -0.8779798 0.4786977 0 -0.7873723 0.6164778 0 -0.7873554 0.6164994 0 -0.6749442 0.7378688 0 -0.6748916 0.737917 0 -0.5444135 0.8388171 0 -0.3987847 0.9170446 0 -0.242464 0.9701604 0 -0.2424808 0.9701562 0 -0.07939499 0.9968433 0 -0.07939487 0.9968433 0 0.08555805 0.9963333 0 0.08555793 0.9963333 0 0.2484218 0.968652 0 0.2484301 0.9686498 0 0.4046359 0.914478 0 0.4046363 0.9144778 0 0.5495907 0.8354341 0 0.5496067 0.8354236 0 0.6794129 0.7337563 0 0.6793961 0.7337718 0 0.7911384 0.6116372 0 0.7911216 0.6116591 0 0.880978 0.4731573 0 0.8809636 0.4731844 0 0.9468124 0.3217863 0 0.9468016 0.3218178 0 0.9868692 0.1615218 0 0.9868859 0.1614201 0 0.9999957 -0.002958714 0 0.9999957 -0.002958714 0 0.9858471 -0.1676475 0 0.9858528 -0.1676136 0 0.9447579 -0.3277689 0 0.9447795 -0.3277071 0 0.8780472 -0.4785742 0 0.8780326 -0.478601 0 0.7872409 -0.6166456 0 0.787224 -0.6166672 0 -0.9977982 -0.06632488 0 -0.9904196 0.1380907 0 -0.9904202 0.1380864 0 -0.91647 0.4001034 0 -0.9164716 0.4000997 0 -0.7745506 0.632512 0 -0.5751691 0.8180347 0 -0.5751671 0.818036 0 -0.3328557 0.9429778 0 -0.332857 0.9429773 0 -0.06637728 0.9977946 0 -0.06637728 0.9977946 0 0.2053773 0.9786829 0 0.2053782 0.9786828 0 0.4617231 0.8870242 0 0.4617214 0.8870251 0 0.6839711 0.7295092 0 0.6839733 0.7295071 0 0.8553071 0.5181215 0 0.8553071 0.5181215 0 0.9634497 0.2678899 0 0.9634507 0.2678857 0 0.999998 -0.002056241 0 0.9999979 -0.00205177 0 0.9624492 -0.271462 0 0.9624504 -0.2714579 0 0.8533151 -0.5213958 0 0.853319 -0.5213892 0 0.681239 -0.7320611 0 0.6812368 -0.7320632 0 0.4583441 -0.8887749 0 0.2014927 -0.9794901 0 0.2014936 -0.9794899 0 -0.06993448 -0.9975516 0 -0.06993448 -0.9975516 0 -0.336647 -0.941631 0 -0.3366441 -0.941632 0 -0.5783516 -0.8157877 0 -0.5783558 -0.8157847 0 -0.7769342 -0.6295819 0 -0.7769386 -0.6295764 0 -0.9179258 -0.3967523 0 -0.9179242 -0.3967559 0 -0.9794728 -0.2015764 0 -0.9909463 -0.134254 -0.001206994 0.6076747 0.3681086 -0.7037242 0.607662 0.3681083 -0.7037352 0.4859267 0.5182821 -0.7037464 0.4858441 0.5182916 -0.7037965 0.3280168 0.6301646 -0.7037738 0.3280302 0.6301504 -0.7037802 0.1459012 0.6952718 -0.7037826 0.1458036 0.6952406 -0.7038338 -0.04714846 0.7088034 -0.7038288 -0.04712235 0.7088549 -0.7037786 -0.236454 0.6698694 -0.7038214 -0.236598 0.6697108 -0.7039239 -0.4085182 0.5810213 -0.703937 -0.4084583 0.5812909 -0.7037491 -0.550273 0.4493604 -0.7037577 -0.5502381 0.4493607 -0.7037848 -0.6510837 0.284242 -0.7037731 -0.6510737 0.2842739 -0.7037695 -0.7036002 0.09810572 -0.7037912 -0.7036202 0.09807807 -0.7037751 -0.7039641 -0.09537124 -0.7038032 -0.7039662 -0.09540003 -0.7037971 -0.6520633 -0.2818418 -0.7038314 -0.6521156 -0.2818087 -0.7037963 -0.5519343 -0.4472539 -0.7037987 -0.5520324 -0.4472172 -0.7037451 -0.4108864 -0.5795735 -0.7037521 -0.4107069 -0.5795831 -0.703849 -0.2391356 -0.6688886 -0.7038482 -0.2392669 -0.6689231 -0.7037708 -0.0496838 -0.7086929 -0.7037656 -0.04973733 -0.7087023 -0.7037523 0.1431559 -0.6958993 -0.7037263 0.1432023 -0.69583 -0.7037853 0.3255929 -0.6313628 -0.7038255 0.3256316 -0.6313586 -0.7038114 0.4839497 -0.520051 -0.7038037 0.4839375 -0.5200721 -0.7037965 0.6061887 -0.3703921 -0.7038075 0.6062187 -0.3701161 -0.7039269 0.6836088 -0.1928098 -0.70392 0.6837272 -0.1932569 -0.7036824 0.710507 -0.001464009 -0.7036887 0.7104131 -0.001305341 -0.7037837 0.684467 0.1903163 -0.7037647 0.6844611 0.1902887 -0.7037778 -1.75875e-6 0 -1 -1.02528e-6 0 -1 -4.27115e-6 0 -1 2.81614e-6 0 -1 -7.29166e-6 0 -1 5.46898e-6 0 -1 -4.05959e-6 0 -1 7.69531e-6 0 -1 0.9764966 0.215533 0 0.9986505 0.05193501 0 0.9986503 0.05193936 0 0.993592 -0.1130266 0 0.9935915 -0.113031 0 -0.3535873 -0.9354015 0 -0.5026783 -0.8644735 0 -0.502675 -0.8644756 0 -0.6380797 -0.7699704 0 -0.6380748 -0.7699744 0 -0.7561447 -0.6544045 0 -0.7561451 -0.6544039 0 -0.8535612 -0.5209925 0 -0.8535654 -0.5209857 0 -0.9276502 -0.3734502 0 -0.9276472 -0.3734577 0 -0.9764738 -0.2156367 0 -0.9764747 -0.2156326 0 -0.9986476 -0.0519914 0 -0.9986476 -0.05199146 0 -0.9935852 0.1130867 0 -0.9935862 0.1130782 0 -0.9614211 0.2750808 0 -0.9614211 0.2750811 0 -0.9029971 0.4296469 0 -0.9030002 0.4296402 0 -0.8200801 0.5722488 0 -0.8200819 0.5722464 0 -0.7145249 0.6996101 0 -0.7145292 0.6996056 0 -0.5898271 0.8075296 0 -0.5898292 0.8075281 0 -0.4486312 0.893717 0 -0.4486334 0.893716 0 -0.2957327 0.9552708 0 -0.2957302 0.9552716 0 -0.1342734 0.9909444 0 -0.1342725 0.9909445 0 0.03067195 0.9995296 0 0.03067189 0.9995296 0 0.1948661 0.9808298 0 0.1948678 0.9808295 0 0.3535244 0.9354254 0 0.3535239 0.9354256 0 0.5027332 0.8644416 0 0.5027355 0.8644404 0 0.6380788 0.7699711 0 0.6380782 0.7699717 0 0.7561401 0.6544098 0 0.7561385 0.6544117 0 0.8535767 0.5209672 0 0.8535751 0.5209699 0 0.9276216 0.3735214 0 0.9764948 0.2155413 0 -1.13971e-5 0 -1 -3.83944e-6 0 -1 -1.89005e-6 0 -1 2.29169e-5 0 -1 -1.85226e-5 0 -1 9.38967e-6 0 -1 2.23109e-6 0 -1 7.16086e-7 0 -1 -1.68471e-6 0 -1 3.16855e-6 0 -1 -5.51268e-5 0 -1 9.98444e-7 0 -1 2.19426e-6 0 -1 2.86959e-6 0 -1 -3.8218e-6 0 -1 -1.45448e-5 0 -1 -8.41969e-7 0 -1 1.10933e-5 0 -1 1.72145e-5 0 -1 -1.17175e-5 0 -1 -0.3016602 -0.9534156 0 -0.4542974 -0.8908502 0 -0.4543114 -0.8908429 0 -0.5946477 -0.8039865 0 -0.5946483 -0.803986 0 -0.7189975 -0.6950126 0 -0.7189801 -0.6950307 0 -0.8235205 -0.5672867 0 -0.8234875 -0.5673344 0 -0.9057052 -0.4239082 0 -0.905692 -0.4239363 0 -0.9631114 -0.2691031 0 -0.9631115 -0.2691028 0 -0.9942486 -0.1070966 0 -0.9942487 -0.1070963 0 -0.998293 0.05840444 0 -0.9982931 0.05840438 0 -0.9751742 0.2214395 0 -0.9751666 0.2214726 0 -0.9253054 0.3792228 0 -0.8503006 0.5262974 0 -0.8502691 0.5263482 0 -0.7520082 0.6591538 0 -0.751991 0.6591734 0 -0.6333406 0.7738733 0 -0.6333747 0.7738453 0 -0.4972919 0.8675833 0 -0.4973073 0.8675745 0 -0.3476969 0.9376071 0 -0.1886076 0.9820525 0 -0.1886205 0.9820501 0 -0.0244807 0.9997004 0 -0.0244798 0.9997003 0 0.1402065 0.9901223 0 0.1402165 0.990121 0 0.3016602 0.9534156 0 0.3016703 0.9534124 0 0.4541847 0.8909076 0 0.4541987 0.8909004 0 0.5947808 0.803888 0 0.5947815 0.8038875 0 0.7189801 0.6950307 0 0.7189627 0.6950487 0 0.8235042 0.5673103 0 0.82352 0.5672872 0 0.9056472 0.4240322 0 0.9056603 0.4240041 0 0.9631114 0.2691031 0 0.9631025 0.2691351 0 0.9942789 0.1068154 0 0.9942678 0.1069188 0 0.9983092 -0.05812698 0 0.9983093 -0.05812692 0 0.9751064 -0.2217374 0 0.975114 -0.2217043 0 0.9252932 -0.3792526 0 0.9253177 -0.3791931 0 0.8502851 -0.5263226 0 0.8503003 -0.5262979 0 0.752129 -0.659016 0 0.6332277 -0.7739656 0 0.63321 -0.7739801 0 0.4972845 -0.8675876 0 0.4972991 -0.8675792 0 0.3476969 -0.9376071 0 0.3477082 -0.9376028 0 0.1888652 -0.982003 0 0.1888655 -0.982003 0 0.02421933 -0.9997068 0 0.02422016 -0.9997068 0 -0.1402114 -0.9901216 0 -0.1402117 -0.9901216 0 0.9877411 0.1561011 0 0.9988401 -0.04815012 0 0.9988404 -0.04814571 0 0.9488108 -0.315845 0 0.9488121 -0.315841 0 0.828409 -0.5601238 0 0.828411 -0.5601208 0 0.6465712 -0.7628538 0 0.4168213 -0.9089885 0 0.4168246 -0.9089869 0 0.1559914 -0.9877585 0 0.1559901 -0.9877586 0 -0.1160585 -0.9932424 0 -0.1160591 -0.9932423 0 -0.3798285 -0.9250569 0 -0.3798254 -0.9250583 0 -0.6153051 -0.788289 0 -0.6153073 -0.7882874 0 -0.8051533 -0.5930668 0 -0.8051513 -0.5930696 0 -0.9353592 -0.3536992 0 -0.9353592 -0.3536992 0 -0.9960841 -0.08841115 0 -0.9960833 -0.08841997 0 -0.9829449 0.1839006 0 -0.9829449 0.1839006 0 -0.8969423 0.4421476 0 -0.8969406 0.442151 0 -0.7445339 0.6675847 0 -0.7445317 0.6675871 0 -0.5367345 0.8437512 0 -0.5367326 0.8437525 0 -0.2890446 0.9573157 0 -0.2890434 0.957316 0 -0.01998299 0.9998003 0 0.2502763 0.9681745 0 0.2502753 0.9681748 0 0.5023083 0.8646886 0 0.5023122 0.8646864 0 0.716874 0.6972028 0 0.7168784 0.6971983 0 0.8784781 0.4777827 0 0.87848 0.4777792 0 0.9572768 0.2891731 0 0.9747818 0.2231567 -0.001206934 -0.5719869 -0.421329 -0.7037848 -0.5718781 -0.4213846 -0.7038398 -0.4371005 -0.559984 -0.703819 -0.4372035 -0.5599732 -0.7037635 -0.2698395 -0.6571885 -0.7037684 -0.2699438 -0.6572207 -0.7036983 -0.08245545 -0.7056587 -0.7037379 -0.08246308 -0.7056605 -0.7037351 0.1108162 -0.7017288 -0.703773 0.1109845 -0.7016271 -0.703848 0.2961013 -0.6457259 -0.7038198 0.2960644 -0.6457418 -0.7038207 0.4593284 -0.5419352 -0.7037924 0.4592501 -0.5420846 -0.7037283 0.5885711 -0.3979582 -0.7037139 0.5885668 -0.3979448 -0.7037252 0.6740719 -0.2243874 -0.7037596 0.674061 -0.2243676 -0.7037763 0.7095718 -0.03420323 -0.7038026 0.7095828 -0.03421044 -0.7037911 0.6924888 0.1585284 -0.7037954 0.6924802 0.1585517 -0.7037987 0.6240566 0.3394036 -0.7038172 0.624005 0.339438 -0.7038463 0.5092338 0.4952546 -0.7038494 0.5093996 0.495209 -0.7037613 0.3568508 0.6142968 -0.7037734 0.3567942 0.614291 -0.7038072 0.1777985 0.6878075 -0.7037817 0.178032 0.6878472 -0.7036837 -0.01419794 0.7103581 -0.7036972 -0.01441693 0.710236 -0.7038161 -0.2053317 0.6800681 -0.7038084 -0.2054432 0.6799196 -0.7039194 -0.3812461 0.5993287 -0.7038868 -0.3811422 0.5994674 -0.7038249 -0.5289216 0.4742588 -0.7037901 -0.528878 0.4744149 -0.7037178 -0.6372364 0.3141288 -0.703742 -0.6372267 0.3140316 -0.7037943 -0.6983025 0.1306446 -0.7037796 -0.6982031 0.1303768 -0.7039278 -0.7075036 -0.06279653 -0.7039143 -0.7076627 -0.06257605 -0.703774 -0.6644666 -0.251263 -0.7038119 -0.6645106 -0.2512508 -0.7037746 -5.21563e-6 0 -1 3.47516e-6 0 -1 1.29103e-6 0 -1 1.00506e-6 0 -1 -8.12015e-6 0 -1 -1.28274e-6 0 -1 1.82245e-6 0 -1 2.81636e-6 0 -1 -0.9530012 -0.302967 0 -0.9898909 -0.141831 0 -0.9898903 -0.1418353 0 -0.9997322 0.02314358 0 -0.9997323 0.02314358 0 -0.9823607 0.1869959 0 -0.9823592 0.1870043 0 -0.938109 0.3463405 0 -0.9381076 0.3463439 0 -0.8681806 0.4962486 0 -0.8681784 0.4962524 0 -0.7748174 0.6321852 0 -0.6603111 0.7509922 0 -0.5274609 0.8495793 0 -0.5274621 0.8495786 0 -0.3804574 0.9247985 0 -0.3804605 0.9247972 0 -0.2231173 0.9747917 0 -0.2231163 0.9747918 0 -0.05972826 0.9982147 0 -0.05972844 0.9982147 0 0.1054819 0.9944213 0 0.1054822 0.9944212 0 0.2677533 0.9634876 0 0.2677556 0.9634869 0 0.4225184 0.9063544 0 0.4225205 0.9063534 0 0.566143 0.8243071 0 0.5661418 0.824308 0 0.6940174 0.7199583 0 0.6940217 0.7199541 0 0.8030292 0.5959398 0 0.8030271 0.5959426 0 0.8901906 0.4555884 0 0.8901869 0.4555958 0 0.9530417 0.3028392 0 0.9530431 0.3028349 0 0.9898862 0.1418636 0 0.9898869 0.1418592 0 0.999736 -0.02298271 0 0.999736 -0.02297836 0 0.98232 -0.18721 0 0.9381005 -0.3463634 0 0.9380992 -0.3463669 0 0.8682593 -0.4961109 0 0.868259 -0.4961113 0 0.7748911 -0.6320948 0 0.7748891 -0.6320974 0 0.6601269 -0.7511543 0 0.5274747 -0.8495708 0 0.5274738 -0.8495713 0 0.3805063 -0.9247784 0 0.3805048 -0.9247789 0 0.2231003 -0.9747955 0 0.2230983 -0.9747959 0 0.05975311 -0.9982132 0 -0.1054823 -0.9944212 0 -0.1054821 -0.9944213 0 -0.2677695 -0.9634831 0 -0.2677717 -0.9634824 0 -0.4225133 -0.9063568 0 -0.4225166 -0.9063553 0 -0.5661898 -0.824275 0 -0.5661945 -0.8242717 0 -0.6939391 -0.7200337 0 -0.8030847 -0.595865 0 -0.8030867 -0.5958622 0 -0.8901929 -0.455584 0 -0.9530034 -0.3029597 0 -3.12266e-5 0 -1 -2.67916e-6 0 -1 -2.21515e-6 0 -1 -3.36909e-6 0 -1 -1.5847e-6 0 -1 3.02234e-6 0 -1 -1.43414e-6 0 -1 -2.85114e-6 0 -1 5.12072e-6 0 -1 5.66809e-6 0 -1 5.02275e-6 0 -1 -5.09575e-6 0 -1 1.14542e-5 0 -1 -7.5654e-6 0 -1 1.27395e-6 0 -1 9.97968e-7 0 -1 -3.89541e-6 0 -1 -3.408e-7 0 -1 2.29232e-5 0 -1 -9.39133e-6 0 -1 3.70494e-5 0 -1 -1.07144e-5 0 -1 1.10703e-5 0 -1 -2.78583e-5 0 -1 5.54078e-5 0 -1 -8.42165e-6 0 -1 4.54579e-6 0 -1 -3.29525e-6 0 -1 3.94605e-6 0 -1 3.70336e-5 0 -1 -5.50358e-5 0 -1 4.42964e-6 0 -1 1.78579e-6 0 -1 -7.52473e-6 0 -1 1.34751e-5 0 -1 -1.18197e-5 0 -1 7.98512e-6 0 -1 2.54694e-6 0 -1 -4.18587e-6 0 -1 -2.54654e-6 0 -1 7.43846e-6 0 -1 -1.10784e-5 0 -1 -2.8652e-6 0 -1 1.56172e-5 0 -1 0.9530012 0.302967 0 0.9898909 0.141831 0 0.9898903 0.1418353 0 0.9997322 -0.02314358 0 0.9997323 -0.02314358 0 0.9823607 -0.1869959 0 0.9823592 -0.1870043 0 0.938109 -0.3463405 0 0.9381076 -0.3463439 0 0.8681806 -0.4962486 0 0.8681784 -0.4962524 0 0.7748174 -0.6321852 0 0.6603111 -0.7509922 0 0.5274609 -0.8495793 0 0.5274621 -0.8495786 0 0.3804574 -0.9247985 0 0.3804605 -0.9247972 0 0.2231173 -0.9747917 0 0.2231163 -0.9747918 0 0.05972826 -0.9982147 0 0.05972844 -0.9982147 0 -0.1054819 -0.9944213 0 -0.1054822 -0.9944212 0 -0.2677533 -0.9634876 0 -0.2677556 -0.9634869 0 -0.4225184 -0.9063544 0 -0.4225205 -0.9063534 0 -0.566143 -0.8243071 0 -0.5661418 -0.824308 0 -0.6940174 -0.7199583 0 -0.6940217 -0.7199541 0 -0.8030292 -0.5959398 0 -0.8030271 -0.5959426 0 -0.8901906 -0.4555884 0 -0.8901869 -0.4555958 0 -0.9530417 -0.3028392 0 -0.9530431 -0.3028349 0 -0.9898862 -0.1418636 0 -0.9898869 -0.1418592 0 -0.999736 0.02298271 0 -0.999736 0.02297836 0 -0.98232 0.18721 0 -0.9381005 0.3463634 0 -0.9380992 0.3463669 0 -0.8682593 0.4961109 0 -0.868259 0.4961113 0 -0.7748911 0.6320948 0 -0.7748891 0.6320974 0 -0.6601269 0.7511543 0 -0.5274747 0.8495708 0 -0.5274738 0.8495713 0 -0.3805063 0.9247784 0 -0.3805048 0.9247789 0 -0.2231003 0.9747955 0 -0.2230983 0.9747959 0 -0.05975311 0.9982132 0 0.1054823 0.9944212 0 0.1054821 0.9944213 0 0.2677695 0.9634831 0 0.2677717 0.9634824 0 0.4225133 0.9063568 0 0.4225166 0.9063553 0 0.5661898 0.824275 0 0.5661945 0.8242717 0 0.6939391 0.7200337 0 0.8030847 0.595865 0 0.8030867 0.5958622 0 0.8901929 0.455584 0 0.9530034 0.3029597 0 1.34767e-5 0 -1 6.9493e-6 0 -1 -3.02366e-6 0 -1 6.58259e-6 0 -1 -1.26714e-5 0 -1 2.34199e-5 0 -1 1.78535e-5 0 -1 -2.29232e-5 0 -1 9.39133e-6 0 -1 -3.70494e-5 0 -1 -1.18929e-5 0 -1 1.25082e-5 0 -1 -1.77415e-5 0 -1 -5.5756e-7 0 -1 2.99622e-6 0 -1 -4.43141e-6 0 -1 2.27347e-7 0 -1 3.89577e-6 0 -1 1.14571e-5 0 -1 7.81791e-6 0 -1 -5.95157e-6 0 -1 -3.82022e-6 0 -1 0.2142091 0.9767878 0 0.3720902 0.9281966 0 0.3720657 0.9282065 0 0.5197675 0.8543078 0 0.5197512 0.8543177 0 0.6532666 0.7571281 0 0.7691202 0.6391042 0 0.7690864 0.6391448 0 0.8636529 0.5040872 0 0.8636532 0.5040867 0 0.934874 0.3549797 0 0.9348971 0.3549188 0 0.9805623 0.1962077 0 0.9805757 0.1961408 0 0.9994871 0.03202503 0 0.9994872 0.03202509 0 0.9911295 -0.1329002 0 0.9911294 -0.1329004 0 0.9557489 -0.294184 0 0.9557586 -0.2941525 0 0.8942998 -0.4474685 0 0.8943274 -0.4474133 0 0.8084546 -0.5885587 0 0.808438 -0.5885815 0 0.7004923 -0.71366 0 0.7004749 -0.7136771 0 0.5736826 -0.8190777 0 0.5736671 -0.8190886 0 0.4308774 -0.9024105 0 0.4308915 -0.9024039 0 0.2763807 -0.9610483 0 0.2763997 -0.9610428 0 0.1146331 -0.9934079 0 0.1146292 -0.9934085 0 -0.05059862 -0.9987192 0 -0.0506004 -0.998719 0 -0.2141849 -0.9767931 0 -0.2141922 -0.9767916 0 -0.3721832 -0.9281593 0 -0.3721827 -0.9281595 0 -0.5196284 -0.8543924 0 -0.519643 -0.8543835 0 -0.6533871 -0.7570241 0 -0.6534043 -0.7570092 0 -0.7689662 -0.6392894 0 -0.7689666 -0.6392889 0 -0.8637741 -0.5038794 0 -0.8637592 -0.5039049 0 -0.9349185 -0.3548626 0 -0.9805657 -0.196191 0 -0.9805591 -0.1962245 0 -0.9994796 -0.03225976 0 -0.9994773 -0.03232926 0 -0.9911201 0.1329702 0 -0.9911247 0.1329359 0 -0.9557489 0.294184 0 -0.9557488 0.2941843 0 -0.8943276 0.4474128 0 -0.8943134 0.4474411 0 -0.808438 0.5885815 0 -0.8084712 0.588536 0 -0.7004575 0.7136942 0 -0.7004923 0.71366 0 -0.5736761 0.8190823 0 -0.4308994 0.9024 0 -0.4308863 0.9024063 0 -0.276316 0.9610669 0 -0.2763165 0.9610668 0 -0.1146509 0.9934058 0 0.05059033 0.9987195 0 0.05058687 0.9987196 0 0.2141945 0.9767911 0 0.4588865 -0.888495 0 0.4588593 -0.888509 1.92345e-5 0.4588352 -0.8885214 0 -0.5399588 -0.8416915 0 -0.5400391 -0.84164 5.19336e-5 -0.5401161 -0.8415905 0 -0.9989008 0.04687541 0 -0.9989008 0.04687482 1.08195e-6 -0.9989005 0.04688185 0 3.92874e-7 0 -1 -5.80936e-7 0 -1 3.87326e-7 0 -1 -1.04057e-6 0 -1 7.90009e-7 0 -1 2.65318e-7 0 -1 -1.9761e-7 0 -1 6.8593e-7 0 -1 1.87886e-7 0 -1 3.95136e-7 0 -1 1.49184e-6 0 -1 -1.23694e-6 0 -1 1.15613e-6 0 -1 -1.41298e-6 0 -1 1.83489e-7 0 -1 -3.83167e-7 0 -1 -1.53325e-6 0 -1 -3.45903e-7 0 -1 -6.99216e-7 0 -1 -3.34319e-7 0 -1 -7.13717e-7 0 -1 1.32178e-7 0 -1 -6.52513e-7 0 -1 1.74826e-7 0 -1 -2.21579e-7 0 -1 -1.47987e-7 0 -1 -5.25317e-7 0 -1 3.42096e-7 0 -1 7.27465e-7 0 -1 -3.6031e-7 0 -1 -2.65319e-7 0 -1 3.22161e-7 0 -1 0.4667397 0.8843893 0.00309962 0.2707321 0.9626545 -8.18738e-4 0.3104985 0.9505674 0.003516197 0.3827298 0.9238588 -0.001760959 0.3825023 0.9239529 -0.001761734 0.2708351 0.9626255 -8.19322e-4 0.1549832 0.9879165 0.001117467 0.1455608 0.9893465 0.002422749 -0.0811603 0.9967001 -0.001372635 -0.02401208 0.9997051 0.003662884 0.03712153 0.9993096 -0.001520812 0.03613144 0.9993459 -0.00151962 -0.08183419 0.9966451 -0.001375198 -0.1988255 0.9800318 0.002480506 -0.1923217 0.9813308 0.001462638 -0.4237285 0.9057877 -0.001723706 -0.35563 0.93462 0.003587305 -0.3131538 0.949702 -9.72518e-4 -0.3127916 0.9498213 -9.72262e-4 -0.4231237 0.9060703 -0.001723587 -0.5275655 0.8495045 0.00408864 -0.5083051 0.8611771 2.71575e-4 -0.6288027 0.7775649 -2.09766e-4 -0.6241949 0.7812688 -2.09303e-4 -0.646611 0.7628132 0.003200352 -0.790442 0.6125365 -6.8854e-4 -0.7662461 0.6425381 0.003460705 -0.7119057 0.7022728 -0.001805901 -0.7127595 0.7014062 -0.001806855 -0.7897109 0.6134787 -6.8836e-4 -0.8573263 0.5147727 8.72161e-4 -0.8638017 0.5038256 0.00257045 -0.9543169 0.2987937 -0.001322567 -0.9365392 0.3505438 0.003676891 -0.9120182 0.4101469 -0.001575946 -0.9122024 0.4097372 -0.00157541 -0.9542174 0.2991111 -0.001323282 -0.9828895 0.1841841 0.00215739 -0.9822872 0.1873747 0.001671373 -0.9986547 -0.05182802 -0.001704812 -0.9998194 0.0186631 0.003584206 -0.9977787 0.06660836 -0.001112997 -0.9977887 0.06645697 -0.001112997 -0.9986487 -0.05194288 -0.001704812 -0.9855392 -0.1694076 0.003696084 -0.9885741 -0.1507353 5.46404e-4 -0.9573751 -0.2888476 -3.76133e-4 -0.9573751 -0.2888476 -3.76157e-4 -0.9573751 -0.2888476 -3.76175e-4 -0.9585535 -0.2849128 -3.76013e-4 -0.9488918 -0.3155843 0.003295421 -0.8647677 -0.502172 -5.14548e-4 -0.8819184 -0.4713898 0.003392398 -0.9181134 -0.3963139 -0.001774609 -0.9181302 -0.3962749 -0.001774847 -0.8637598 -0.5039037 -5.14425e-4 -0.7992641 -0.6009798 6.26555e-4 -0.78961 -0.6136032 0.002698779 -0.6358938 -0.7717756 -0.001209437 -0.6745471 -0.7382229 0.003631472 -0.7227847 -0.6910713 -0.001650273 -0.7226679 -0.6911935 -0.001650571 -0.6348774 -0.772612 -0.001209199 -0.5401642 -0.8415578 0.001848459 -0.5400151 -0.8416533 0.001876413 -0.327414 -0.9448797 -0.001604914 -0.3899795 -0.9208164 0.003644108 -0.4365293 -0.8996894 -0.001193284 -0.437561 -0.8991881 -0.001192748 -0.3266862 -0.9451316 -0.001602053 -0.2133201 -0.9769766 0.003391146 -0.228993 -0.9734278 7.7118e-4 -0.09461361 -0.9955139 -5.60299e-4 -0.09619796 -0.9953622 -5.6032e-4 -0.06088292 -0.9981393 0.00336945 0.1405072 -0.9900797 -3.7821e-4 0.1084752 -0.9940937 0.003307402 0.02207636 -0.9997547 -0.001777529 0.02211642 -0.9997539 -0.001779377 0.1414455 -0.989946 -3.77644e-4 0.2563048 -0.966596 3.88769e-4 0.2750906 -0.961414 0.002867996 0.4764859 -0.8791815 -0.001110374 0.4334384 -0.901176 0.003620445 0.3689184 -0.9294604 -0.001664221 0.3690193 -0.9294202 -0.001663684 0.4755216 -0.8797035 -0.001111149 0.5770277 -0.8167231 0.001613855 0.57953 -0.8149483 0.002054154 0.7527722 -0.6582792 -0.001574635 0.7090245 -0.7051744 0.00365436 0.6694637 -0.7428436 -0.001338481 0.6696084 -0.7427132 -0.001338005 0.7524173 -0.6586849 -0.001574099 0.8252801 -0.5647151 0.003083884 0.817965 -0.5752671 0.001032471 0.8863486 -0.463018 -6.79296e-4 0.8863026 -0.4631062 -6.79157e-4 0.9034112 -0.4287615 0.003451108 0.9348667 -0.3549946 -0.001781582 0.9347807 -0.3552212 -0.001781284 0.962874 -0.2699325 0.003200769 0.9702911 -0.2419407 -1.97371e-4 0.994648 -0.1033216 -1.91533e-4 0.9678196 -0.2503432 0.02556747 0.9920789 -0.1255502 0.004084706 0.9938226 0.110976 -9.69418e-4 0.9977962 0.06625658 0.003572583 0.9999727 -0.007202565 -0.001703202 0.9999698 -0.007588386 -0.001703202 0.9937403 0.1117109 -9.6938e-4 0.9737805 0.2274857 0.001331865 0.9722601 0.2338918 0.00225687 0.8929407 0.450172 -0.001490652 0.9187054 0.3949264 0.003681063 0.9400224 0.3411101 -0.001416444 0.9398225 0.3416602 -0.00141704 0.8927566 0.4505369 -0.001489698 0.8335523 0.552434 0.002736449 0.8387216 0.5445591 0.001266777 0.7626107 0.6468571 -8.15543e-4 0.7622542 0.6472774 -8.14046e-4 0.73473 0.6783506 0.003515958 0.6803861 0.7328518 -0.001757085 0.6807227 0.7325392 -0.001757383 0.6094897 0.7927879 0.00311315 0.5888555 0.8082383 0 0.4893102 0.87211 0 0.9876222 -0.007444322 -0.1566749 0.3644546 -0.9179438 -0.1566911 -0.7138602 -0.6828224 -0.155426 -0.9068761 -0.3914166 -0.1561057 -0.900964 0.4047077 -0.1564471 -0.7039566 0.69276 -0.1566169 0.3778222 0.912639 -0.1560147 0.4062843 0.2045772 -0.8905511 0.342247 -0.2993726 -0.8906419 -0.1488026 -0.4296612 -0.8906453 -0.4540537 -0.02354484 -0.8906632 -0.1923939 0.4114777 -0.890882 0.09228175 0.1266045 -0.9876515 0.1065204 0.1147207 -0.9876703 0.1556458 0.01737236 -0.9876602 0.1566309 -0.001134455 -0.9876566 0.1554183 -0.01969909 -0.9876523 0.1520661 -0.03795945 -0.9876412 0.1464366 -0.05557256 -0.9876579 0.07457858 -0.1376143 -0.9876742 0.05778372 -0.1455687 -0.9876593 0.04016357 -0.15148 -0.987644 0.02200746 -0.1550319 -0.9876644 0.003452479 -0.1566265 -0.987652 -0.09962546 -0.120944 -0.9876474 -0.1131083 -0.1082565 -0.9876676 -0.1253116 -0.09419703 -0.9876356 -0.1354675 -0.07865715 -0.9876546 -0.1439837 -0.06213152 -0.9876277 -0.1493946 0.04681307 -0.9876689 -0.1428681 0.06420421 -0.9876572 -0.1342949 0.08063948 -0.9876549 -0.1238006 0.0959658 -0.9876559 -0.1116008 0.1099826 -0.9876483 0.04244023 0.1509149 -0.9876354 0.05996882 0.1447679 -0.9876468 0.07669538 0.1366977 -0.9876394 -0.06635403 0.1419968 -0.9876407 -0.06633663 0.141875 -0.9876594 -0.04909211 0.1487356 -0.9876577 -0.1565124 -0.00809884 -0.9876428 -0.1564702 -0.00811243 -0.9876494 -0.1563203 0.0104174 -0.9876516 -0.05124551 -0.1479653 -0.987664 -0.05123704 -0.1479519 -0.9876665 -0.06835991 -0.1408688 -0.9876654 0.1179929 -0.1031967 -0.9876376 0.1180076 -0.1032285 -0.9876326 0.1049396 -0.1164962 -0.9876317 0.1398396 0.07046085 -0.987664 0.1399732 0.07048004 -0.9876437 0.1473039 0.05349111 -0.9876439 -0.3734798 0.6011661 -0.7064787 -0.2397033 0.3858295 -0.8908861 -0.2398214 0.386372 -0.8906192 -0.08266085 0.1331695 -0.9876402 -0.08264267 0.1331149 -0.987649 -0.6970881 -0.1200525 -0.7068633 -0.4480581 -0.0771622 -0.8906683 -0.4481931 -0.07713824 -0.8906024 -0.1544454 -0.02658092 -0.9876437 -0.1543511 -0.02659559 -0.987658 -0.1507706 -0.6913196 -0.7066438 -0.09688246 -0.4442347 -0.8906567 -0.0969181 -0.4442832 -0.8906286 -0.03337126 -0.1529878 -0.9876645 -0.0334019 -0.1530311 -0.9876567 0.5839241 -0.3997367 -0.7065715 0.3751804 -0.2568385 -0.8906592 0.3752217 -0.2568945 -0.8906257 0.1293497 -0.08855742 -0.9876368 0.1292309 -0.08839899 -0.9876665 0.5900889 0.3910468 -0.7063127 0.3792086 0.2512937 -0.8905348 0.3788229 0.2511961 -0.8907266 0.1304976 0.08653289 -0.9876651 0.1305083 0.08653271 -0.9876638 0.02619117 0.7075848 -0.706143 -0.5564799 0.6961638 -0.4535265 -0.4419119 0.5528382 -0.7064587 -0.4419477 0.5529412 -0.7063558 -0.2839301 0.3552455 -0.890609 -0.2838912 0.3551257 -0.8906692 -0.09783911 0.1223886 -0.9876481 -0.09779649 0.1222863 -0.9876649 -0.7058919 0.04700577 -0.7067582 -0.8541779 -0.2541143 -0.4536585 -0.6779997 -0.2016954 -0.706849 -0.6788019 -0.2016121 -0.7061024 -0.4359724 -0.1294918 -0.8905953 -0.4358711 -0.1294957 -0.8906443 -0.1501395 -0.04460674 -0.9876581 -0.1500545 -0.0446074 -0.9876709 -0.3093465 -0.636901 -0.70616 -0.08582174 -0.8875944 -0.4525605 -0.06809693 -0.7042666 -0.7066622 -0.0679745 -0.7040446 -0.7068951 -0.04369968 -0.452618 -0.8906331 -0.04378783 -0.4527944 -0.8905392 -0.015078 -0.1559134 -0.9876557 -0.01505154 -0.1558539 -0.9876654 0.4738788 -0.5255835 -0.7065416 0.7898903 -0.4125479 -0.4537373 0.6272436 -0.3275932 -0.706575 0.6274518 -0.3278328 -0.7062789 0.4030073 -0.2105655 -0.8906443 0.4030027 -0.2105565 -0.8906486 0.1387836 -0.07250899 -0.9876648 0.1389117 -0.07264518 -0.9876368 0.6653866 0.2413997 -0.7063901 0.6793378 0.5768162 -0.4536336 0.5395935 0.4581686 -0.706343 0.5396312 0.458182 -0.7063055 0.3465262 0.2942175 -0.8907052 0.3463436 0.2941624 -0.8907945 0.1193422 0.1013597 -0.9876658 0.1194078 0.1013855 -0.9876552 0.03299981 0.8907776 -0.4532399 0.03296804 0.8907247 -0.4533461 -0.07260656 0.8883541 -0.453382 -0.3089525 0.9381361 -0.1563627 -0.1962849 0.9680023 -0.1563454 -0.1772018 0.8739034 -0.4526504 -0.07238852 0.8887769 -0.4525876 -0.05747669 0.7057051 -0.7061704 0.02616059 0.707488 -0.706241 0.01679003 0.4540787 -0.8908034 0.005775094 0.156538 -0.9876551 -0.01278853 0.1561139 -0.9876564 -0.03711885 0.4531243 -0.8906744 -0.09028404 0.4455806 -0.8906778 -0.1406086 0.6939385 -0.7061718 -0.2217004 0.6724294 -0.7061782 -0.2791081 0.8465516 -0.4532651 -0.3773791 0.8075621 -0.4532423 -0.01274931 0.1562842 -0.9876298 -0.03112757 0.1536547 -0.9876343 -0.09028071 0.4456637 -0.8906366 -0.1424693 0.4317836 -0.8906545 -0.2217332 0.6720139 -0.7065632 -0.2996746 0.6410573 -0.7065696 -0.3774079 0.8073333 -0.4536256 -0.4702314 0.7570475 -0.4536095 -0.5211439 0.8390114 -0.1564261 -0.6212465 0.7678553 -0.1563687 -0.8892676 0.05913889 -0.453548 -0.8894047 0.05922627 -0.4532679 -0.89017 -0.04619091 -0.4532813 -0.9457018 -0.285157 -0.1559924 -0.9734656 -0.1673296 -0.156095 -0.8785956 -0.1510265 -0.4530572 -0.8903356 -0.04610335 -0.452965 -0.7071518 -0.03662031 -0.7061128 -0.706515 0.04733198 -0.7061135 -0.4538819 0.03040522 -0.8905429 -0.389208 -0.8018082 -0.4534541 -0.3895379 -0.8019938 -0.4528423 -0.2918375 -0.8425014 -0.452794 -0.09345716 -0.9833064 -0.156123 -0.2106257 -0.9650153 -0.1561487 -0.1900849 -0.8709235 -0.4531666 -0.2917039 -0.8424069 -0.4530556 -0.2314345 -0.6683703 -0.7069082 -0.3087542 -0.6363733 -0.7068945 -0.1983565 -0.408833 -0.890792 0.5968073 -0.6619809 -0.4534341 0.5967969 -0.6619015 -0.4535637 0.6707026 -0.5868279 -0.4536421 0.8753605 -0.4574548 -0.1564587 0.8151791 -0.5576654 -0.1565014 0.7356026 -0.5032423 -0.4534713 0.6707383 -0.5869255 -0.4534629 0.5327828 -0.466215 -0.7062479 0.47399 -0.5258365 -0.7062787 0.3042588 -0.3375421 -0.8907817 0.8377029 0.3040566 -0.4536556 0.8379638 0.3040069 -0.4532071 0.7959551 0.4012846 -0.4532398 0.7532759 0.6390068 -0.1557105 0.8233994 0.5456782 -0.1557201 0.7431194 0.4924807 -0.4530302 0.7961021 0.4012551 -0.4530075 0.6317297 0.3184168 -0.7067732 0.6649457 0.2414196 -0.7067983 0.4274699 0.155196 -0.8906087 0.0766437 0.1366503 -0.98765 0.2221778 0.3961241 -0.8909112 0.222572 0.3964791 -0.8906548 0.3465734 0.6173805 -0.706207 0.3460624 0.6169731 -0.7068133 0.436001 0.7773303 -0.4534984 0.4363516 0.7775099 -0.452853 0.4834125 0.8613802 -0.1560022 0.4832932 0.8613708 -0.1564236 0.059987 0.144792 -0.9876421 0.1740182 0.4200221 -0.8906734 0.1737148 0.419698 -0.8908855 0.2707085 0.6540202 -0.7063813 0.2708021 0.6541272 -0.7062463 0.3409024 0.8234757 -0.4535122 0.3409643 0.8235294 -0.4533681 0.3778262 0.9125732 -0.1563898 0.3780699 0.912601 -0.1556361 0.267472 0.9507545 -0.1566033 0.04239338 0.1508513 -0.9876471 0.1229018 0.437316 -0.8908703 0.1231486 0.4376687 -0.890663 0.1917365 0.6814183 -0.7063329 0.1917057 0.6814057 -0.7063535 0.2414174 0.8581079 -0.4531762 0.241249 0.857987 -0.4534946 0.267346 0.950796 -0.156567 0.2674024 0.9508022 -0.1564328 0.02430391 0.154884 -0.9876337 0.07044428 0.4489099 -0.890796 0.07036304 0.4487518 -0.8908821 0.1096748 0.6994709 -0.7061954 0.1096156 0.6993977 -0.7062771 0.1380178 0.880625 -0.4532668 0.1380765 0.8807104 -0.4530829 0.1529647 0.9756801 -0.1570042 0.1530709 0.9757114 -0.1567061 -0.1963758 0.9679419 -0.1566044 -0.08082062 0.9843243 -0.1567597 -0.08044904 0.9843007 -0.1570994 -0.08016216 0.9844431 -0.156352 0.03656536 0.9870204 -0.1563771 0.03666669 0.9870765 -0.155999 0.03568351 0.9869487 -0.1570316 0.02431231 0.1548995 -0.987631 0.005827486 0.15669 -0.9876307 0.01690024 0.4543262 -0.8906751 -0.03711324 0.4531136 -0.8906799 -0.05773639 0.7049073 -0.7069457 -0.1407628 0.6931485 -0.7069166 -0.1773805 0.8734633 -0.4534292 -0.2791281 0.8464735 -0.4533985 -0.3093098 0.9379801 -0.1565915 -0.5211004 0.839102 -0.1560844 -0.4179527 0.8949599 -0.1560853 -0.4181922 0.8949052 -0.1557565 -0.418509 0.8946144 -0.1565744 -0.3092828 0.9379875 -0.1566003 -0.6164981 0.7716339 -0.1565607 -0.6167297 0.7715944 -0.1558422 -0.5564843 0.6962382 -0.4534067 -0.4702365 0.7571794 -0.4533839 -0.3735389 0.6014778 -0.7061823 -0.2996945 0.6414843 -0.7061737 -0.1924395 0.4119037 -0.8906752 -0.1424641 0.4317698 -0.8906621 -0.04908823 0.1487709 -0.9876526 -0.03113991 0.153541 -0.9876515 -0.1115538 0.1098911 -0.9876638 -0.3236544 0.3188337 -0.8908384 -0.3238112 0.3191367 -0.8906728 -0.5042222 0.4969338 -0.7062696 -0.5041793 0.4968658 -0.7063482 -0.6349192 0.6257102 -0.4531715 -0.6348775 0.6255142 -0.4535004 -0.7035278 0.6931566 -0.1567887 -0.7033353 0.6938095 -0.1547515 -0.7800214 0.6059775 -0.1560705 -0.1238227 0.09599936 -0.9876498 -0.3593871 0.278633 -0.8906204 -0.3591378 0.2782548 -0.8908392 -0.5593147 0.4333468 -0.7066665 -0.5595215 0.4337296 -0.706268 -0.7042877 0.5459451 -0.4537875 -0.7043961 0.5462489 -0.4532532 -0.7805945 0.6053347 -0.1556992 -0.7806609 0.6049645 -0.1568006 -0.134298 0.08064156 -0.9876544 -0.3896867 0.2339941 -0.890725 -0.3898188 0.2341564 -0.8906245 -0.6068602 0.364525 -0.7062876 -0.6066229 0.3642085 -0.7066547 -0.7641468 0.4587668 -0.4534456 -0.7640632 0.4585993 -0.4537555 -0.8468419 0.5082765 -0.1565691 -0.8468222 0.5084688 -0.1560504 -0.14287 0.06420773 -0.9876566 -0.4145825 0.1863211 -0.8907334 -0.414605 0.1863417 -0.8907186 -0.6456601 0.2901986 -0.7063341 -0.6456949 0.2902272 -0.7062906 -0.8131514 0.3655032 -0.4529816 -0.812986 0.3652321 -0.4534967 -0.900834 0.4047003 -0.157213 -0.9008551 0.4051235 -0.1559978 -0.9425967 0.2955079 -0.1555208 -0.1494503 0.0468555 -0.9876585 -0.4340183 0.1360757 -0.8905682 -0.4337501 0.1358626 -0.8907313 -0.6753031 0.2115246 -0.7065572 -0.6754958 0.2117028 -0.7063196 -0.8503394 0.2664932 -0.4537667 -0.850629 0.2668572 -0.4530096 -0.9425137 0.2956832 -0.1556903 -0.9424629 0.2950643 -0.1571647 -0.1538839 0.02884364 -0.9876679 -0.4471134 0.08380788 -0.8905425 -0.4470489 0.08375799 -0.8905795 -0.6953842 0.1303003 -0.7067268 -0.6955484 0.1304186 -0.7065433 -0.8759929 0.1642552 -0.453494 -0.8758609 0.1641193 -0.4537982 -0.970924 0.1819315 -0.1555876 -0.9709284 0.1819314 -0.1555609 -0.9734517 -0.1673353 -0.1561752 -0.9863893 -0.05133056 -0.1562099 -0.9863747 -0.05119186 -0.1563473 -0.9863765 -0.05118036 -0.1563394 -0.9855263 0.06555044 -0.1563366 -0.9856511 0.06578922 -0.155447 -0.985647 0.06572091 -0.1555025 -0.9468018 -0.2814154 -0.1561148 -0.9468521 -0.281681 -0.1553288 -0.8541845 -0.2541142 -0.4536461 -0.8783165 -0.1511319 -0.4535628 -0.6973237 -0.1199861 -0.7066422 -0.7065687 -0.03683078 -0.7066855 -0.4536855 -0.02364057 -0.8908483 -0.4532948 0.03015899 -0.8908504 -0.156275 0.01039731 -0.9876589 -0.1539276 0.02886348 -0.9876605 -0.143697 -0.06210273 -0.9876713 -0.4171323 -0.1802777 -0.8907866 -0.4174562 -0.1803043 -0.8906294 -0.6495124 -0.2805359 -0.706706 -0.6501011 -0.2805477 -0.7061597 -0.8186896 -0.3533105 -0.45268 -0.8181583 -0.3533791 -0.4535861 -0.9066475 -0.391601 -0.1569685 -0.9068444 -0.3914727 -0.1561489 -0.8531268 -0.4979197 -0.1557261 -0.1356323 -0.07869493 -0.987629 -0.3932545 -0.2281575 -0.8906712 -0.3929972 -0.2281223 -0.8907937 -0.6123253 -0.3554207 -0.7062109 -0.6117854 -0.3553606 -0.7067089 -0.7706996 -0.4476578 -0.4534584 -0.7711814 -0.4476274 -0.452669 -0.854234 -0.4958241 -0.1563417 -0.8540626 -0.4959451 -0.1568934 -0.1251962 -0.09415984 -0.9876538 -0.363235 -0.2731862 -0.8907467 -0.3633843 -0.2732301 -0.8906723 -0.5655441 -0.4252439 -0.7066312 -0.566016 -0.4253462 -0.7061916 -0.7126727 -0.5355491 -0.4530838 -0.7124149 -0.5355461 -0.4534927 -0.7896226 -0.5935945 -0.1553766 -0.7895136 -0.5936372 -0.1557671 -0.113287 -0.1083422 -0.9876376 -0.3285331 -0.3141999 -0.8906989 -0.3284823 -0.3141652 -0.8907299 -0.5117178 -0.4894158 -0.7061284 -0.5111776 -0.4892171 -0.7066571 -0.6439858 -0.6163379 -0.4532218 -0.6441314 -0.616352 -0.4529955 -0.7136178 -0.6828265 -0.1565175 -0.7140206 -0.6826964 -0.1552426 -0.6271699 -0.76323 -0.1553644 -0.09950971 -0.1208689 -0.9876683 -0.2888458 -0.3508455 -0.8907725 -0.2889707 -0.3509153 -0.8907045 -0.4499614 -0.5464131 -0.7063764 -0.4501931 -0.5465363 -0.7061334 -0.5665662 -0.6878055 -0.4537911 -0.5668782 -0.6878965 -0.4532632 -0.6281336 -0.7622424 -0.1563158 -0.6280504 -0.7622659 -0.1565354 -0.08463919 -0.1318718 -0.9876468 -0.2454531 -0.3824447 -0.8907799 -0.245485 -0.382457 -0.8907659 -0.3824442 -0.5958395 -0.7061954 -0.3822928 -0.5957409 -0.7063605 -0.4813826 -0.750133 -0.4534 -0.4811432 -0.7500472 -0.4537957 -0.533317 -0.8313642 -0.1562265 -0.5336071 -0.8313481 -0.1553182 -0.2107146 -0.9650428 -0.1558586 -0.3226926 -0.9335673 -0.1559543 -0.3232699 -0.9332506 -0.1566526 -0.3233866 -0.9332486 -0.1564239 -0.431313 -0.8885443 -0.1563912 -0.4311217 -0.88853 -0.1569991 -0.4321687 -0.8881632 -0.1561942 -0.09501218 -0.9830957 -0.1565108 -0.09478938 -0.9832428 -0.1557199 -0.08553123 -0.8871804 -0.4534264 -0.1899827 -0.8708623 -0.4533272 -0.1508265 -0.6913719 -0.7065808 -0.2316727 -0.6686303 -0.7065843 -0.1489272 -0.4298177 -0.890549 -0.1987014 -0.4091821 -0.8905549 -0.06845438 -0.1409695 -0.9876445 -0.08464759 -0.1318794 -0.987645 0.02180361 -0.9873766 -0.1568826 0.003482401 -0.1565304 -0.987667 0.01011466 -0.4547452 -0.8905642 0.01008993 -0.4548135 -0.8905295 0.01568925 -0.7072889 -0.7067506 0.01574021 -0.7071521 -0.7068863 0.01984173 -0.8914118 -0.4527597 0.01981234 -0.8914335 -0.4527184 0.02194499 -0.9874234 -0.1565682 0.02184557 -0.9874528 -0.1563966 0.1396541 -0.9777803 -0.1563407 0.02199548 -0.1551001 -0.9876539 0.0638656 -0.4503726 -0.8905537 0.0638774 -0.4503517 -0.8905634 0.09934777 -0.700457 -0.7067461 0.09933662 -0.700446 -0.7067585 0.1251949 -0.8827923 -0.4527737 0.1252037 -0.8827844 -0.4527867 0.1386922 -0.9778748 -0.1566065 0.1387692 -0.9778289 -0.1568248 0.04017043 -0.1513306 -0.9876667 0.1166583 -0.4394702 -0.8906497 0.1166366 -0.4396506 -0.8905635 0.1814199 -0.6838593 -0.706699 0.1814271 -0.6837844 -0.7067695 0.2286367 -0.861711 -0.4529674 0.2286013 -0.8618599 -0.4527019 0.2532099 -0.9546377 -0.1566897 0.2531474 -0.954676 -0.1565574 0.05779224 -0.1456459 -0.9876474 0.1677688 -0.4228333 -0.8905423 0.1677591 -0.4226104 -0.89065 0.2611685 -0.6579146 -0.7063565 0.261167 -0.65758 -0.7066686 0.3288912 -0.8280939 -0.4539726 0.3287689 -0.8286806 -0.4529895 0.364259 -0.918128 -0.1560658 0.3643735 -0.9179964 -0.1565723 0.4697355 -0.8688827 -0.1561771 0.07460182 -0.1377114 -0.9876589 0.2166318 -0.399901 -0.8905897 0.2166483 -0.3999644 -0.8905571 0.3370537 -0.6222513 -0.7065395 0.3370869 -0.6224732 -0.7063282 0.4244226 -0.7837361 -0.4534571 0.4244485 -0.7834581 -0.453913 0.470538 -0.8685501 -0.1556107 0.4706572 -0.8684077 -0.1560453 0.09035217 -0.1278149 -0.9876739 0.2622939 -0.3710378 -0.8908047 0.2624051 -0.3714633 -0.8905946 0.4083594 -0.5780529 -0.7064684 0.40833 -0.5780205 -0.7065117 0.5142595 -0.7279598 -0.4534446 0.5142633 -0.7279488 -0.4534577 0.5699398 -0.8067368 -0.1560273 0.5699399 -0.8067212 -0.156107 0.8151628 -0.5577834 -0.1561647 0.7431558 -0.6506432 -0.1561498 0.7434068 -0.650437 -0.1558142 0.7435009 -0.6501737 -0.1564633 0.6613554 -0.7335861 -0.1563983 0.6612915 -0.73378 -0.155758 0.6613754 -0.733672 -0.1559106 0.8754321 -0.4574255 -0.1561424 0.875355 -0.4574855 -0.1563996 0.7901151 -0.4129411 -0.4529876 0.735737 -0.503523 -0.4529412 0.5837779 -0.3995324 -0.7068078 0.5325234 -0.4656727 -0.7068011 0.3421385 -0.2991911 -0.8907446 0.3042793 -0.3376162 -0.8907467 0.104887 -0.1163796 -0.9876511 0.09040004 -0.1279619 -0.9876506 0.9233893 -0.3508584 -0.1557267 0.1465453 -0.05566102 -0.9876368 0.4248628 -0.1613715 -0.8907586 0.4250121 -0.1614993 -0.8906642 0.6618129 -0.2514815 -0.70623 0.6617804 -0.2514483 -0.7062722 0.8329932 -0.3165027 -0.4538155 0.8330212 -0.316536 -0.453741 0.9233829 -0.3508848 -0.1557046 0.9234046 -0.3506253 -0.1561606 0.9560747 -0.2476887 -0.1567534 0.1519621 -0.03790295 -0.9876593 0.4410939 -0.110006 -0.8906934 0.4410286 -0.1099688 -0.8907304 0.6862792 -0.1711158 -0.706923 0.6868529 -0.1715403 -0.7062627 0.865156 -0.2160825 -0.4525633 0.8646506 -0.2155422 -0.4537853 0.9584245 -0.2389112 -0.1560255 0.9584346 -0.239003 -0.1558227 0.1554704 -0.01972037 -0.9876437 0.4512327 -0.05723899 -0.8905688 0.4510025 -0.0571208 -0.8906931 0.702256 -0.08895361 -0.7063454 0.7017531 -0.08865457 -0.7068826 0.884331 -0.111734 -0.4532926 0.8846522 -0.1119926 -0.4526014 0.9798244 -0.1240463 -0.1567059 0.9798088 -0.1239873 -0.1568503 0.1566665 -0.001143574 -0.9876509 0.4546658 -0.003317534 -0.890656 0.4547971 -0.003369927 -0.8905887 0.7076162 -0.005236387 -0.7065777 0.707822 -0.005321085 -0.7063708 0.8915398 -0.006709456 -0.4528929 0.8913748 -0.006595194 -0.4532192 0.9876454 -0.007309198 -0.1565355 0.987547 -0.007148444 -0.157162 0.9816672 0.1103385 -0.1554185 0.1556708 0.017367 -0.9876564 0.4518745 0.05040794 -0.8906563 0.4518952 0.0504024 -0.8906461 0.7034466 0.07847529 -0.7064025 0.7032248 0.07852196 -0.7066182 0.8857561 0.09892612 -0.4534862 0.8860777 0.09875595 -0.4528946 0.9816899 0.1094001 -0.1559378 0.9815603 0.1096375 -0.1565857 0.1525041 0.03567069 -0.9876589 0.4428567 0.1035827 -0.8905889 0.4427133 0.1036009 -0.8906581 0.6892086 0.1612728 -0.7063871 0.6892323 0.1612648 -0.7063657 0.8677086 0.2030352 -0.4537163 0.8678127 0.2029911 -0.4535369 0.9617223 0.2249637 -0.1564661 0.9619444 0.2247176 -0.1554518 0.8233907 0.5456824 -0.155752 0.8818514 0.4450263 -0.1558518 0.8819763 0.4446468 -0.156228 0.8819654 0.4446689 -0.1562264 0.9284485 0.3369885 -0.1562758 0.928524 0.3369263 -0.1559613 0.9282417 0.3374674 -0.1564711 0.7529556 0.6393763 -0.1557433 0.7529727 0.6393042 -0.1559566 0.6793756 0.5768222 -0.4535693 0.7427718 0.4924901 -0.4535897 0.5896588 0.3909587 -0.7067205 0.6318445 0.3184254 -0.7066667 0.405811 0.2045098 -0.8907824 0.4271242 0.1551979 -0.8907743 0.1472065 0.05348736 -0.9876585 0.1524977 0.03566819 -0.9876601 0.6723452 0.7235416 -0.1563317 0.1066033 0.1147643 -0.9876564 0.3096451 0.3333568 -0.8905017 0.30915 0.3330963 -0.8907712 0.4812306 0.5185126 -0.7067968 0.4816679 0.5187175 -0.7063485 0.6064678 0.6531208 -0.4534645 0.6063383 0.6530838 -0.4536911 0.6721001 0.7239058 -0.1556982 0.672085 0.7239224 -0.1556859 0.09219241 0.1265392 -0.9876682 0.267751 0.3675158 -0.8906411 0.2679749 0.3676728 -0.890509 0.4166436 0.571662 -0.7068314 0.4166679 0.5716702 -0.7068105 0.5251548 0.7205076 -0.452859 0.5248159 0.720395 -0.4534308 0.5815836 0.7983179 -0.1563621 0.5816177 0.7983102 -0.1562755 1.20633e-6 0 -1 -6.91391e-6 0 -1 2.78671e-6 0 -1 -1.24955e-6 0 -1 2.57064e-6 0 -1 -6.83284e-6 0 -1 -0.9268632 0.3753993 0 -0.9268899 0.3753333 -3.65439e-5 -0.9269168 0.3752671 0 -0.1382824 0.9903929 0 -0.1382848 0.9903925 3.84672e-6 -0.138286 0.9903923 0 0.9268659 -0.3753927 0 0.9268899 -0.3753333 -3.65439e-5 0.9269142 -0.3752738 0 0.1382835 -0.9903928 0 0.138283 -0.9903928 0 1.56234e-6 0 -1 -1.49233e-6 0 -1 -6.85771e-7 0 -1 -1.97647e-7 0 -1 -7.81018e-7 0 -1 1.92701e-7 0 -1 1.54904e-6 0 -1 3.94571e-7 0 -1 -5.90834e-7 0 -1 1.90477e-7 0 -1 -3.83212e-7 0 -1 0 0 -1 -7.51446e-7 0 -1 -3.89012e-7 0 -1 1.46764e-6 0 -1 -3.83179e-7 0 -1 3.93141e-7 0 -1 -9.40861e-7 0 -1 2.62658e-7 0 -1 -5.98554e-7 0 -1 0 0 -1 -1.93659e-7 0 -1 7.40153e-7 0 -1 -3.60268e-7 0 -1 9.66836e-7 0 -1 -6.91768e-7 0 -1 -3.49752e-7 0 -1 -3.56804e-7 0 -1 1.32173e-7 0 -1 -3.49664e-7 0 -1 2.65025e-7 0 -1 -3.30249e-7 0 -1 4.74684e-7 0 -1 -0.2218968 0.9750652 0.003109693 -0.4216215 0.9067716 -8.61946e-4 -0.3833352 0.9236028 0.003502607 -0.3113549 0.9502921 -0.00175625 -0.3117496 0.9501627 -0.001756906 -0.4206465 0.9072243 -8.61667e-4 -0.5259033 0.8505437 0.001087248 -0.5340059 0.8454774 0.002394855 -0.7106624 0.7035319 -0.001413643 -0.6691492 0.7431192 0.003638505 -0.6228902 0.7823078 -0.001503288 -0.622536 0.7825898 -0.001505732 -0.7110718 0.703118 -0.001413762 -0.7891509 0.6141945 0.00244832 -0.785281 0.619138 0.001486301 -0.9112859 0.4117707 -0.001722514 -0.8784999 0.4777292 0.003562331 -0.8563218 0.5164418 -9.46505e-4 -0.8560032 0.5169697 -9.45715e-4 -0.9111588 0.412052 -0.001722753 -0.9535921 0.3010736 0.004090905 -0.9466039 0.322399 2.90631e-4 -0.9834935 0.1809441 -1.889e-4 -0.9825313 0.1860975 -1.89389e-4 -0.9874658 0.1578009 0.003185093 -0.9987541 -0.04989767 -7.04613e-4 -0.9999296 -0.01135843 0.003444194 -0.9976357 0.06870269 -0.001781165 -0.9976299 0.06878572 -0.001781105 -0.9986951 -0.0510658 -7.04605e-4 -0.9858565 -0.1675895 8.21943e-4 -0.9836087 -0.1802985 0.002547204 -0.9188657 -0.394568 -0.001326978 -0.9389834 -0.3439431 0.003646135 -0.9591051 -0.2830457 -0.001582086 -0.9591649 -0.2828434 -0.001581966 -0.9191418 -0.3939249 -0.001327395 -0.8657265 -0.500513 0.0021739 -0.8674067 -0.497597 0.00166583 -0.7236875 -0.6901258 -0.001701056 -0.7708104 -0.6370544 0.003623902 -0.800593 -0.5992076 -0.001089513 -0.8011411 -0.5984747 -0.001089811 -0.7243354 -0.6894457 -0.001700818 -0.6373372 -0.7705761 0.003730118 -0.6520445 -0.7581806 5.32308e-4 -0.5440587 -0.8390471 -3.49214e-4 -0.5417683 -0.8405279 -3.48595e-4 -0.5145899 -0.8574302 0.003301739 -0.3289145 -0.9443597 -5.5117e-4 -0.3622776 -0.9320641 0.003390908 -0.43883 -0.8985683 -0.001789271 -0.4383533 -0.898801 -0.001789987 -0.3298583 -0.9440304 -5.50748e-4 -0.2151434 -0.9765823 6.17187e-4 -0.1994152 -0.9799113 0.002712547 0.02035772 -0.999792 -0.001223683 -0.03108227 -0.9995102 0.003644824 -0.09795427 -0.9951897 -0.001602232 -0.09872752 -0.9951132 -0.001602351 0.0198943 -0.9998013 -0.001222372 0.1384069 -0.9903736 0.001879394 0.138298 -0.990389 0.001862525 0.3671402 -0.9301643 -0.001628756 0.3037908 -0.9527319 0.003635346 0.2544958 -0.9670732 -0.001222968 0.2542033 -0.96715 -0.001222193 0.3668621 -0.9302739 -0.001630008 0.4745028 -0.8802475 0.00340557 0.4602813 -0.8877729 7.84031e-4 0.5773218 -0.8165166 -5.55557e-4 0.5750287 -0.8181332 -5.55675e-4 0.6037678 -0.7971531 0.003389358 0.7513745 -0.659876 -3.93418e-4 0.7297714 -0.6836833 0.003274261 0.6682351 -0.7439481 -0.001784861 0.6681376 -0.7440357 -0.001784563 0.7510253 -0.6602734 -3.93528e-4 0.8240344 -0.5665397 3.80439e-4 0.8349049 -0.5503869 0.002856016 0.9341369 -0.3569135 -0.001114308 0.9158366 -0.4015351 0.003604173 0.8853572 -0.4649085 -0.001672267 0.8853334 -0.4649538 -0.001672148 0.9339694 -0.3573514 -0.00111407 0.969778 -0.2439839 0.00160098 0.9705327 -0.2409608 0.002045989 0.9999532 -0.009545147 -0.001555562 0.9973025 -0.0733118 0.003652632 0.9918007 -0.1277869 -0.001345753 0.9918353 -0.1275191 -0.001345276 0.9999543 -0.009432673 -0.001555562 0.9940385 0.1089858 0.003088295 0.995377 0.09603977 0.001010298 0.9738716 0.2270982 -7.27944e-4 0.9742035 0.2256703 -7.27989e-4 0.9647733 0.2630606 0.003424048 0.940733 0.3391437 -0.001781404 0.9406531 0.3393651 -0.001781165 0.9064298 0.4223445 0.003194093 0.8939201 0.4482263 -1.82752e-4 0.8220225 0.569455 -1.8561e-4 0.8919416 0.4515416 0.02346467 0.8346809 0.5507189 0.004093825 0.6817563 0.7315788 -9.6993e-4 0.7140404 0.7000954 0.003588318 0.7637097 0.6455577 -0.001708328 0.7636661 0.6456092 -0.001706838 0.6820383 0.7313159 -9.7005e-4 0.5906381 0.8069356 0.001354932 0.5854209 0.8107265 0.002256453 0.3846722 0.9230521 -0.001492857 0.4399929 0.8979939 0.003657579 0.4907351 0.8713077 -0.001391589 0.4912498 0.8710178 -0.001392364 0.3841717 0.9232605 -0.001492321 0.2728953 0.9620398 0.002740204 0.2819335 0.9594332 0.001265645 0.1567072 0.9876448 -8.27785e-4 0.1568494 0.9876223 -8.28406e-4 0.1157704 0.9932699 0.003501057 0.03893589 0.9992402 -0.001778423 0.03903597 0.9992363 -0.001778602 -0.05381006 0.9985465 0.003068983 -0.07918721 0.9968599 0 -0.1967066 0.9804625 0 0.7542458 0.6376637 -0.1565192 0.8744075 -0.4592501 -0.1565281 -0.09751975 -0.9829055 -0.1561623 -0.4329729 -0.8877728 -0.1561861 -0.947413 -0.2793751 -0.1560715 -0.9855 0.06795972 -0.1554713 -0.3079188 0.9384717 -0.1563875 0.1747304 0.4196236 -0.8907219 0.4542635 -0.004217088 -0.8908575 0.1667945 -0.4227166 -0.8907807 -0.3294199 -0.3137215 -0.89054 -0.4141132 0.1870688 -0.8907949 -0.01245582 0.1560385 -0.9876725 0.006098866 0.1565328 -0.987654 0.1069481 0.1146743 -0.9876295 0.1196042 0.1011469 -0.987656 0.1308267 0.08633548 -0.9876389 0.1399965 0.07018733 -0.9876613 0.1473501 0.05314409 -0.9876557 0.1463552 -0.05592924 -0.9876499 0.1386581 -0.07283216 -0.9876586 0.1290834 -0.08872199 -0.9876568 0.1176168 -0.1033263 -0.9876691 0.1045833 -0.1165037 -0.9876686 0.003128111 -0.156659 -0.9876478 -0.01537507 -0.1558047 -0.9876683 -0.0336616 -0.1529268 -0.9876641 -0.05158376 -0.1479042 -0.9876555 -0.06867015 -0.1407345 -0.987663 -0.1439608 -0.06178313 -0.9876529 -0.1502453 -0.04436272 -0.987653 -0.1544901 -0.02624297 -0.9876458 -0.1564105 -0.007819056 -0.9876613 -0.1563125 0.01074272 -0.9876493 -0.06606543 0.1420627 -0.9876505 -0.04875767 0.1489679 -0.9876393 -0.03080505 0.1535303 -0.9876638 -0.1427688 0.06450176 -0.9876521 -0.1427432 0.0644831 -0.987657 -0.134142 0.08088177 -0.9876559 -0.1133624 -0.10802 -0.9876643 -0.1134899 -0.1080843 -0.9876427 -0.125473 -0.09388625 -0.9876447 0.05752199 -0.1458302 -0.987636 0.05751723 -0.1457654 -0.9876459 0.0398963 -0.1515383 -0.9876459 0.1568177 -0.001514375 -0.9876264 0.1566441 -0.001453936 -0.987654 0.1553813 -0.01997071 -0.9876527 0.06031608 0.1446658 -0.9876405 0.06016445 0.1444913 -0.9876753 0.07683491 0.1363558 -0.9876759 -0.6747566 0.2128661 -0.7066764 -0.4333054 0.136695 -0.8908204 -0.4335363 0.1368651 -0.890682 -0.1493998 0.04716598 -0.9876514 -0.149409 0.04717361 -0.9876496 -0.4513034 -0.5454683 -0.7062504 -0.2899937 -0.3505082 -0.8905323 -0.2896419 -0.3502895 -0.8907328 -0.09977573 -0.1206653 -0.9876663 -0.09992945 -0.1207644 -0.9876386 0.3358072 -0.622739 -0.7067034 0.2157093 -0.4000203 -0.8907601 0.2157939 -0.4004789 -0.8905334 0.07435148 -0.1379866 -0.9876394 0.07431781 -0.137795 -0.9876687 0.7036955 0.07713139 -0.7063027 0.4515715 0.04949402 -0.8908612 0.451681 0.04946064 -0.8908076 0.1558957 0.01707327 -0.987626 0.155727 0.01710635 -0.987652 0.1928843 0.6810067 -0.7064174 0.123866 0.437326 -0.8907318 0.1238335 0.4372626 -0.8907675 0.04270875 0.1508122 -0.9876396 0.04271382 0.1508163 -0.9876386 -0.440725 0.553619 -0.7065886 -0.8755527 0.1658962 -0.4537467 -0.6951678 0.1317253 -0.7066755 -0.6955316 0.1319455 -0.7062764 -0.4466568 0.08474117 -0.8906832 -0.4464179 0.08460694 -0.8908159 -0.1539425 0.02917844 -0.9876489 -0.1540104 0.0292133 -0.9876373 -0.566426 -0.4240382 -0.7066493 -0.4831519 -0.7491689 -0.4531117 -0.3837068 -0.5949816 -0.7062337 -0.3831176 -0.5945743 -0.7068963 -0.2462176 -0.3821057 -0.8907145 -0.2463518 -0.3822125 -0.8906316 -0.08490836 -0.1317331 -0.9876422 -0.08483105 -0.1316713 -0.987657 0.1800932 -0.6842283 -0.7066811 0.5127593 -0.7289293 -0.4535858 0.407072 -0.5786817 -0.7066965 0.4071069 -0.5788164 -0.7065662 0.2617216 -0.3721135 -0.8905242 0.2617119 -0.3721093 -0.8905288 0.09006375 -0.1280519 -0.9876697 0.09005433 -0.1280217 -0.9876744 0.7019972 -0.09052741 -0.7064027 0.8681679 0.201119 -0.4536912 0.6896588 0.1597701 -0.7062892 0.6893225 0.1598221 -0.7066055 0.4426681 0.1026333 -0.8907926 0.4428969 0.1026105 -0.8906815 0.1526314 0.03536009 -0.9876504 0.152624 0.03536403 -0.9876514 0.3475302 0.616338 -0.7066472 0.1399677 0.8803225 -0.4532564 0.1111328 0.6989645 -0.7064688 0.1109619 0.6987289 -0.7067287 0.07128393 0.4488657 -0.8907516 0.07139974 0.4490919 -0.8906283 0.0246101 0.1547929 -0.9876404 0.02462601 0.1548219 -0.9876355 -0.5551285 0.6976249 -0.4529371 -0.5550999 0.6972948 -0.4534801 -0.6336464 0.6267749 -0.4534816 -0.8454482 0.5107475 -0.1560592 -0.7793598 0.6068332 -0.1560513 -0.703355 0.5476598 -0.4531673 -0.6336831 0.6269869 -0.453137 -0.5031437 0.4978265 -0.7064101 -0.4407698 0.5538076 -0.7064129 -0.2831316 0.3557341 -0.8906682 -0.09758758 0.1225793 -0.9876493 -0.1113903 0.1101942 -0.9876484 -0.3232396 0.3197649 -0.8906552 -0.3587824 0.279318 -0.8906496 -0.5584304 0.4347432 -0.7065083 -0.6059202 0.3656408 -0.7065179 -0.7632488 0.4605714 -0.4531287 -0.8123478 0.3671195 -0.4531162 -0.1113997 0.1102137 -0.9876453 -0.1236488 0.09628367 -0.9876439 -0.3588914 0.2794688 -0.8905584 -0.3894626 0.2349382 -0.8905746 -0.6057478 0.3653963 -0.7067922 -0.6446927 0.2913132 -0.7067589 -0.8122869 0.3670527 -0.4532796 -0.8500508 0.2682107 -0.4532955 -0.9418566 0.2971793 -0.1568145 -0.9713314 0.1787273 -0.1567548 -0.9713313 0.1787273 -0.1567548 -0.9713313 0.1787274 -0.1567548 -0.7136691 -0.5340788 -0.4532507 -0.7133865 -0.5340688 -0.4537072 -0.6450991 -0.6148543 -0.4536533 -0.537572 -0.8286726 -0.1559426 -0.6296792 -0.7610462 -0.1559257 -0.5684322 -0.6870348 -0.4526236 -0.645732 -0.6149669 -0.4525991 -0.5123095 -0.4879127 -0.7067391 -0.5663595 -0.4240374 -0.7067031 -0.3640528 -0.2725529 -0.8906068 0.2267323 -0.8623297 -0.4527474 0.2268643 -0.8619078 -0.4534838 0.3272001 -0.8290205 -0.4535033 0.5701919 -0.8064257 -0.156713 0.4687863 -0.8693043 -0.1566826 0.4231204 -0.7846062 -0.4531692 0.3271605 -0.8292295 -0.4531494 0.2597311 -0.6583209 -0.706508 0.1800748 -0.6843672 -0.7065512 0.1156906 -0.4396825 -0.8906712 0.8838446 -0.1138193 -0.4537224 0.8840783 -0.1140058 -0.4532198 0.8913394 -0.008257389 -0.4532614 0.9618977 0.2243617 -0.1562519 0.9818295 0.1075729 -0.1563298 0.8862876 0.09709602 -0.4528431 0.8915407 -0.008373498 -0.4528635 0.7072331 -0.006660997 -0.7069492 0.7015224 -0.0902369 -0.7069115 0.4511641 -0.05804902 -0.8905512 0.4378467 0.7764001 -0.4533138 0.4377585 0.7763554 -0.4534752 0.3426423 0.8227782 -0.4534671 0.1547558 0.9754233 -0.156844 0.2691038 0.9502544 -0.1568434 0.2428063 0.8573884 -0.4537956 0.3424868 0.8226854 -0.4537529 0.271916 0.6531646 -0.7067092 0.3474865 0.6162865 -0.7067137 0.2232778 0.395994 -0.890694 -0.03081041 0.1534796 -0.9876714 -0.08945214 0.4455946 -0.8907546 -0.08942931 0.4458271 -0.8906406 -0.1392775 0.6943256 -0.7060552 -0.1393408 0.6940436 -0.7063198 -0.1753802 0.8735581 -0.4540243 -0.1752228 0.873919 -0.4533903 -0.1941785 0.9684394 -0.1562687 -0.1942712 0.968343 -0.1567497 -0.04875159 0.1488108 -0.9876633 -0.1415314 0.4319967 -0.8907008 -0.1415297 0.4318801 -0.8907576 -0.220434 0.6726803 -0.7063357 -0.2203958 0.6729405 -0.7060998 -0.2773596 0.8468608 -0.4537606 -0.2773838 0.8467469 -0.4539582 -0.3075292 0.938737 -0.1555598 -0.307556 0.9386916 -0.1557807 -0.4154292 0.8960486 -0.1565744 -0.06607282 0.1421357 -0.9876396 -0.1916406 0.4122528 -0.890686 -0.1916452 0.4122162 -0.8907019 -0.2984121 0.6418544 -0.7063804 -0.2984057 0.6418535 -0.706384 -0.3757962 0.8083034 -0.4532359 -0.3758344 0.808026 -0.4536989 -0.416576 0.8956112 -0.1560298 -0.4164774 0.895728 -0.1556217 -0.08239078 0.1332609 -0.9876505 -0.2390806 0.3866994 -0.8906763 -0.2390924 0.3866935 -0.8906756 -0.3721323 0.601864 -0.7065956 -0.3721556 0.6020739 -0.7064046 -0.4687766 0.7583721 -0.4529021 -0.4687691 0.7581861 -0.4532213 -0.5194277 0.8400883 -0.156354 -0.5194282 0.8400724 -0.1564377 -0.7793908 0.6066052 -0.1567813 -0.7022978 0.6944115 -0.1567502 -0.702142 0.6945297 -0.1569243 -0.7019833 0.6949288 -0.1558638 -0.6150466 0.7729259 -0.1558948 -0.6151821 0.7726351 -0.1567996 -0.6148802 0.7729462 -0.1564498 -0.08240717 0.1333298 -0.9876398 -0.09760993 0.122637 -0.9876399 -0.2831228 0.3557184 -0.8906773 -0.3232066 0.3196979 -0.8906912 -0.503092 0.4976242 -0.7065895 -0.558353 0.4346218 -0.7066441 -0.7032774 0.547423 -0.4535736 -0.7631522 0.4603722 -0.4534934 -0.8457357 0.5101816 -0.1563522 -0.9418931 0.2973947 -0.1561861 -0.8999817 0.4069559 -0.1562688 -0.9001134 0.4067878 -0.1559475 -0.9001153 0.4067333 -0.1560782 -0.8458456 0.5101009 -0.1560204 -0.9705976 0.1838466 -0.1553732 -0.9704039 0.1840861 -0.1562972 -0.875804 0.1661256 -0.4531774 -0.8500997 0.2682785 -0.4531636 -0.6748878 0.2129824 -0.7065161 -0.644873 0.2915066 -0.7065146 -0.4143584 0.1873012 -0.8906321 -0.3893956 0.2348502 -0.890627 -0.1341603 0.08091682 -0.9876505 -0.1236276 0.0962556 -0.9876493 -0.1563776 0.01076692 -0.9876387 -0.4536453 0.03124576 -0.8906344 -0.4533103 0.03109914 -0.8908101 -0.7058774 0.04842692 -0.7066767 -0.7062082 0.04860776 -0.7063337 -0.8892642 0.06119531 -0.4532818 -0.889068 0.06105458 -0.4536854 -0.9853867 0.06766396 -0.156316 -0.9854777 0.06787145 -0.1556511 -0.9864239 -0.05059045 -0.1562321 -0.1564692 -0.007803082 -0.9876521 -0.4541706 -0.02263987 -0.890627 -0.4541593 -0.02265918 -0.8906323 -0.7067227 -0.03524953 -0.706612 -0.7066919 -0.03525573 -0.7066425 -0.8904847 -0.04442548 -0.4528394 -0.8902574 -0.04453545 -0.4532753 -0.986418 -0.04937058 -0.1566598 -0.9864706 -0.04927015 -0.1563591 -0.1544035 -0.02625459 -0.987659 -0.4480437 -0.07618546 -0.8907597 -0.4482595 -0.07615011 -0.8906541 -0.6980145 -0.1185666 -0.7061995 -0.697597 -0.1186725 -0.7065942 -0.8787661 -0.1495046 -0.4532313 -0.8790042 -0.1493898 -0.4528071 -0.9737804 -0.1654936 -0.1560883 -0.9737513 -0.1655348 -0.156226 -0.1502943 -0.04435968 -0.9876457 -0.4358627 -0.1286532 -0.8907706 -0.4358798 -0.1286379 -0.8907644 -0.6789641 -0.2003963 -0.7062925 -0.6790503 -0.200383 -0.7062135 -0.8547724 -0.2522327 -0.453589 -0.8549817 -0.2521759 -0.4532259 -0.9474425 -0.2794333 -0.1557874 -0.9473137 -0.2795695 -0.1563264 -0.9077866 -0.3891279 -0.1565349 -0.1439507 -0.06178373 -0.9876543 -0.4179514 -0.1793801 -0.8905838 -0.4175634 -0.1793498 -0.8907718 -0.6498568 -0.2791242 -0.7069484 -0.6505643 -0.279132 -0.7062942 -0.8194529 -0.3515906 -0.4526378 -0.818876 -0.3516992 -0.4535966 -0.9076046 -0.3897961 -0.1559259 -0.9076636 -0.3897467 -0.1557061 -0.1356441 -0.07840132 -0.9876508 -0.3937164 -0.2275686 -0.8906177 -0.3937706 -0.2275846 -0.8905897 -0.6126279 -0.3540693 -0.7066273 -0.6122881 -0.3540321 -0.7069402 -0.7716335 -0.4461701 -0.4533366 -0.7720325 -0.446143 -0.4526833 -0.8552597 -0.4942414 -0.155745 -0.8550708 -0.4943636 -0.1563926 -0.6294775 -0.7610804 -0.1565716 -0.7154039 -0.680947 -0.1565521 -0.7150509 -0.6815248 -0.1556476 -0.7148211 -0.681639 -0.1562029 -0.7907974 -0.5918191 -0.1561722 -0.7907373 -0.5918415 -0.1563915 -0.7913743 -0.5911501 -0.1557829 -0.5351137 -0.8302205 -0.1561644 -0.5351518 -0.8301519 -0.1563981 -0.4828683 -0.7490422 -0.4536232 -0.5678613 -0.6868513 -0.4536177 -0.450726 -0.5451819 -0.70684 -0.5122037 -0.4878727 -0.7068434 -0.3293176 -0.3136733 -0.8905948 -0.3640828 -0.2725827 -0.8905855 -0.1253623 -0.09385389 -0.9876618 -0.1355673 -0.07838499 -0.9876626 -0.06869131 -0.1407654 -0.9876572 -0.1994172 -0.4086459 -0.890641 -0.1994473 -0.4086797 -0.8906187 -0.310361 -0.6359481 -0.7065735 -0.3100869 -0.6356949 -0.7069216 -0.3908265 -0.8012128 -0.4531146 -0.3908252 -0.8011934 -0.4531501 -0.4330059 -0.8876499 -0.1567914 -0.4334994 -0.8876609 -0.1553595 -0.3257929 -0.9325079 -0.1558465 -0.05156111 -0.1478726 -0.9876615 -0.1497585 -0.4295065 -0.8905597 -0.1496521 -0.4293668 -0.8906449 -0.2328538 -0.6680737 -0.7067225 -0.2329276 -0.6681804 -0.7065973 -0.293415 -0.8416759 -0.4533094 -0.2935103 -0.8417377 -0.4531329 -0.3252321 -0.9327225 -0.155734 -0.3248569 -0.9326818 -0.1567573 -0.03369623 -0.1529878 -0.9876534 -0.09778112 -0.4439477 -0.8907016 -0.09793174 -0.4442026 -0.890558 -0.1524289 -0.6914101 -0.7061995 -0.1521111 -0.6909298 -0.7067378 -0.1916236 -0.8704191 -0.4534879 -0.1916987 -0.8704875 -0.4533247 -0.2124313 -0.9646202 -0.1561434 -0.2125135 -0.9646374 -0.1559253 -0.01538693 -0.155833 -0.9876636 -0.04469859 -0.452711 -0.8905363 -0.04455786 -0.452423 -0.8906897 -0.06932204 -0.7038857 -0.7069225 -0.06967943 -0.70454 -0.7062352 -0.08775633 -0.8873266 -0.4527144 -0.08746194 -0.8869708 -0.4534679 -0.09692305 -0.982913 -0.1564863 -0.09673899 -0.9828374 -0.1570742 0.01965099 -0.9875946 -0.1557911 0.003170549 -0.1565356 -0.9876673 0.009209573 -0.4547995 -0.8905463 0.00921297 -0.4548236 -0.890534 0.01432669 -0.7073586 -0.7067097 0.01441538 -0.7071625 -0.7069042 0.0181632 -0.8910402 -0.453561 0.01788634 -0.8914931 -0.4526813 0.01981526 -0.9876119 -0.1556609 0.02010726 -0.9874855 -0.1564228 0.02168858 -0.1551986 -0.9876452 0.06291949 -0.4502475 -0.8906842 0.06287324 -0.4504998 -0.89056 0.09779757 -0.700754 -0.706668 0.09780031 -0.7007897 -0.7066322 0.1232407 -0.8830878 -0.4527337 0.1234577 -0.8826417 -0.4535439 0.1368229 -0.9781984 -0.1562288 0.1367162 -0.9782809 -0.1558052 0.4686869 -0.8694663 -0.1560804 0.3623691 -0.9188744 -0.1560727 0.3626534 -0.9188252 -0.1557011 0.3626636 -0.9188137 -0.1557451 0.2511842 -0.955328 -0.15574 0.251362 -0.9551778 -0.1563732 0.2511016 -0.9552643 -0.1562634 0.5679331 -0.8080466 -0.1565652 0.5681374 -0.8080047 -0.1560401 0.5127772 -0.7292736 -0.4530118 0.4231014 -0.7847059 -0.4530142 0.3358212 -0.6228348 -0.7066124 0.2597352 -0.6582089 -0.7066107 0.1668043 -0.4227024 -0.8907857 0.1157172 -0.4394758 -0.8907697 0.0398913 -0.1515057 -0.9876512 0.02169543 -0.1551534 -0.9876522 0.6600852 -0.7348811 -0.1556837 0.1045711 -0.1164652 -0.9876745 0.3038514 -0.3384169 -0.8905888 0.3039091 -0.3385505 -0.8905184 0.4726585 -0.5265454 -0.7066428 0.4726741 -0.5265806 -0.706606 0.5953242 -0.6632261 -0.4535641 0.5953145 -0.6632415 -0.4535544 0.6597708 -0.7350464 -0.156235 0.6598911 -0.7348545 -0.1566292 0.7420017 -0.6521501 -0.1553509 0.1176106 -0.1033223 -0.9876701 0.3416724 -0.3001585 -0.8905981 0.3416993 -0.3001868 -0.8905782 0.5318285 -0.4672248 -0.7062999 0.5316742 -0.4669018 -0.7066295 0.6694926 -0.5879398 -0.4539896 0.6695796 -0.5881676 -0.4535661 0.7421856 -0.6519454 -0.1553314 0.7422049 -0.6518397 -0.155682 0.1290326 -0.08865302 -0.9876697 0.3747211 -0.2574631 -0.8906722 0.3747915 -0.2575519 -0.8906168 0.5833349 -0.4008696 -0.7064164 0.5834444 -0.4010185 -0.7062414 0.7345244 -0.5048698 -0.4534098 0.734407 -0.5045357 -0.4539715 0.8140774 -0.5592666 -0.156521 0.8140246 -0.5596805 -0.1553115 0.1386609 -0.07283943 -0.9876577 0.4025662 -0.2114716 -0.8906292 0.4025022 -0.2114034 -0.8906744 0.6265497 -0.329075 -0.7065021 0.6266301 -0.3291782 -0.7063828 0.7890806 -0.414506 -0.4533616 0.7890763 -0.4144717 -0.4534004 0.8744469 -0.4593142 -0.1561191 0.8744388 -0.4591582 -0.156623 0.9225333 -0.3529571 -0.1560566 0.1463149 -0.05589485 -0.9876578 0.4244453 -0.1621495 -0.8908163 0.4247418 -0.1623813 -0.8906328 0.66117 -0.2527642 -0.7063743 0.6610423 -0.2526757 -0.7065253 0.8326079 -0.3182559 -0.453296 0.8326161 -0.3182526 -0.4532833 0.9226785 -0.3526706 -0.1558455 0.9226719 -0.3525463 -0.1561656 0.1519394 -0.03827172 -0.9876486 0.4410985 -0.1110999 -0.8905555 0.4406528 -0.1108216 -0.8908108 0.6864739 -0.17264 -0.7063632 0.6864197 -0.1726062 -0.7064241 0.8642164 -0.2172995 -0.4537743 0.8644427 -0.2175427 -0.4532263 0.9579139 -0.2410894 -0.1558104 0.9578939 -0.2409919 -0.1560842 0.981779 0.1076315 -0.1566062 0.9876316 -0.009349644 -0.1565132 0.9876685 -0.009135842 -0.1562929 0.9877663 -0.009417235 -0.1556572 0.9797014 -0.1261681 -0.1557782 0.9797285 -0.1262041 -0.1555784 0.9797284 -0.125888 -0.1558353 0.962363 0.2229204 -0.1554476 0.9623492 0.2228301 -0.1556628 0.8683305 0.201085 -0.4533947 0.8860133 0.09722203 -0.4533523 0.7034521 0.077192 -0.7065386 0.7076394 -0.006816267 -0.706541 0.4547311 -0.004382014 -0.890618 0.4510051 -0.05795931 -0.8906375 0.1553806 -0.01996862 -0.9876529 0.1519235 -0.03826403 -0.9876514 0.9291501 0.3352141 -0.1559218 0.1473628 0.05314385 -0.9876538 0.4278286 0.1542809 -0.8905954 0.4276254 0.1542903 -0.8906914 0.6658061 0.2402192 -0.7063971 0.6656439 0.2402133 -0.706552 0.8381107 0.3024595 -0.4539702 0.8382701 0.3024049 -0.4537121 0.9291556 0.3352005 -0.1559187 0.9292799 0.335036 -0.1555308 0.8811287 0.4464523 -0.1558616 0.1400228 0.07019257 -0.9876571 0.4065188 0.2037795 -0.890627 0.4065536 0.2037897 -0.8906088 0.6329863 0.3172907 -0.7061552 0.6327738 0.3172705 -0.7063546 0.7966279 0.3994265 -0.4536987 0.7964213 0.399457 -0.4540344 0.8829085 0.4428138 -0.1561684 0.8829984 0.4427562 -0.1558228 0.1306922 0.08629941 -0.9876599 0.37924 0.2504172 -0.8907684 0.3795406 0.2504952 -0.8906184 0.5907469 0.3898777 -0.7064088 0.590982 0.3899281 -0.7061844 0.7441044 0.490948 -0.453077 0.7436897 0.4909352 -0.4537714 0.8242688 0.5441252 -0.1565532 0.8244974 0.543998 -0.1557892 0.1197118 0.1011881 -0.9876386 0.3470441 0.2933486 -0.8907902 0.3471127 0.2933729 -0.8907554 0.5409041 0.4571693 -0.705988 0.5404378 0.4570196 -0.7064419 0.6804572 0.5754365 -0.4537078 0.6808328 0.5754648 -0.4531082 0.754326 0.637599 -0.1563967 0.7543277 0.6376022 -0.1563755 0.6736759 0.7223052 -0.1563204 0.1067918 0.1145889 -0.9876564 0.3098359 0.3324567 -0.8907718 0.3098083 0.3324466 -0.8907852 0.4823626 0.5176074 -0.7066888 0.483071 0.5179306 -0.7059676 0.6081438 0.6520057 -0.4528244 0.6076169 0.6518841 -0.4537056 0.673473 0.7225315 -0.1561489 0.6733576 0.7225632 -0.1564994 0.09260338 0.1265395 -0.9876298 0.2684642 0.3668558 -0.8906986 0.2683883 0.3668118 -0.8907395 0.4177977 0.5710031 -0.7066829 0.4177536 0.570972 -0.706734 0.5263222 0.7193663 -0.453318 0.5266163 0.7194899 -0.45278 0.5833691 0.7970192 -0.1563368 0.5833683 0.7970295 -0.1562873 0.2695758 0.9503533 -0.1554273 0.3795145 0.9120371 -0.1554256 0.3797491 0.9118956 -0.1556825 0.3800174 0.9118852 -0.1550875 0.485272 0.8605013 -0.1550765 0.4846515 0.8605141 -0.1569349 0.4852059 0.8603081 -0.1563495 0.1549264 0.9755186 -0.1560816 0.1551023 0.9753917 -0.1566988 0.139979 0.8802929 -0.4533104 0.2430272 0.8575806 -0.4533137 0.1930372 0.6811652 -0.7062228 0.272266 0.6534929 -0.7062707 0.1749155 0.4198324 -0.8905872 0.2234229 0.3961276 -0.8905982 0.07698857 0.1365011 -0.9876438 0.09252983 0.1264885 -0.9876431 0.03856009 0.9871051 -0.1553592 0.00614047 0.1566555 -0.9876343 0.01780879 0.4543027 -0.8906694 0.0178321 0.4543777 -0.8906307 0.02774095 0.7069287 -0.7067406 0.02772736 0.7069071 -0.7067627 0.03493458 0.8906993 -0.4532486 0.03493195 0.8906637 -0.4533189 0.03871327 0.987062 -0.1555961 0.03845959 0.9870033 -0.1560301 -0.01242703 0.1561493 -0.9876553 -0.03607285 0.4532596 -0.8906484 -0.03609079 0.4532483 -0.8906534 -0.05618894 0.7056667 -0.7063125 -0.05631786 0.7052702 -0.7066982 -0.07095009 0.8884986 -0.4533613 -0.07094585 0.888492 -0.4533748 -0.07861298 0.9845063 -0.1567398 -0.07822763 0.984762 -0.1553204 0.4310855 0.9023111 0 0.4310287 0.9023382 -3.26991e-5 0.4309751 0.9023639 0 0.9969581 0.07793951 0 0.9969634 0.07787221 3.55836e-5 0.996968 0.07781261 0 0.5659725 -0.8244243 0 0.565941 -0.8244459 2.11578e-5 0.5659131 -0.824465 0 1.27002e-6 0 -1 -8.02132e-7 0 -1 1.26847e-6 0 -1 1.42091e-6 0 -1 -0.9969575 -0.07794737 0 -0.9969634 -0.07787233 3.55836e-5 -0.996968 -0.07781261 0 -2.08154e-7 0 -1 -3.90603e-7 0 -1 6.91859e-7 0 -1 3.38234e-7 0 -1 2.62745e-7 0 -1 -6.91877e-7 0 -1 -7.90069e-7 0 -1 7.66441e-7 0 -1 1.44492e-7 0 -1 5.45445e-7 0 -1 -9.54801e-7 0 -1 5.1308e-7 0 -1 -1.46758e-6 0 -1 -6.9184e-7 0 -1 2.62755e-7 0 -1 1.69087e-7 0 -1 -1.76631e-7 0 -1 -1.65175e-7 0 -1 -7.06606e-7 0 -1 -3.94603e-7 0 -1 7.90123e-7 0 -1 -7.78031e-7 0 -1 -1.96905e-7 0 -1 -2.09664e-7 0 -1 -3.81031e-7 0 -1 3.9185e-7 0 -1 1.32176e-7 0 -1 -3.49667e-7 0 -1 0.3530949 0.9355825 0.003082156 0.1486699 0.9888865 -8.6294e-4 0.1897603 0.9818243 0.00348562 0.2643504 0.9644252 -0.001758515 0.2648621 0.9642847 -0.001762866 0.1500542 0.9886775 -8.63332e-4 0.03069376 0.9995282 0.001093983 0.02100569 0.9997764 0.002421438 -0.2047642 0.9788104 -0.001395046 -0.148169 0.9889553 0.003669321 -0.08777868 0.996139 -0.001488626 -0.08773463 0.9961428 -0.001488208 -0.2057191 0.9786101 -0.001395523 -0.3191714 0.947694 0.00244379 -0.3132049 0.9496845 0.001478731 -0.5331901 0.8459938 -0.001745581 -0.4691176 0.8831286 0.003567755 -0.4292477 0.9031864 -9.42899e-4 -0.4281744 0.9036957 -9.46136e-4 -0.5323038 0.8465517 -0.001744568 -0.6294451 0.7770342 0.004096806 -0.611662 0.7911192 2.56194e-4 -0.7125172 0.7016547 -1.83506e-4 -0.7168272 0.6972509 -1.83861e-4 -0.7365791 0.676344 0.003194928 -0.8604515 0.509532 -6.99404e-4 -0.8402348 0.542212 0.003437697 -0.7942934 0.607532 -0.001769959 -0.7941169 0.6077626 -0.001770555 -0.8603335 0.5097311 -6.98697e-4 -0.9147008 0.4041309 8.5169e-4 -0.9198034 0.3923712 0.002564609 -0.9841011 0.177605 -0.001321434 -0.9729204 0.2311112 0.003670871 -0.9559868 0.2934054 -0.00159341 -0.9562655 0.2924957 -0.001592636 -0.9840239 0.1780323 -0.001321732 -0.998167 0.06048029 0.002158343 -0.9979692 0.06367737 0.001677393 -0.9844337 -0.1757482 -0.001692712 -0.994347 -0.1061195 0.003584682 -0.9982991 -0.05829119 -0.001113057 -0.9982903 -0.05844157 -0.001113057 -0.9845341 -0.175185 -0.00169301 -0.9566375 -0.2912569 0.003762543 -0.9621588 -0.2724889 5.08712e-4 -0.9171491 -0.3985442 -3.64241e-4 -0.9155176 -0.4022778 -3.64453e-4 -0.9021689 -0.4313705 0.003286659 -0.7955741 -0.6058562 -5.26526e-4 -0.8163529 -0.5775436 0.00336945 -0.8615727 -0.5076312 -0.001791715 -0.861546 -0.5076764 -0.00179094 -0.7954912 -0.6059651 -5.27163e-4 -0.7182174 -0.6958186 6.30675e-4 -0.7071038 -0.7071047 0.002697825 -0.5348498 -0.8449464 -0.00121206 -0.5772936 -0.8165286 0.003619134 -0.6307346 -0.775997 -0.001633644 -0.6313771 -0.7754743 -0.001633346 -0.5341923 -0.8453621 -0.001210749 -0.4311783 -0.9022648 0.001854538 -0.4309304 -0.9023832 0.001898229 -0.2067481 -0.9783929 -0.001627147 -0.2722861 -0.9622094 0.003657162 -0.3213878 -0.9469469 -0.001205027 -0.3209425 -0.947098 -0.001206576 -0.2072042 -0.9782964 -0.001627087 -0.08989578 -0.9959454 0.003399193 -0.1059102 -0.9943754 7.77352e-4 0.03037381 -0.9995386 -5.56278e-4 0.02839177 -0.9995968 -5.56876e-4 0.06388705 -0.9979515 0.003383934 0.2624042 -0.9649581 -3.76944e-4 0.2313657 -0.9728614 0.003279209 0.147081 -0.9891229 -0.001758933 0.1463445 -0.9892322 -0.001760601 0.2626474 -0.9648919 -3.78594e-4 0.3747195 -0.9271382 3.93875e-4 0.3925446 -0.9197286 0.002850711 0.582001 -0.8131873 -0.001089811 0.542362 -0.8401374 0.003600418 0.4818168 -0.8762704 -0.001690983 0.4819391 -0.8762031 -0.001690268 0.5832045 -0.8123247 -0.001088917 0.6741511 -0.7385917 0.00158143 0.6765735 -0.7363723 0.002052783 0.8286793 -0.5597216 -0.001550972 0.7912923 -0.6114272 0.003651916 0.7569068 -0.6535215 -0.001312792 0.7563706 -0.6541423 -0.001312136 0.8289696 -0.5592916 -0.001551568 0.8891466 -0.4576123 0.003073155 0.8832241 -0.46895 0.001030802 0.9379866 -0.3466709 -7.15614e-4 0.9370175 -0.3492817 -7.1519e-4 0.9497451 -0.3130058 0.003421247 0.9717193 -0.2361326 -0.001796901 0.9717668 -0.2359367 -0.00179708 0.9890238 -0.1477222 0.003188133 0.9928689 -0.1192113 -1.88047e-4 0.9997751 0.02121162 -1.84084e-4 0.9917768 -0.1254896 0.02512431 0.9917768 -0.1254894 0.02512437 0.9917768 -0.1254897 0.02512443 0.9999914 -9.26098e-4 0.004044651 0.9722378 0.2339932 -9.88047e-4 0.9817819 0.1899778 0.003567457 0.993113 0.1171481 -0.001718163 0.9931669 0.1166908 -0.001718163 0.9724667 0.2330402 -9.88534e-4 0.9377241 0.3473785 0.00134778 0.9355157 0.3532781 0.002235054 0.8301044 0.5576063 -0.001468658 0.862383 0.5062431 0.003678441 0.8902702 0.4554306 -0.001424551 0.8900714 0.455819 -0.001425862 0.8293104 0.5587863 -0.001468062 0.7583538 0.6518375 0.002735376 0.7644801 0.6446462 0.001251518 0.6756972 0.7371789 -8.39765e-4 0.6757639 0.7371177 -8.38829e-4 0.6445074 0.7645901 0.003502428 0.58406 0.8117088 -0.001748442 0.5835125 0.8121023 -0.001747965 0.5058932 0.8625907 0.003086864 0.4836602 0.875256 0 0.3768872 0.9262592 0 0.9810706 0.1152575 -0.1556159 0.4759891 -0.8654086 -0.156533 -0.6236775 -0.7659927 -0.1558256 -0.8509142 -0.5014625 -0.1564626 -0.9444769 0.2889248 -0.1564799 -0.7843673 0.6003382 -0.1560829 0.2616189 0.9524812 -0.1559973 0.3769853 0.2534847 -0.8908578 0.3766696 -0.2543342 -0.8907493 -0.0939837 -0.4447301 -0.8907201 -0.4476128 -0.07998287 -0.8906434 -0.2423139 0.3845881 -0.8907166 0.07571643 0.1370364 -0.987668 0.09148401 0.1272146 -0.9876473 0.1524768 0.03663349 -0.9876279 0.1555193 0.01839619 -0.9876616 0.1567559 -2.17449e-4 -0.9876374 0.1554474 -0.01865911 -0.987668 0.1522883 -0.03697812 -0.9876441 0.09117192 -0.1273727 -0.9876558 0.07547527 -0.1371964 -0.9876642 0.05874353 -0.1452929 -0.9876433 0.04114878 -0.1512525 -0.9876384 0.02299541 -0.1550401 -0.9876406 -0.08376544 -0.1323987 -0.9876508 -0.09887361 -0.1215398 -0.9876499 -0.1125062 -0.1089981 -0.9876548 -0.1245722 -0.0949009 -0.9876617 -0.1349106 -0.07951384 -0.9876623 -0.1542528 0.02792418 -0.9876368 -0.1497693 0.04585766 -0.987657 -0.1434481 0.06337833 -0.9876264 -0.1348631 0.07984918 -0.9876417 -0.1245195 0.09529477 -0.9876304 0.02333241 0.1549876 -0.9876409 0.0414403 0.1510835 -0.987652 0.05907666 0.14515 -0.9876444 -0.08349186 0.1326048 -0.9876462 -0.08345407 0.1324528 -0.9876699 -0.06719297 0.1413958 -0.9876702 -0.1542863 -0.02753913 -0.9876424 -0.1541915 -0.02755385 -0.9876568 -0.1563562 -0.009119093 -0.9876587 -0.03246134 -0.1533951 -0.9876317 -0.0323891 -0.1532582 -0.9876553 -0.05033969 -0.1483301 -0.9876559 0.1298428 -0.08764505 -0.9876534 0.1299011 -0.0877093 -0.9876401 0.1186071 -0.102463 -0.9876406 0.1301606 0.08744084 -0.9876297 0.1299592 0.08738291 -0.9876613 0.1393913 0.07136875 -0.9876622 -0.4453186 0.5499233 -0.7065945 -0.2860637 0.3532694 -0.8907123 -0.2861214 0.3534261 -0.8906316 -0.09860318 0.1217992 -0.9876449 -0.0986256 0.1218484 -0.9876366 -0.6772626 -0.2058801 -0.706349 -0.4350742 -0.1322625 -0.8906273 -0.4346711 -0.1322721 -0.8908228 -0.1499279 -0.04562371 -0.9876437 -0.1499363 -0.04562395 -0.9876425 -0.06368046 -0.7050324 -0.7063102 -0.04089188 -0.4527353 -0.8907068 -0.04090118 -0.4527568 -0.8906955 -0.01410716 -0.1561588 -0.9876313 -0.01402735 -0.1559683 -0.9876624 0.6294536 -0.3237163 -0.7063964 0.4041793 -0.2078546 -0.89075 0.4042516 -0.2079353 -0.8906983 0.1393049 -0.0716564 -0.9876536 0.1393461 -0.07169675 -0.9876448 0.5367779 0.4614879 -0.7063275 0.3444896 0.2961634 -0.8908503 0.3446619 0.2962478 -0.8907555 0.1189164 0.1022125 -0.9876292 0.1187719 0.1021499 -0.9876531 -0.06213641 0.7052243 -0.7062563 -0.6388733 0.6215379 -0.453356 -0.5071752 0.4934306 -0.7066114 -0.5072398 0.4935797 -0.7064608 -0.325926 0.3171551 -0.8906094 -0.3257876 0.31689 -0.8907544 -0.1123584 0.1092883 -0.9876395 -0.1123655 0.1092838 -0.9876391 -0.7063743 -0.0412566 -0.7066352 -0.8162083 -0.3585066 -0.4530751 -0.6480535 -0.2846502 -0.7064 -0.6477195 -0.28465 -0.7067064 -0.4159907 -0.1828092 -0.8908045 -0.416422 -0.1828438 -0.8905959 -0.1434954 -0.06300699 -0.9876433 -0.1435107 -0.06300806 -0.987641 -0.2273533 -0.670091 -0.7066036 0.02542018 -0.8907318 -0.453818 0.02019613 -0.7076568 -0.7062677 0.02024638 -0.7075072 -0.7064161 0.01300251 -0.4543854 -0.8907103 0.01297861 -0.4544652 -0.89067 0.004469752 -0.1565435 -0.987661 0.004429817 -0.1566901 -0.9876379 0.5354568 -0.4625095 -0.7066619 0.8352717 -0.3115801 -0.4530333 0.6631669 -0.2473892 -0.7064052 0.6628506 -0.2470889 -0.706807 0.4259738 -0.158785 -0.8906929 0.4258357 -0.1586933 -0.8907752 0.1468454 -0.05471938 -0.9876449 0.1468874 -0.05476176 -0.9876363 0.6300215 0.3225624 -0.706418 0.6021806 0.6569243 -0.4536839 0.4783626 0.5218563 -0.7062827 0.4780428 0.5217165 -0.7066025 0.3070407 0.3350853 -0.8907547 0.3070125 0.3350764 -0.8907678 0.1058285 0.1155054 -0.9876532 0.1059581 0.1155784 -0.9876308 -0.0780884 0.8878569 -0.453445 -0.07821059 0.8876572 -0.4538146 -0.182572 0.8721683 -0.4538612 -0.4229396 0.8926264 -0.1560134 -0.3154612 0.9360345 -0.1559609 -0.2845572 0.8443239 -0.4540313 -0.1826198 0.8720555 -0.4540586 -0.1451249 0.6930161 -0.706164 -0.0621109 0.7052776 -0.7062051 -0.03988105 0.4528497 -0.8906945 -0.01376521 0.1560688 -0.9876503 -0.03208732 0.1533616 -0.9876492 -0.09310698 0.4450213 -0.8906667 -0.1450927 0.4308915 -0.890663 -0.2258965 0.6708587 -0.7063422 -0.303704 0.6393609 -0.7063864 -0.382531 0.8053026 -0.4529438 -0.4751422 0.7543812 -0.4529339 -0.03209477 0.1532472 -0.9876666 -0.04999601 0.1483781 -0.9876661 -0.1450934 0.4306043 -0.8908019 -0.1950732 0.4104372 -0.8907793 -0.3036961 0.6389958 -0.7067199 -0.3770427 0.5986106 -0.7067561 -0.4751359 0.7543534 -0.4529867 -0.560911 0.6929444 -0.4529979 -0.6214912 0.7677751 -0.1557893 -0.7040587 0.6928177 -0.155901 -0.7040586 0.6928177 -0.155901 -0.7040585 0.6928178 -0.155901 -0.8898621 -0.05172276 -0.4532885 -0.8894627 -0.05193364 -0.4540475 -0.87709 -0.1567206 -0.4540395 -0.9060032 -0.3936387 -0.1555852 -0.9451045 -0.2874159 -0.1554656 -0.8525648 -0.2592737 -0.4537737 -0.877204 -0.1566739 -0.4538354 -0.6967411 -0.124446 -0.7064455 -0.706591 -0.04117333 -0.7064234 -0.4539718 -0.02644711 -0.8906235 -0.2862986 -0.844044 -0.4534568 -0.2864092 -0.8441551 -0.4531799 -0.1845878 -0.8720503 -0.4532723 0.02999389 -0.9872379 -0.156402 -0.08868038 -0.9837121 -0.1563535 -0.08004051 -0.887881 -0.4530573 -0.1846469 -0.8721058 -0.4531414 -0.146587 -0.6923586 -0.7065069 -0.2274032 -0.6701501 -0.7065315 -0.1461763 -0.4307778 -0.8905409 0.6745305 -0.5824123 -0.4536569 0.6746179 -0.5827172 -0.4531351 0.7389092 -0.4987392 -0.4530702 0.9263361 -0.3425647 -0.1566875 0.8781458 -0.4520221 -0.1566394 0.7927507 -0.4080684 -0.4527984 0.7389507 -0.4988799 -0.4528474 0.5863173 -0.3958283 -0.70679 0.535417 -0.4624294 -0.7067446 0.3441962 -0.2972822 -0.8905911 0.7933393 0.4061589 -0.4534841 0.7933059 0.4061556 -0.4535455 0.7397875 0.4969452 -0.4536077 0.6674517 0.7281958 -0.1556895 0.7489448 0.644079 -0.1557045 0.6756317 0.5810211 -0.4538022 0.7397023 0.4969601 -0.4537304 0.5873808 0.3946171 -0.7065841 0.6298462 0.3225423 -0.7065835 0.4044191 0.2070978 -0.8908175 0.05898058 0.1450348 -0.9876672 0.1712267 0.4210526 -0.8907279 0.171496 0.4213548 -0.8905332 0.2669236 0.6558097 -0.7061625 0.2664979 0.655386 -0.7067164 0.3356689 0.8254851 -0.4537628 0.3357797 0.8255444 -0.4535731 0.3721458 0.9149684 -0.1560142 0.372298 0.9149857 -0.1555486 0.04145878 0.1511132 -0.9876468 0.1203064 0.4385032 -0.890641 0.1202181 0.4383679 -0.8907196 0.1870524 0.6820722 -0.7069575 0.1875528 0.6827347 -0.706185 0.23611 0.8594789 -0.4533742 0.2359229 0.8592962 -0.4538177 0.2615443 0.9526088 -0.1553419 0.2610766 0.9524789 -0.1569176 0.148166 0.9764306 -0.1569401 0.02329659 0.1549227 -0.9876519 0.06760394 0.4495282 -0.8907043 0.06765806 0.4496477 -0.8906399 0.1053047 0.6998394 -0.7064955 0.1050786 0.6994418 -0.7069227 0.1324478 0.8816084 -0.4530169 0.1322883 0.8814541 -0.4533637 0.1466005 0.9767917 -0.1561611 0.1468608 0.9768656 -0.1554526 0.004838168 0.156634 -0.987645 0.01403474 0.4544126 -0.8906808 0.01402527 0.4543522 -0.8907118 0.02184367 0.7076267 -0.7062489 0.02174133 0.7073917 -0.7064874 0.02738159 0.8909013 -0.4533708 0.02750676 0.8910739 -0.453024 0.03047555 0.987223 -0.1564033 0.03031384 0.987146 -0.1569202 -0.3153027 0.9361926 -0.1553308 -0.2032216 0.9667277 -0.155366 -0.2023748 0.9667814 -0.1561346 -0.2022649 0.9668645 -0.1557625 -0.08654308 0.9839888 -0.1558095 -0.08669686 0.9838691 -0.1564779 -0.08665943 0.9838945 -0.1563388 0.004799902 0.1565405 -0.9876599 -0.01377725 0.1560285 -0.9876565 -0.03995913 0.4525071 -0.8908652 -0.09315675 0.4446205 -0.8908616 -0.1451601 0.692806 -0.7063629 -0.2258903 0.6707849 -0.7064143 -0.2844522 0.8446857 -0.4534237 -0.38256 0.8050157 -0.4534288 -0.4239228 0.8920412 -0.1566909 -0.6216241 0.7674145 -0.1570311 -0.5257227 0.836043 -0.1569964 -0.5264137 0.8358001 -0.1559705 -0.5266183 0.8355376 -0.1566852 -0.4239512 0.8920433 -0.1566022 -0.7080336 0.6887237 -0.1560389 -0.7079412 0.6887402 -0.1563847 -0.6388646 0.6215488 -0.4533532 -0.5608747 0.6927094 -0.4534021 -0.4453271 0.5500089 -0.7065226 -0.3771054 0.5988633 -0.7065086 -0.2423927 0.3849372 -0.8905443 -0.1951234 0.4109379 -0.8905375 -0.06721234 0.1415516 -0.9876466 -0.04999244 0.1485205 -0.9876449 -0.1244822 0.09524899 -0.9876396 -0.3610677 0.2762647 -0.8906784 -0.3609847 0.2761424 -0.8907499 -0.5619723 0.4298828 -0.7066738 -0.5620693 0.43005 -0.706495 -0.7080228 0.5416998 -0.4530618 -0.7079766 0.541593 -0.4532617 -0.7844931 0.6001151 -0.1563094 -0.7845302 0.5999994 -0.156567 -0.8497093 0.503331 -0.1570098 -0.8497093 0.503331 -0.1570099 -0.8497093 0.503331 -0.1570099 -0.1349033 0.07989037 -0.9876329 -0.3912853 0.2317209 -0.8906185 -0.3912132 0.2316359 -0.8906723 -0.6088212 0.3604758 -0.7066782 -0.608846 0.3605245 -0.7066319 -0.767243 0.4543159 -0.4526978 -0.7671539 0.4541211 -0.4530442 -0.8498855 0.5030986 -0.1568012 -0.8498757 0.5032615 -0.1563305 -0.1433759 0.0633099 -0.9876412 -0.4157443 0.1835886 -0.8907592 -0.4160019 0.183818 -0.8905916 -0.647271 0.2860092 -0.7065684 -0.6471222 0.2858566 -0.7067665 -0.8154001 0.3601762 -0.4532061 -0.8155731 0.360467 -0.4526635 -0.9033842 0.3992809 -0.1564353 -0.903381 0.3991012 -0.1569113 -0.1499285 0.04596745 -0.9876278 -0.4345503 0.1332363 -0.890738 -0.434522 0.1331967 -0.8907577 -0.6765658 0.2074106 -0.706569 -0.6765761 0.2074068 -0.7065602 -0.8522915 0.2612745 -0.4531391 -0.8522763 0.2612829 -0.4531626 -0.9442908 0.2894749 -0.1565859 -0.9443593 0.289812 -0.1555457 -0.9720472 0.1759679 -0.1554332 -0.1541516 0.0278654 -0.9876542 -0.4470527 0.08081877 -0.8908493 -0.4472367 0.08091682 -0.8907479 -0.6964186 0.1259918 -0.7064894 -0.6963691 0.1259688 -0.7065423 -0.8771054 0.1586493 -0.4533392 -0.8771705 0.1587207 -0.4531885 -0.9720726 0.1758756 -0.1553789 -0.9719673 0.1754186 -0.1565507 -0.1564643 0.009471476 -0.9876383 -0.4538952 0.02746671 -0.8906317 -0.4535059 0.02730053 -0.8908352 -0.7062795 0.04252606 -0.7066547 -0.7064268 0.04260319 -0.7065028 -0.8897709 0.0536552 -0.4532429 -0.889741 0.0536375 -0.4533035 -0.9859054 0.05943578 -0.1563908 -0.98605 0.0597288 -0.1553641 -0.9448445 -0.2876608 -0.1565894 -0.9724073 -0.1729911 -0.1565191 -0.9724215 -0.1737591 -0.1555773 -0.9724897 -0.1736281 -0.1552976 -0.9862029 -0.05731546 -0.1553022 -0.98605 -0.05756992 -0.1561768 -0.9860249 -0.05772471 -0.1562781 -0.9042361 -0.3973248 -0.1564937 -0.9042432 -0.3974165 -0.1562197 -0.8158482 -0.3585641 -0.4536776 -0.8526194 -0.2592455 -0.4536873 -0.6771352 -0.2058985 -0.7064656 -0.6967796 -0.1244257 -0.706411 -0.4477655 -0.07996368 -0.8905684 -0.4540734 -0.02643007 -0.8905723 -0.1564159 -0.009102106 -0.9876495 -0.1563984 0.009443402 -0.987649 -0.1350522 -0.07954221 -0.9876407 -0.3916636 -0.2306791 -0.8907227 -0.3919069 -0.2307362 -0.8906009 -0.6098728 -0.359058 -0.7064931 -0.6096183 -0.3590186 -0.7067328 -0.7683729 -0.4525254 -0.4525748 -0.7680748 -0.4525337 -0.4530723 -0.8509834 -0.5013862 -0.1563309 -0.8509886 -0.5013896 -0.1562914 -0.7856761 -0.5986366 -0.1560364 -0.1245805 -0.09490245 -0.9876605 -0.3617071 -0.27554 -0.8906434 -0.3615174 -0.2754834 -0.890738 -0.5629395 -0.4289686 -0.7064595 -0.5629237 -0.4289583 -0.7064784 -0.7088678 -0.5401733 -0.4535628 -0.7094638 -0.5402196 -0.4525748 -0.785855 -0.5983805 -0.1561179 -0.7857893 -0.5984084 -0.1563415 -0.1124576 -0.1089748 -0.9876628 -0.3263878 -0.3162844 -0.8907498 -0.3266083 -0.3163737 -0.8906373 -0.508256 -0.4923398 -0.7065957 -0.5083563 -0.49237 -0.7065024 -0.6402679 -0.6201515 -0.453287 -0.6402014 -0.6201226 -0.4534207 -0.7094944 -0.6872622 -0.1558473 -0.7094116 -0.6872879 -0.1561112 -0.09885787 -0.1215315 -0.9876524 -0.2869118 -0.3527151 -0.8906592 -0.2867167 -0.3525961 -0.8907691 -0.4465848 -0.5491794 -0.7063739 -0.4464006 -0.5490836 -0.7065648 -0.562229 -0.6915484 -0.4534969 -0.5623456 -0.6915783 -0.4533067 -0.6231448 -0.7663487 -0.1562061 -0.6229371 -0.7664079 -0.1567428 -0.5276949 -0.835039 -0.1557179 -0.08378475 -0.1324071 -0.987648 -0.2431472 -0.3842645 -0.8906291 -0.2430908 -0.3842104 -0.8906678 -0.3782346 -0.597795 -0.7068095 -0.378559 -0.5980316 -0.7064357 -0.4767643 -0.7531346 -0.4533038 -0.4766464 -0.7530805 -0.4535173 -0.5282527 -0.834591 -0.1562278 -0.5282864 -0.8345897 -0.1561204 -0.06756049 -0.1413664 -0.9876494 -0.1961589 -0.4104487 -0.8905357 -0.1960012 -0.4102686 -0.8906533 -0.3050348 -0.6385074 -0.7065849 -0.3048946 -0.6383901 -0.7067513 -0.3841314 -0.8042985 -0.453373 -0.3841484 -0.8043171 -0.4533255 -0.4256707 -0.8912457 -0.1564788 -0.4259197 -0.8912659 -0.1556842 -0.08879733 -0.9837611 -0.1559787 -0.2046687 -0.966326 -0.1559642 -0.2045509 -0.9663666 -0.1558675 -0.2041992 -0.9663237 -0.1565921 -0.3172593 -0.9353191 -0.156604 -0.3174504 -0.9353526 -0.1560153 -0.3169827 -0.9354525 -0.1563673 0.02804458 -0.9873809 -0.1558605 0.0280357 -0.987376 -0.1558928 0.02529686 -0.8909479 -0.4534004 -0.07991415 -0.8876866 -0.4534606 -0.06342732 -0.7045758 -0.7067885 -0.1464317 -0.6921321 -0.7067609 -0.0941447 -0.4449909 -0.8905729 -0.14614 -0.4307343 -0.8905678 -0.0503118 -0.1482829 -0.9876645 -0.06748819 -0.1412849 -0.987666 0.1452853 -0.9771043 -0.1554338 0.02299571 -0.155042 -0.9876403 0.06666773 -0.4495036 -0.8907873 0.06663322 -0.4497656 -0.8906576 0.1036858 -0.6998881 -0.7066866 0.1036062 -0.7001745 -0.7064145 0.1304791 -0.8817743 -0.4532653 0.1306331 -0.8814545 -0.4538424 0.1448018 -0.977049 -0.1562297 0.1445644 -0.9771661 -0.1557167 0.259498 -0.9531 -0.1557606 0.04115271 -0.1512347 -0.9876409 0.1193079 -0.43847 -0.8907917 0.1193122 -0.4385434 -0.8907549 0.1858181 -0.6829923 -0.7063945 0.1858671 -0.6827031 -0.7066612 0.2340967 -0.859843 -0.4537279 0.234006 -0.8601163 -0.4532562 0.2593144 -0.9531478 -0.1557734 0.2592146 -0.9532352 -0.1554044 0.05874359 -0.1453227 -0.9876388 0.1703355 -0.4213963 -0.8907363 0.170322 -0.4212677 -0.8907997 0.265352 -0.6563209 -0.7062799 0.2653488 -0.6562738 -0.7063249 0.3340856 -0.8262881 -0.4534699 0.3341209 -0.826092 -0.453801 0.3703316 -0.9156123 -0.156553 0.3701496 -0.9158433 -0.1556294 0.0755015 -0.13732 -0.987645 0.2191174 -0.3985217 -0.8905999 0.219088 -0.3982952 -0.8907085 0.3409524 -0.6198582 -0.7067725 0.3410217 -0.6203643 -0.7062948 0.4294841 -0.7812938 -0.4529057 0.4295221 -0.7809398 -0.4534798 0.4759635 -0.86538 -0.1567687 0.4758882 -0.8655025 -0.1563204 0.5760974 -0.8023858 -0.1558489 0.0911585 -0.1273277 -0.9876628 0.2646556 -0.369679 -0.8906711 0.2647037 -0.3697904 -0.8906106 0.4118342 -0.5753355 -0.7066694 0.4118026 -0.5752345 -0.70677 0.5189065 -0.7248372 -0.4531524 0.5189056 -0.7249823 -0.4529213 0.574832 -0.8031151 -0.1567621 0.5748039 -0.8031544 -0.1566638 0.1056089 -0.1156986 -0.9876541 0.306607 -0.3358985 -0.8905978 0.3065496 -0.3357765 -0.8906636 0.4770566 -0.522539 -0.7066612 0.4770555 -0.5225219 -0.7066746 0.6008837 -0.6581492 -0.4536283 0.6009348 -0.6584216 -0.4531649 0.6659079 -0.7296055 -0.1557 0.6659191 -0.729578 -0.1557816 0.8781378 -0.4519503 -0.1568917 0.8187189 -0.5523624 -0.1568289 0.8185709 -0.5525068 -0.1570924 0.8184865 -0.552833 -0.1563832 0.7475924 -0.6455034 -0.1563044 0.7476025 -0.6454768 -0.1563655 0.7471616 -0.6461458 -0.1557088 0.925581 -0.3450129 -0.1557751 0.9255904 -0.3449969 -0.1557554 0.8349898 -0.3112486 -0.4537802 0.7924311 -0.4075155 -0.4538549 0.6294499 -0.3237034 -0.7064056 0.5865427 -0.3961864 -0.7064022 0.3768261 -0.2545285 -0.8906275 0.344159 -0.2972119 -0.8906289 0.1185731 -0.1023959 -0.9876515 0.105611 -0.115704 -0.9876533 0.9598973 -0.2330213 -0.1558791 0.1523246 -0.03700202 -0.9876376 0.4417212 -0.1073055 -0.8907122 0.4416114 -0.1072233 -0.8907765 0.6878278 -0.1670048 -0.706401 0.6874808 -0.1667723 -0.7067936 0.866007 -0.2100827 -0.4537588 0.8663038 -0.2103923 -0.4530486 0.9598571 -0.2331188 -0.1559805 0.9598634 -0.2332367 -0.1557661 0.9798787 -0.123744 -0.1566048 0.1555907 -0.01872873 -0.9876441 0.4512807 -0.05431383 -0.8907277 0.4513165 -0.05433017 -0.8907086 0.7029153 -0.0846256 -0.7062215 0.7027352 -0.08451956 -0.7064133 0.8850805 -0.1064326 -0.4531058 0.8847357 -0.1061467 -0.4538454 0.9807113 -0.1176813 -0.156066 0.9807508 -0.1177601 -0.1557578 0.1565668 -1.56945e-4 -0.9876674 0.4545548 -4.58876e-4 -0.8907186 0.4545184 -4.36437e-4 -0.8907374 0.7080359 -6.78109e-4 -0.7061762 0.7079834 -6.61489e-4 -0.7062289 0.8910622 -8.35386e-4 -0.4538807 0.891474 -0.001106798 -0.4530705 0.9878282 -0.001225888 -0.1555444 0.9876601 -9.06772e-4 -0.1566104 0.1556683 0.01836508 -0.9876387 0.4515982 0.05327826 -0.8906294 0.4514179 0.05332899 -0.8907176 0.7024846 0.08297681 -0.7068454 0.7032079 0.08277148 -0.7061498 0.8854244 0.1042075 -0.4529509 0.884916 0.1044577 -0.4538858 0.9808621 0.1158026 -0.1565233 0.9809083 0.1157091 -0.1563023 0.9604659 0.2302257 -0.1565296 0.1522588 0.03664755 -0.987661 0.4416539 0.1063071 -0.8908652 0.4421404 0.1062591 -0.8906295 0.6885231 0.1654645 -0.7060861 0.6876999 0.1656078 -0.7068544 0.866425 0.2086501 -0.4536219 0.8667855 0.2085143 -0.4529952 0.9603463 0.231027 -0.1560822 0.9602713 0.2311098 -0.1564209 0.1470519 0.05444854 -0.987629 0.4261101 0.1577737 -0.8908074 0.4260334 0.1577731 -0.8908442 0.6636813 0.245779 -0.7064841 0.6640286 0.2457711 -0.7061605 0.8358801 0.309365 -0.4534292 0.8357712 0.3093914 -0.4536116 0.9263677 0.3429228 -0.1557151 0.9261897 0.3430899 -0.156404 0.7491965 0.6439843 -0.1548837 0.8193342 0.5519804 -0.1549488 0.8198964 0.5507662 -0.1562896 0.8199031 0.5507662 -0.1562556 0.8791813 0.4501045 -0.1563527 0.879465 0.4499031 -0.1553336 0.87919 0.4503039 -0.1557282 0.6675188 0.7281133 -0.1557873 0.6674877 0.7281609 -0.1556981 0.6022002 0.6569248 -0.4536571 0.6757423 0.5810533 -0.4535962 0.5366597 0.4614435 -0.7064462 0.5875312 0.3946459 -0.7064431 0.377644 0.253661 -0.8905286 0.4050061 0.2071909 -0.8905292 0.1395653 0.07139515 -0.9876357 0.1470199 0.05444592 -0.987634 0.5764064 0.802184 -0.1557452 0.09156656 0.1272717 -0.9876323 0.2654658 0.3689991 -0.8907118 0.2653777 0.3689225 -0.8907698 0.4132208 0.5744575 -0.7065743 0.4131934 0.5744361 -0.7066078 0.5204756 0.7235759 -0.4533686 0.5202864 0.7235016 -0.4537044 0.5766506 0.801889 -0.1563593 0.5769037 0.8018169 -0.1557939 0.07581973 0.1371368 -0.9876461 0.2201392 0.3981568 -0.8905111 0.2198137 0.3978531 -0.8907272 0.3421211 0.6192191 -0.7067679 0.3422788 0.6193538 -0.7065735 0.4310984 0.7800684 -0.4534839 0.4311629 0.7801117 -0.4533481 0.4778409 0.8645623 -0.1555639 0.4777558 0.8645666 -0.1558016 0.2067295 -0.9783982 0 0.2068098 -0.9783812 -4.61613e-5 0.2068915 -0.9783639 0 0.9507117 -0.3100763 0 0.9507244 -0.3100376 -2.50033e-5 0.9507392 -0.3099919 0 0.7438329 0.6683657 0 0.7438347 0.6683637 0 -0.2067336 0.9783973 0 -0.206811 0.978381 -4.23145e-5 -0.2068899 0.9783642 0 -0.9506984 0.3101171 0 -0.9507253 0.3100346 -4.90451e-5 -0.9507501 0.3099588 0 -6.7439e-7 0 -1 1.45438e-6 0 -1 -7.6198e-7 0 -1 1.97267e-7 0 -1 1.93649e-7 0 -1 -1.42757e-6 0 -1 -9.19243e-7 0 -1 2.63061e-7 0 -1 0 0 -1 1.44515e-7 0 -1 -1.97697e-7 0 -1 -3.90524e-7 0 -1 7.66495e-7 0 -1 -7.90359e-7 0 -1 3.91882e-7 0 -1 -3.53254e-7 0 -1 3.30332e-7 0 -1 3.92995e-7 0 -1 -5.74806e-7 0 -1 3.93889e-7 0 -1 -3.85383e-7 0 -1 3.6999e-7 0 -1 2.31311e-7 0 -1 -3.75896e-7 0 -1 -1.49236e-6 0 -1 7.74521e-7 0 -1 -3.94593e-7 0 -1 7.2741e-7 0 -1 -1.59045e-6 0 -1 -3.42233e-7 0 -1 -5.19067e-7 0 -1 -5.07227e-7 0 -1 -4.50424e-7 0 -1 0.6845624 0.7289478 0.003105401 0.5162126 0.85646 -8.32988e-4 0.5514298 0.834214 0.00351566 0.6140812 0.789241 -0.001769781 0.6135554 0.7896498 -0.001770079 0.5158301 0.8566906 -8.31469e-4 0.4113714 0.9114671 0.001095116 0.4025945 0.9153752 0.002411842 0.1855062 0.9826421 -0.001431107 0.2420799 0.9702494 0.003669142 0.3008529 0.9536694 -0.001512646 0.3003929 0.9538143 -0.001510798 0.186288 0.9824942 -0.001431882 0.06812459 0.9976738 0.002458155 0.07459789 0.9972127 0.001460731 -0.1682502 0.9857428 -0.001729786 -0.09519201 0.9954527 0.003561854 -0.05017459 0.99874 -0.001001477 -0.05114209 0.9986909 -0.001002073 -0.1673446 0.985897 -0.001728057 -0.2835435 0.9589506 0.004108846 -0.2617576 0.9651337 2.68048e-4 -0.3966212 0.9179825 -1.99588e-4 -0.394984 0.9186881 -1.99789e-4 -0.4212999 0.9069159 0.003184199 -0.5996688 0.800248 -6.89557e-4 -0.5684282 0.8227257 0.00345391 -0.5008969 0.8655052 -0.001759588 -0.5003697 0.86581 -0.001759707 -0.5991137 0.8006637 -6.8984e-4 -0.6901769 0.7236403 8.70396e-4 -0.6992391 0.7148834 0.002554297 -0.8407412 0.5414357 -0.001314878 -0.8100226 0.5863873 0.003658056 -0.7707042 0.6371913 -0.00157839 -0.7706962 0.6372008 -0.001578688 -0.8410528 0.5409515 -0.00131452 -0.8989214 0.4381049 0.002153098 -0.8974924 0.4410268 0.0016644 -0.9766827 0.2146815 -0.001707732 -0.9591189 0.282981 0.00358498 -0.944477 0.3285759 -0.001101911 -0.9441986 0.3293752 -0.001101791 -0.9766221 0.2149571 -0.001707017 -0.9952174 0.09761458 0.003719866 -0.9931492 0.1168527 5.0396e-4 -0.999853 -0.01714605 -3.70391e-4 -0.9997842 -0.02077043 -3.70364e-4 -0.9986032 -0.05273443 0.003282904 -0.9669742 -0.2548737 -5.39782e-4 -0.9753634 -0.2205786 0.003373563 -0.9903368 -0.1386716 -0.001791596 -0.9903271 -0.1387413 -0.001791477 -0.9672287 -0.2539064 -5.39034e-4 -0.9299453 -0.3676977 6.28054e-4 -0.9239706 -0.382454 0.002705991 -0.8175001 -0.5759271 -0.001221895 -0.8460831 -0.5330387 0.003653883 -0.8799777 -0.4750122 -0.00160861 -0.8804063 -0.4742177 -0.001607835 -0.8180477 -0.5751491 -0.001222252 -0.7439926 -0.6681853 0.001880586 -0.7439313 -0.6682535 0.001894772 -0.5657873 -0.8245497 -0.001652419 -0.6202082 -0.7844288 0.003642499 -0.6598135 -0.7514284 -0.00123471 -0.6586837 -0.752419 -0.001233696 -0.5663326 -0.8241752 -0.001654505 -0.4645506 -0.8855402 0.003384947 -0.4787523 -0.8779498 7.60203e-4 -0.3569917 -0.9341074 -5.51571e-4 -0.356606 -0.9342547 -5.51123e-4 -0.3232895 -0.9462941 0.003378212 -0.1271913 -0.9918782 -3.34438e-4 -0.1588676 -0.9872943 0.003319203 -0.2440041 -0.9697726 -0.001787424 -0.2433907 -0.9699268 -0.001786708 -0.1254428 -0.9921008 -3.33754e-4 -0.008898377 -0.9999604 4.21687e-4 0.01007544 -0.9999452 0.002837836 0.2263 -0.974057 -0.001105189 0.179225 -0.9838016 0.003600597 0.109131 -0.994026 -0.001715302 0.1095489 -0.9939799 -0.001715123 0.2256662 -0.9742041 -0.001104712 0.339798 -0.9404971 0.001610875 0.3428558 -0.9393858 0.002076506 0.5508052 -0.8346324 -0.001549422 0.496513 -0.8680217 0.003649711 0.4488269 -0.8936179 -0.001293659 0.4482359 -0.8939145 -0.001291871 0.55188 -0.8339221 -0.00155127 0.645867 -0.763444 0.003050327 0.6361081 -0.7715995 0.00101751 0.7321053 -0.6811912 -7.07269e-4 0.7317769 -0.6815439 -7.06928e-4 0.7574836 -0.6528453 0.00343734 0.8069534 -0.5906126 -0.001747667 0.8075574 -0.5897867 -0.001748204 0.8568394 -0.5155738 0.003196001 0.8712572 -0.4908267 -1.65762e-4 0.931624 -0.3634236 -1.65395e-4 0.8728064 -0.4875025 0.02346134 0.9233199 -0.3840102 0.004042804 0.9876411 -0.1567292 -9.74192e-4 0.9796566 -0.2006499 0.003540039 0.9622788 -0.27206 -0.001734733 0.9621549 -0.2724978 -0.001734554 0.9878307 -0.1555305 -9.74181e-4 0.9992519 -0.03865504 0.001321077 0.9994803 -0.0321567 0.002233862 0.9803248 0.1973854 -0.001511335 0.9905354 0.1372088 0.00366503 0.9968015 0.07990562 -0.001411736 0.9968351 0.07948541 -0.001411676 0.9803389 0.1973152 -0.001511037 0.9502313 0.3115336 0.002727806 0.9531306 0.3025569 0.001252472 0.9063601 0.4225055 -8.4601e-4 0.9066362 0.4219124 -8.46273e-4 0.8882556 0.4593362 0.003507912 0.8504498 0.5260536 -0.001747608 0.8501334 0.5265647 -0.00174731 0.7978061 0.6029062 0.003085315 0.7821245 0.6231222 0 0.7031072 0.7110839 0 0.9504604 -0.2691934 -0.1554355 0.1082116 -0.9818823 -0.1555554 -0.8695881 -0.4684701 -0.1560527 -0.9782288 -0.1370729 -0.1558192 -0.7611853 0.6293593 -0.1565371 -0.4942619 0.8551941 -0.1560398 0.6059542 0.7799009 -0.1567623 0.4455685 0.08959126 -0.8907538 0.2504822 -0.3793471 -0.8907045 -0.257595 -0.3749194 -0.8905505 -0.4439809 0.09764152 -0.8907003 -0.07649672 0.4479624 -0.8907739 0.1225785 0.09762871 -0.9876453 0.1332758 0.08247828 -0.9876412 0.1548467 -0.02457576 -0.9876328 0.1506712 -0.04261976 -0.9876649 0.1446263 -0.06017059 -0.9876552 0.1365625 -0.07689559 -0.9876425 0.1264844 -0.09253042 -0.9876436 0.03545981 -0.1526359 -0.9876462 0.01712572 -0.1558724 -0.9876287 -0.001403987 -0.1566374 -0.9876552 -0.01991403 -0.1553816 -0.9876539 -0.03816068 -0.1519469 -0.9876518 -0.1281787 -0.09022414 -0.9876385 -0.1379109 -0.07441002 -0.9876456 -0.1456381 -0.05755358 -0.9876626 -0.1514705 -0.03993201 -0.9876549 -0.1551229 -0.02174508 -0.9876558 -0.1317686 0.08484077 -0.9876432 -0.1208283 0.09982568 -0.9876413 -0.1081302 0.1134209 -0.9876455 -0.09392511 0.1253178 -0.9876607 -0.07846111 0.1356993 -0.9876384 0.08088469 0.1342293 -0.9876438 0.0961973 0.1236694 -0.9876498 0.1101606 0.1114532 -0.9876452 -0.02633923 0.1544702 -0.9876464 -0.02635568 0.154338 -0.9876666 -0.007874846 0.1563843 -0.9876649 -0.1529659 0.0336138 -0.9876596 -0.153032 0.0336526 -0.9876481 -0.1479812 0.05155968 -0.9876453 -0.08864945 -0.1291173 -0.9876589 -0.08878487 -0.1292235 -0.9876329 -0.1034241 -0.1178432 -0.9876317 0.08633959 -0.1306994 -0.9876554 0.0863716 -0.1308085 -0.9876382 0.07031947 -0.1400994 -0.9876373 0.1536453 0.03089046 -0.9876432 0.1536309 0.03089004 -0.9876455 0.1561888 0.01252216 -0.9876479 -0.2006039 0.6789155 -0.7062804 -0.1287785 0.4358388 -0.8907641 -0.1287899 0.4356757 -0.8908423 -0.04442453 0.150282 -0.9876446 -0.04442751 0.150228 -0.9876527 -0.7044395 0.06914961 -0.7063876 -0.4524292 0.04440993 -0.8906939 -0.4523119 0.04435122 -0.8907565 -0.1558634 0.01528346 -0.9876604 -0.1559782 0.01533478 -0.9876415 -0.3288971 -0.626637 -0.7065075 -0.2113864 -0.4027463 -0.8905679 -0.210991 -0.4023817 -0.8908265 -0.07273721 -0.1387199 -0.9876569 -0.07272535 -0.1387073 -0.9876595 0.4572767 -0.5403195 -0.706366 0.2936623 -0.3469807 -0.8907114 0.2935842 -0.3468231 -0.8907986 0.1012139 -0.1195637 -0.987654 0.1012022 -0.1195447 -0.9876575 0.6727337 0.2206775 -0.7062087 0.4318638 0.1416655 -0.8907439 0.4317883 0.1416685 -0.89078 0.1488893 0.04885047 -0.9876466 0.1489294 0.04885029 -0.9876405 0.2128331 0.6751128 -0.7063461 -0.3520057 0.8188249 -0.4534511 -0.279592 0.6503877 -0.7062749 -0.2795955 0.6501871 -0.7064581 -0.1794669 0.4173521 -0.8908473 -0.1794962 0.4178633 -0.8906018 -0.06182968 0.1439424 -0.9876526 -0.06181675 0.1438632 -0.9876649 -0.6682723 0.2326719 -0.7065946 -0.8910341 -0.01843106 -0.4535621 -0.7076932 -0.01463794 -0.7063682 -0.7078888 -0.01456153 -0.7061738 -0.4543635 -0.00934422 -0.8907673 -0.4543551 -0.009353578 -0.8907717 -0.1566944 -0.003225088 -0.9876419 -0.1566514 -0.003237783 -0.9876487 -0.4667881 -0.5317683 -0.7066339 -0.3175649 -0.8325989 -0.4537969 -0.2522065 -0.6612457 -0.7065028 -0.2522898 -0.6613189 -0.7064044 -0.1619386 -0.4244832 -0.8908367 -0.1622461 -0.4248604 -0.8906009 -0.05587869 -0.1463176 -0.9876583 -0.05591219 -0.1463664 -0.9876492 0.3175297 -0.6324046 -0.7065687 0.6521288 -0.6071693 -0.4539532 0.518053 -0.4823294 -0.7063848 0.5182552 -0.4827535 -0.7059467 0.3325374 -0.3097556 -0.8907695 0.3325048 -0.3097302 -0.8907905 0.1146134 -0.1067604 -0.9876569 0.1145846 -0.1067053 -0.9876662 0.705796 0.05638116 -0.706168 0.8082026 0.3760173 -0.4532321 0.6419622 0.2986837 -0.7061675 0.6417073 0.2986807 -0.7064005 0.4119774 0.1917502 -0.8907899 0.4122049 0.1917731 -0.8906797 0.1421161 0.06611657 -0.9876394 0.1419632 0.06609874 -0.9876626 0.267893 0.8501565 -0.4532852 0.2680556 0.8502941 -0.4529308 0.165626 0.8759933 -0.4529942 -0.05051863 0.9864108 -0.1563383 0.06735503 0.9854072 -0.1563208 0.0607745 0.8891132 -0.4536347 0.1653648 0.8757134 -0.4536303 0.1312936 0.6952815 -0.706644 0.2125946 0.6748378 -0.7066807 0.1364849 0.4332388 -0.8908849 0.04710978 0.1494352 -0.9876487 0.029123 0.1539506 -0.9876493 0.08455336 0.4469282 -0.890565 0.03099459 0.4537948 -0.8905671 0.04821646 0.7059171 -0.7066514 -0.03547817 0.7066617 -0.7066617 -0.04470533 0.8904603 -0.4528599 -0.149655 0.8789831 -0.4527605 0.02907681 0.1538614 -0.9876645 0.01065605 0.1562312 -0.987663 0.03093701 0.4536409 -0.8906475 -0.02279716 0.4541508 -0.8906331 -0.03547418 0.7066764 -0.7066472 -0.119086 0.6974521 -0.7066676 -0.1499585 0.8782477 -0.4540855 -0.2526507 0.8544322 -0.453997 -0.2800819 0.9471994 -0.1561007 -0.3916584 0.9067855 -0.1560252 -0.8416634 0.2929359 -0.4536423 -0.8417724 0.2930771 -0.4533488 -0.8705464 0.1913673 -0.4533517 -0.9877054 -0.01679128 -0.1554229 -0.9831085 0.09663802 -0.1554313 -0.8870294 0.08718609 -0.4534066 -0.8705453 0.1913834 -0.4533468 -0.691007 0.1519059 -0.7067064 -0.6681593 0.2325695 -0.7067352 -0.4293188 0.1494418 -0.8907035 -0.5880643 -0.670033 -0.4530302 -0.5882065 -0.6700698 -0.4527909 -0.50468 -0.7350037 -0.452844 -0.3525462 -0.9226865 -0.1560804 -0.4589597 -0.8746325 -0.1561214 -0.4141394 -0.7892479 -0.4534052 -0.5043633 -0.7348818 -0.4533944 -0.4003649 -0.5833597 -0.7066821 -0.4667122 -0.5317265 -0.7067154 -0.2998293 -0.3415933 -0.8907393 0.3999364 -0.7968329 -0.4528887 0.3999619 -0.7965788 -0.4533133 0.4912555 -0.7437624 -0.453305 0.7231661 -0.6727384 -0.1563776 0.6380868 -0.7538872 -0.1565229 0.5759484 -0.6804707 -0.4530377 0.4912697 -0.743883 -0.4530917 0.3900315 -0.5906028 -0.7064446 0.3175458 -0.6325903 -0.7063952 0.2040338 -0.4064571 -0.890597 0.8885052 0.07095241 -0.4533478 0.8884701 0.07096332 -0.453415 0.8737517 0.1757478 -0.4535092 0.8953326 0.4169566 -0.1566104 0.8953326 0.4169566 -0.1566103 0.8953325 0.4169566 -0.1566104 0.9383726 0.3081106 -0.1566041 0.8464202 0.2779432 -0.454225 0.8733495 0.1758837 -0.4542309 0.6934426 0.1396605 -0.7068468 0.7050803 0.05661296 -0.7068641 0.4531867 0.03639453 -0.8906724 0.1101434 0.1114448 -0.987648 0.3196029 0.3233813 -0.8906619 0.3195663 0.3233557 -0.8906843 0.4973867 0.5032857 -0.7066187 0.497604 0.5033802 -0.7063983 0.626699 0.6339654 -0.4531406 0.6264944 0.6339043 -0.4535087 0.6942362 0.7024742 -0.1567358 0.6945156 0.7023854 -0.155894 0.09622812 0.1236951 -0.9876435 0.2792984 0.3590126 -0.890563 0.2790955 0.3588822 -0.8906791 0.4344367 0.5586308 -0.7065384 0.434363 0.5585953 -0.7066117 0.547037 0.7034869 -0.4537146 0.5473694 0.7036067 -0.4531274 0.6064952 0.7796158 -0.1560865 0.6065989 0.7795947 -0.155788 0.5095088 0.846195 -0.1560605 0.08086031 0.1342121 -0.9876481 0.2344706 0.3891708 -0.8908253 0.2348817 0.3895236 -0.8905627 0.3656713 0.6064197 -0.7060735 0.3652812 0.6061502 -0.7065066 0.4599287 0.7632003 -0.4538624 0.4599729 0.7632316 -0.4537649 0.509838 0.8459694 -0.156208 0.5098933 0.845966 -0.1560466 0.06445097 0.1428424 -0.9876448 0.1868055 0.4140194 -0.8908938 0.1869055 0.4141144 -0.8908287 0.2912267 0.6452482 -0.7062873 0.2914112 0.6454142 -0.7060596 0.3668019 0.8123936 -0.4532914 0.3665135 0.8122112 -0.4538515 0.406264 0.9002894 -0.1562969 0.406331 0.9003012 -0.1560541 0.0672847 0.9853754 -0.1565511 0.1839836 0.9703741 -0.1566025 0.1835035 0.970547 -0.1560937 0.1832131 0.9704832 -0.1568292 0.2968249 0.941965 -0.1568347 0.2971854 0.9420438 -0.1556743 0.2966997 0.9421123 -0.1561852 0.06446337 0.1428585 -0.9876417 0.04713732 0.1494595 -0.9876436 0.1367304 0.4335898 -0.8906766 0.08443808 0.4467325 -0.8906741 0.1314583 0.695496 -0.7064023 0.04836589 0.7061994 -0.706359 0.06090801 0.8892858 -0.4532783 -0.04482978 0.8902684 -0.4532248 -0.0496757 0.9865208 -0.1559143 -0.2800686 0.947202 -0.1561086 -0.1652956 0.9738063 -0.1561377 -0.1658052 0.9738385 -0.1553943 -0.1661878 0.9736395 -0.1562304 -0.04955756 0.9864736 -0.1562502 -0.390143 0.9074379 -0.1560289 -0.3901701 0.9074457 -0.1559158 -0.3520219 0.8187406 -0.4535906 -0.252575 0.8546715 -0.4535884 -0.200598 0.6788017 -0.7063914 -0.1189979 0.6978293 -0.70631 -0.07644557 0.4482998 -0.8906085 -0.02279311 0.4542037 -0.8906062 -0.007852852 0.1564702 -0.9876515 0.01068615 0.156311 -0.9876502 -0.07842391 0.1355424 -0.9876629 -0.2276265 0.3934136 -0.8907368 -0.2276961 0.393714 -0.8905863 -0.3542372 0.6125159 -0.7066401 -0.3542587 0.6126875 -0.7064806 -0.4463508 0.7719594 -0.4526033 -0.4463852 0.7714778 -0.45339 -0.494637 0.8548704 -0.1566238 -0.4946913 0.8547737 -0.156979 -0.5916877 0.7908999 -0.1561511 -0.09396433 0.1254436 -0.987641 -0.2726646 0.364016 -0.8905876 -0.2725775 0.3637303 -0.8907311 -0.4242695 0.5661483 -0.7067331 -0.4242998 0.5662549 -0.7066294 -0.5345737 0.7134158 -0.4530663 -0.5346015 0.7137246 -0.4525467 -0.5921708 0.7905696 -0.1559922 -0.5922664 0.7903831 -0.1565732 -0.1080857 0.1133358 -0.9876602 -0.3137319 0.3289713 -0.8907021 -0.3138416 0.3291805 -0.8905861 -0.488363 0.51225 -0.7064712 -0.4882726 0.5119965 -0.7067175 -0.6154016 0.6452984 -0.4526267 -0.6153461 0.6450632 -0.453037 -0.6817532 0.7146517 -0.1564791 -0.6817133 0.71475 -0.1562033 -0.1208174 0.09980446 -0.9876448 -0.3504221 0.2894788 -0.8907337 -0.3504731 0.2895507 -0.8906902 -0.5454567 0.4506465 -0.7066788 -0.5455548 0.4508166 -0.7064945 -0.6871822 0.5678504 -0.45313 -0.6872872 0.5681508 -0.4525936 -0.7612167 0.629269 -0.1567474 -0.7612029 0.6293252 -0.1565887 -0.830739 0.5342999 -0.1561938 -0.131777 0.08485507 -0.9876409 -0.3820092 0.2459753 -0.8908228 -0.3821309 0.2461433 -0.8907241 -0.5952717 0.3834142 -0.7061482 -0.5949509 0.3829598 -0.7066649 -0.7492829 0.4823108 -0.4538187 -0.7494577 0.4826769 -0.4531405 -0.8303427 0.534763 -0.1567155 -0.8303449 0.5347443 -0.1567669 -0.1408536 0.06865841 -0.9876469 -0.4085699 0.1991489 -0.8907359 -0.4084628 0.1990473 -0.8908078 -0.6361238 0.3099727 -0.7065858 -0.6363964 0.3103314 -0.7061828 -0.8010733 0.3906038 -0.4535533 -0.8009798 0.3904611 -0.4538409 -0.8878971 0.4328088 -0.1559342 -0.887889 0.4327368 -0.1561797 -0.9830159 0.09642058 -0.1561499 -0.9646408 0.2123309 -0.1561534 -0.9647488 0.2120793 -0.1558272 -0.964748 0.2120516 -0.1558704 -0.9328846 0.3246903 -0.1558926 -0.932868 0.324538 -0.1563086 -0.9326689 0.325343 -0.1558231 -0.9875789 -0.02051126 -0.1557796 -0.987536 -0.0204221 -0.1560627 -0.8910427 -0.018431 -0.4535454 -0.8869867 0.08717274 -0.4534927 -0.7046008 0.06923055 -0.7062187 -0.6914308 0.1522179 -0.7062246 -0.4442499 0.09779459 -0.8905494 -0.4295377 0.1496177 -0.8905684 -0.1479431 0.05153352 -0.9876524 -0.1408357 0.06863355 -0.9876512 -0.1551737 -0.02173846 -0.9876481 -0.4501475 -0.06306201 -0.8907248 -0.4500437 -0.06307584 -0.8907761 -0.7012216 -0.09829747 -0.7061346 -0.7011845 -0.09829807 -0.7061712 -0.8825842 -0.1237302 -0.4535813 -0.8825975 -0.1237327 -0.4535546 -0.9781574 -0.1371209 -0.1562246 -0.9782724 -0.1369747 -0.1556313 -0.9552979 -0.2507039 -0.156696 -0.9552984 -0.2507039 -0.1566926 -0.9552979 -0.2507039 -0.156696 -0.1514644 -0.03993183 -0.9876558 -0.439814 -0.1159442 -0.8905732 -0.4395161 -0.115979 -0.8907158 -0.6840872 -0.1805153 -0.70671 -0.6846798 -0.180425 -0.7061589 -0.8619481 -0.2271458 -0.4532661 -0.8617731 -0.2272096 -0.4535667 -0.9550496 -0.2517806 -0.1564825 -0.9551048 -0.2517354 -0.156218 -0.1456879 -0.05755883 -0.9876548 -0.4228654 -0.1670684 -0.8906587 -0.42302 -0.1670724 -0.8905847 -0.6581315 -0.2599323 -0.7066103 -0.6580378 -0.2599373 -0.7066957 -0.8292375 -0.327564 -0.4528434 -0.8290335 -0.327599 -0.4531913 -0.918634 -0.3629847 -0.1560569 -0.9184634 -0.3631464 -0.1566834 -0.1378099 -0.0743882 -0.9876614 -0.4001129 -0.2159804 -0.8906527 -0.4001051 -0.2159813 -0.8906561 -0.6225681 -0.3360617 -0.706733 -0.6226963 -0.3360896 -0.7066067 -0.7845335 -0.4234402 -0.4529961 -0.7846621 -0.4234074 -0.4528044 -0.8691789 -0.4690317 -0.1566441 -0.8690706 -0.4690933 -0.1570596 -0.8079324 -0.5680885 -0.1565907 -0.128125 -0.09020197 -0.9876475 -0.3717806 -0.2617402 -0.8906578 -0.3717964 -0.2617482 -0.8906489 -0.5786268 -0.4073513 -0.7065805 -0.5785125 -0.4073425 -0.7066792 -0.7289712 -0.5132797 -0.4529294 -0.7289345 -0.5132733 -0.4529955 -0.8076134 -0.5686709 -0.1561222 -0.8073924 -0.5688239 -0.1567063 -0.1165854 -0.1047746 -0.9876387 -0.3380588 -0.3038186 -0.890736 -0.3382143 -0.3038737 -0.8906581 -0.5263305 -0.4729026 -0.7066395 -0.5263723 -0.4729121 -0.706602 -0.663173 -0.5958316 -0.452975 -0.6632319 -0.5958235 -0.4528995 -0.7346468 -0.6599957 -0.1571617 -0.7348117 -0.6599381 -0.1566317 -0.4588317 -0.8746405 -0.1564528 -0.5593672 -0.8140215 -0.156453 -0.5591107 -0.8142742 -0.156054 -0.5587948 -0.8143653 -0.1567083 -0.6514815 -0.7422806 -0.1568171 -0.6517259 -0.7422331 -0.1560239 -0.6505195 -0.7430627 -0.1571056 -0.3522393 -0.9228091 -0.1560475 -0.3522844 -0.9227473 -0.1563111 -0.3179897 -0.8329216 -0.4529065 -0.4143942 -0.7893824 -0.452938 -0.329002 -0.6267175 -0.7063872 -0.4006231 -0.5835372 -0.7063891 -0.2571926 -0.3746084 -0.8907977 -0.2997716 -0.3415657 -0.8907693 -0.1034164 -0.1178343 -0.9876337 -0.1166226 -0.1047943 -0.9876322 -0.2409948 -0.9577821 -0.156764 -0.03817522 -0.1519639 -0.9876486 -0.1108143 -0.4411466 -0.8905671 -0.110787 -0.4411008 -0.8905934 -0.172298 -0.6860111 -0.7068961 -0.1726053 -0.6864237 -0.7064206 -0.2174379 -0.8647139 -0.452759 -0.2169663 -0.8642917 -0.4537901 -0.2404983 -0.958046 -0.1559116 -0.2403991 -0.9580403 -0.1561002 -0.123892 -0.9798448 -0.1567006 -0.01991808 -0.15539 -0.9876525 -0.05781936 -0.4510838 -0.8906068 -0.05787825 -0.4511871 -0.8905506 -0.09006696 -0.7021082 -0.7063513 -0.08976978 -0.701551 -0.7069425 -0.1131311 -0.8841174 -0.453363 -0.113372 -0.8844161 -0.4527195 -0.1255717 -0.9795741 -0.1570556 -0.125617 -0.979599 -0.1568641 -0.001404464 -0.1566488 -0.9876534 -0.004078149 -0.4547024 -0.8906342 -0.004091501 -0.454738 -0.8906159 -0.006367325 -0.7076263 -0.7065582 -0.006434381 -0.7077721 -0.7064115 -0.00810182 -0.8911098 -0.4537156 -0.008252859 -0.8913465 -0.4532478 -0.009145677 -0.9877985 -0.1554686 -0.008788406 -0.987612 -0.1566694 0.01715737 -0.155712 -0.9876536 0.04976522 -0.4516513 -0.8908056 0.04968529 -0.4519932 -0.8906366 0.07734721 -0.7036077 -0.7063665 0.07741057 -0.7033455 -0.7066206 0.09751069 -0.8859856 -0.4533447 0.09759813 -0.8858039 -0.4536803 0.1081697 -0.9817555 -0.1563823 0.107814 -0.9820196 -0.1549637 0.2229034 -0.9622091 -0.1564218 0.03545349 -0.1527418 -0.98763 0.102766 -0.442751 -0.8907361 0.1027719 -0.4426256 -0.8907977 0.1600137 -0.6891667 -0.7067143 0.1599446 -0.6894782 -0.706426 0.2015014 -0.8686116 -0.4526713 0.2016444 -0.8681877 -0.4534201 0.2234643 -0.9621409 -0.1560402 0.2235162 -0.9620965 -0.1562396 0.05321013 -0.1474089 -0.9876434 0.1544182 -0.4277868 -0.8905916 0.1544073 -0.4274365 -0.8907617 0.2404187 -0.6655272 -0.7065922 0.2404287 -0.66539 -0.706718 0.3029836 -0.83852 -0.4528634 0.3029449 -0.8386644 -0.452622 0.3355608 -0.9289683 -0.1562591 0.3356118 -0.9289096 -0.1564986 0.6379944 -0.7541292 -0.1557316 0.5451251 -0.8237761 -0.1556648 0.5443282 -0.8241127 -0.1566691 0.544101 -0.8244324 -0.1557733 0.4430878 -0.8828235 -0.1558715 0.4432832 -0.8825644 -0.1567807 0.4427198 -0.8829393 -0.1562607 0.7228612 -0.6732397 -0.1556284 0.7226888 -0.6733017 -0.1561594 0.6522384 -0.6076779 -0.4531145 0.575932 -0.6804515 -0.4530873 0.4572616 -0.540239 -0.7064372 0.390043 -0.5906208 -0.7064231 0.2504699 -0.3792786 -0.8907372 0.203981 -0.4061505 -0.8907489 0.07030093 -0.1399757 -0.9876561 0.05320668 -0.1473174 -0.9876571 0.7977281 -0.5826286 -0.1554798 0.1264045 -0.09241044 -0.9876651 0.3669687 -0.2682903 -0.8907045 0.366882 -0.2681397 -0.8907855 0.5714687 -0.4176831 -0.7063742 0.5716865 -0.418051 -0.7059802 0.7192171 -0.5259319 -0.4540072 0.7192153 -0.5259252 -0.4540178 0.7972701 -0.5830101 -0.1563962 0.7971226 -0.5834101 -0.1556549 0.862318 -0.4817377 -0.1560017 0.136572 -0.0768963 -0.9876412 0.396137 -0.2230466 -0.8906884 0.3961387 -0.2230424 -0.8906886 0.6164893 -0.3471142 -0.7067197 0.616723 -0.3473971 -0.7063767 0.7765295 -0.4374505 -0.4534745 0.7763947 -0.4371255 -0.4540184 0.8606614 -0.4845833 -0.1563364 0.8606612 -0.4848605 -0.1554757 0.1446966 -0.06022816 -0.9876414 0.4199957 -0.174822 -0.8905284 0.4197351 -0.1745891 -0.890697 0.6532014 -0.2716938 -0.7067606 0.6532407 -0.2717267 -0.7067115 0.8227797 -0.3422389 -0.4537689 0.8228882 -0.3423965 -0.4534529 0.9120433 -0.3795072 -0.1554074 0.9120177 -0.3793102 -0.1560369 0.1507157 -0.04264593 -0.987657 0.4374048 -0.1237679 -0.8907069 0.4377276 -0.1239728 -0.8905197 0.6809874 -0.1928701 -0.7064399 0.6807618 -0.1926975 -0.7067044 0.85776 -0.2427943 -0.4530991 0.8574721 -0.242488 -0.4538074 0.9505061 -0.2687792 -0.1558716 0.9504888 -0.2687293 -0.1560626 0.9757183 -0.1535915 -0.1561521 0.1546542 -0.02447307 -0.9876656 0.4486969 -0.07100927 -0.8908585 0.4489654 -0.07115429 -0.8907117 0.6992725 -0.1108149 -0.7062139 0.6990919 -0.1107203 -0.7064076 0.8804392 -0.1394157 -0.4531999 0.8804611 -0.1394547 -0.4531455 0.9754885 -0.1545156 -0.1566756 0.9755795 -0.1548074 -0.1558187 0.1566583 -0.00609225 -0.9876341 0.4543418 -0.01766383 -0.8906524 0.453966 -0.01751756 -0.8908468 0.7074777 -0.02730751 -0.706208 0.7074884 -0.02729398 -0.7061978 0.8906873 -0.0343644 -0.4533159 0.8907102 -0.03440302 -0.4532678 0.9869647 -0.03809487 -0.156364 0.9870071 -0.03819841 -0.1560704 0.9387412 0.3077606 -0.1550757 0.9684802 0.1949236 -0.1550842 0.9684891 0.1947886 -0.1551976 0.9683775 0.1949682 -0.1556678 0.9846694 0.07862854 -0.1557043 0.9844767 0.07893377 -0.1567647 0.9845746 0.07849007 -0.1563717 0.8955203 0.4167502 -0.1560857 0.8955356 0.4166565 -0.156248 0.8081821 0.3760228 -0.4532645 0.8470156 0.2777723 -0.4532186 0.6728864 0.2206645 -0.7060673 0.6942883 0.1395071 -0.7060465 0.4457916 0.08956962 -0.8906443 0.45324 0.03637129 -0.8906462 0.1561496 0.01253348 -0.9876539 0.1565304 -0.006042242 -0.9876547 0.8396925 0.5200607 -0.1563757 0.1331297 0.08244419 -0.9876637 0.3863244 0.2392483 -0.8907939 0.3865681 0.2393009 -0.890674 0.6016541 0.3724445 -0.70661 0.6018926 0.372489 -0.7063832 0.7581174 0.4691692 -0.4529222 0.7579318 0.4691861 -0.453215 0.8397761 0.5198251 -0.1567097 0.840012 0.5196143 -0.1561436 0.1226169 0.0976451 -0.987639 0.3556395 0.283221 -0.8906775 0.3554038 0.2831247 -0.8908023 0.5536139 0.4410202 -0.7064085 0.5534105 0.4409624 -0.7066038 0.6970482 0.5554172 -0.4534707 0.6973998 0.5554366 -0.452906 0.7726563 0.6153838 -0.1559006 0.7724986 0.6154589 -0.1563854 -0.4760467 -0.1570701 -0.8652794 -0.4437462 -0.2331897 -0.8652815 -0.3993414 -0.3029953 -0.8652863 -0.4934436 0.08838576 -0.8652754 -0.5012467 0.006254673 -0.8652819 -0.4953928 -0.07658648 -0.8652864 -0.3917716 0.312741 -0.8652792 -0.4378844 0.2439985 -0.8652873 -0.4667238 0.1809226 -0.8656997 -0.1958959 0.4614129 -0.8652878 -0.2690503 0.4229748 -0.8652769 -0.3350551 0.3728678 -0.8652789 -0.09004294 0.4919728 -0.8659417 0.1288767 0.4844344 -0.8652827 0.04744952 0.499042 -0.8652778 -0.03542399 0.500032 -0.8652821 0.3439466 0.3646571 -0.8652896 0.2792232 0.4163115 -0.8652856 0.2068709 0.4566029 -0.865285 0.4760378 0.1570656 -0.8652852 0.4437462 0.2331897 -0.8652815 0.3993447 0.3030093 -0.8652799 0.4934343 -0.08837205 -0.8652821 0.5012503 -0.006263732 -0.8652797 0.4953873 0.07662379 -0.8652862 0.391766 -0.3127365 -0.8652834 0.4378865 -0.2439902 -0.8652884 0.4666789 -0.181043 -0.8656988 0.1958979 -0.4614177 -0.8652848 0.2690503 -0.4229748 -0.8652769 0.3350551 -0.3728678 -0.8652789 -0.04744964 -0.4990434 -0.8652771 0.03542411 -0.5000336 -0.8652812 0.09004223 -0.491969 -0.865944 -0.2792263 -0.41631 -0.8652853 -0.2068676 -0.4566057 -0.8652843 -0.128876 -0.4844319 -0.8652843 -0.343945 -0.3646664 -0.8652863 0.1301227 -0.4833804 -0.8656856 0.4795954 -0.1418869 -0.8659425 -0.1301223 0.4833785 -0.8656867 -0.4795342 0.1420471 -0.8659502 0.07909458 -0.9968671 0 0.07908606 -0.9968678 1.65824e-5 0.07907897 -0.9968684 0 -0.9029193 0.4298103 0 -0.9028538 0.4299478 6.63295e-5 -0.9027916 0.4300785 0 -1.59641e-7 0 -1 -3.14475e-7 0 -1 1.64011e-7 0 -1 0 0 -1 0 0 -1 1.25025e-7 0 -1 0 0 -1 0 0 -1 -2.54482e-7 0 -1 2.5712e-7 0 -1 0 0 -1 -3.42864e-7 0 -1 2.52489e-7 0 -1 -1.63002e-7 0 -1 0 0 -1 0 0 -1 -2.97758e-7 0 -1 1.72135e-7 0 -1 -3.25805e-7 0 -1 0 0 -1 0 0 -1 2.41294e-7 0 -1 -1.66794e-7 0 -1 -3.29962e-7 0 -1 1.58395e-7 0 -1 0 0 -1 1.71794e-7 0 -1 -2.11267e-7 0 -1 3.14342e-7 0 -1 0 0 -1 0 0 -1 0.9352357 -0.354014 0.002907812 0.9890781 -0.1473879 -0.001232266 0.9807935 -0.1950172 0.003538787 0.9646452 -0.2635463 -0.001794159 0.9646808 -0.2634155 -0.001791656 0.9890285 -0.1477199 -0.001232624 0.9995555 -0.02975529 0.001885235 0.999511 -0.03122973 0.001662552 0.9960131 0.08920079 -0.001111149 0.9960037 0.08930528 -0.001110911 0.9909971 0.1338394 0.003461182 0.9786143 0.2056963 -0.00182271 0.978626 0.2056401 -0.001823663 0.9554558 0.2951189 0.003051459 0.9471713 0.3207282 -2.28222e-4 0.8938515 0.4483633 -2.22198e-4 0.946562 0.3216483 0.02372556 0.9028704 0.4298968 0.003740727 0.7763553 0.6302941 -0.001340925 0.8077647 0.5894942 0.003567814 0.8455371 0.5339139 -0.001738131 0.8453615 0.5341921 -0.001745641 0.7774179 0.6289831 -0.001351952 0.6963534 0.7176956 0.002216994 0.6998968 0.7142425 0.001450955 0.6063072 0.7952299 -9.93307e-4 0.6070107 0.7946931 -9.91235e-4 0.5727872 0.8196969 0.003473639 0.4031834 0.9151192 -3.69527e-4 0.4299178 0.9028627 0.003111004 0.5085098 0.8610542 -0.001868665 0.5078259 0.8614578 -0.001867711 0.4061126 0.913823 -3.68856e-4 0.2918659 0.9564592 4.39954e-4 0.2756913 0.9612426 0.002649068 0.05906009 0.9982534 -0.001443684 0.1134348 0.9935391 0.003580689 0.1768867 0.9842298 -0.001697182 0.176567 0.9842872 -0.001705884 0.05914682 0.9982483 -0.001442253 -0.05951261 0.9982246 0.002460181 -0.0516138 0.9986665 0.001212358 -0.1754772 0.9844832 -8.49925e-4 -0.1754772 0.9844832 -8.49857e-4 -0.1754772 0.9844832 -8.49892e-4 -0.1769063 0.9842274 -8.52516e-4 -0.2150776 0.9765912 0.003387272 -0.4032531 0.9150883 -5.45972e-4 -0.3732047 0.9277435 0.003207743 -0.2925276 0.9562553 -0.001870095 -0.2920746 0.9563937 -0.001868128 -0.3989608 0.9169679 -5.49022e-4 -0.3989608 0.9169679 -5.49002e-4 -0.3989608 0.9169679 -5.48998e-4 -0.5086727 0.8609598 6.68921e-4 -0.5207092 0.8537303 0.002560138 -0.6967428 0.7173195 -0.001534402 -0.6539207 0.7565545 0.00361973 -0.606595 0.7950095 -0.001587927 -0.6074645 0.7943453 -0.001591265 -0.6970309 0.7170395 -0.001532196 -0.7765961 0.629993 0.002729713 -0.7697072 0.6383965 9.87973e-4 -0.8443838 0.5357384 -6.71472e-4 -0.8457489 0.5335807 -6.72092e-4 -0.8641903 0.5031542 0.003300607 -0.9473353 0.320243 -6.99954e-4 -0.9352332 0.354017 0.003313422 -0.9027947 0.4300678 -0.001862466 -0.9027964 0.4300642 -0.0018633 -0.9474241 0.31998 -7.02084e-4 -0.9786168 0.2056901 8.63028e-4 -0.9807984 0.19501 0.002367377 -0.9995521 -0.02988243 -0.001610398 -0.9995054 0.03124171 0.00361675 -0.9960542 0.08873534 -0.001504838 -0.996017 0.08915108 -0.001505553 -0.9995625 -0.02953636 -0.001610338 -0.9889906 -0.1479464 0.003087818 -0.9910023 -0.1338433 7.43759e-4 -0.964603 -0.263706 -5.64652e-4 -0.9647006 -0.263349 -5.62982e-4 -0.9554551 -0.2951188 0.003243863 -0.875684 -0.4828838 -8.70969e-4 -0.8938516 -0.4483506 0.003365159 -0.9264896 -0.376316 -0.001848757 -0.926595 -0.3760563 -0.001845657 -0.8753969 -0.4834043 -8.7103e-4 -0.8125694 -0.5828636 0.001073002 -0.8077557 -0.5895133 0.00222826 -0.6528518 -0.757484 -0.001657843 -0.6998929 -0.7142387 0.003607213 -0.7377448 -0.6750783 -0.00141853 -0.7377036 -0.6751234 -0.001411437 -0.6525125 -0.7577763 -0.001648366 -0.5587832 -0.8293069 0.00339353 -0.5728065 -0.8196905 5.36218e-4 -0.4542209 -0.8908891 -3.78077e-4 -0.4563642 -0.8897931 -3.79192e-4 -0.4298985 -0.9028719 0.003125548 -0.2347255 -0.9720612 -0.001028656 -0.2756907 -0.9612403 0.003426849 -0.3478767 -0.9375386 -0.001827597 -0.3485155 -0.9373013 -0.001826167 -0.2364548 -0.971642 -0.001024425 -0.1181767 -0.9929918 0.001346945 -0.1134353 -0.9935434 0.002035081 0.1188305 -0.9929131 -0.001733958 0.0516135 -0.9986608 0.003593623 0 -0.9999992 -0.001335203 0 -0.9999992 -0.001336634 0.1180639 -0.9930045 -0.00173527 0.235001 -0.971988 0.003735065 0.2151465 -0.9765818 2.56663e-4 0.3425211 -0.9395102 -1.74559e-4 0.3484639 -0.9373223 -1.84371e-4 0.373073 -0.9277971 0.003041028 0.5587096 -0.8293627 -0.001073122 0.520725 -0.8537173 0.003522992 0.4563864 -0.8897799 -0.001812756 0.4569171 -0.8895074 -0.001818001 0.5591245 -0.8290832 -0.001071512 0.6529827 -0.7573711 0.001647412 0.6539238 -0.7565582 0.001835644 0.738136 -0.6746509 -0.001259386 0.7379102 -0.6748979 -0.001255989 0.7697091 -0.6383851 0.003523528 0.8125885 -0.5828351 -0.001792073 0.8124948 -0.5829657 -0.001791179 0.8641914 -0.5031549 0.002910971 0.8756696 -0.4829109 0 0.9267457 -0.3756892 0 0.7289911 -0.6662924 -0.1569284 0.4513291 -0.8786744 -0.1556708 -0.3442555 -0.9258651 -0.1557632 -0.9151114 -0.3713856 -0.1569844 0.9837476 0.08807355 -0.1564729 0.9527968 -0.2601907 -0.156458 0.05376237 -0.4512369 -0.8907833 -0.2966076 -0.3442541 -0.8907936 -0.4540246 -0.01349216 -0.890887 -0.3167297 0.3260924 -0.8906998 0.02676606 0.4534718 -0.8908686 0.3532982 0.2866001 -0.8905285 0.1373225 -0.07566589 -0.9876322 0.1272311 -0.09130173 -0.987662 0.1155624 -0.1056928 -0.9876611 0.1023347 -0.118677 -0.9876455 0.08755564 -0.1300548 -0.9876335 0.07157087 -0.1393312 -0.9876561 -0.03679198 -0.1522128 -0.9876627 -0.05450969 -0.1468991 -0.9876484 -0.1371299 -0.07567816 -0.987658 -0.145285 -0.05890965 -0.9876345 -0.1485121 0.05017822 -0.9876368 -0.1414518 0.06738036 -0.9876495 -0.06323552 0.1433495 -0.9876499 -0.04579371 0.150002 -0.9876247 0.06322842 0.1435189 -0.9876258 0.07964456 0.1349412 -0.9876476 0.1484173 0.05017167 -0.9876514 0.1534346 0.03230774 -0.9876306 0.1558949 0.01390337 -0.9876758 0.1566061 -0.004589855 -0.9876505 0.1548823 -0.02309191 -0.9876631 0.1511348 -0.04130488 -0.9876499 0.1450842 -0.05882334 -0.9876692 0.1217021 0.09874349 -0.9876429 0.1217606 0.09877544 -0.9876324 0.1325345 0.08373773 -0.987635 0.009262621 0.1564469 -0.987643 0.009229183 0.1563625 -0.9876567 0.02769106 0.1541743 -0.9876555 -0.1091818 0.1124472 -0.9876412 -0.1091384 0.1123704 -0.9876548 -0.09503823 0.124516 -0.9876556 -0.1567853 -0.004674196 -0.9876217 -0.1568256 -0.004660248 -0.9876154 -0.1562725 0.01394879 -0.9876155 -0.102328 -0.1187505 -0.9876372 -0.1022948 -0.1187312 -0.9876431 -0.1155661 -0.1057632 -0.9876531 0.01852411 -0.1556828 -0.9876334 0.01854145 -0.1556247 -0.9876423 0 -0.1567152 -0.9876438 0.4926586 0.5074203 -0.706974 0.316876 0.3263825 -0.8905415 0.3167358 0.3263254 -0.8906124 0.1091788 0.1124861 -0.9876371 0.1092391 0.1125137 -0.9876272 -0.04211026 0.7065641 -0.7063951 -0.02703678 0.4536544 -0.8907675 -0.02699291 0.4535284 -0.890833 -0.009312331 0.1564625 -0.98764 -0.009335219 0.1563273 -0.9876613 -0.5498454 0.4459365 -0.7062654 -0.3529064 0.2862141 -0.8908079 -0.3531317 0.2864747 -0.8906348 -0.1217145 0.09873586 -0.9876421 -0.1216464 0.09863913 -0.9876601 -0.6999492 -0.1045116 -0.7065044 -0.4491576 -0.06706291 -0.8909322 -0.44937 -0.06702196 -0.8908281 -0.1551298 -0.02313977 -0.9876232 -0.154904 -0.0231719 -0.9876578 -0.3952335 -0.5870658 -0.7065015 -0.2538067 -0.377008 -0.8907566 -0.2540979 -0.3772418 -0.8905746 -0.08756881 -0.1300076 -0.9876385 -0.08758741 -0.1300142 -0.987636 0.1663638 -0.6880747 -0.7063119 0.1067844 -0.4416544 -0.8908078 0.1068124 -0.4413927 -0.8909342 0.03688448 -0.1524216 -0.9876271 0.0368815 -0.1522691 -0.9876508 0.5983093 0.377918 -0.7065437 0.5404117 0.7083787 -0.4540426 0.5404118 0.7083788 -0.4540426 0.5404117 0.7083788 -0.4540426 0.4288656 0.562214 -0.7070996 0.429455 0.5625317 -0.7064889 0.2759678 0.3614847 -0.8906014 0.2757365 0.3613409 -0.8907313 0.09511405 0.1246386 -0.9876328 0.09519326 0.124714 -0.9876157 0.125012 0.6959695 -0.7071058 -0.1576185 0.8773257 -0.4532726 -0.1251724 0.6967216 -0.7063363 -0.1251698 0.6965894 -0.7064671 -0.08036684 0.4472422 -0.8907949 -0.08035683 0.4474815 -0.8906756 -0.02768176 0.1541535 -0.9876591 -0.0276786 0.1541789 -0.9876552 -0.4294803 0.562573 -0.7064406 -0.7536876 0.475645 -0.4535603 -0.5986081 0.377783 -0.7063628 -0.5986332 0.3778404 -0.7063108 -0.3844608 0.2426659 -0.8906758 -0.3846252 0.2428345 -0.8905587 -0.1324389 0.0836156 -0.9876581 -0.1324368 0.08359795 -0.9876599 -0.7054018 0.06292045 -0.7060095 -0.8598235 -0.2352672 -0.4531586 -0.6826406 -0.186772 -0.7064829 -0.6829205 -0.1867753 -0.7062115 -0.438226 -0.1198326 -0.8908413 -0.4386024 -0.1198421 -0.8906548 -0.1510678 -0.04127526 -0.9876614 -0.1510432 -0.0412783 -0.987665 -0.5227811 -0.4781552 -0.705739 -0.4069783 -0.7930009 -0.4533412 -0.3231933 -0.6297366 -0.7063837 -0.3229222 -0.6294549 -0.7067587 -0.2075585 -0.4045794 -0.8906374 -0.2077909 -0.4048906 -0.8904418 -0.07158041 -0.139483 -0.987634 -0.07147806 -0.1393703 -0.9876573 0 -0.7082195 -0.7059924 0.3104954 -0.8349129 -0.4544371 0.2467595 -0.6635382 -0.7062768 0.2467226 -0.6638723 -0.7059756 0.1581836 -0.4256362 -0.8909612 0.1582607 -0.4260507 -0.8907493 0.05455935 -0.1468812 -0.9876484 0.05457615 -0.1470599 -0.9876208 0.7542465 0.4758735 -0.45239 0.7534121 0.47588 -0.4537713 0.6917527 0.5616952 -0.4538466 0.598926 0.7854694 -0.1559666 0.6880081 0.7087321 -0.1560249 0.6209565 0.6396796 -0.4530157 0.6922205 0.5616918 -0.4531372 0.5493303 0.445746 -0.7067863 0.5979658 0.3778293 -0.7068819 0.3842056 0.2427702 -0.8907574 0.1576333 0.8773368 -0.4532463 0.1575912 0.8773261 -0.4532813 0.05253654 0.8897811 -0.4533536 -0.1733029 0.9724468 -0.155928 -0.173303 0.9724467 -0.1559279 -0.05867737 0.986081 -0.155568 -0.05294549 0.8897867 -0.4532952 0.05253791 0.8898282 -0.4532611 0.04167872 0.705895 -0.7070893 0.1251278 0.6960124 -0.7070431 0.08057498 0.4481889 -0.8903002 -0.5409702 0.7080176 -0.4539411 -0.5410323 0.708694 -0.4528101 -0.6210492 0.6397596 -0.4527754 -0.834008 0.5293114 -0.1557565 -0.7670765 0.6223861 -0.1556574 -0.6921938 0.5616409 -0.4532409 -0.6209991 0.6395911 -0.4530822 -0.4930097 0.5077773 -0.7064728 -0.4294541 0.5625319 -0.7064892 -0.2761425 0.3617132 -0.8904544 -0.8877621 0.07919198 -0.4534392 -0.8878145 0.07916861 -0.4533409 -0.8908913 -0.02665632 -0.4534338 -0.9527168 -0.2604948 -0.1564396 -0.9768403 -0.1459763 -0.1564414 -0.8815441 -0.1317123 -0.4533565 -0.8909049 -0.02667671 -0.4534059 -0.7076274 -0.02117514 -0.7062685 -0.705181 0.06279534 -0.7062411 -0.4525133 0.04029577 -0.8908467 -0.6576046 -0.6014971 -0.453605 -0.6575756 -0.6014375 -0.4537261 -0.5816851 -0.6752246 -0.4535573 -0.448608 -0.8797476 -0.1574646 -0.4486081 -0.8797476 -0.1574646 -0.448608 -0.8797476 -0.1574645 -0.5514469 -0.8192321 -0.1573704 -0.4977633 -0.7394833 -0.4532065 -0.5818783 -0.6751921 -0.4533579 -0.4618687 -0.5359431 -0.7067124 -0.5218195 -0.4778079 -0.7066853 -0.3351164 -0.3068537 -0.8908074 0 -0.8911508 -0.4537074 0 -0.891075 -0.4538562 0.1054394 -0.8848486 -0.4537901 0.3383892 -0.9280133 -0.1558336 0.2320166 -0.96024 -0.1552663 0.2092791 -0.866144 -0.4538689 0.1054438 -0.8847664 -0.4539494 0.08380198 -0.7031836 -0.7060526 0 -0.7082554 -0.7059563 0 -0.4542979 -0.89085 0.1452804 -0.05896794 -0.9876317 0.4215317 -0.1710909 -0.8905274 0.4208664 -0.1705784 -0.8909403 0.6559104 -0.2658409 -0.7064774 0.6562613 -0.2661492 -0.7060353 0.826056 -0.3350172 -0.4532052 0.8260021 -0.3350141 -0.4533059 0.9152932 -0.3712308 -0.156288 0.9152658 -0.3710161 -0.1569578 0.1510509 -0.04124921 -0.9876651 0.4388953 -0.1198514 -0.8905092 0.4387379 -0.1197698 -0.8905978 0.6827837 -0.1864003 -0.7064427 0.6827942 -0.1864253 -0.7064261 0.8597661 -0.2347571 -0.453532 0.8599017 -0.2348843 -0.4532092 0.9527896 -0.2602452 -0.1564117 0.952793 -0.2603152 -0.1562745 0.977051 -0.1457712 -0.155313 0.1549516 -0.02312272 -0.9876515 0.4499002 -0.06713509 -0.890552 0.449985 -0.06718862 -0.8905051 0.6997869 -0.1044826 -0.7066696 0.6999288 -0.104568 -0.7065163 0.8814489 -0.1317131 -0.4535413 0.8814793 -0.1317024 -0.4534849 0.9770157 -0.1460025 -0.1553173 0.9768858 -0.1455957 -0.1565123 0.1565447 -0.004577815 -0.9876603 0.4545882 -0.01328474 -0.8906027 0.4546577 -0.01331639 -0.8905668 0.7068168 -0.02067571 -0.7070944 0.7072415 -0.02085965 -0.7066643 0.8909205 -0.02627676 -0.4533987 0.8909143 -0.02623987 -0.4534127 0.9872611 -0.02910292 -0.1564241 0.9874218 -0.02940082 -0.1553515 0.1560165 0.01388353 -0.987657 0.4531342 0.04032397 -0.8905299 0.4530786 0.04034614 -0.8905572 0.7045915 0.06275135 -0.7068331 0.7043526 0.06279081 -0.7070677 0.8877825 0.07916373 -0.4534044 0.8877437 0.07917416 -0.4534785 0.9840344 0.08775627 -0.1548392 0.9837285 0.088234 -0.1565021 0.9664779 0.2030783 -0.1570983 0.1531852 0.03233039 -0.9876686 0.4447007 0.09386104 -0.8907477 0.445149 0.09379786 -0.8905305 0.6923269 0.1458887 -0.7066824 0.6920946 0.1459227 -0.7069028 0.8721687 0.1838922 -0.4533272 0.8721381 0.1839014 -0.4533823 0.9665011 0.2037972 -0.1560205 0.9668208 0.203231 -0.1547736 0.935531 0.3175931 -0.15465 0.1485622 0.05017131 -0.9876296 0.4312525 0.1456425 -0.8903985 0.4305329 0.145626 -0.8907494 0.6702274 0.226713 -0.7066799 0.670209 0.2267136 -0.7066972 0.8438307 0.2854497 -0.454388 0.8444236 0.2853301 -0.4533604 0.9359547 0.3162497 -0.1548389 0.9354118 0.3167493 -0.1570817 0.141433 0.06741482 -0.9876498 0.4103114 0.1955671 -0.890729 0.4109522 0.1956554 -0.8904141 0.6388749 0.3041746 -0.7066236 0.6387616 0.3041276 -0.7067461 0.8052551 0.3833989 -0.4522936 0.8039809 0.3835126 -0.454459 0.8913695 0.425204 -0.1570418 0.8919798 0.4247274 -0.1548508 0.8919798 0.4247274 -0.1548508 0.8919798 0.4247274 -0.1548508 0.6877138 0.7087783 -0.1571092 0.7678074 0.6212008 -0.1567841 0.7668839 0.6226842 -0.1554142 0.7668839 0.6226841 -0.1554142 0.7669314 0.6226446 -0.1553385 0.8355035 0.5271818 -0.1549628 0.8355034 0.5271819 -0.1549628 0.8355035 0.5271818 -0.1549628 0.8350736 0.5273405 -0.1567299 0.8348808 0.5275298 -0.1571197 0.5995343 0.7849562 -0.1562132 0.5994326 0.7851284 -0.1557372 0.5410513 0.7086663 -0.4528307 0.6211014 0.639657 -0.4528487 0.4926543 0.5073883 -0.707 0.5490856 0.44564 -0.7070431 0.3530448 0.2865296 -0.8906517 0.3843727 0.2428172 -0.8906726 0.1325674 0.08374536 -0.9876299 0.1415678 0.06743556 -0.9876291 0.5023744 0.8506152 -0.1551581 0.5023744 0.8506152 -0.1551581 0.5023743 0.8506152 -0.1551581 0.07978051 0.1350712 -0.9876188 0.2311328 0.3913102 -0.8907604 0.2311492 0.3913604 -0.8907341 0.3601069 0.6097068 -0.7061026 0.3597945 0.6094958 -0.7064438 0.453023 0.7674189 -0.4536943 0.4528923 0.7672864 -0.4540486 0.5021242 0.8507186 -0.1554008 0.5021243 0.8507185 -0.1554008 0.5021243 0.8507185 -0.1554008 0.5016018 0.8508647 -0.1562848 0.4009444 0.9026569 -0.1563785 0.4009444 0.9026569 -0.1563786 0.4009444 0.9026569 -0.1563785 0.06313186 0.1433872 -0.9876511 0.1831137 0.4158959 -0.8907861 0.1832186 0.4160436 -0.8906955 0.2854817 0.6482541 -0.7058803 0.2853783 0.6481279 -0.7060379 0.3589842 0.8152868 -0.4543542 0.3592721 0.8156178 -0.453532 0.3981764 0.9039588 -0.1559293 0.3982863 0.9039807 -0.1555221 0.04584902 0.1500062 -0.9876214 0.1330783 0.4354107 -0.8903414 0.132498 0.4346307 -0.8908089 0.2061965 0.6763699 -0.7071117 0.2070741 0.6774129 -0.7058556 0.2605816 0.8524476 -0.4532443 0.260155 0.852057 -0.4542227 0.2884408 0.9447066 -0.1559854 0.2882694 0.944671 -0.1565169 -0.0587781 0.9859249 -0.156516 0.05842071 0.9859663 -0.1563895 0.05822181 0.9860583 -0.1558821 0.05833655 0.986038 -0.155968 0.1746814 0.9722337 -0.1557186 0.1746837 0.9722332 -0.1557187 0.1746836 0.9722332 -0.1557187 0.1747418 0.9722977 -0.1552497 0.1744097 0.9722509 -0.155915 -0.1747417 0.9721598 -0.1561112 -0.1747417 0.9721598 -0.1561112 -0.1747418 0.9721598 -0.1561112 -0.1745926 0.9722018 -0.1560167 -0.1745926 0.9722018 -0.1560167 -0.1745926 0.9722018 -0.1560167 -0.1575683 0.8773635 -0.4532171 -0.05292832 0.8898099 -0.4532518 -0.04204785 0.7068979 -0.7060648 0.04210823 0.7068723 -0.7060867 0.02706295 0.4543007 -0.8904374 0.08042025 0.4479271 -0.8904459 0.02767491 0.1541455 -0.9876605 0.04569113 0.1497431 -0.9876687 -0.2889862 0.9446408 -0.155373 -0.04576671 0.1497627 -0.9876623 -0.1328557 0.4347357 -0.8907044 -0.1328238 0.4347538 -0.8907003 -0.206892 0.6771888 -0.706124 -0.2069209 0.6769037 -0.7063888 -0.2604835 0.852126 -0.453905 -0.2603979 0.8524482 -0.4533487 -0.2885667 0.9446844 -0.1558872 -0.2885667 0.9446843 -0.1558872 -0.2885668 0.9446844 -0.1558872 -0.288499 0.9447141 -0.1558316 -0.394063 0.9057077 -0.1562308 -0.3940629 0.9057077 -0.1562308 -0.0632618 0.143503 -0.9876258 -0.1833452 0.4158973 -0.8907379 -0.1833277 0.4158349 -0.8907707 -0.2853916 0.6473345 -0.70676 -0.2854378 0.6479414 -0.7061851 -0.3592429 0.815463 -0.4538333 -0.3592298 0.8155217 -0.4537382 -0.3982474 0.9041029 -0.1549105 -0.3983363 0.9039328 -0.1556721 -0.07965409 0.134979 -0.9876417 -0.2311913 0.391767 -0.8905444 -0.2311201 0.3913204 -0.8907592 -0.3599756 0.6094939 -0.7063531 -0.3598986 0.6091387 -0.7066988 -0.4532202 0.7671058 -0.4540266 -0.4532261 0.7671973 -0.4538661 -0.5023777 0.8503984 -0.156331 -0.5024172 0.8503871 -0.1562653 -0.7671038 0.6222407 -0.1561039 -0.7671038 0.6222407 -0.1561039 -0.7671038 0.6222407 -0.1561039 -0.688484 0.7082741 -0.1560055 -0.6879467 0.7086517 -0.1566597 -0.6880759 0.7084286 -0.1571006 -0.5995525 0.7846823 -0.1575138 -0.5992842 0.7853495 -0.1551929 -0.5992841 0.7853495 -0.155193 -0.5992842 0.7853495 -0.155193 -0.599987 0.7846271 -0.1561284 -0.8353455 0.5270074 -0.1564015 -0.8353114 0.5270558 -0.1564195 -0.7535951 0.4754825 -0.4538844 -0.692103 0.5612705 -0.453838 -0.5498034 0.4458744 -0.7063373 -0.4929858 0.5077657 -0.7064977 -0.3167618 0.3262646 -0.8906253 -0.2760351 0.3614545 -0.8905927 -0.09499275 0.1243869 -0.9876762 -0.07959651 0.134784 -0.9876729 -0.8916421 0.4247525 -0.1567155 -0.1413645 0.0673086 -0.9876668 -0.4104161 0.1954168 -0.8907137 -0.4106101 0.1955811 -0.8905882 -0.638688 0.3042288 -0.7067691 -0.6390836 0.3046186 -0.7062434 -0.8049542 0.3836848 -0.4525868 -0.8046794 0.3832417 -0.4534502 -0.8917013 0.4246718 -0.1565972 -0.8916952 0.4247763 -0.1563487 -0.9357064 0.3160848 -0.1566654 -0.1484131 0.0501216 -0.9876545 -0.4306242 0.145416 -0.8907396 -0.4306887 0.1454621 -0.8907009 -0.6702626 0.2263621 -0.7067589 -0.670349 0.226456 -0.706647 -0.8444059 0.2852485 -0.4534448 -0.8447145 0.2855426 -0.4526842 -0.9356355 0.3162862 -0.1566824 -0.9356216 0.3162977 -0.1567416 -0.1533703 0.03229433 -0.987641 -0.444559 0.09361666 -0.8908442 -0.4447474 0.09372502 -0.8907387 -0.6930412 0.1460446 -0.7059497 -0.6923496 0.1455925 -0.7067213 -0.8722289 0.1834204 -0.4534026 -0.8722624 0.1834471 -0.4533273 -0.9665675 0.2032738 -0.1562921 -0.9665161 0.203133 -0.1567925 -0.9767302 -0.1461082 -0.1570046 -0.9871647 -0.02920913 -0.157012 -0.9872245 -0.02955263 -0.1565714 -0.9872499 -0.02948057 -0.1564241 -0.9837859 0.08773404 -0.1564223 -0.9837337 0.08764213 -0.1568022 -0.9837652 0.08807331 -0.1563622 -0.9527515 -0.260097 -0.1568889 -0.9528029 -0.2602577 -0.1563096 -0.8604882 -0.2350527 -0.4520071 -0.8822853 -0.1314091 -0.4520003 -0.7005721 -0.1043424 -0.7059118 -0.7080172 -0.021048 -0.7058815 -0.453957 -0.0134924 -0.8909215 -0.4523462 0.04022639 -0.8909348 -0.1561468 0.01388859 -0.9876362 -0.1533635 0.03228926 -0.9876422 -0.1450815 -0.05888676 -0.9876659 -0.4214009 -0.1710377 -0.8905994 -0.4211758 -0.171013 -0.8907107 -0.6551573 -0.2660034 -0.7071146 -0.6562054 -0.2659993 -0.7061437 -0.8263458 -0.3349801 -0.4527043 -0.8260552 -0.3350403 -0.4531896 -0.9153929 -0.3712568 -0.155642 -0.9149441 -0.3716514 -0.1573303 -0.8648426 -0.4775422 -0.1549217 -0.1372971 -0.07571184 -0.9876322 -0.3982037 -0.2195879 -0.8906263 -0.398286 -0.2196277 -0.8905796 -0.6198568 -0.3417987 -0.7063649 -0.6190494 -0.3417584 -0.707092 -0.7798264 -0.4305021 -0.4544655 -0.7808564 -0.4304483 -0.4527445 -0.86513 -0.4769055 -0.1552787 -0.8650298 -0.4769976 -0.1555539 -0.1272314 -0.09129732 -0.9876624 -0.3691484 -0.264899 -0.8908188 -0.3695042 -0.2649695 -0.8906503 -0.5757608 -0.412882 -0.705711 -0.5751388 -0.4127524 -0.7062938 -0.7239763 -0.5195481 -0.4537931 -0.7236127 -0.5195377 -0.4543846 -0.8023199 -0.5760575 -0.156335 -0.8027411 -0.5758277 -0.1550137 -0.5519847 -0.8192062 -0.155609 -0.644534 -0.7485184 -0.1558724 -0.6446809 -0.7483373 -0.1561341 -0.6448978 -0.748251 -0.1556515 -0.7288861 -0.6666883 -0.1557304 -0.7286828 -0.666778 -0.1562963 -0.7285774 -0.6668421 -0.1565144 -0.4508014 -0.8789235 -0.1557934 -0.4508014 -0.8789235 -0.1557934 -0.4508014 -0.8789235 -0.1557934 -0.4509968 -0.8785927 -0.157089 -0.4071974 -0.7932651 -0.4526821 -0.4978795 -0.739524 -0.4530127 -0.3952153 -0.5870423 -0.7065311 -0.4621311 -0.5360836 -0.7064342 -0.2969969 -0.34453 -0.8905572 -0.3355325 -0.3069751 -0.8906089 -0.1156731 -0.1058312 -0.9876334 -0.1273688 -0.0913487 -0.9876399 -0.05448567 -0.146875 -0.9876533 -0.157922 -0.4257152 -0.8909698 -0.1584877 -0.4264041 -0.8905399 -0.2466579 -0.6636306 -0.7062255 -0.2463129 -0.6632375 -0.706715 -0.3102573 -0.8354264 -0.4536553 -0.3102574 -0.8354265 -0.4536554 -0.3102574 -0.8354265 -0.4536554 -0.3105394 -0.8356468 -0.453056 -0.3441382 -0.9260774 -0.1547567 -0.3435785 -0.9259199 -0.1569277 -0.2335492 -0.9595809 -0.1570329 -0.2335492 -0.9595808 -0.157033 -0.2335492 -0.9595808 -0.157033 -0.03686499 -0.1523184 -0.9876437 -0.1070559 -0.4423388 -0.8904356 -0.1064653 -0.4414561 -0.8909443 -0.1657936 -0.6874626 -0.7070415 -0.1662788 -0.688178 -0.7062312 -0.2094422 -0.8668362 -0.4524699 -0.2089186 -0.8663583 -0.453626 -0.2089186 -0.8663581 -0.453626 -0.2089187 -0.8663582 -0.4536261 -0.2315536 -0.9602416 -0.1559455 -0.2318881 -0.9603309 -0.1548951 -0.01844829 -0.1554942 -0.9876646 -0.05352705 -0.4511671 -0.8908329 -0.05388516 -0.4518609 -0.8904596 -0.08386218 -0.7032454 -0.7059837 -0.08333241 -0.7023704 -0.7069171 -0.104979 -0.8848141 -0.4539644 -0.1055079 -0.8854237 -0.452651 -0.105508 -0.8854237 -0.4526512 -0.105508 -0.8854237 -0.4526512 -0.1168637 -0.9807103 -0.1566849 -0.1167111 -0.9806718 -0.1570392 0.2321237 -0.9601109 -0.1559032 0.1166233 -0.9808638 -0.1559011 0.1168833 -0.9808745 -0.1556392 0.1173565 -0.9806466 -0.1567156 0.1173565 -0.9806466 -0.1567157 0.1173565 -0.9806466 -0.1567157 0 -0.9876263 -0.1568258 0 -0.9876492 -0.1566817 0 -0.9876492 -0.1566817 0 -0.9876492 -0.1566817 0 -0.9876641 -0.156588 0 -0.987664 -0.1565881 3.21657e-6 -0.987664 -0.1565881 0.3442195 -0.9258919 -0.1556828 0.344061 -0.9258862 -0.156067 0.3104264 -0.8353597 -0.4536625 0.2092707 -0.8662325 -0.4537039 0.166296 -0.6883491 -0.7060604 0.08383345 -0.7033365 -0.7058964 0.05376863 -0.4511032 -0.8908507 0 -0.4543786 -0.8908087 0 -0.1566919 -0.9876475 -0.01851296 -0.1555939 -0.9876476 0.07161849 -0.1395433 -0.9876227 0.207703 -0.4046881 -0.8905544 0.2075505 -0.4041351 -0.890841 0.3233713 -0.6296632 -0.7063677 0.323374 -0.6300823 -0.7059926 0.323374 -0.6300823 -0.7059926 0.323374 -0.6300823 -0.7059926 0.4068291 -0.7926923 -0.4540144 0.4068307 -0.7926278 -0.4541257 0.4510576 -0.8787903 -0.1558035 0.4508954 -0.8790587 -0.1547546 0.4508954 -0.8790587 -0.1547547 0.4508955 -0.8790588 -0.1547548 0.5522319 -0.8187557 -0.157096 0.08751779 -0.1299315 -0.9876531 0.2540415 -0.3771672 -0.8906221 0.2541193 -0.377275 -0.8905543 0.3951063 -0.5866007 -0.7069588 0.3952353 -0.5870644 -0.7065017 0.4980863 -0.7398145 -0.4523104 0.498048 -0.7387334 -0.454116 0.552095 -0.8188769 -0.1569453 0.5518468 -0.8192065 -0.1560959 0.1023651 -0.1187357 -0.9876352 0.2969059 -0.3443828 -0.8906444 0.2970418 -0.3445819 -0.8905221 0.4619649 -0.535892 -0.7066882 0.4619328 -0.5356479 -0.7068942 0.5823284 -0.67526 -0.4526783 0.5823441 -0.6755481 -0.452228 0.6448566 -0.7480497 -0.1567855 0.6448774 -0.7479857 -0.1570051 0.1156134 -0.1057744 -0.9876464 0.335511 -0.3069639 -0.890621 0.3354974 -0.3069865 -0.8906182 0.5222627 -0.4778696 -0.7063161 0.5221817 -0.4775851 -0.7065683 0.6575418 -0.6013869 -0.4538421 0.6578404 -0.6020754 -0.4524943 0.7287033 -0.6669424 -0.1554976 0.728783 -0.6665552 -0.1567788 0.8025225 -0.5758064 -0.1562201 0.12725 -0.09131205 -0.9876587 0.3696885 -0.2652698 -0.8904843 0.369535 -0.2650107 -0.8906252 0.5752338 -0.4125306 -0.706346 0.5752974 -0.4126264 -0.7062382 0.7242374 -0.5194712 -0.4534645 0.7242472 -0.5193108 -0.4536322 0.8027437 -0.5756165 -0.1557825 0.8026837 -0.5757271 -0.1556826 0.1371994 -0.07554149 -0.9876588 0.397844 -0.2190477 -0.8909199 0.3985245 -0.2197761 -0.8904363 0.6201027 -0.3419598 -0.706071 0.6199599 -0.3417469 -0.7062994 0.7805906 -0.430296 -0.4533473 0.7805808 -0.4302964 -0.4533639 0.8649175 -0.4767884 -0.1568146 0.8648916 -0.4769722 -0.156397 -0.9324839 0.3612117 0 -0.9894408 0.1449376 0 -0.9894409 0.1449376 0 -0.9881814 -0.1532892 0 -0.9881799 -0.1532991 0 -0.8990804 -0.4377836 0 -0.8990765 -0.4377918 0 -0.7300255 -0.6834199 0 -0.7300356 -0.6834092 0 -0.4961794 -0.8682202 0 -0.2183967 -0.9758601 0 -0.2183946 -0.9758607 0 0.07884943 -0.9968866 0 0.07884865 -0.9968867 0 0.3693814 -0.9292779 0 0.3693779 -0.9292793 0 0.6268591 -0.7791327 0 0.6268541 -0.7791368 0 0.8287276 -0.5596524 0 0.8287321 -0.5596454 0 0.9567697 -0.290847 0 0.9567697 -0.2908471 0 0.9999905 0.004359781 0 0.9999905 0.004359781 0 0.9542964 0.2988621 0 0.9542935 0.2988713 0 0.8236953 0.5670328 0 0.8236999 0.567026 0 0.6201439 0.7844882 0 0.6201488 0.7844843 0 0.361352 0.9324295 0 0.3613553 0.9324282 0 0.07044833 0.9975155 0 0.0704469 0.9975155 0 -0.226791 0.9739435 0 -0.5038594 0.8637856 0 -0.7360098 0.676971 0 -0.7360097 0.6769711 0 -0.8682799 0.4960744 0 -0.9029116 0.4298248 0.00115323 0 0 -1 1.26748e-7 0 -1 3.31854e-7 0 -1 -3.26015e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 2.31936e-7 0 -1 0 0 -1 0 0 -1 1.61922e-7 0 -1 0 0 -1 3.42977e-7 0 -1 0 0 -1 -1.7019e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -1.29164e-7 0 -1 2.98617e-7 0 -1 -3.33654e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 1.65955e-7 0 -1 0 0 -1 1.38588e-7 0 -1 -3.73008e-7 0 -1 1.57237e-7 0 -1 0.9110291 -0.4123318 0.002917408 0.9777387 -0.2098225 -0.00124073 0.9664524 -0.2568216 0.0035308 0.9461577 -0.3237015 -0.001755237 0.9459397 -0.324338 -0.001755356 0.9775547 -0.2106782 -0.001242756 0.995718 -0.09242397 0.001911044 0.9955397 -0.09433007 0.001621007 0.9997087 0.0241121 -0.001111567 0.999657 0.02616775 -0.00111103 0.9974663 0.07105547 0.003476023 0.9896551 0.1434563 -0.001799583 0.9896464 0.1435163 -0.001799285 0.9721836 0.2342002 0.003067076 0.9656173 0.2599676 -1.7746e-4 0.9204914 0.3907631 -1.7393e-4 0.9667879 0.2543735 0.02480363 0.9280975 0.372319 0.003712952 0.8145371 0.58011 -0.001361131 0.8434299 0.5372275 0.003577411 0.8778123 0.4790016 -0.001761913 0.8774554 0.479655 -0.001762866 0.8146657 0.5799292 -0.001361012 0.7404955 0.6720579 0.002150118 0.7435593 0.6686685 0.001438021 0.6560792 0.7546915 -9.91342e-4 0.6557625 0.7549666 -9.75643e-4 0.6234918 0.7818225 0.003435194 0.4599047 0.8879683 -3.79028e-4 0.4860447 0.8739283 0.003149926 0.5620354 0.8271111 -0.001852571 0.5619273 0.8271846 -0.001844048 0.4637129 0.8859855 -3.7818e-4 0.3518877 0.9360421 4.39971e-4 0.3358371 0.9419162 0.002683877 0.1223429 0.992487 -0.00139445 0.1759145 0.9843989 0.003593921 0.2384049 0.9711644 -0.001662552 0.2388101 0.9710649 -0.001652956 0.1214999 0.9925906 -0.001398861 0.004004955 0.999989 0.002487063 0.01179933 0.9999297 0.001257419 -0.1148002 0.9933884 -8.32386e-4 -0.1146053 0.9934108 -8.4261e-4 -0.1529783 0.9882238 0.003365278 -0.3442916 0.9388626 -5.26279e-4 -0.3136446 0.9495351 0.003214597 -0.2307611 0.9730087 -0.001885831 -0.2312359 0.9728959 -0.00188452 -0.3483146 0.9373776 -5.31699e-4 -0.4532372 0.8913898 6.10701e-4 -0.4655978 0.8849929 0.002495884 -0.6499843 0.7599462 -0.00153464 -0.6050304 0.7961944 0.003586649 -0.5555927 0.8314531 -0.001595973 -0.5547064 0.8320447 -0.001600623 -0.6496187 0.7602588 -0.001532614 -0.7351723 0.6778748 0.002756237 -0.7276852 0.6859107 9.87244e-4 -0.8099097 0.5865542 -7.0402e-4 -0.810132 0.5862471 -7.07325e-4 -0.83071 0.5566956 0.003323137 -0.9251136 0.3796897 -6.69563e-4 -0.9110232 0.4123421 0.003303825 -0.8740486 0.4858351 -0.00183916 -0.8738301 0.4862281 -0.001841485 -0.9264946 0.3763077 -6.73199e-4 -0.9635724 0.2674465 8.48509e-4 -0.9664525 0.2568345 0.002366721 -0.9994286 0.03376275 -0.001612544 -0.9955345 0.09432959 0.003585815 -0.9884856 0.151308 -0.001516044 -0.9883908 0.1519253 -0.001515984 -0.9994294 0.03373968 -0.001611828 -0.996388 -0.08486157 0.003073871 -0.9974712 -0.07106864 8.00682e-4 -0.9792809 -0.202506 -5.13731e-4 -0.9793787 -0.2020326 -5.14097e-4 -0.9722563 -0.2338957 0.003248453 -0.9045198 -0.4264309 -8.47446e-4 -0.9203702 -0.3910337 0.003371834 -0.9486045 -0.316459 -0.00188148 -0.9483831 -0.3171215 -0.001879334 -0.9043284 -0.4268368 -8.47034e-4 -0.8475017 -0.5307916 0.001104176 -0.8434333 -0.5372296 0.002181529 -0.6992966 -0.7148298 -0.001643896 -0.7435616 -0.6686577 0.003620088 -0.7789784 -0.6270493 -0.00142467 -0.7797269 -0.6261183 -0.00141555 -0.6992806 -0.7148454 -0.001648366 -0.6098932 -0.7924763 0.003416061 -0.6234954 -0.7818269 5.2136e-4 -0.5129783 -0.8584015 -3.72792e-4 -0.5120211 -0.8589728 -3.74315e-4 -0.4860447 -0.8739283 0.003180563 -0.2958754 -0.9552261 -9.80747e-4 -0.3358615 -0.9419051 0.003445446 -0.4066173 -0.9135968 -0.001815557 -0.4061971 -0.9137837 -0.001821696 -0.2957009 -0.9552801 -9.76673e-4 -0.2957009 -0.9552801 -9.76671e-4 -0.2957009 -0.9552801 -9.76672e-4 -0.1807766 -0.9835233 0.001355648 -0.1758946 -0.9844069 0.002065896 0.05553013 -0.9984556 -0.001726567 -0.01180303 -0.9999239 0.003594756 -0.06343203 -0.9979853 -0.001341462 -0.06191837 -0.9980803 -0.001326978 0.05543369 -0.9984609 -0.001724243 0.172852 -0.9849408 0.003735303 0.1529579 -0.9882327 2.78168e-4 0.2914037 -0.9566002 -1.80453e-4 0.2914036 -0.9566002 -1.78347e-4 0.2914037 -0.9566002 -1.78399e-4 0.2882938 -0.957542 -1.75181e-4 0.313545 -0.9495685 0.003042936 0.5052394 -0.8629785 -0.001138865 0.465615 -0.8849806 0.003484487 0.3996645 -0.9166597 -0.001813948 0.3997795 -0.9166097 -0.00181204 0.5041745 -0.863601 -0.0011397 0.6038465 -0.7970991 0.001620829 0.6050332 -0.7961981 0.001848042 0.6932035 -0.720741 -0.001221835 0.6937698 -0.7201959 -0.001216769 0.7276744 -0.6859135 0.003547906 0.7743676 -0.6327335 -0.001811325 0.7734861 -0.6338108 -0.001814663 0.830711 -0.5566963 0.00293672 0.8435561 -0.5370412 0 0.9011586 -0.4334894 0 0.684848 -0.7120329 -0.1548954 0.3948852 -0.9053765 -0.1560739 -0.4012027 -0.9025517 -0.1563233 -0.9366104 -0.3131645 -0.1571276 -0.8630718 0.4802777 -0.1563349 0.9874017 0.02386933 -0.1564231 0.9344866 -0.320395 -0.1551836 0.0252406 -0.4539499 -0.8906697 -0.3178163 -0.3247783 -0.8907928 -0.4539271 0.01522392 -0.8909088 -0.2957659 0.3461497 -0.8903387 0.05557328 0.4516303 -0.8904728 0.370787 0.2637678 -0.8904739 0.1321746 -0.08409935 -0.9876524 0.1212956 -0.09927535 -0.9876396 0.108679 -0.1127253 -0.9876649 0.09462529 -0.1249707 -0.9876378 0.07916873 -0.1352934 -0.9876376 0.06259959 -0.1436266 -0.9876502 -0.04634672 -0.1496827 -0.9876472 -0.06369018 -0.1430948 -0.9876576 -0.1414871 -0.06681716 -0.9876826 -0.1488187 -0.04960477 -0.9876196 -0.1449601 0.05941605 -0.987652 -0.1369356 0.0761671 -0.9876473 -0.05400228 0.1471358 -0.987641 -0.03622764 0.1523634 -0.9876604 0.0722112 0.1392794 -0.9876167 0.08807557 0.1296295 -0.9876432 0.1514107 0.0407136 -0.9876322 0.1551404 0.02257132 -0.9876346 0.1568694 0.003968954 -0.9876115 0.1559416 -0.01446342 -0.9876605 0.1531606 -0.03288447 -0.9876541 0.1481802 -0.05071634 -0.9876591 0.1413352 -0.06805664 -0.9876197 0.1275328 0.09077107 -0.987672 0.1276588 0.09080988 -0.9876522 0.1374819 0.07511919 -0.9876517 0.01913923 0.1555149 -0.9876482 0.01912432 0.15542 -0.9876635 0.03740477 0.1521281 -0.9876528 -0.1018357 0.1191097 -0.9876449 -0.1018818 0.1192342 -0.9876251 -0.08709847 0.1304937 -0.987616 -0.1565834 0.00521022 -0.9876511 -0.1567006 0.005255997 -0.9876322 -0.1549665 0.02373808 -0.9876346 -0.1095386 -0.1120289 -0.9876492 -0.109728 -0.1121315 -0.9876165 -0.1221953 -0.0983622 -0.98762 0.008717715 -0.1564477 -0.9876478 0.008700489 -0.1564786 -0.987643 -0.009882688 -0.1563733 -0.9876486 0.5244314 0.4757714 -0.7061256 0.3369989 0.3057286 -0.890484 0.3364221 0.305496 -0.8907819 0.115881 0.105228 -0.9876734 0.1160415 0.1053031 -0.9876466 0.002941071 0.7082566 -0.705949 0.001889169 0.4549421 -0.8905191 0.001751661 0.454371 -0.8908108 6.03726e-4 0.1566635 -0.9876519 6.26491e-4 0.1567745 -0.9876343 -0.5200835 0.4796878 -0.7066915 -0.3346641 0.3086757 -0.8903478 -0.3344185 0.3082728 -0.8905797 -0.1152042 0.1062017 -0.9876484 -0.1151864 0.1061617 -0.9876547 -0.7051183 -0.06011909 -0.7065366 -0.4525689 -0.03859466 -0.8908938 -0.4527649 -0.03853929 -0.8907966 -0.156088 -0.01328819 -0.9876538 -0.1560508 -0.01330113 -0.9876595 -0.4313814 -0.5608301 -0.7066681 -0.2770577 -0.3601967 -0.8907848 -0.277428 -0.3604573 -0.8905641 -0.09556061 -0.1241623 -0.9876497 -0.09567886 -0.1242513 -0.9876272 0.1222963 -0.6972696 -0.7062994 0.07853585 -0.4477592 -0.8906986 0.07861232 -0.4474391 -0.8908527 0.02711379 -0.1543233 -0.9876483 0.02708822 -0.1544615 -0.9876275 0.6215285 0.3393392 -0.7060816 0.5848097 0.6728687 -0.4530401 0.4644916 0.5344399 -0.7061314 0.4638739 0.534168 -0.706743 0.2979632 0.3431016 -0.8907858 0.2980694 0.3431553 -0.8907295 0.1027566 0.1182995 -0.9876469 0.1027299 0.1182771 -0.9876523 0.1686675 0.6869551 -0.706855 -0.1018573 0.8853989 -0.4535351 -0.08093154 0.7035166 -0.7060556 -0.08112835 0.7028146 -0.7067319 -0.05211889 0.4515053 -0.890745 -0.05204677 0.4516339 -0.8906841 -0.01794964 0.1557556 -0.9876326 -0.01791363 0.1558486 -0.9876186 -0.3929861 0.5887039 -0.706392 -0.7223356 0.5226375 -0.4528591 -0.5730798 0.4146566 -0.7068518 -0.5730397 0.4144358 -0.7070139 -0.368766 0.2666772 -0.8904466 -0.368766 0.2666772 -0.8904465 -0.368766 0.2666772 -0.8904466 -0.3687112 0.266667 -0.8904723 -0.1269108 0.09178882 -0.9876581 -0.1269972 0.09190624 -0.987636 -0.6992215 0.1070708 -0.7068417 -0.8732303 -0.1802198 -0.4527579 -0.6931223 -0.1430535 -0.7064823 -0.6924712 -0.1431561 -0.7070997 -0.4449689 -0.09199047 -0.8908089 -0.4454837 -0.09193092 -0.8905577 -0.1533591 -0.03164613 -0.9876638 -0.1534147 -0.03164643 -0.9876551 -0.5513159 -0.4438146 -0.7064555 -0.4558992 -0.7652239 -0.45452 -0.3621662 -0.6078975 -0.7066091 -0.3626327 -0.608228 -0.7060852 -0.232936 -0.3906992 -0.8905588 -0.2329192 -0.3906875 -0.8905683 -0.08027458 -0.1346487 -0.9876365 -0.08022093 -0.134609 -0.9876463 -0.04459536 -0.7063848 -0.7064219 0.2569514 -0.8531939 -0.4539121 0.204151 -0.6778805 -0.7062581 0.204118 -0.6777606 -0.7063828 0.204118 -0.6777606 -0.7063827 0.204118 -0.6777606 -0.7063827 0.1309889 -0.4349464 -0.890878 0.1309777 -0.4349197 -0.8908928 0.04522293 -0.1501649 -0.9876261 0.04523241 -0.1501001 -0.9876356 0.7820405 0.4270364 -0.45393 0.7821185 0.4270295 -0.4538022 0.726051 0.5167893 -0.4536285 0.6480541 0.7455083 -0.1557022 0.731396 0.6639167 -0.1558032 0.6601539 0.5992616 -0.4528602 0.7264577 0.5167287 -0.4530459 0.5770266 0.410441 -0.706101 0.6214586 0.3393286 -0.7061482 0.399114 0.2179165 -0.8906293 0.2128816 0.8657011 -0.4530377 0.2128816 0.8657011 -0.4530376 0.2128816 0.8657011 -0.4530377 0.2124827 0.8653827 -0.4538326 0.2124828 0.8653827 -0.4538326 0.2124827 0.8653827 -0.4538326 0.1086583 0.8843947 -0.4539158 0.1086584 0.8843947 -0.4539158 0.1086583 0.8843947 -0.4539158 -0.113367 0.9811113 -0.1567436 0.003976762 0.9876579 -0.1565763 0.003590047 0.8916115 -0.4527869 0.1091087 0.8849495 -0.452725 0.08663362 0.702657 -0.7062349 0.1690181 0.6875609 -0.706182 0.1086137 0.4418395 -0.8904948 -0.495142 0.7410923 -0.4534498 -0.4951267 0.7417123 -0.4524517 -0.5794548 0.6778197 -0.4525402 -0.8002778 0.5791803 -0.1552608 -0.7261784 0.6697577 -0.1552083 -0.6551396 0.6042233 -0.4535487 -0.5792947 0.6770401 -0.4539101 -0.5792947 0.6770401 -0.4539102 -0.5792946 0.6770402 -0.4539102 -0.4599574 0.5375785 -0.7067168 -0.3929268 0.5884102 -0.7066696 -0.2524656 0.3780721 -0.8906866 -0.880944 0.134936 -0.4535748 -0.8808923 0.1349 -0.453686 -0.8907265 0.02981984 -0.4535605 -0.9673012 -0.1997875 -0.1562481 -0.9673012 -0.1997876 -0.1562481 -0.9841412 -0.08382213 -0.1563327 -0.8880752 -0.07561606 -0.4534366 -0.8908298 0.02990043 -0.4533525 -0.7069861 0.02372854 -0.7068294 -0.6992639 0.1070764 -0.706799 -0.4494436 0.06882822 -0.8906532 -0.693836 -0.5589773 -0.454022 -0.6944112 -0.5589964 -0.4531183 -0.623342 -0.6372906 -0.4531065 -0.5065523 -0.8479324 -0.1562544 -0.6026731 -0.7825919 -0.1559976 -0.6026731 -0.7825918 -0.1559976 -0.5440289 -0.706542 -0.4525825 -0.6236139 -0.6373413 -0.4526608 -0.4949631 -0.5058605 -0.7064821 -0.5512086 -0.4437969 -0.7065504 -0.3539261 -0.2849451 -0.8908101 -0.05613386 -0.8895198 -0.4534355 -0.05616641 -0.8896774 -0.453122 0.04934269 -0.8899263 -0.4534276 0.2877369 -0.9446696 -0.1575021 0.2877369 -0.9446696 -0.1575021 0.2877369 -0.9446696 -0.1575022 0.1710796 -0.9726234 -0.1572755 0.1544328 -0.877979 -0.4531043 0.04928308 -0.8901641 -0.4529671 0.03910297 -0.7062876 -0.7068443 -0.04434108 -0.7058288 -0.7069934 -0.02848434 -0.4534109 -0.8908465 0.141169 -0.0679233 -0.9876527 0.4097355 -0.1971455 -0.8906462 0.4093278 -0.1967378 -0.8909237 0.6374605 -0.3064142 -0.7069332 0.6380749 -0.307159 -0.7060551 0.8029932 -0.3865357 -0.4536433 0.8028165 -0.3863127 -0.4541457 0.8901793 -0.4283303 -0.1552866 0.8901786 -0.4281961 -0.1556607 0.1483784 -0.05086129 -0.9876219 0.430226 -0.1474761 -0.8905934 0.4300949 -0.1473807 -0.8906724 0.6698484 -0.2295271 -0.7061307 0.6691502 -0.228936 -0.7069839 0.8431853 -0.2884885 -0.4536662 0.8431419 -0.2884622 -0.4537637 0.9345799 -0.3197507 -0.1559486 0.934531 -0.3197221 -0.1563003 0.9655587 -0.2080748 -0.1562092 0.1531281 -0.03286403 -0.9876598 0.4445374 -0.09539121 -0.8906667 0.4446433 -0.0954715 -0.8906052 0.6922435 -0.1486384 -0.706191 0.6922501 -0.1486607 -0.7061798 0.8713545 -0.1871156 -0.4535738 0.8712955 -0.1870808 -0.4537014 0.9658007 -0.2073659 -0.1556553 0.9657733 -0.207277 -0.1559433 0.1560112 -0.01449167 -0.987649 0.4529213 -0.04207849 -0.8905569 0.4526858 -0.04200029 -0.8906804 0.7040532 -0.06531786 -0.7071371 0.7049062 -0.0657801 -0.7062438 0.8880525 -0.0828852 -0.4522091 0.8873628 -0.08235478 -0.4536573 0.9834694 -0.09128099 -0.1563832 0.983471 -0.09128701 -0.1563698 0.1565733 0.004051506 -0.9876581 0.4541457 0.01175653 -0.8908498 0.4546025 0.01162439 -0.8906186 0.70738 0.01807469 -0.7066024 0.7068732 0.0182861 -0.7071039 0.8910582 0.02305573 -0.4533033 0.8916537 0.02270483 -0.4521486 0.9875474 0.02513569 -0.155301 0.9871429 0.02579313 -0.1577458 0.9774771 0.1417058 -0.1563902 0.1552994 0.0225532 -0.9876101 0.4499791 0.06534451 -0.8906452 0.4496287 0.06540542 -0.8908178 0.6997348 0.1017829 -0.7071149 0.7002257 0.1016779 -0.7066439 0.8822518 0.128111 -0.4530115 0.8821104 0.1281635 -0.4532719 0.9774926 0.1420453 -0.1559853 0.9776563 0.1417257 -0.1552487 0.9551966 0.2513495 -0.1562781 0.9551967 0.2513493 -0.1562782 0.9551967 0.2513494 -0.1562782 0.1513968 0.0407238 -0.9876339 0.4388837 0.1180474 -0.8907558 0.4391758 0.1180275 -0.8906145 0.6839993 0.1838199 -0.7059429 0.6827406 0.1840012 -0.7071131 0.8602846 0.2318355 -0.4540517 0.8608946 0.231642 -0.452993 0.9538537 0.2566652 -0.1558405 0.9537208 0.2567824 -0.1564594 0.1455658 0.05836373 -0.9876256 0.4220752 0.169228 -0.8906258 0.4217673 0.1692114 -0.890775 0.6571314 0.26365 -0.7061637 0.6573855 0.2636572 -0.7059244 0.8270729 0.3317164 -0.4537785 0.8269469 0.3317253 -0.4540013 0.9166903 0.3677299 -0.1563772 0.9166798 0.3677447 -0.1564033 0.731491 0.6638836 -0.155498 0.8047366 0.5728938 -0.1555368 0.8047714 0.5728244 -0.1556128 0.8045294 0.5729813 -0.1562849 0.8669046 0.4733676 -0.156204 0.8671747 0.4731944 -0.1552261 0.8666789 0.4737634 -0.1562569 0.6477667 0.7457622 -0.1556826 0.6478039 0.7456796 -0.1559238 0.5844296 0.6727568 -0.4536963 0.6597134 0.5991276 -0.4536789 0.5235474 0.4754713 -0.7069832 0.5761001 0.4102553 -0.7069649 0.3701115 0.2635518 -0.8908187 0.3986646 0.2178357 -0.8908503 0.137485 0.07512187 -0.9876511 0.1454097 0.05834776 -0.9876495 0.5551711 0.8169972 -0.1558865 0.08803617 0.1296141 -0.9876487 0.2553145 0.3758972 -0.890795 0.2553878 0.3759093 -0.890769 0.3978621 0.5856338 -0.7062144 0.397408 0.585384 -0.7066772 0.5004955 0.737241 -0.4538502 0.5009171 0.7374718 -0.4530093 0.5550143 0.8171153 -0.1558265 0.5550801 0.8171032 -0.1556553 0.4581526 0.8748797 -0.1571043 0.0721094 0.1391831 -0.9876378 0.2089055 0.4032307 -0.8909342 0.2090849 0.4034013 -0.8908147 0.3257856 0.628562 -0.7062391 0.3258095 0.6285077 -0.7062763 0.4104406 0.7917568 -0.4523935 0.4097687 0.7913144 -0.4537743 0.4541919 0.8770952 -0.1562492 0.4543575 0.8771005 -0.1557372 0.4543575 0.8771005 -0.1557372 0.4543575 0.8771005 -0.1557372 0.05521529 0.1467915 -0.9876253 0.1601836 0.4258459 -0.8905035 0.1596744 0.4252413 -0.8908838 0.2486714 0.6622578 -0.7068078 0.2490316 0.6626483 -0.7063148 0.3136219 0.8345153 -0.4530184 0.3136219 0.8345153 -0.4530184 0.3136219 0.8345153 -0.4530185 0.3138463 0.8347526 -0.4524256 0.3475472 0.924387 -0.157225 0.3475013 0.9243956 -0.1572752 0.003955304 0.9876182 -0.1568268 0.1199976 0.9803163 -0.1567819 0.120379 0.9802697 -0.1567808 0.120851 0.9803766 -0.155746 0.2359532 0.9592003 -0.1557591 0.2354395 0.9590859 -0.1572344 0.235951 0.9590234 -0.1568481 0.2359511 0.9590234 -0.1568481 0.235951 0.9590234 -0.1568481 -0.1132096 0.9813171 -0.1555651 -0.1128954 0.9812255 -0.1563692 -0.1018669 0.8853792 -0.4535712 0.00325042 0.8911736 -0.4536512 0.002580106 0.7073052 -0.7069036 0.08636432 0.702073 -0.7068486 0.05551612 0.4513055 -0.890641 0.1085007 0.4416344 -0.8906103 0.03735435 0.152045 -0.9876675 0.05501949 0.1465578 -0.9876709 -0.2279309 0.9610514 -0.156294 -0.03622269 0.1526416 -0.9876177 -0.1049538 0.4422671 -0.8907214 -0.1049353 0.4425126 -0.8906016 -0.1634473 0.6892722 -0.7058249 -0.1635723 0.688292 -0.7067519 -0.2061041 0.8672519 -0.4532055 -0.2061324 0.8670454 -0.4535878 -0.2284668 0.9609894 -0.1558922 -0.2284208 0.9610573 -0.1555404 -0.343747 0.9261777 -0.1550256 -0.3437469 0.9261777 -0.1550256 -0.3437469 0.9261778 -0.1550256 -0.05398112 0.1470689 -0.9876522 -0.1566379 0.4267335 -0.8907093 -0.1566738 0.4267356 -0.8907021 -0.244033 0.6646777 -0.7061525 -0.2440816 0.6651632 -0.7056785 -0.2440816 0.6651632 -0.7056785 -0.2440815 0.6651632 -0.7056785 -0.3069171 0.8363981 -0.4541367 -0.3068008 0.8368645 -0.4533557 -0.3399758 0.9273423 -0.156374 -0.340068 0.9273439 -0.1561635 -0.07100754 0.1396897 -0.9876461 -0.2060128 0.4052693 -0.8906826 -0.2060184 0.4052812 -0.8906759 -0.3207652 0.6309989 -0.7063641 -0.3207628 0.6312199 -0.7061677 -0.4037133 0.794471 -0.4536867 -0.4038057 0.7940801 -0.4542885 -0.4477778 0.8805669 -0.1552321 -0.4477576 0.8806105 -0.1550427 -0.7261947 0.6695978 -0.1558208 -0.6417308 0.7509753 -0.1556205 -0.641903 0.7508691 -0.1554227 -0.6420165 0.7506381 -0.1560688 -0.5487181 0.8212906 -0.1561735 -0.5487658 0.8212479 -0.1562305 -0.5479736 0.8219824 -0.1551451 -0.800171 0.5790523 -0.1562851 -0.8004317 0.5789459 -0.1553412 -0.7221115 0.522289 -0.4536181 -0.655116 0.6042407 -0.4535593 -0.5200604 0.4796707 -0.7067201 -0.4600949 0.5376322 -0.7065864 -0.2952689 0.3450314 -0.8909375 -0.2522755 0.3775574 -0.8909589 -0.08701837 0.1302331 -0.9876575 -0.07100844 0.1396074 -0.9876577 -0.1369724 0.07621735 -0.9876384 -0.3973827 0.2211272 -0.8906121 -0.3975223 0.2212511 -0.8905189 -0.61852 0.344251 -0.7063457 -0.6179962 0.3436157 -0.7071132 -0.7787837 0.4330127 -0.4538677 -0.77898 0.4334775 -0.4530866 -0.8631885 0.4803172 -0.1555676 -0.8632104 0.4798175 -0.1569807 -0.9152528 0.371698 -0.1554121 -0.1449687 0.05942749 -0.98765 -0.4207471 0.1724752 -0.8906313 -0.4208463 0.1725305 -0.8905739 -0.654672 0.2683875 -0.7066631 -0.6548337 0.2685469 -0.7064527 -0.8245732 0.3381495 -0.453579 -0.8244976 0.3380641 -0.4537799 -0.9138121 0.3747146 -0.1566413 -0.9138458 0.3750572 -0.1556215 -0.1509587 0.04188591 -0.9876524 -0.4381566 0.1215667 -0.8906405 -0.4382945 0.1216748 -0.8905578 -0.6815958 0.1892105 -0.7068428 -0.6817421 0.1892828 -0.7066822 -0.8587698 0.2384485 -0.4534938 -0.8587276 0.2383766 -0.4536118 -0.9518748 0.2642225 -0.155309 -0.9518698 0.2641943 -0.1553875 -0.9841482 -0.08377778 -0.1563125 -0.9871343 0.03334808 -0.1563768 -0.9871891 0.03304249 -0.1560963 -0.9872876 0.03335136 -0.1554059 -0.9764607 0.1495698 -0.1554136 -0.9764094 0.1494585 -0.1558431 -0.9764054 0.1501518 -0.1551997 -0.9672291 -0.1995048 -0.1570529 -0.9672908 -0.1998241 -0.1562657 -0.8729435 -0.1803212 -0.4532704 -0.8881905 -0.07557469 -0.4532176 -0.7054531 -0.06002736 -0.7062101 -0.7075574 0.02400904 -0.7062479 -0.4544662 0.01541513 -0.8906307 -0.4495395 0.06885671 -0.8906027 -0.1549482 0.02373272 -0.9876375 -0.151026 0.04194229 -0.9876396 -0.1485753 -0.04960024 -0.9876565 -0.431023 -0.1438781 -0.8907965 -0.4314371 -0.1438944 -0.8905933 -0.6718108 -0.2240406 -0.7060285 -0.6707312 -0.2241184 -0.7070295 -0.8451284 -0.2823845 -0.4538912 -0.8458526 -0.282214 -0.4526462 -0.9369498 -0.3126061 -0.1562138 -0.937004 -0.3125934 -0.1559134 -0.8932361 -0.4215011 -0.1564168 -0.14188 -0.06688439 -0.9876217 -0.4114471 -0.1939464 -0.8905594 -0.4110378 -0.1939114 -0.8907561 -0.6403259 -0.3020824 -0.7062075 -0.6404051 -0.3020599 -0.7061454 -0.8058756 -0.3801201 -0.4539532 -0.8059124 -0.3800673 -0.4539318 -0.8933321 -0.4213002 -0.1564092 -0.8934077 -0.4212343 -0.1561558 -0.1326376 -0.08307701 -0.9876768 -0.3849844 -0.2411365 -0.8908649 -0.3856178 -0.2413154 -0.8905425 -0.6000645 -0.3755148 -0.7063366 -0.6001567 -0.3754909 -0.7062709 -0.7552304 -0.4725092 -0.4542712 -0.7552304 -0.4725091 -0.4542711 -0.7552304 -0.4725091 -0.4542712 -0.7553898 -0.4725521 -0.4539614 -0.8375774 -0.5239759 -0.1546403 -0.8370546 -0.5242375 -0.1565721 -0.8370546 -0.5242375 -0.1565721 -0.602329 -0.7826322 -0.1571204 -0.6905643 -0.7059577 -0.1573047 -0.6905642 -0.7059578 -0.1573048 -0.6905642 -0.7059577 -0.1573048 -0.6905431 -0.706008 -0.1571719 -0.6906247 -0.7059315 -0.157157 -0.7690694 -0.6195725 -0.1570427 -0.7694845 -0.6194067 -0.1556569 -0.770385 -0.6185533 -0.1545923 -0.5057385 -0.8484271 -0.1562049 -0.5057469 -0.8483949 -0.1563531 -0.505747 -0.8483949 -0.1563532 -0.5057469 -0.8483949 -0.1563531 -0.4564045 -0.7655841 -0.4534048 -0.5434663 -0.7063072 -0.4536238 -0.4316611 -0.5610108 -0.7063537 -0.4951033 -0.5059516 -0.7063184 -0.3178144 -0.3247861 -0.8907907 -0.3539965 -0.2849867 -0.8907688 -0.122199 -0.09837257 -0.9876186 -0.1329885 -0.08316016 -0.9876226 -0.0637319 -0.1431421 -0.987648 -0.1851682 -0.4158849 -0.8903665 -0.1848228 -0.4154819 -0.8906263 -0.2873716 -0.645999 -0.7071796 -0.2883021 -0.6468986 -0.7059775 -0.3630339 -0.8145744 -0.4524103 -0.3619977 -0.813875 -0.4544942 -0.401393 -0.9024634 -0.1563444 -0.4016645 -0.9024737 -0.1555858 -0.2919721 -0.9435385 -0.1564849 -0.2919721 -0.9435386 -0.1564849 -0.291972 -0.9435386 -0.1564849 -0.04629862 -0.1496306 -0.9876575 -0.1344751 -0.4346039 -0.8905256 -0.1346965 -0.4349417 -0.8903273 -0.2092432 -0.6756728 -0.7068831 -0.2090092 -0.6754435 -0.7071713 -0.2634975 -0.8515416 -0.4532616 -0.2639509 -0.8519405 -0.4522469 -0.2923046 -0.9434517 -0.1563877 -0.2922309 -0.9434226 -0.1567004 -0.02831733 -0.1542085 -0.9876325 -0.08202731 -0.4466885 -0.8909215 -0.08237475 -0.4474039 -0.8905304 -0.1281699 -0.6961193 -0.7063926 -0.1279481 -0.6957619 -0.7067848 -0.1612012 -0.8766024 -0.453412 -0.1612157 -0.8766517 -0.4533118 -0.1786478 -0.9714617 -0.1560357 -0.1785569 -0.9714428 -0.1562573 0.1707333 -0.9728772 -0.1560779 0.05475407 -0.9862108 -0.1561741 0.05468165 -0.9862236 -0.1561181 0.05468165 -0.9862236 -0.1561182 0.05484724 -0.9861753 -0.1563654 -0.06220591 -0.9857501 -0.1562921 -0.06266647 -0.9859789 -0.1546567 -0.06116354 -0.9858207 -0.1562587 0.2847628 -0.9458255 -0.1559632 0.2843858 -0.9457409 -0.1571584 0.2567673 -0.8539019 -0.4526831 0.1543909 -0.878271 -0.4525525 0.1224763 -0.6967255 -0.7068049 0.0390796 -0.7061488 -0.7069842 0.02513957 -0.4542552 -0.8905169 -0.02876329 -0.4540634 -0.890505 -0.009911775 -0.156473 -0.9876326 -0.02832758 -0.1541826 -0.9876363 0.06262266 -0.143724 -0.9876345 0.1816323 -0.416868 -0.8906351 0.1816545 -0.4164791 -0.8908125 0.2826895 -0.6481391 -0.7071084 0.2827247 -0.6489068 -0.70639 0.3560217 -0.8171641 -0.4533117 0.3560585 -0.8168189 -0.4539043 0.3560586 -0.816819 -0.4539044 0.3560586 -0.816819 -0.4539044 0.3947483 -0.9055352 -0.155499 0.3947483 -0.9055352 -0.155499 0.3947483 -0.9055352 -0.1554991 0.394781 -0.9054487 -0.1559191 0.394781 -0.9054487 -0.1559191 0.3947809 -0.9054487 -0.1559191 0.4979718 -0.8530394 -0.1560384 0.07913953 -0.1352236 -0.9876495 0.2297456 -0.3925485 -0.8905743 0.2297634 -0.3925838 -0.8905542 0.3573873 -0.6106348 -0.7066821 0.3572897 -0.6101278 -0.7071692 0.450369 -0.7690782 -0.4535269 0.4503344 -0.7692674 -0.45324 0.4990565 -0.8525001 -0.1555194 0.4990943 -0.8524624 -0.1556047 0.09460049 -0.1249379 -0.9876443 0.2745422 -0.3625799 -0.8905967 0.2745695 -0.3626554 -0.8905575 0.4270944 -0.564109 -0.7066621 0.4271022 -0.564094 -0.7066695 0.5379095 -0.7104567 -0.4537674 0.5379151 -0.7105945 -0.4535447 0.5962697 -0.7876754 -0.155016 0.5964108 -0.7872925 -0.1564123 0.1087616 -0.1128914 -0.9876368 0.3154072 -0.3273742 -0.8906989 0.3153994 -0.3274396 -0.8906776 0.4910832 -0.5098179 -0.7063449 0.4909593 -0.5095559 -0.7066201 0.6182615 -0.6416795 -0.4538725 0.6182945 -0.6417799 -0.4536854 0.6853848 -0.7113837 -0.1555025 0.6853848 -0.7113838 -0.1555025 0.6853848 -0.7113837 -0.1555025 0.6853409 -0.7114455 -0.1554133 0.7639028 -0.6260442 -0.1565928 0.1211967 -0.09913003 -0.9876663 0.3520064 -0.2879142 -0.890616 0.3519294 -0.287755 -0.890698 0.5479409 -0.4480109 -0.7064327 0.5479258 -0.4481049 -0.7063847 0.6898264 -0.5641586 -0.4537231 0.6898086 -0.5640742 -0.453855 0.7647742 -0.6253873 -0.1549555 0.7649326 -0.624962 -0.155887 0.1322581 -0.08418893 -0.9876336 0.3831708 -0.2439167 -0.8908899 0.3835272 -0.2443502 -0.8906177 0.5972632 -0.3805287 -0.7060273 0.5970307 -0.3801654 -0.7064195 0.7515249 -0.4785498 -0.4540929 0.7515646 -0.4786343 -0.4539383 0.8331696 -0.5306155 -0.1558061 0.8331925 -0.5304487 -0.1562517 -0.9077742 0.4194592 0 -0.9783412 0.2069993 0 -0.9783391 0.207009 0 -0.9958921 -0.09054952 0 -0.9958902 -0.09056955 0 -0.9249407 -0.3801115 0 -0.9249407 -0.3801115 0 -0.7717894 -0.6358783 0 -0.7717795 -0.6358903 0 -0.550051 -0.8351311 0 -0.2797757 -0.9600654 0 -0.2797731 -0.9600663 0 0.01609915 -0.9998704 0 0.01609915 -0.9998704 0 0.3096938 -0.9508364 0 0.3096939 -0.9508364 0 0.5763291 -0.8172177 0 0.7917202 -0.610884 0 0.7917202 -0.6108841 0 0.9365491 -0.3505366 0 0.9365458 -0.3505454 0 0.9982548 -0.05905431 0 0.9982548 -0.05905431 0 0.9713177 0.2377861 0 0.9713153 0.2377957 0 0.8578113 0.513965 0 0.8578156 0.5139576 0 0.6685451 0.7436716 0 0.6685451 0.7436717 0 0.4194799 0.9077646 0 0.419476 0.9077665 0 0.1334864 0.9910507 0 0.133485 0.9910508 0 -0.1647466 0.9863359 0 -0.1647482 0.9863356 0 -0.448141 0.8939629 0 -0.4481452 0.8939609 0 -0.6918492 0.722042 0 -0.8348148 0.5505311 0 -0.8737586 0.4863588 0.001159489 0.8790062 0.4768015 -0.002918004 0.9600847 0.2797068 0.001214146 0.9454755 0.3256741 -0.00355035 0.9203159 0.3911719 0.001766145 0.9201905 0.3914669 0.001759171 0.9604367 0.2784957 0.001213192 0.9864019 0.1643406 -0.001872658 0.9861775 0.1656842 -0.001664996 0.9989483 0.04583823 0.001112759 0.9989281 0.04627579 0.00111258 0.9999934 9.66113e-4 -0.003513932 0.9973396 -0.07287317 0.001834988 0.9974169 -0.0718069 0.001834928 0.9865465 -0.1634532 -0.003029286 0.9818189 -0.1898204 2.29369e-4 0.9461385 -0.3237624 2.25425e-4 0.9822466 -0.1859831 -0.02453619 0.9822466 -0.1859831 -0.02453619 0.9822466 -0.1859831 -0.02453619 0.952552 -0.3043532 -0.003737688 0.8543306 -0.5197282 0.001373231 0.879894 -0.4751569 -0.003529548 0.9097589 -0.4151335 0.001764655 0.9095647 -0.4155589 0.001765131 0.8547171 -0.5190924 0.00137782 0.786852 -0.6171381 -0.002164065 0.7897141 -0.6134735 -0.001445174 0.7085091 -0.7057011 9.80298e-4 0.7084133 -0.7057973 9.80837e-4 0.6779976 -0.735056 -0.003462791 0.5228125 -0.8524477 3.69599e-4 0.5478439 -0.8365747 -0.00314331 0.6198506 -0.7847179 0.001816391 0.6198906 -0.7846863 0.001815915 0.5228805 -0.852406 3.72928e-4 0.4183689 -0.9082772 -4.0843e-4 0.4025637 -0.9153881 -0.002686202 0.1928761 -0.9812221 0.001467883 0.2465639 -0.9691199 -0.003612041 0.3079425 -0.9514036 0.001653134 0.3076616 -0.9514945 0.001646339 0.1941112 -0.9809786 0.001458823 0.07555109 -0.997139 -0.002469718 0.08350533 -0.9965066 -0.001217305 -0.04047942 -0.9991801 8.26267e-4 -0.04299384 -0.9990751 8.37491e-4 -0.0815947 -0.9966599 -0.003369033 -0.2763283 -0.9610632 5.89651e-4 -0.2443936 -0.9696707 -0.003226518 -0.1604298 -0.9870455 0.001849174 -0.1602938 -0.9870676 0.001858651 -0.2752276 -0.9613789 5.89498e-4 -0.3877964 -0.921745 -6.01532e-4 -0.4008696 -0.9161318 -0.002518117 -0.5938916 -0.8045437 0.001547694 -0.5461325 -0.837691 -0.003632009 -0.4941052 -0.8694007 0.001590132 -0.4939024 -0.869516 0.00157839 -0.5924043 -0.8056393 0.001546978 -0.6845331 -0.7289764 -0.00279659 -0.6766719 -0.736284 -0.00106132 -0.7675881 -0.6409434 6.67871e-4 -0.7659466 -0.6429039 6.67204e-4 -0.7884613 -0.6150753 -0.00333327 -0.8956177 -0.4448243 7.50037e-4 -0.8788701 -0.4770497 -0.003313601 -0.8365597 -0.547873 0.001848995 -0.8366934 -0.5476685 0.001846432 -0.8944375 -0.4471926 7.4846e-4 -0.8944375 -0.4471927 7.48414e-4 -0.8944375 -0.4471927 7.48443e-4 -0.9419056 -0.3358767 -8.48582e-4 -0.9454749 -0.3256866 -0.002345919 -0.9943875 -0.1057883 0.001562714 -0.9862229 -0.1653831 -0.003583908 -0.9750723 -0.2218822 0.001537799 -0.9749217 -0.2225433 0.001535952 -0.9945695 -0.1040623 0.001562416 -0.9999127 0.01285606 -0.003063559 -0.9999994 -9.53237e-4 -7.87639e-4 -0.9915379 0.1298169 5.03984e-4 -0.9913515 0.1312333 5.04556e-4 -0.9865458 0.1634533 -0.003253519 -0.9327564 0.3605065 8.44937e-4 -0.9461252 0.3237833 -0.003405451 -0.9689287 0.2473334 0.00184673 -0.9688657 0.2475801 0.001845896 -0.9324203 0.3613747 8.42917e-4 -0.8836039 0.4682338 -0.001084148 -0.8798972 0.4751591 -0.002196311 -0.7489869 0.6625828 0.001689136 -0.789866 0.6132693 -0.003572225 -0.8219959 0.5694916 0.001432955 -0.8223069 0.5690426 0.001433134 -0.7493023 0.662226 0.001689672 -0.6653026 0.7465661 -0.003401935 -0.6780207 0.7350426 -5.18178e-4 -0.5681664 0.8229136 4.01813e-4 -0.5724195 0.8199609 3.97956e-4 -0.547844 0.8365748 -0.003111064 -0.3639218 0.9314291 9.38059e-4 -0.4024291 0.9154447 -0.003445386 -0.4712069 0.8820208 0.00184077 -0.4716206 0.8817998 0.00183624 -0.3630362 0.9317747 9.38715e-4 -0.2509806 0.9679912 -0.001378118 -0.2466671 0.9690982 -0.002027213 -0.01686972 0.9998563 0.001726686 -0.08348345 0.9965029 -0.00354892 -0.1343892 0.9909278 0.001344025 -0.1352121 0.9908158 0.001336991 -0.01689195 0.9998559 0.001724421 0.1017629 0.9948017 -0.003758132 0.08156788 0.9966678 -2.84553e-4 0.2191486 0.9756915 1.72543e-4 0.2191488 0.9756915 1.73559e-4 0.2191487 0.9756915 1.73603e-4 0.2189393 0.9757385 1.75168e-4 0.2444792 0.9696499 -0.00301826 0.4419555 0.8970364 0.001083552 0.4008778 0.9161247 -0.003535687 0.3323189 0.9431654 0.001809895 0.3323153 0.9431666 0.001806974 0.442497 0.8967694 0.001093089 0.5446131 0.838686 -0.00160706 0.5461409 0.8376912 -0.001887679 0.6409931 0.7675459 0.001222372 0.6399899 0.7683824 0.001217305 0.6765137 0.7364214 -0.003561556 0.7262827 0.687394 0.001728892 0.7270743 0.6865566 0.001734554 0.7884565 0.6150838 -0.002924203 0.8026182 0.5964931 0 0.8676624 0.497154 0 0.633106 0.7581296 0.1562579 0.3282438 0.931596 0.1561573 -0.4659267 0.8710219 0.1556698 -0.9570264 0.2446093 0.1557782 -0.8263762 -0.5409364 0.1564942 0.9865337 0.04523402 0.1571795 0.9089926 0.3866855 0.1555859 -0.007627785 0.454497 0.8907157 -0.3406708 0.3012248 0.8906217 -0.4519249 -0.0478779 0.8907703 -0.2698183 -0.365857 0.8907003 0.08769935 -0.4456925 0.8908799 0.3882173 -0.2360914 0.8908132 0.1259282 0.09368437 0.9876059 0.1138018 0.1076008 0.9876595 0.1005146 0.1206139 0.9875977 0.08545243 0.1315814 0.9876154 0.06924962 0.1406117 0.98764 0.05216807 0.1478381 0.9876348 -0.05703276 0.1461566 0.9876161 -0.07397818 0.1383884 0.9876112 -0.1463783 0.05647104 0.9876155 -0.1518511 0.03884434 0.9876398 -0.1404398 -0.06974124 0.98763 -0.1313489 -0.08596843 0.9876016 -0.04331105 -0.1507981 0.9876155 -0.02523887 -0.1548536 0.987615 0.08204776 -0.1337683 0.9876105 0.09714859 -0.1230612 0.9876326 0.1539692 -0.02973902 0.9876281 0.1563618 -0.01136302 0.9876345 0.1566681 0.007246494 0.9876248 0.1548863 0.02581357 0.9875951 0.1504758 0.04380875 0.9876426 0.144374 0.06136029 0.9876189 0.1359977 0.07788509 0.987643 0.1340312 -0.08153349 0.9876174 0.1340375 -0.08154559 0.9876155 0.1427712 -0.06514745 0.9876094 0.03034204 -0.154085 0.9875917 0.03028315 -0.1539315 0.9876174 0.04827094 -0.1493083 0.9876118 -0.09310925 -0.1261897 0.9876269 -0.09306949 -0.1262121 0.9876278 -0.07749444 -0.1363834 0.9876205 -0.1561249 -0.0166043 0.9875978 -0.155901 -0.01651632 0.9876347 -0.1529123 -0.03480082 0.9876269 -0.1173362 0.1038606 0.9876463 -0.1175884 0.103989 0.9876028 -0.1290735 0.08938223 0.9875985 -0.002649068 0.1569617 0.9876012 -0.002628028 0.1569045 0.9876103 -0.02114486 0.1555208 0.9876063 0.5568684 -0.4366388 0.7065721 0.3576083 -0.2803792 0.8907883 0.3572189 -0.280229 0.8909918 0.1234263 -0.09681892 0.9876195 0.1234695 -0.09684133 0.9876118 0.05354684 -0.7055512 0.7066331 0.03437018 -0.4529182 0.8908893 0.03465068 -0.4534581 0.8906038 0.01196348 -0.15652 0.9876024 0.01191365 -0.15643 0.9876172 -0.4843575 -0.5158997 0.706573 -0.3111642 -0.3314021 0.8907017 -0.3111687 -0.3314362 0.8906875 -0.1073126 -0.1142815 0.9876355 -0.1073086 -0.1143382 0.9876294 -0.7075269 0.009196102 0.7066267 -0.4544482 0.005914866 0.8907535 -0.4545395 0.005876123 0.8907073 -0.1569454 0.002037107 0.9876053 -0.1567095 0.002098739 0.9876425 -0.4707899 0.5282866 0.7065905 -0.3025988 0.3395182 0.8905961 -0.3019579 0.3392193 0.8909274 -0.1041827 0.1170129 0.9876508 -0.1043854 0.1171445 0.9876137 0.07193881 0.7035239 0.7070212 0.04623132 0.4521733 0.8907312 0.04620087 0.4522672 0.890685 0.01595103 0.1561422 0.9876059 0.01595324 0.1560413 0.9876217 0.6432494 -0.2932584 0.7072693 0.6316167 -0.6292289 0.4529144 0.5013678 -0.4994454 0.7065301 0.5008529 -0.4992309 0.7070467 0.3215996 -0.3205611 0.8909627 0.3221625 -0.3208025 0.8906723 0.1111996 -0.1107547 0.9876073 0.1112248 -0.1107591 0.987604 0.2177568 -0.6731488 0.7067196 -0.03800255 -0.8904361 0.4535189 -0.03017139 -0.7070263 0.7065434 -0.03021311 -0.7067756 0.7067925 -0.01941645 -0.4544011 0.8905856 -0.01939231 -0.4545812 0.8904942 -0.006676614 -0.1567217 0.9876202 -0.00670129 -0.1566556 0.9876306 -0.3495767 -0.6151269 0.7066931 -0.6829192 -0.573372 0.4526214 -0.5419502 -0.4550055 0.7065833 -0.5418419 -0.4547746 0.706815 -0.3482447 -0.2922581 0.8906801 -0.3482049 -0.2922397 0.8907016 -0.1201193 -0.1008257 0.9876262 -0.1202124 -0.1009533 0.9876018 -0.6902111 -0.1575616 0.7062458 -0.8837532 0.116747 0.4531561 -0.7015038 0.0927152 0.7066091 -0.700767 0.09288066 0.7073181 -0.4506587 0.05971997 0.8906965 -0.4508132 0.05971413 0.8906188 -0.1553699 0.02057874 0.987642 -0.1554722 0.02054953 0.9876266 -0.5814414 0.4028139 0.7068712 -0.5101659 0.7308391 0.4534369 -0.4050296 0.5802104 0.7066165 -0.4045894 0.5799565 0.707077 -0.2598307 0.3724434 0.89094 -0.2604544 0.372884 0.8905735 -0.08980119 0.1286063 0.9876216 -0.08981984 0.1285987 0.9876208 -0.09523957 0.7010576 0.7067162 0.1951945 0.8698151 0.4531233 0.1548815 0.690133 0.7069146 0.1547689 0.6904335 0.7066457 0.09942513 0.4435469 0.8907193 0.09948766 0.4434117 0.8907796 0.03434902 0.1531102 0.987612 0.03435027 0.1531127 0.9876116 0.811286 -0.3698104 0.4528304 0.8111839 -0.3698354 0.4529928 0.7615643 -0.4633818 0.4530974 0.6998173 -0.6970839 0.1559804 0.7772114 -0.6096135 0.1559291 0.701167 -0.5499368 0.4538 0.7611994 -0.4634268 0.4536641 0.6038977 -0.3676379 0.7072129 0.6433665 -0.2932671 0.7071591 0.4135521 -0.1885194 0.8907497 0.2748677 -0.8484636 0.4522802 0.2743514 -0.8480625 0.4533448 0.1722841 -0.8746024 0.4531985 -0.03999495 -0.9868695 0.15649 0.07455265 -0.9848518 0.1565533 0.06728327 -0.8886938 0.4535377 0.1720904 -0.8742979 0.4538592 0.1366755 -0.6943625 0.7065272 0.2178702 -0.6732696 0.7065696 0.1397923 -0.4320201 0.890964 -0.4404566 -0.7753711 0.4525459 -0.440531 -0.7752279 0.4527186 -0.5292019 -0.7175281 0.4528784 -0.7579901 -0.6331948 0.1565744 -0.7579901 -0.6331948 0.1565745 -0.7579901 -0.6331948 0.1565744 -0.6761695 -0.7198268 0.1569847 -0.6101157 -0.6495054 0.453764 -0.5291548 -0.7169349 0.4538717 -0.4196799 -0.5686427 0.7074703 -0.3493985 -0.6141772 0.7076067 -0.2244285 -0.3945026 0.8910666 -0.8690453 -0.1982505 0.4532739 -0.8692401 -0.1984063 0.4528321 -0.886636 -0.09394913 0.4528248 -0.9792941 0.1280886 0.1567687 -0.9792941 0.1280887 0.1567687 -0.9792941 0.1280887 0.1567686 -0.9875461 0.01323604 0.1567726 -0.891287 0.01191651 0.4532831 -0.8864099 -0.09378308 0.4533014 -0.7030642 -0.07437711 0.7072262 -0.6893934 -0.1570075 0.7071672 -0.4427609 -0.1008391 0.8909514 -0.7324806 0.5076557 0.4536056 -0.7328039 0.5077084 0.453024 -0.6676204 0.5907945 0.4530397 -0.5612634 0.8126835 0.1566173 -0.6570771 0.7373619 0.1566756 -0.5930077 0.665442 0.4533529 -0.6674607 0.5906626 0.4534466 -0.5298038 0.4689056 0.7067075 -0.5815692 0.4028355 0.7067538 -0.3737453 0.2588647 0.8906759 -0.1201858 0.8832007 0.4533343 -0.1199336 0.8828012 0.4541785 -0.0147264 0.8908125 0.4541327 0.216655 0.9635638 0.156861 0.216655 0.9635639 0.156861 0.2166549 0.9635639 0.156861 0.1005819 0.9825261 0.1566068 0.09077298 0.8866477 0.4534491 -0.01496684 0.8912594 0.4532469 -0.01188188 0.7073869 0.7067268 -0.09530609 0.7010419 0.7067227 -0.06125104 0.4504678 0.8906891 0.1361957 0.07805168 0.9876025 0.3945128 0.2261123 0.8906363 0.3946325 0.2262641 0.8905447 0.6137937 0.3519103 0.7066941 0.6135401 0.3516567 0.7070404 0.7733017 0.4432167 0.4533912 0.7733581 0.4433924 0.453123 0.8569664 0.4913148 0.155623 0.8569575 0.4910392 0.1565384 0.1442631 0.0612874 0.9876396 0.418438 0.1777392 0.8906843 0.4185335 0.177804 0.8906264 0.6507617 0.2764602 0.7071626 0.6511384 0.2768105 0.7066787 0.8202762 0.3487166 0.4533695 0.8202478 0.3486296 0.4534877 0.9090591 0.3863996 0.1559068 0.9090353 0.386386 0.15608 0.94871 0.2751585 0.1556828 0.1506186 0.04388391 0.9876176 0.4366931 0.1272668 0.8905628 0.4364844 0.1271178 0.8906866 0.6788381 0.1977071 0.707171 0.6788685 0.1977546 0.7071285 0.8559103 0.2493169 0.453055 0.8557651 0.2491683 0.4534108 0.948331 0.2761239 0.1562822 0.9483433 0.276261 0.1559643 0.1546565 0.02568316 0.9876345 0.4480748 0.07443267 0.8908922 0.4487193 0.07474988 0.8905411 0.697722 0.1162198 0.7068784 0.6973512 0.1160274 0.7072757 0.8796572 0.1463518 0.452531 0.8794634 0.1461122 0.4529851 0.9742257 0.1618577 0.1571196 0.9743996 0.1623353 0.1555398 0.1568592 0.007293343 0.9875941 0.4543466 0.02112734 0.8905744 0.4536861 0.0208792 0.890917 0.7061492 0.03250843 0.7073165 0.7066214 0.03270387 0.7068358 0.8905195 0.0412274 0.4530733 0.8908451 0.0414105 0.4524163 0.9866436 0.0458768 0.156301 0.9865567 0.04571199 0.1568964 0.9851881 -0.07084453 0.1561591 0.1564162 -0.01134502 0.9876261 0.4531593 -0.03286308 0.8908236 0.453644 -0.03273648 0.8905816 0.7060871 -0.05093246 0.706291 0.7050373 -0.05130177 0.7073122 0.8888976 -0.06465458 0.4535205 0.8891996 -0.06448501 0.4529523 0.9852744 -0.07147896 0.1553228 0.9850625 -0.07197844 0.1564319 0.9704487 -0.1838272 0.1563228 0.9704489 -0.1838269 0.1563228 0.9704488 -0.1838272 0.1563228 0.1539385 -0.02974802 0.9876325 0.4463306 -0.08627939 0.8906992 0.4461263 -0.08629906 0.8907996 0.6941812 -0.1343231 0.7071562 0.6950337 -0.1341174 0.7063574 0.8755194 -0.1689617 0.4526785 0.8750873 -0.169128 0.4534511 0.9698026 -0.1874214 0.1560655 0.9697805 -0.1874668 0.1561477 0.149378 -0.04778772 0.9876248 0.4329134 -0.1385002 0.8907322 0.4330043 -0.1385002 0.890688 0.6734366 -0.2154031 0.7071667 0.6734531 -0.2153882 0.7071555 0.8491458 -0.2716022 0.4529722 0.8493252 -0.2715511 0.4526663 0.9406819 -0.3007627 0.1570339 0.9408594 -0.3005958 0.1562879 0.7772493 -0.6095821 0.155863 0.844277 -0.5127913 0.1556968 0.8439223 -0.513491 0.1553133 0.8439224 -0.513491 0.1553133 0.8439223 -0.513491 0.1553133 0.8440485 -0.5134266 0.1548402 0.8989406 -0.4097735 0.1548923 0.8985596 -0.4100074 0.1564757 0.8982715 -0.4104858 0.1568757 0.6997535 -0.6971847 0.155816 0.699745 -0.6971088 0.1561928 0.6315441 -0.6291766 0.4530882 0.70161 -0.5500628 0.4529619 0.5570177 -0.4366815 0.7064281 0.6047239 -0.3677745 0.7064355 0.3881721 -0.2360616 0.8908408 0.4133957 -0.1885203 0.8908223 0.1429356 -0.06517273 0.9875839 0.149596 -0.04779112 0.9875916 0.61231 -0.7751523 0.1556128 0.6123101 -0.7751523 0.1556129 0.61231 -0.7751523 0.1556128 0.09730803 -0.1231969 0.9876 0.2818158 -0.356751 0.8906787 0.2817868 -0.3566861 0.890714 0.4384762 -0.5550732 0.7068469 0.4382807 -0.5549632 0.7070544 0.5524178 -0.699513 0.4533389 0.5526769 -0.6995501 0.4529659 0.6123027 -0.7750923 0.1559403 0.6123147 -0.7750648 0.1560298 0.5165934 -0.8419723 0.1556085 0.08193105 -0.1336694 0.9876334 0.2373867 -0.3873344 0.8908534 0.2376779 -0.3875449 0.8906841 0.3698088 -0.6030482 0.7068058 0.3698083 -0.6029989 0.7068482 0.465864 -0.7596638 0.4537419 0.4660811 -0.759784 0.4533177 0.5165075 -0.8420212 0.1556293 0.5164256 -0.8420609 0.155686 0.06562441 -0.1425395 0.9876112 0.1899105 -0.4124046 0.8909862 0.1900629 -0.4126391 0.8908451 0.2960078 -0.6426149 0.7067006 0.2958935 -0.6424494 0.7068988 0.3730981 -0.8101417 0.4521816 0.3724318 -0.8096674 0.4535784 0.4126379 -0.8971453 0.1576719 0.4133052 -0.8972193 0.1554878 0.07462859 -0.9849015 0.1562041 0.1917265 -0.9689561 0.1560932 0.1909283 -0.9692647 0.1551532 0.1909283 -0.9692647 0.1551532 0.1909283 -0.9692646 0.1551532 0.1905067 -0.9691358 0.1564705 0.3043915 -0.9396305 0.1563345 0.304103 -0.9395778 0.1572096 0.3037916 -0.9395764 0.157819 0.3037916 -0.9395764 0.1578191 0.3037916 -0.9395765 0.1578191 -0.04247379 -0.9869098 0.1555793 -0.04192936 -0.9866539 0.1573401 -0.03785222 -0.8907201 0.4529735 0.06748586 -0.8889073 0.453089 0.05358856 -0.7057194 0.706462 0.1367257 -0.6943968 0.7064837 0.08776402 -0.4457446 0.8908476 0.1399142 -0.4321555 0.8908793 0.04840189 -0.1494756 0.9875801 0.06577831 -0.1426841 0.9875802 -0.1584472 -0.974855 0.1566914 -0.02524507 -0.1547787 0.9876266 -0.07316321 -0.4485235 0.8907715 -0.07308298 -0.4490929 0.8904911 -0.1135866 -0.6979517 0.7070795 -0.1134708 -0.6982061 0.706847 -0.1430273 -0.8800321 0.4528652 -0.1430273 -0.8800321 0.4528651 -0.1430273 -0.880032 0.4528653 -0.1431988 -0.8796023 0.4536452 -0.1587044 -0.9748729 0.1563196 -0.1583264 -0.9750242 0.1557586 -0.2718111 -0.9496405 0.1558898 -0.04330217 -0.1508293 0.987611 -0.1253693 -0.4366102 0.8908727 -0.1253523 -0.4368072 0.8907786 -0.1951822 -0.6801294 0.7066315 -0.1952787 -0.6797273 0.7069916 -0.2461158 -0.8567576 0.4532036 -0.2461608 -0.857128 0.4524782 -0.2726632 -0.949417 0.1557635 -0.2729173 -0.949209 0.1565836 -0.06087172 -0.1445856 0.9876182 -0.1760826 -0.4182714 0.8910915 -0.1761468 -0.4187561 0.8908511 -0.2743116 -0.6520983 0.706768 -0.2743486 -0.6523165 0.7065523 -0.3457755 -0.8221654 0.4521984 -0.3458095 -0.8217252 0.452972 -0.3831226 -0.9103543 0.1564362 -0.3830299 -0.9104446 0.1561371 -0.6761448 -0.7199986 0.1563021 -0.5850906 -0.7957723 0.1562546 -0.5863947 -0.7950954 0.1548048 -0.5866545 -0.7947167 0.1557626 -0.4878536 -0.8588846 0.1559365 -0.4880759 -0.8586926 0.1562975 -0.4877857 -0.8588795 0.156177 -0.4877857 -0.8588795 0.1561771 -0.4877856 -0.8588795 0.1561771 -0.7565087 -0.6349636 0.1565762 -0.7566707 -0.6349271 0.1559396 -0.6827347 -0.5728658 0.4535397 -0.6101053 -0.6497023 0.4534959 -0.4843522 -0.5157767 0.7066664 -0.4198952 -0.569387 0.7067436 -0.2699054 -0.3659976 0.890616 -0.2246006 -0.3954035 0.8906238 -0.07753711 -0.1364794 0.9876039 -0.06087088 -0.144665 0.9876067 -0.131304 -0.08596539 0.9876078 -0.3802556 -0.2489469 0.8907475 -0.3803715 -0.2490632 0.8906656 -0.5916231 -0.387426 0.7070242 -0.5917703 -0.3875381 0.7068395 -0.7461088 -0.4886318 0.4522837 -0.7459772 -0.4884244 0.4527248 -0.8262867 -0.5410746 0.1564885 -0.8263521 -0.5411338 0.1559374 -0.8834007 -0.4419112 0.1559416 -0.1405676 -0.06986504 0.987603 -0.4071041 -0.2023553 0.8906844 -0.40696 -0.2022124 0.8907827 -0.6336584 -0.3148574 0.7066413 -0.6334245 -0.3146499 0.7069435 -0.798145 -0.3964336 0.4536575 -0.7984306 -0.3970407 0.4526227 -0.7984306 -0.3970407 0.4526228 -0.7984306 -0.3970407 0.4526228 -0.8845635 -0.4398956 0.1550469 -0.884625 -0.4392996 0.1563798 -0.1476916 -0.05264866 0.9876312 -0.4277209 -0.1524344 0.8909651 -0.4282022 -0.152799 0.8906713 -0.6666554 -0.2378897 0.7063846 -0.6664122 -0.2376343 0.7066999 -0.8396331 -0.2994005 0.453184 -0.839461 -0.2991869 0.4536436 -0.930345 -0.3315643 0.1565999 -0.9303951 -0.3317788 0.1558462 -0.9878362 0.01272231 0.1549768 -0.9825581 -0.1028782 0.1549053 -0.9822027 -0.1040815 0.1563495 -0.9823276 -0.1045079 0.1552757 -0.9631286 -0.2197281 0.1552512 -0.9629436 -0.2190944 0.1572811 -0.962887 -0.2199131 0.1564831 -0.9792307 0.1296314 0.1558942 -0.9790959 0.1292274 0.157072 -0.8839831 0.1166627 0.4527293 -0.891595 0.01174235 0.4526816 -0.7073203 0.009302139 0.706832 -0.7033979 -0.07453268 0.7068779 -0.4519394 -0.04790818 0.8907614 -0.4430291 -0.1010053 0.8907992 -0.1530728 -0.03490787 0.9875982 -0.147886 -0.05277121 0.9875956 -0.1519451 0.03883588 0.9876257 -0.4405003 0.1125668 0.8906673 -0.4405789 0.1125796 0.8906269 -0.6848688 0.1750024 0.7073394 -0.6849288 0.1749831 0.707286 -0.863997 0.2207381 0.4525305 -0.8636406 0.2209049 0.4531291 -0.9567992 0.2446724 0.1570692 -0.9572058 0.2443016 0.1551579 -0.9210012 0.3570671 0.1557564 -0.1461747 0.05646193 0.9876462 -0.4242507 0.1638704 0.8905941 -0.4241839 0.1638447 0.8906307 -0.6594247 0.254723 0.7073014 -0.6593819 0.254714 0.7073447 -0.8318287 0.3213428 0.4525482 -0.8318247 0.3213529 0.4525485 -0.921361 0.3559046 0.1562884 -0.9211741 0.3560872 0.1569727 -0.1386456 0.07345265 0.9876144 -0.401688 0.2128545 0.8906962 -0.4019349 0.2128716 0.8905808 -0.6251145 0.3311211 0.7068175 -0.6245528 0.3310024 0.7073693 -0.7874708 0.4173655 0.4535372 -0.7880553 0.4173117 0.4525704 -0.8730911 0.4623578 0.1547171 -0.8728252 0.4625511 0.1556367 -0.657077 0.7373489 0.156737 -0.739927 0.6541271 0.1569263 -0.739691 0.6545711 0.1561856 -0.739907 0.6544604 0.1556252 -0.8118679 0.5627164 0.1556304 -0.8120524 0.5625557 0.1552482 -0.8124522 0.5621742 0.1545365 -0.5654711 0.8099969 0.155395 -0.565504 0.8098747 0.1559109 -0.5104187 0.7309576 0.4529611 -0.5931462 0.6654908 0.4531 -0.4709302 0.5283567 0.7064447 -0.5300932 0.4689624 0.7064528 -0.3403944 0.3011396 0.8907562 -0.3734786 0.2587726 0.8908146 -0.1289536 0.08936077 0.9876161 -0.138686 0.07344985 0.9876089 -0.07393914 0.1383287 0.9876225 -0.2143911 0.4011166 0.8905852 -0.2143786 0.401108 0.890592 -0.3333991 0.6237938 0.7069133 -0.3333339 0.6237336 0.706997 -0.4201252 0.7862213 0.4531567 -0.4199216 0.7860799 0.4535906 -0.4653452 0.8711745 0.1565533 -0.4654029 0.8711743 0.1563827 -0.4654029 0.8711743 0.1563827 -0.4654029 0.8711743 0.1563828 -0.3585619 0.9203979 0.1558886 -0.05703544 0.1461632 0.987615 -0.1651025 0.42311 0.8909091 -0.1655259 0.4235864 0.8906042 -0.2575131 0.6589227 0.7067587 -0.2574099 0.6587451 0.706962 -0.3244983 0.8303983 0.4529235 -0.3243851 0.8302871 0.4532083 -0.3594315 0.9199797 0.1563534 -0.3594608 0.9199604 0.1563997 -0.03939747 0.1518641 0.987616 -0.1141915 0.4401663 0.8906257 -0.1138294 0.4395207 0.8909907 -0.177361 0.6848103 0.7068083 -0.1773528 0.684714 0.7069037 -0.2235016 0.8628639 0.4533354 -0.2237011 0.8629979 0.4529818 -0.2478527 0.9561423 0.1560806 -0.2479184 0.9561565 0.1558884 0.1005057 0.9825304 0.1566298 -0.01668447 0.9875558 0.156382 -0.01632511 0.9876446 0.1558585 -0.01666665 0.9877449 0.1551849 -0.1332028 0.9788279 0.1554127 -0.1327341 0.978644 0.1569634 -0.1327341 0.9786441 0.1569634 -0.1335511 0.9786589 0.1561762 0.2162719 0.9637947 0.1559684 0.2160261 0.9637232 0.1567493 0.1950825 0.8702594 0.4523179 0.1950824 0.8702595 0.4523179 0.1950824 0.8702594 0.4523178 0.09051191 0.8872287 0.4523635 0.09051191 0.8872287 0.4523636 0.09051185 0.8872287 0.4523636 0.07183933 0.7038608 0.706696 -0.01184153 0.7073359 0.7067785 -0.007600426 0.4544048 0.8907629 -0.06115472 0.4502542 0.8908038 -0.02111726 0.1555578 0.9876011 -0.0394212 0.151901 0.9876093 0.05216044 0.1479842 0.9876133 0.1510871 0.4287253 0.8907117 0.1510469 0.4284645 0.890844 0.2353708 0.6676491 0.7062899 0.2353816 0.6673625 0.706557 0.2964911 0.8405738 0.4533529 0.2965101 0.8405848 0.45332 0.328515 0.9313282 0.1571805 0.3282088 0.9315868 0.1562856 0.3282088 0.9315868 0.1562856 0.4371002 0.88584 0.1556633 0.06924831 0.1406231 0.9876386 0.2009807 0.408043 0.8905659 0.2008814 0.4076588 0.8907644 0.3124778 0.6341575 0.7072496 0.3126333 0.635173 0.7062689 0.3936854 0.7999213 0.4529214 0.3937032 0.7997179 0.4532648 0.4362468 0.886134 0.1563823 0.4364473 0.8859075 0.1571044 0.08545589 0.1314722 0.9876297 0.2476115 0.3809984 0.8908023 0.2476649 0.3813104 0.890654 0.3854969 0.5935494 0.7064639 0.3852889 0.5926584 0.7073249 0.4857401 0.7472115 0.4535765 0.4857012 0.7476369 0.4529166 0.5380876 0.8282682 0.1563124 0.53798 0.8284662 0.155632 0.100471 0.1205503 0.9876099 0.2907277 0.348821 0.8909553 0.2907984 0.3490443 0.8908448 0.4530102 0.5437746 0.7064638 0.4529407 0.5437334 0.7065399 0.5707459 0.6851965 0.4524985 0.5706944 0.6845347 0.4535639 0.5706944 0.6845347 0.4535639 0.6324324 0.7585545 0.156922 0.6322301 0.7590525 0.1553211 0.7181568 0.6781138 0.1562455 0.1140103 0.1079163 0.9876011 0.3302624 0.3126112 0.8906184 0.3299511 0.3120171 0.890942 0.5137292 0.4858283 0.7071444 0.5139536 0.4863597 0.706616 0.6479524 0.6131657 0.4518688 0.6478701 0.6128659 0.4523935 0.6478701 0.6128658 0.4523935 0.6478701 0.6128659 0.4523935 0.7174069 0.6786326 0.1574336 0.7173097 0.6788719 0.1568432 0.1257893 0.09342777 0.987648 0.3651357 0.2712452 0.8905627 0.3651023 0.2711387 0.890609 0.5677741 0.4216727 0.7069829 0.5676727 0.4215004 0.707167 0.7157437 0.5314531 0.4530658 0.7160345 0.532044 0.4519112 0.7927654 0.5890581 0.1566327 0.7927395 0.5891638 0.1563657 -0.8720259 -0.4894598 0 -0.9533748 -0.3017891 0 -0.9533828 -0.3017638 0 -0.9994424 -0.03339236 0 -0.9994414 -0.0334202 0 -0.9713681 0.2375798 0 -0.9713616 0.2376061 0 -0.8712305 0.4908743 0 -0.8712306 0.4908743 0 -0.7065385 0.7076747 0 -0.7065523 0.7076608 0 -0.4894649 0.872023 0 -0.4894531 0.8720297 0 -0.2357717 0.9718084 0 -0.2357654 0.9718101 0 0.03487807 0.9993916 0 0.03487807 0.9993916 0 0.3033005 0.952895 0 0.3032965 0.9528962 0 0.5490167 0.8358114 0 0.7542564 0.65658 0 0.7542427 0.6565959 0 0.9033478 0.4289088 0 0.9033586 0.4288861 0 0.9855692 0.1692732 0 0.9855669 0.1692868 0 0.9946621 -0.1031858 0 0.9946636 -0.1031721 0 0.9300073 -0.367541 0 0.9300169 -0.3675169 0 0.7964289 -0.6047322 0 0.7964088 -0.6047587 0 0.6032892 -0.7975226 0 0.6032891 -0.7975226 0 0.3664475 -0.9304388 0 0.3664475 -0.9304388 0 0.1013711 -0.9948487 0 0.1013767 -0.9948482 0 -0.1707607 -0.9853125 0 -0.1707701 -0.9853109 0 -0.4299729 -0.9028418 0 -0.4299728 -0.9028418 0 -0.6579464 -0.7530649 0 -0.6579326 -0.7530769 0 -0.7971926 -0.603725 0 -0.8365342 -0.5479134 -0.001214683 0.4649832 0.8853196 0 0.6041279 0.7968875 0 0.6041222 0.7968918 0 0.7270559 0.6865783 0 0.7270556 0.6865787 0 0.8302296 0.5574216 0 0.8302299 0.5574213 0 0.910622 0.4132404 0 0.9106125 0.4132615 0 0.966201 0.2577901 0 0.9661979 0.257802 0 0.9954509 0.09527695 0 0.9954508 0.09527713 0 0.9975386 -0.07012009 0 0.9975395 -0.07010734 0 0.9724078 -0.2332878 0 0.9724019 -0.2333123 0 0.9208206 -0.3899865 0 0.920816 -0.3899977 0 0.8439632 -0.5364013 0 0.8439629 -0.5364016 0 0.7443044 -0.6678405 0 0.6239919 -0.7814308 0 0.6240045 -0.7814208 0 0.4872944 -0.8732378 0 0.4872938 -0.8732382 0 0.3365091 -0.9416803 0 0.1771579 -0.9841825 0 0.1771601 -0.9841821 0 0.01242065 -0.9999229 0 -0.15198 -0.9883837 0 -0.3126974 -0.9498528 0 -0.3126901 -0.9498553 0 -0.4648373 -0.8853961 0 -0.4648267 -0.8854017 0 -0.604283 -0.7967699 0 -0.6042835 -0.7967694 0 -0.7268952 -0.6867485 0 -0.7268947 -0.6867489 0 -0.8302311 -0.5574193 0 -0.8302371 -0.5574104 0 -0.9106133 -0.4132596 0 -0.910618 -0.4132493 0 -0.9661977 -0.2578021 0 -0.9661979 -0.257802 0 -0.9954801 -0.09497058 0 -0.9954825 -0.09494525 0 -0.9975612 0.06979793 0 -0.9975612 0.06979799 0 -0.9724064 0.2332936 0 -0.9724007 0.2333174 0 -0.9208206 0.3899865 0 -0.920816 0.3899977 0 -0.8440646 0.5362417 0 -0.8440586 0.5362512 0 -0.7441561 0.6680058 0 -0.6239982 0.7814258 0 -0.4872944 0.8732378 0 -0.4872938 0.8732382 0 -0.3365302 0.9416728 0 -0.1771349 0.9841867 0 -0.1771347 0.9841867 0 -0.01242065 0.9999229 0 0.15198 0.9883837 0 0.1519819 0.9883833 0 0.3125768 0.9498925 0 -0.5928172 -0.8053371 0 -0.7439215 -0.668267 0 -0.7439147 -0.6682747 0 -0.896771 -0.4424951 0 -0.8967599 -0.4425175 0 -0.982935 -0.1839538 0 -0.9829349 -0.1839537 0 -0.9961419 0.08775693 0 -0.9961419 0.08775693 0 -0.9354223 0.3535326 0 -0.9354223 0.3535326 0 -0.8053847 0.5927526 0 -0.8053912 0.5927436 0 -0.6157385 0.7879506 0 -0.6157453 0.7879454 0 -0.3801585 0.9249214 0 -0.3801634 0.9249194 0 -0.1167519 0.9931612 0 -0.1167551 0.9931607 0 0.1556764 0.9878082 0 0.1556764 0.9878082 0 0.4164143 0.909175 0 0.4164196 0.9091726 0 0.6462923 0.7630899 0 0.6463061 0.7630783 0 0.8280196 0.5606992 0 0.8280131 0.5607088 0 0.9487186 0.316122 0 0.9487228 0.3161095 0 0.998825 0.04846525 0 0.9988243 0.04847913 0 0.9749296 -0.2225139 0 0.9749265 -0.2225271 0 0.8787062 -0.4773632 0 0.8787003 -0.4773739 0 0.7171419 -0.6969271 0 0.717135 -0.6969344 0 0.5027174 -0.8644508 0 0.5027235 -0.8644472 0 0.2507294 -0.9680573 0 0.2507328 -0.9680564 0 -0.01981312 -0.9998037 0 -0.01981341 -0.9998038 0 -0.2885718 -0.9574583 0 -0.2885718 -0.9574583 0 -0.4777204 -0.8785119 0 -0.5365138 -0.8438907 -0.001212477 -4.72393e-6 0 -1 9.8631e-6 0 -1 3.03074e-7 0 -1 1.48681e-6 0 -1 -8.4391e-6 0 -1 4.84816e-6 0 -1 -9.39708e-7 0 -1 3.28255e-7 0 -1 7.40477e-6 0 -1 -1.65526e-6 0 -1 -1.50708e-6 0 -1 -8.44195e-6 0 -1 2.54373e-6 0 -1 -2.48203e-6 0 -1 4.93213e-6 0 -1 -2.21984e-6 0 -1 -1.83742e-6 0 -1 9.47831e-6 0 -1 -1.61825e-6 0 -1 -4.76245e-6 0 -1 -1.53243e-5 0 -1 1.5556e-5 0 -1 7.12874e-6 0 -1 -8.08454e-6 0 -1 1.55357e-5 0 -1 -7.6838e-6 0 -1 2.28102e-5 0 -1 4.58999e-6 0 -1 -7.39479e-6 0 -1 -0.3652408 -0.9309131 0 -0.5465963 -0.8373963 0 -0.5466125 -0.8373857 0 -0.7524262 -0.6586766 0 -0.7524085 -0.6586968 0 -0.9022095 -0.4312981 0 -0.9022232 -0.4312692 0 -0.9850763 -0.1721183 0 -0.9850764 -0.1721183 0 -0.9949687 0.100186 0 -0.9949687 0.100186 0 -0.9309456 0.3651579 0 -0.9309577 0.3651272 0 -0.798131 0.6024839 0 -0.798131 0.602484 0 -0.6057975 0.795619 0 -0.6058146 0.7956059 0 -0.3687054 0.9295464 0 -0.3687052 0.9295464 0 -0.1045604 0.9945186 0 -0.1045567 0.9945189 0 0.168017 0.9857841 0 0.1680111 0.9857851 0 0.4277306 0.9039064 0 0.4277166 0.9039129 0 0.6555695 0.7551349 0 0.6555519 0.7551502 0 0.8351092 0.5500843 0 0.8351254 0.5500597 0 0.9524778 0.3046082 0 0.9524983 0.304544 0 0.9993461 0.03615933 0 0.9993474 0.03612393 0 0.9720614 -0.2347265 0 0.9720615 -0.2347266 0 0.8726675 -0.488315 0 0.8726524 -0.4883419 0 0.7085751 -0.7056354 0 0.7085751 -0.7056354 0 0.4918957 -0.8706542 0 0.4918805 -0.8706628 0 0.2388074 -0.9710669 0 0.2388074 -0.971067 0 -0.03201383 -0.9994875 0 -0.03201496 -0.9994874 0 -0.2350689 -0.9719788 0 -0.3008547 -0.9536693 -0.001207172 -0.07427412 0.7064774 -0.7038275 -0.07409441 0.7066363 -0.7036869 -0.26196 0.6604127 -0.7037273 -0.2619863 0.6603339 -0.7037914 -0.4303842 0.5652289 -0.7037654 -0.430375 0.5652019 -0.7037928 -0.5669962 0.4280211 -0.703785 -0.5670259 0.4280008 -0.7037734 -0.6613551 0.2593959 -0.7037922 -0.6613015 0.2590769 -0.7039599 -0.7067145 0.07116216 -0.703911 -0.7067203 0.07118284 -0.703903 -0.6997363 -0.1222459 -0.7038643 -0.6999517 -0.1220387 -0.7036861 -0.6410015 -0.3064017 -0.7037294 -0.6408208 -0.3065481 -0.7038303 -0.5344862 -0.4679089 -0.7038365 -0.5346304 -0.4678586 -0.7037604 -0.3883255 -0.5949119 -0.7037637 -0.3884096 -0.5949073 -0.7037211 -0.2137502 -0.6775573 -0.7037237 -0.2136159 -0.6775298 -0.703791 -0.02274638 -0.7100536 -0.7037802 -0.02277404 -0.7100539 -0.7037791 0.1696499 -0.6898521 -0.7037919 0.1695911 -0.6899187 -0.7037408 0.3494665 -0.6185575 -0.7037471 0.3494538 -0.6185359 -0.7037723 0.5034253 -0.5013481 -0.7037137 0.5034299 -0.5013237 -0.7037279 0.6199907 -0.3469279 -0.7037419 0.6199628 -0.3469057 -0.7037774 0.6905812 -0.1667479 -0.7037705 0.6905986 -0.1667711 -0.7037479 0.7099705 0.02566653 -0.7037636 0.7099866 0.02566021 -0.7037476 0.6766911 0.2163668 -0.7037575 0.6765906 0.2164684 -0.7038229 0.5932347 0.3907642 -0.7038294 0.5931503 0.3907942 -0.703884 0.4656732 0.5364046 -0.7038598 0.4659371 0.5363742 -0.7037082 0.3038892 0.6422017 -0.7037246 0.3036752 0.6421824 -0.7038346 0.1193503 0.7002686 -0.703832 0.119382 0.7002819 -0.7038134 -0.4495649 -0.8932477 0 -0.6216678 -0.7832811 0 -0.621685 -0.7832674 0 -0.8098745 -0.5866032 0 -0.8098577 -0.5866264 0 -0.9382264 -0.3460221 0 -0.9967793 -0.08019524 0 -0.9967792 -0.08019524 0 -0.9814895 0.1915161 0 -0.9814828 0.1915503 0 -0.8933078 0.4494455 0 -0.8933078 0.4494454 0 -0.7389543 0.6737556 0 -0.7389542 0.6737557 0 -0.5299295 0.8480418 0 -0.5299295 0.8480417 0 -0.281193 0.9596513 0 -0.2811929 0.9596513 0 -0.01203715 0.9999276 0 -0.01203757 0.9999276 0 0.2581842 0.9660958 0 0.2581841 0.9660958 0 0.5093025 0.8605876 0 0.5093179 0.8605785 0 0.7225174 0.6913527 0 0.7224997 0.6913713 0 0.8823636 0.4705682 0 0.8823636 0.4705683 0 0.9765372 0.2153488 0 0.9765446 0.2153151 0 0.9984084 -0.05639857 0 0.9984084 -0.05639863 0 0.9462489 -0.3234394 0 0.8238193 -0.5668526 0 0.8238359 -0.5668286 0 0.6404623 -0.7679896 0 0.6404797 -0.7679752 0 0.4092181 -0.9124366 0 0.4092181 -0.9124366 0 0.1480475 -0.9889804 0 0.1480475 -0.9889804 0 -0.1242538 -0.9922505 0 -0.1242538 -0.9922505 0 -0.3236131 -0.9461895 0 -0.3874871 -0.9218744 -0.00120759 -0.008550703 0.7104125 -0.7037336 -0.008639991 0.71037 -0.7037755 -0.1997544 0.6817142 -0.703821 -0.1997555 0.6817027 -0.7038319 -0.376441 0.6024373 -0.7038193 -0.3763872 0.6025238 -0.703774 -0.5249887 0.4786618 -0.7037541 -0.524996 0.4786607 -0.7037493 -0.6346012 0.3192753 -0.7038072 -0.6345957 0.3192718 -0.7038139 -0.697209 0.1360539 -0.7038388 -0.6972529 0.136173 -0.7037723 -0.7081111 -0.05698013 -0.7037983 -0.708225 -0.05681127 -0.7036973 -0.6665679 -0.2458543 -0.703735 -0.6663455 -0.2459968 -0.7038958 -0.5752468 -0.4166954 -0.7038865 -0.5756645 -0.4165117 -0.7036536 -0.4417159 -0.5565103 -0.7036927 -0.4416246 -0.5565366 -0.7037292 -0.2753062 -0.6549778 -0.7037121 -0.275119 -0.6549437 -0.703817 -0.08827066 -0.7048929 -0.7037999 -0.08820694 -0.7048857 -0.7038152 0.1051738 -0.7025634 -0.7038062 0.1050192 -0.7026796 -0.7037132 0.2907162 -0.648225 -0.7037674 0.2908136 -0.6481077 -0.7038352 0.4549368 -0.5455129 -0.7038809 0.4548819 -0.5456987 -0.7037723 0.5852842 -0.4027075 -0.7037537 0.5852865 -0.4025779 -0.7038258 0.6721984 -0.2297727 -0.7038138 0.6721919 -0.2297987 -0.7038115 0.7092696 -0.04008305 -0.7037969 0.7092564 -0.04005283 -0.7038119 0.693716 0.152971 -0.7038167 0.6938202 0.1528488 -0.7037406 0.6268941 0.3343155 -0.7037308 0.6268271 0.3343642 -0.7037674 0.5132788 0.4911493 -0.7037879 0.5133752 0.491136 -0.7037268 0.3618521 0.6114236 -0.7037218 0.3617259 0.611422 -0.703788 0.1834236 0.6863331 -0.7037774 0.1834946 0.6863497 -0.7037428 7.2898e-6 0 -1 -2.29032e-5 0 -1 -1.15935e-6 0 -1 -2.53395e-6 0 -1 8.60742e-7 0 -1 1.56411e-5 0 -1 -1.21874e-5 0 -1 -2.56394e-6 0 -1 2.0316e-6 0 -1 -1.1589e-6 0 -1 -0.4756135 -0.8796545 0 -0.6446334 -0.764492 0 -0.6446507 -0.7644774 0 -0.8269544 -0.562269 0 -0.8269708 -0.562245 0 -0.9480246 -0.3181969 0 -0.9480353 -0.3181651 0 -0.998709 -0.05079799 0 -0.9987072 -0.05083334 0 -0.9753577 0.2206296 0 -0.9753577 0.2206296 0 -0.8797029 0.4755239 0 -0.8796879 0.4755515 0 -0.7186082 0.6954153 0 -0.7186258 0.695397 0 -0.504653 0.8633223 0 -0.5046684 0.8633133 0 -0.2528852 0.9674963 0 -0.2528852 0.9674963 0 0.01763314 0.9998446 0 0.01763308 0.9998446 0 0.2866428 0.9580376 0 0.2866427 0.9580376 0 0.5346038 0.8451028 0 0.7427489 0.6695701 0 0.8958329 0.444391 0 0.8958329 0.4443913 0 0.9824945 0.1862916 0 0.982501 0.1862574 0 0.9963171 -0.0857461 0 0.9963141 -0.08578133 0 0.9362488 -0.3513379 0 0.9362487 -0.351338 0 0.8066463 -0.5910345 0 0.8066463 -0.5910346 0 0.6174324 -0.786624 0 0.6174322 -0.7866241 0 0.3821567 -0.9240975 0 0.3821442 -0.9241029 0 0.1186825 -0.9929323 0 0.1186867 -0.9929319 0 -0.1536656 -0.988123 0 -0.3510199 -0.9363681 0 -0.4142493 -0.9101627 -0.001209855 0.01252454 0.7102864 -0.7038013 0.01230835 0.7101643 -0.7039284 -0.1796224 0.6872029 -0.7039092 -0.1795398 0.6872763 -0.7038586 -0.3584958 0.6132578 -0.7038435 -0.358395 0.6133986 -0.7037722 -0.5105285 0.4940522 -0.7037564 -0.5105138 0.4940127 -0.7037948 -0.6249639 0.3378379 -0.7037654 -0.6249413 0.3378564 -0.7037766 -0.692945 0.1567584 -0.703743 -0.692898 0.1565787 -0.7038292 -0.7094439 -0.03609842 -0.7038368 -0.7095994 -0.03585439 -0.7036926 -0.6735724 -0.2260693 -0.7036995 -0.6733876 -0.2262097 -0.7038313 -0.5874547 -0.3994106 -0.703824 -0.5875364 -0.3993715 -0.703778 -0.4579685 -0.5431246 -0.7037617 -0.457814 -0.5431335 -0.7038554 -0.2942687 -0.6465279 -0.7038519 -0.2946069 -0.6465778 -0.7036647 -0.1091787 -0.702063 -0.7036957 -0.1088795 -0.7019258 -0.7038789 0.08430868 -0.7053301 -0.7038477 0.08426904 -0.7053613 -0.7038213 0.2714837 -0.6564961 -0.7037823 0.2715217 -0.6564193 -0.7038393 0.4386128 -0.5587891 -0.7038279 0.4385432 -0.5589742 -0.7037243 0.5730849 -0.4199038 -0.7037432 0.5730897 -0.4197491 -0.7038317 0.6651124 -0.2496024 -0.7037927 0.6650773 -0.249529 -0.7038519 0.707724 -0.06091791 -0.7038577 0.7077592 -0.06100201 -0.7038151 0.6979431 0.1323297 -0.7038213 0.6980629 0.1321818 -0.7037302 0.6364822 0.3157292 -0.7037085 0.6364516 0.3157554 -0.7037243 0.5276958 0.4757182 -0.7037254 0.5275949 0.475741 -0.7037855 0.3797985 0.6003792 -0.7037742 0.3797396 0.6003648 -0.7038183 0.2036324 0.6805989 -0.7037891 0.2036549 0.680592 -0.7037892 -1.37689e-6 0 -1 7.29054e-6 0 -1 -1.40846e-6 0 -1 -3.37947e-6 0 -1 1.72101e-6 0 -1 -3.64474e-6 0 -1 3.44305e-6 0 -1 -4.02033e-6 0 -1 -7.83e-6 0 -1 -5.12905e-6 0 -1 7.82473e-6 0 -1 -3.64631e-6 0 -1 3.52006e-6 0 -1 -0.5801586 -0.8145037 0 -0.7337573 -0.6794117 0 -0.7337396 -0.6794309 0 -0.8898656 -0.4562228 0 -0.8898512 -0.456251 0 -0.979967 -0.1991603 0 -0.9799669 -0.1991604 0 -0.9973862 0.07225567 0 -0.9973837 0.07229095 0 -0.9408057 0.3389467 0 -0.9407942 0.3389782 0 -0.8145328 0.5801175 0 -0.6277315 0.7784299 0 -0.6277486 0.7784162 0 -0.3945164 0.9188889 0 -0.3945164 0.9188889 0 -0.1319158 0.991261 0 -0.1319204 0.9912604 0 0.140397 0.9900954 0 0.1404019 0.9900946 0 0.4022388 0.9155348 0 0.4022387 0.9155349 0 0.6343968 0.7730077 0 0.8194012 0.5732204 0 0.8194013 0.5732205 0 0.9437303 0.3307163 0 0.9437302 0.3307164 0 0.9979459 0.06406372 0 0.9979481 0.06402844 0 0.9781991 -0.2076695 0 0.8859295 -0.4638199 0 0.8859295 -0.46382 0 0.727943 -0.6856378 0 0.7279251 -0.6856567 0 0.5158804 -0.8566607 0 0.515896 -0.8566513 0 0.2658901 -0.9640033 0 0.2658992 -0.9640009 0 -0.004398047 -0.9999904 0 -0.2738007 -0.9617865 0 -0.2738007 -0.9617866 0 -0.4637712 -0.8859551 0 -0.5231846 -0.8522186 -0.001206994 0.09974151 0.7033711 -0.7037903 0.09972929 0.7033656 -0.7037975 -0.09371656 0.7041894 -0.7038 -0.09372019 0.7041918 -0.7037973 -0.2802801 0.6528064 -0.7037664 -0.280377 0.6526479 -0.7038747 -0.445911 0.5529478 -0.7038552 -0.4458445 0.5531853 -0.7037107 -0.5786781 0.4121466 -0.7037519 -0.5787032 0.4119626 -0.7038391 -0.6683145 0.2408062 -0.7038239 -0.6683255 0.2408485 -0.7037991 -0.7085254 0.05133467 -0.7038157 -0.7086547 0.05158221 -0.7036674 -0.6962839 -0.1415114 -0.7036784 -0.6961627 -0.1416691 -0.7037665 -0.6321643 -0.3241146 -0.7037883 -0.6319832 -0.3242326 -0.7038967 -0.521203 -0.4826099 -0.7038716 -0.5213385 -0.4825659 -0.7038014 -0.3716629 -0.6053912 -0.7038241 -0.3716573 -0.6054054 -0.7038148 -0.1945049 -0.6832307 -0.7038208 -0.1944934 -0.683234 -0.7038208 -0.003121137 -0.7103741 -0.7038174 -0.003138542 -0.7103825 -0.7038089 0.1888841 -0.6847957 -0.7038307 0.1887756 -0.6849359 -0.7037234 0.3665027 -0.6086107 -0.7037534 0.3664998 -0.6086516 -0.7037194 0.5171816 -0.4871371 -0.7037191 0.5171914 -0.4870788 -0.7037523 0.6294379 -0.3295304 -0.7037171 0.6294269 -0.3294005 -0.7037877 0.6949253 -0.1475256 -0.7037863 0.6949303 -0.1476395 -0.7037574 0.7090013 0.04551297 -0.7037371 0.7089674 0.04555559 -0.7037684 0.6704501 0.2349388 -0.7037759 0.6703391 0.2350894 -0.7038314 0.5820688 0.407167 -0.7038545 0.5822452 0.4071025 -0.7037457 0.450708 0.5491893 -0.7037425 0.4505339 0.5492177 -0.7038319 0.2857291 0.6503524 -0.7038471 0.2857818 0.6503478 -0.7038299 -0.1424062 0.9898083 0 0.1424082 0.989808 0 0.1424043 0.9898086 0 0.4152607 0.9097025 0 0.4152658 0.9097002 0 0.6549456 0.7556761 0 0.6549524 0.7556703 0 0.8411895 0.5407406 0 0.8411956 0.540731 0 0.9594749 0.2817941 0 0.9594749 0.2817941 0 0.9594749 -0.2817941 0 0.9594749 -0.2817941 0 0.8411956 -0.540731 0 0.8411894 -0.5407406 0 0.6549524 -0.7556703 0 0.6549456 -0.7556761 0 0.4152659 -0.9097002 0 0.4152607 -0.9097025 0 0.1424129 -0.9898074 0 0.1424167 -0.9898068 0 -0.1424148 -0.9898071 0 -0.1424129 -0.9898074 0 -0.4153482 -0.9096625 0 -0.4153586 -0.9096578 0 -0.6548376 -0.7557696 0 -0.6548376 -0.7557697 0 -0.8412948 -0.5405766 0 -0.8412948 -0.5405766 0 -0.9594712 -0.2818067 0 -0.9594786 -0.2817816 0 -0.9594786 0.2817816 0 -0.9594712 0.2818067 0 -0.8412948 0.5405766 0 -0.8412948 0.5405766 0 -0.6548376 0.7557696 0 -0.6548376 0.7557697 0 -0.4153586 0.9096578 0 -0.4153482 0.9096625 0 -0.1424044 0.9898086 0 0.4999881 0.8660323 0 0.4999904 0.866031 0 -0.4999888 0.8660318 0 -0.4999881 0.8660323 0 0.4999904 -0.8660311 0 0.4999881 -0.8660323 0 -0.4999881 -0.8660323 0 -0.4999889 -0.8660318 0 5.95428e-7 0 -1 -7.96747e-7 0 -1 -4.38297e-6 0 -1 8.10709e-7 0 -1 2.73935e-7 0 -1 7.96787e-7 0 -1 -5.95377e-7 0 -1 6.99325e-7 0 -1 -1.91785e-6 0 -1 2.46542e-6 0 -1 2.81126e-6 0 -1 -2.81145e-6 0 -1 0.3037664 -0.9527465 0 0.02319347 -0.999731 0 0.02319407 -0.999731 0 -0.2595297 -0.9657351 0 -0.2595297 -0.9657351 0 -0.5208566 -0.8536443 0 -0.5208565 -0.8536443 0 -0.7404829 -0.6720752 0 -0.7404897 -0.6720678 0 -0.899783 -0.4363379 0 -0.8997936 -0.4363158 0 -0.9862374 -0.1653355 0 -0.9862374 -0.1653355 0 -0.9928432 0.1194264 0 -0.9928399 0.1194533 0 -0.9189979 0.3942625 0 -0.9190078 0.3942396 0 -0.770788 0.6370919 0 -0.7708147 0.6370595 0 -0.5599341 0.8285371 0 -0.5599341 0.8285372 0 -0.3038257 0.9527277 0 -0.3038336 0.9527252 0 -0.02318841 0.9997311 0 -0.02318871 0.9997312 0 0.2595297 0.9657351 0 0.2595297 0.9657351 0 0.5209596 0.8535813 0 0.5209535 0.8535851 0 0.7403636 0.6722066 0 0.7403636 0.6722067 0 0.8998007 0.4363014 0 0.8997899 0.4363234 0 0.9862729 0.1651234 0 0.9928674 -0.1192249 0 0.9928689 -0.1192114 0 0.918909 -0.3944698 0 0.9189188 -0.3944468 0 0.770808 -0.6370676 0 0.770808 -0.6370676 0 0.5600354 -0.8284687 0 0.5600417 -0.8284646 0 0.3037625 -0.9527478 0 -0.3500761 -0.9367213 0 -0.3500767 -0.936721 0 0.6361809 -0.77154 0 0.6361801 -0.7715406 0 -0.6361941 0.7715291 0 -0.636195 0.7715284 0 0.3500767 0.936721 0 0.9862582 0.1652114 0 0.9862588 0.1652081 0 4.38364e-6 0 -1 -4.38258e-6 0 -1 -5.95337e-7 0 -1 -2.15703e-6 0 -1 1.13201e-6 0 -1 1.40556e-6 0 -1 -1.13199e-6 0 -1 2.15692e-6 0 -1 -1.13218e-6 0 -1 -1.40591e-6 0 -1 1.132e-6 0 -1 -3.19639e-6 0 -1 -7.01849e-7 0 -1 5.95337e-7 0 -1 3.19641e-6 0 -1 7.02009e-7 0 -1 -0.9862631 -0.1651819 0 -0.9862634 -0.1651803 0 0.6463598 0.7630328 0 0.7629399 0.6464695 0 0.7629398 0.6464696 0 0.8590669 0.5118635 0 0.8590669 0.5118634 0 0.9315831 0.3635288 0 0.9315831 0.3635288 0 0.9787189 0.2052059 0 0.9787189 0.2052059 0 0.999152 0.04117679 0 0.999152 0.04117679 0 0.9923144 -0.1237424 0 0.9584901 -0.2851259 0 0.9584771 -0.2851695 0 0.8984068 -0.4391642 0 0.8983975 -0.4391833 0 0.8138394 -0.5810899 0 0.8138282 -0.5811057 0 0.7071225 -0.7070911 0 0.5810836 -0.8138439 0 0.5810948 -0.813836 0 0.4391831 -0.8983977 0 0.4391829 -0.8983977 0 0.2853479 -0.958424 0 0.2853479 -0.958424 0 0.1237361 -0.9923152 0 -0.04139542 -0.9991429 0 -0.04139542 -0.9991429 0 -0.2052092 -0.9787181 0 -0.2052092 -0.9787182 0 -0.3635185 -0.9315871 0 -0.3635105 -0.9315902 0 -0.5118897 -0.8590513 0 -0.5118688 -0.8590638 0 -0.646348 -0.7630428 0 -0.6463598 -0.7630328 0 -0.7630452 -0.6463452 0 -0.7630568 -0.6463314 0 -0.8590564 -0.5118809 0 -0.8590669 -0.5118634 0 -0.931591 -0.3635082 0 -0.9315831 -0.3635288 0 -0.9787189 -0.2052059 0 -0.9787165 -0.2052173 0 -0.9991436 -0.0413782 0 -0.9991431 -0.04139006 0 -0.9923158 0.1237307 0 -0.9923144 0.1237424 0 -0.9584285 0.285333 0 -0.9584252 0.2853439 0 -0.8983882 0.4392026 0 -0.8984068 0.4391642 0 -0.8138282 0.5811055 0 -0.8138394 0.5810899 0 -0.7071106 0.707103 0 -0.7071107 0.707103 0 -0.5810949 0.8138359 0 -0.5810835 0.813844 0 -0.4392766 0.8983518 0 -0.4392673 0.8983566 0 -0.2853415 0.9584259 0 -0.2853479 0.958424 0 -0.1237361 0.9923152 0 0.04138725 0.9991433 0 0.04138821 0.9991432 0 0.2051742 0.9787256 0 0.3635185 0.9315871 0 0.3635105 0.9315902 0 0.5119732 0.8590015 0 0.5119627 0.8590078 0 0.6463598 0.7630329 0 -0.99133 -0.1313957 0 -0.9881971 0.1531883 0 -0.9881971 0.1531883 0 -0.90503 0.425348 0 -0.9050298 0.425348 0 -0.7484562 0.6631843 0 -0.5314123 0.8471134 0 -0.5314061 0.8471173 0 -0.2711874 0.9625266 0 -0.2711874 0.9625266 0 0.01100307 0.9999395 0 0.01100337 0.9999396 0 0.2923114 0.9563232 0 0.2923075 0.9563244 0 0.5497689 0.8353168 0 0.7629166 0.646497 0 0.7629166 0.646497 0 0.9141314 0.4054184 0 0.9141312 0.4054184 0 0.9913282 0.1314091 0 0.9913353 0.1313555 0 0.9881971 -0.1531883 0 0.9881971 -0.1531883 0 0.9050456 -0.4253145 0 0.9050247 -0.4253592 0 0.7484427 -0.6631996 0 0.748463 -0.6631767 0 0.5314062 -0.8471173 0 0.5314122 -0.8471134 0 0.271256 -0.9625073 0 0.271256 -0.9625073 0 -0.01101183 -0.9999394 0 -0.01101213 -0.9999394 0 -0.2923114 -0.9563232 0 -0.2923113 -0.9563232 0 -0.5496687 -0.8353828 0 -0.5496562 -0.835391 0 -0.7629166 -0.646497 0 -0.7629166 -0.646497 0 -0.9141263 -0.4054298 0 -0.9141312 -0.4054184 0 -0.9913318 -0.1313822 0 -0.8604809 0.5094827 0 -0.8604824 0.5094802 0 -0.8714615 -0.4904641 0 -0.8714615 -0.4904641 0 0.8714612 0.4904646 0 0.8714604 0.4904658 0 0.8604813 -0.5094823 0 0.8604812 -0.5094822 0 -0.01097005 -0.9999399 0 -0.01097011 -0.9999399 0 -1.57076e-6 0 -1 1.41492e-6 0 -1 -5.95489e-7 0 -1 5.39223e-7 0 -1 -1.98104e-6 0 -1 -6.37253e-6 0 -1 -7.53203e-7 0 -1 1.98104e-6 0 -1 4.27307e-6 0 -1 -3.67945e-6 0 -1 6.37251e-6 0 -1 -6.80945e-7 0 -1 8.55928e-7 0 -1 5.95495e-7 0 -1 -1.27835e-6 0 -1 1.09576e-6 0 -1 -5.95486e-7 0 -1 3.49676e-7 0 -1 1.27837e-6 0 -1 -1.09576e-6 0 -1 0.01097005 0.9999399 0 0.01097011 0.9999399 0 -0.999656 -0.02623081 0 -0.9665599 0.2564411 0 -0.9665565 0.2564538 0 -0.8550677 0.5185166 0 -0.8550616 0.5185266 0 -0.6744167 0.738351 0 -0.6744031 0.7383634 0 -0.4391341 0.8984217 0 -0.4391341 0.8984217 0 -0.1682013 0.9857527 0 -0.1681991 0.9857531 0 0.1163905 0.9932036 0 0.1163904 0.9932036 0 0.3913756 0.9202312 0 0.3913804 0.920229 0 0.6350046 0.7725085 0 0.6350179 0.7724974 0 0.8267506 0.5625688 0 0.8267505 0.5625688 0 0.9517518 0.3068687 0 0.9517519 0.3068688 0 0.9996623 0.02598559 0 0.9996617 0.02601283 0 0.9665565 -0.2564538 0 0.9665565 -0.2564538 0 0.8551764 -0.5183371 0 0.8551643 -0.5183571 0 0.6742877 -0.7384688 0 0.6743013 -0.7384564 0 0.4392309 -0.8983743 0 0.4392255 -0.898377 0 0.1681562 -0.9857604 0 0.1681629 -0.9857593 0 -0.1164172 -0.9932005 0 -0.1164188 -0.9932003 0 -0.3913804 -0.920229 0 -0.3913706 -0.9202333 0 -0.6348976 -0.7725963 0 -0.6348976 -0.7725964 0 -0.8268584 -0.5624104 0 -0.8268584 -0.5624103 0 -0.951748 -0.3068811 0 -0.9517558 -0.3068564 0 -0.9996563 -0.02621722 0 -0.8019731 0.5973603 0 -0.8019747 0.5973581 0 -0.9183206 -0.3958377 0 -0.9183194 -0.3958405 0 0.9183098 0.3958628 0 0.9183109 0.39586 0 0.8019598 -0.5973781 0 0.8019599 -0.5973781 0 -0.1163347 -0.9932101 0 -0.1163352 -0.99321 0 6.80956e-7 0 -1 1.59312e-6 0 -1 -1.78599e-6 0 -1 5.66033e-7 0 -1 1.75717e-6 0 -1 -2.2646e-6 0 -1 -6.99332e-7 0 -1 4.76401e-6 0 -1 -1.59313e-6 0 -1 1.78647e-6 0 -1 -5.66033e-7 0 -1 -1.75768e-6 0 -1 2.26405e-6 0 -1 -3.57199e-6 0 -1 6.3918e-7 0 -1 0.1163346 0.9932101 0 0.116335 0.9932101 0 2.38313e-6 0 -1 -0.961443 0.2750044 0 -0.9614429 0.2750047 0 -0.9030311 0.4295755 0 -0.9030342 0.4295688 0 -0.8200631 0.5722731 0 -0.8200612 0.5722761 0 -0.7144697 0.6996664 0 -0.5898289 0.8075283 0 -0.5898268 0.8075298 0 -0.4486102 0.8937275 0 -0.4486125 0.8937265 0 -0.2957389 0.9552689 0 -0.1343067 0.9909398 0 -0.1343076 0.9909398 0 0.0306946 0.9995288 0 0.03069442 0.9995289 0 0.1948188 0.9808394 0 0.1948204 0.980839 0 0.3535873 0.9354015 0 0.6648106 -0.5038097 0.5515458 -0.1039106 0.8276445 0.5515498 -0.5964314 0.1507601 0.7883788 -0.596417 0.1507556 0.7883905 -0.5964229 0.1507596 0.7883854 -0.596428 0.1507523 0.7883828 -0.5964201 0.1507545 0.7883884 -0.5963965 0.1507576 0.7884056 -0.5964147 0.1507582 0.7883918 -0.5964165 0.150757 0.7883906 -0.5963655 0.1507084 0.7884384 -0.5964131 0.1507522 0.7883941 0.6866797 0.3669064 0.6275752 0.6866732 0.3668695 0.627604 0.6866723 0.3668655 0.6276072 0.6866798 0.3668918 0.6275837 0.6866716 0.3668773 0.6276011 0.6866672 0.366871 0.6276097 0.6866716 0.3668746 0.6276028 0.6866861 0.3668829 0.627582 0.6866737 0.3668787 0.6275981 0.6866656 0.3668789 0.6276068 0.6867271 0.3668631 0.6275486 0.6866668 -0.3668673 0.6276122 0.6866654 -0.3668576 0.6276194 0.6866862 -0.3669114 0.6275653 0.6866672 -0.3670201 0.6275225 0.6866735 -0.3668696 0.6276037 0.68667 -0.3668769 0.6276032 0.6866731 -0.3668766 0.6276 0.686685 -0.3668956 0.6275758 0.6866765 -0.3668774 0.6275958 0.6866781 -0.3668776 0.6275939 0.686673 -0.3668771 0.6275998 -0.5964159 -0.1507581 0.7883908 -0.5964158 -0.1507568 0.7883912 -0.5964117 -0.1507532 0.788395 -0.596414 -0.1507545 0.788393 -0.5964279 -0.1507617 0.7883811 -0.5963982 -0.1507522 0.7884054 -0.5964192 -0.1507552 0.788389 -0.5964147 -0.1507551 0.7883923 -0.5964254 -0.1507525 0.7883847 -0.5964233 -0.1507548 0.7883859 0.007658541 0.9844766 0.1753491 0.007644414 0.9844774 0.175345 0.007657945 0.9844761 0.1753516 0.007643461 0.9844779 0.1753423 0.007653594 0.9844764 0.1753503 0.007671773 0.9844762 0.175351 0.007661938 0.9844762 0.1753512 0.007660984 0.9844757 0.175354 0.007680416 0.9844743 0.1753615 0.007645547 0.9844775 0.1753448 0.007659077 0.9844762 0.1753515 0.007643938 0.9844776 0.1753444 0.007653594 0.9844765 0.1753497 0.007668018 0.9844751 0.1753568 0.007651984 0.9844771 0.1753465 0.007654726 0.9844762 0.175351 0.007668375 0.9844741 0.1753621 0.007705509 0.9844707 0.1753799 0.007663309 0.9844753 0.1753565 0.007640123 0.9844782 0.1753411 0.007642805 0.9844792 0.1753351 0.00765717 0.9844771 0.1753457 0.007649898 0.9844769 0.1753477 0.007724642 0.9844752 0.1753539 0.007659792 0.984476 0.1753526 0.007644295 0.9844776 0.1753439 0.007600843 0.9844863 0.1752973 0.007659971 0.9844763 0.1753507 0.007657468 0.984476 0.1753527 0.00766015 0.9844759 0.175353 0.007658064 0.9844762 0.1753514 0.007655382 0.984476 0.1753528 0.007657289 0.984476 0.1753522 0.007653176 0.984476 0.175352 0.007654368 0.9844763 0.1753509 0.007657527 0.9844764 0.1753501 0.007656157 0.9844766 0.1753493 0.007578909 0.9844792 0.1753379 0.00766617 0.9844753 0.1753559 0.007649242 0.984479 0.1753359 0.007651448 0.9844755 0.1753557 0.007657825 0.9844763 0.1753508 0.007656395 0.9844759 0.1753531 0.007721722 0.9844626 0.1754248 0.007663965 0.9844756 0.1753548 0.007599413 0.9844845 0.175307 0.007654845 0.9844769 0.1753476 0.007658243 0.9844764 0.1753504 0.007695972 0.9844704 0.175382 0.007524728 0.9844704 0.1753892 0.007524669 0.9844705 0.1753892 0.007524728 0.9844705 0.1753892 0.007673144 0.9844757 0.1753532 0.007654249 0.9844771 0.1753464 0.00764954 0.9844771 0.1753464 0.007670342 0.9844767 0.1753478 0.007619082 0.9844626 0.175429 0.007668256 0.9844771 0.1753461 0.007661402 0.9844694 0.1753896 0.007792115 0.9844838 0.1753027 0.007659673 0.9844763 0.1753504 0.007657945 0.9844767 0.1753487 0.007651567 0.9844764 0.1753501 0.007199048 0.9844753 0.1753759 0.00765413 0.984477 0.1753471 0.007660806 0.9844759 0.1753524 0.007930755 0.984461 0.1754246 0.007657051 0.9844766 0.1753488 0.007652759 0.9844755 0.1753554 0.007620632 0.9844771 0.1753481 0.00765109 0.9844762 0.1753521 0.007652044 0.9844763 0.1753513 0.007658779 0.9844759 0.1753532 0.007646262 0.9844768 0.1753486 0.007653951 0.9844772 0.1753455 0.007657349 0.9844765 0.1753494 0.007656276 0.9844765 0.1753497 0.007656574 0.9844766 0.1753494 0.007656574 0.9844765 0.1753496 0.00770992 0.9844692 0.1753882 0.007639408 0.984479 0.1753367 0.007657527 0.984476 0.1753522 0.00765562 0.9844767 0.1753488 0.007655858 0.9844761 0.1753517 0.007698833 0.9844712 0.1753776 0.007654905 0.9844763 0.1753504 0.007656097 0.9844762 0.1753512 0.007656335 0.9844764 0.1753503 0.007652163 0.9844772 0.1753456 0.007657766 0.9844763 0.1753508 0.007648944 0.9844762 0.1753517 0.007655739 0.984476 0.1753526 0.007661342 0.9844756 0.1753545 0.007657587 0.9844762 0.1753516 0.007646083 0.9844764 0.1753504 0.007647752 0.9844776 0.175344 0.007631301 0.9844782 0.175341 0.007655858 0.9844766 0.1753493 0.04411417 9.17365e-4 0.9990261 0.04494309 0.001322209 0.9989888 0.1918786 -0.002441048 0.9814156 0.1909716 0.00426197 0.9815864 0.1990993 0.004625141 0.9799684 0.4160856 -8.28472e-4 0.9093252 0.1994499 -9.0322e-4 0.9799077 0.1949149 -0.00102818 0.9808197 0.1949149 -0.00102818 0.9808197 0.1949148 -0.00102818 0.9808197 0.1919292 -0.001078009 0.9814082 0.1993139 0.004327476 0.9799261 0.199894 0.004341542 0.979808 0.4201375 0.001978158 0.9074583 0.4180832 0.001931071 0.9084067 0.4160114 0.001922011 0.9093574 0.4198404 0.002905964 0.9075934 0.566006 -6.48108e-4 0.8244009 0.04362887 -2.16305e-5 0.9990479 0.04362994 -1.17213e-5 0.9990478 0.04418468 -2.98123e-4 0.9990234 0.04484015 9.25809e-4 0.9989938 0.04526644 9.37235e-4 0.9989746 0.04364055 4.93821e-6 0.9990473 0.03209966 0.005928039 0.9994671 0.04363787 -0.007657349 0.9990181 0.04363006 1.71451e-5 0.9990478 0.04357278 1.52342e-4 0.9990503 0.04362064 -3.35127e-6 0.9990482 0.04361987 -1.82655e-5 0.9990482 0.04351449 -2.45837e-5 0.9990528 -0.9815886 -4.16677e-4 0.1910073 -0.9418866 -0.01180231 0.3357238 -0.8378348 0.00242269 0.5459185 -0.8221606 -0.005530297 0.5692288 -0.9816219 -4.46925e-4 0.1908359 -0.9816547 -4.53102e-4 0.1906675 -0.981948 -5.12897e-4 0.1891508 -0.9507746 0.004095137 0.3098563 -0.9419518 -0.005905508 0.3356963 -0.9514766 -0.009879231 0.3075629 -0.9514185 -0.00986433 0.307743 -0.2089542 -0.0146889 0.9778152 -0.1758988 0.01267647 0.9843267 -0.4223144 0.00558561 0.9064323 -0.4501882 -0.01687902 0.8927743 -0.175503 0.02501976 0.984161 -0.4517294 -0.03751194 0.891366 -0.2077154 0.008652508 0.978151 -0.838735 -0.009792149 0.5444517 -0.8388223 -0.009788691 0.5443173 -0.8219645 -0.01539093 0.5693309 -0.6667554 0.004030466 0.7452659 -0.6454352 -0.00132507 0.7638139 -0.667717 -0.005561113 0.7443944 -0.6452975 -0.001650393 0.7639296 -0.6688651 -0.01856416 0.743152 -0.4221633 0.01084238 0.906455 -0.4489631 0.001508176 0.893549 -0.4480176 0.001643061 0.8940232 -0.4480177 0.001643121 0.8940232 -0.4480177 0.001643121 0.8940232 -0.9816254 2.2561e-5 0.1908187 -0.9816272 0 0.190809 -0.9816297 0 0.1907963 -0.9815831 -2.91275e-4 0.1910358 -0.9815866 -2.8855e-4 0.1910178 -0.9816535 -3.04646e-4 0.1906731 -0.9816305 0 0.190792 -0.9816291 2.99737e-6 0.1907997 -0.9816277 0 0.1908072 -0.981626 1.85345e-5 0.1908152 -0.9816176 1.89996e-5 0.1908583 0.5735713 0 0.8191556 0.5735785 1.68333e-5 0.8191507 0.5668005 1.47557e-4 0.8238551 0.5661025 -2.34312e-4 0.8243349 0.5661336 -2.38332e-4 0.8243135 0.5668841 -2.10906e-4 0.8237977 -0.2083962 -0.01455795 0.9779362 -0.2094351 -0.01468634 0.9777123 -0.2094351 -0.01468634 0.9777123 -0.2094351 -0.01468634 0.9777123 -0.1756112 -0.01211118 0.9843851 0.01278418 0.01012176 0.9998671 0.03206515 0.002003729 0.9994838 0.01263552 -0.002693176 0.9999166 0.01269936 -0.002697348 0.9999157 0.007651925 -0.9844784 0.1753392 0.007547557 -0.9844865 0.1752976 0.007698774 -0.984474 0.1753619 0.007634341 -0.9844771 0.1753473 0.007655262 -0.9844766 0.1753491 0.007661938 -0.9844762 0.1753512 0.007669448 -0.9844762 0.1753509 0.007653594 -0.9844764 0.1753503 0.007653474 -0.9844765 0.1753495 0.007656872 -0.9844762 0.175351 0.007647037 -0.9844774 0.1753452 0.007697701 -0.9844716 0.1753752 0.007651388 -0.9844769 0.1753478 0.007650852 -0.9844776 0.1753436 0.007647633 -0.984475 0.1753579 0.007658064 -0.9844747 0.1753593 0.007659137 -0.9844766 0.1753494 0.007664501 -0.9844749 0.1753583 0.007654905 -0.9844784 0.1753393 0.007652997 -0.9844769 0.1753476 0.007658302 -0.9844765 0.1753497 0.007615625 -0.9844806 0.175328 0.007665395 -0.9844759 0.1753524 0.008066058 -0.984395 0.1757878 0.00762856 -0.9844776 0.1753451 0.00764656 -0.9844781 0.1753411 0.007646322 -0.984477 0.1753471 0.0076586 -0.984476 0.1753521 0.007425308 -0.9845274 0.1750737 0.007657885 -0.9844757 0.1753541 0.00761193 -0.9844852 0.1753032 0.007652938 -0.9844767 0.1753486 0.007654964 -0.984476 0.1753522 0.007655322 -0.9844759 0.1753537 0.007680475 -0.984475 0.1753568 0.007656395 -0.9844764 0.1753505 0.007638216 -0.9844785 0.175339 0.007670938 -0.9844738 0.1753642 0.007659912 -0.9844763 0.1753507 0.008274257 -0.9844493 0.1754741 0.007650554 -0.9844761 0.1753519 0.007656693 -0.9844765 0.1753493 0.007654011 -0.9844769 0.175347 0.007646262 -0.9844768 0.1753486 0.007658779 -0.9844759 0.1753532 0.007652044 -0.9844763 0.1753513 0.007651865 -0.9844757 0.1753545 0.007114052 -0.9844954 0.1752664 0.007650792 -0.9844768 0.1753484 0.007683098 -0.9844763 0.1753498 0.007662773 -0.9844758 0.1753534 0.007234096 -0.984489 0.1752976 0.007659018 -0.984477 0.1753467 0.007676899 -0.9844755 0.1753541 0.007634878 -0.9844766 0.17535 0.007654488 -0.984476 0.1753523 0.00719875 -0.9844965 0.1752571 0.007665932 -0.984476 0.1753519 0.007663488 -0.9844757 0.1753537 0.007651865 -0.984476 0.1753526 0.007656395 -0.9844765 0.1753499 0.007657647 -0.9844766 0.1753491 0.007652342 -0.9844764 0.1753503 0.007655858 -0.9844762 0.1753516 0.007653176 -0.984476 0.175352 0.007657289 -0.984476 0.1753522 0.007655382 -0.984476 0.1753528 0.007652938 -0.9844772 0.1753461 0.007660031 -0.9844757 0.1753543 0.007657229 -0.9844759 0.1753529 0.007645606 -0.9844777 0.1753433 0.007663726 -0.9844753 0.1753556 0.007660925 -0.984476 0.1753526 0.007639884 -0.9844785 0.1753389 0.007656037 -0.9844765 0.1753495 0.007678687 -0.9844732 0.1753671 0.007662832 -0.9844766 0.1753492 0.007638633 -0.9844781 0.1753414 0.007646501 -0.9844781 0.1753408 0.00770992 -0.9844692 0.1753882 0.007656455 -0.9844765 0.1753496 0.007656574 -0.9844766 0.1753494 0.007656812 -0.9844764 0.1753498 0.007667005 -0.9844782 0.1753392 0.007656335 -0.9844762 0.1753515 0.007656157 -0.9844766 0.1753492 0.007656753 -0.9844763 0.1753509 0.007655024 -0.984476 0.1753526 0.007655441 -0.9844761 0.1753518 0.007654666 -0.9844764 0.1753504 0.007654607 -0.9844764 0.17535 0.007656693 -0.9844762 0.1753513 0.007653117 -0.9844703 0.1753851 0.007655322 -0.9844765 0.1753503 0.00766766 -0.9844731 0.1753683 0.007655024 -0.9844765 0.1753497 0.007656037 -0.9844761 0.1753519 0.007656395 -0.984476 0.1753525 0.007639586 -0.9844782 0.1753413 -0.5909168 0.02546817 0.8063305 -0.358135 -0.005966186 0.9336507 0.04412186 8.28378e-5 0.9990262 0.1919184 5.16767e-4 0.9814108 0.1841169 6.36296e-4 0.9829042 0.191896 4.16853e-4 0.9814153 0.1868216 -5.77774e-4 0.9823937 0.04516679 -4.42272e-4 0.9989795 0.4160345 -0.002098798 0.9093465 0.408057 -0.002069115 0.912954 0.4160716 -0.002274513 0.909329 0.4080706 -0.007595241 0.9129189 0.1907631 0.003949046 0.9816282 0.1893537 0.003977119 0.9819009 0.189354 0.003977179 0.9819009 0.1893541 0.003977179 0.9819008 0.1871221 0.004029095 0.9823284 0.04508841 6.682e-5 0.9989831 0.04506778 6.32197e-5 0.998984 0.04418468 8.67545e-4 0.999023 0.04362738 4.33963e-5 0.9990479 0.0436269 4.25151e-5 0.999048 0.04359352 -7.11158e-5 0.9990494 0.04366332 2.03077e-5 0.9990464 0.04351449 2.45837e-5 0.9990528 0.04353874 2.74977e-5 0.9990518 0.0436213 -2.71148e-5 0.9990481 -0.9815776 -0.004628956 0.191008 -0.9743068 0.007245242 0.2251086 -0.9816308 3.01133e-4 0.1907902 -0.7700964 0.01417982 0.6377701 -0.821879 0.02661538 0.56904 -0.7725159 0.04930949 0.6330782 -0.7725159 0.04930943 0.6330781 -0.7725158 0.04930943 0.6330782 -0.9410104 -0.04468923 0.3354137 -0.8990369 5.42522e-5 0.437873 -0.8992303 9.84846e-5 0.4374758 -0.9418585 0.01510304 0.3356704 -0.9015158 0.0521419 0.4295933 -0.9817525 -0.02097427 0.1890029 -0.9736021 -0.009240329 0.2280648 -0.9735739 -0.00925076 0.2281847 -0.1754156 -0.04609721 0.9834147 -0.4223065 -0.009111821 0.9064073 -0.3601565 0.02269792 0.9326158 -0.5907133 0.02546399 0.8064798 -0.7700241 0.01417785 0.6378573 -0.8217772 -0.02591699 0.5692194 -0.5910971 0.03698849 0.805752 -0.5910974 0.03699493 0.8057513 -0.5910972 0.03698855 0.8057519 -0.6452511 0.02324312 0.763617 -0.5898464 0.01383203 0.807397 -0.6451695 -0.01985675 0.7637815 -0.4222136 -0.008382558 0.9064576 -0.9815866 2.8855e-4 0.1910178 -0.981658 3.28403e-4 0.1906505 -0.9815829 2.50488e-4 0.1910367 -0.9816254 1.75653e-5 0.1908187 -0.9816274 -1.79221e-5 0.1908082 -0.9816176 -2.02663e-5 0.1908583 -0.9816278 -1.77861e-5 0.1908061 -0.9816229 -3.05222e-5 0.1908313 -0.9816277 -9.29482e-6 0.1908072 -0.9816232 3.94868e-5 0.1908296 -0.9816301 -2.09132e-5 0.1907939 -0.9816318 0 0.1907855 -0.9816303 3.80291e-6 0.1907931 -0.9816217 1.13516e-5 0.1908377 -0.9816291 -9.50576e-6 0.1907994 0.5735782 0 0.8191509 0.5735659 -2.85603e-5 0.8191596 0.5674708 -0.002342522 0.8233902 0.5661171 -0.001581847 0.8243233 0.5669251 -0.00157994 0.8237679 0.5660113 -0.001551151 0.8243961 0.5676255 -7.84978e-4 0.8232865 0.4084359 -1.50523e-4 0.9127871 0.043621 -2.52129e-5 0.9990482 0.04275971 -1.99539e-4 0.9990854 0.03209447 0.00797522 0.9994531 0.04300475 0.00686115 0.9990514 0.0320422 0.009519457 0.9994412 0.04281854 0.01407337 0.9989838 -0.1082499 -0.02219337 0.993876 -0.1753755 -0.01170593 0.9844321 -0.108412 -0.01929491 0.9939188 -0.1759124 -0.002900362 0.9844017 -0.1095488 0.0281955 0.9935814 -0.3582699 -0.005964517 0.9335991 0.02274 0 0.9997415 0.09417605 0.003802239 0.9955483 0.401643 -8.81564e-4 0.915796 0.3740022 -0.004458725 0.9274172 0.2791006 -7.52397e-4 0.9602616 0.3734181 7.07954e-4 0.9276629 0.2791069 0.002424478 0.960257 0.2505345 -0.001332342 0.9681069 0.2790895 -0.001134991 0.9602645 0.2504414 -0.002719879 0.968128 0.09417849 -8.53937e-4 0.995555 0.1186727 0.001292228 0.9929326 0.1186593 0.001292169 0.9929342 -5.59333e-5 0 1 0 0 1 -1.53384e-6 0 1 -0.3737148 0 0.9275437 -0.3737158 0 0.9275433 -0.3737146 0 0.9275438 -0.3737158 0 0.9275433 -0.04764235 0.8569725 0.5131555 -0.7659817 -0.3872227 0.5131576 -0.1940723 0.9640023 0.1817573 -0.500003 0 0.8660237 -0.4999738 0 0.8660407 -0.4999738 0 0.8660405 -0.5000007 -6.64645e-6 0.866025 -0.4999989 -1.1544e-6 0.8660261 -0.5000026 0 0.8660239 -0.5000025 0 0.8660239 -0.5000004 1.19213e-6 0.8660253 -0.4999985 5.67094e-6 0.8660264 -0.4999743 0 0.8660402 -0.1940723 -0.9640023 0.1817573 -0.7659817 0.3872227 0.5131576 -0.04764235 -0.8569725 0.5131555 -0.1039106 -0.8276445 0.5515497 0.6648109 0.5038093 0.5515458 0.4439269 -0.7689142 0.4601087 0.4439253 -0.7689099 0.4601173 0.4439285 -0.7689072 0.460119 0.443926 -0.7689063 0.4601227 0.4439288 -0.768908 0.4601171 0.3665823 -0.7912629 0.4894082 -0.2068541 -0.7864947 0.5819258 -0.393704 -0.7189357 0.5728252 -0.3202459 -0.7470747 0.5825135 -0.2228862 -0.7719982 0.5952653 -0.3353258 -0.7449375 0.5767363 -0.3353576 -0.7449288 0.5767291 -0.09054636 -0.8081251 0.5820097 -0.08508092 -0.8085269 0.5822761 0.006620049 -0.8196638 0.5728066 -0.08538657 -0.8092819 0.5811817 0.002042174 -0.8207775 0.5712445 0.1642487 -0.8236149 0.5428453 0.08879083 -0.8191887 0.5666093 0.3937417 -0.7828154 0.4818379 0.2899278 -0.807985 0.5129348 0.1648918 -0.8208287 0.5468555 0.1890165 -0.8189449 0.5418505 0.1889609 -0.8189499 0.5418623 -0.4106616 -0.7112886 0.5704609 -0.4106624 -0.7112886 0.5704604 -0.4106627 -0.7112885 0.5704602 -0.2041851 -0.4267688 0.881009 -0.2041854 -0.4267697 0.8810086 -0.1566748 -0.4612727 0.8733158 0.347805 -0.6823042 0.6430341 -0.1802113 -0.4505842 0.8743556 -0.05179017 -0.5151779 0.8555171 -0.1501713 -0.4501364 0.8802419 -0.05119687 -0.5135866 0.8565091 0.007802724 -0.5565497 0.8307777 0.1469482 -0.6154009 0.7743954 0.01157772 -0.5447195 0.8385384 0.1482816 -0.6105765 0.7779517 0.1937495 -0.6376942 0.7455248 0.3464643 -0.6876256 0.6380702 0.1945051 -0.6305141 0.751412 0.3682816 -0.6842309 0.6294417 0.4427271 -0.7088308 0.5491372 0.4344995 8.32532e-7 0.9006721 0.4345 0 0.9006719 0.4344996 0 0.9006721 0.4344997 -8.94694e-7 0.9006721 0.2790868 0.003062665 0.9602611 0.1179625 0.001137495 0.9930175 0.09417366 -0.001262485 0.9955551 0.1186597 -0.001292169 0.9929341 0.09417605 -0.003802239 0.9955483 0.2505564 0.001332223 0.9681012 0.2505345 0.001332342 0.9681068 0.2791069 -0.002424478 0.960257 0.3734181 -7.07954e-4 0.9276629 0.2791006 7.52397e-4 0.9602616 0.3740022 0.004458725 0.9274172 0.401643 8.81564e-4 0.915796 -3.2226e-7 0 1 0 0 1 2.3691e-5 0 1 -2.09768e-5 0 1 -5.94737e-5 0 1 2.0581e-5 0 1 -0.2041856 0.4267694 0.8810086 -0.204185 0.4267692 0.8810089 0.3332214 0.6773078 0.6559098 0.347149 0.6849869 0.6405315 0.3470985 0.684977 0.6405695 0.3332011 0.6813265 0.6517448 0.1476818 0.6127435 0.7763604 0.1320688 0.6084173 0.7825511 0.1469359 0.6154617 0.7743494 0.1318238 0.6097657 0.7815424 -0.05314254 0.5188161 0.8532326 -0.04527652 0.5221352 0.8516601 -0.05267602 0.5175551 0.8540269 -0.04485332 0.5211289 0.8522986 -0.177858 0.4454435 0.877466 -0.1814021 0.4435672 0.877691 0.4427271 0.7088308 0.5491372 0.4439253 0.7689101 0.4601173 0.4439275 0.7689053 0.4601229 0.4439276 0.7689073 0.4601194 0.4439288 0.768908 0.4601171 0.4439269 0.7689145 0.4601084 0.2788938 0.8050717 0.5235245 0.371926 0.7895303 0.4881733 0.4329156 0.7724987 0.4645751 0.08487385 0.8232418 0.5613105 0.05637961 0.8201084 0.569424 0.3282803 0.7997338 0.5026509 0.3281978 0.799751 0.5026774 0.2763142 0.809681 0.5177522 0.1625742 0.8226874 0.5447525 0.08352786 0.8277034 0.5549147 -0.06118261 0.8121333 0.5802553 0.04903692 0.8224087 0.5667797 -0.3739195 0.7274641 0.5753088 -0.3643557 0.7320117 0.5756769 -0.1678152 0.7966096 0.5807334 -0.2568039 0.7698718 0.584251 -0.1662642 0.7936023 0.5852791 -0.2672546 0.7591653 0.5935007 -0.1482998 0.797931 0.5842204 -0.4106625 0.7112881 0.5704609 -0.4106619 0.7112887 0.5704606 -0.4106627 0.7112886 0.5704602 + + + + + + + + + + + + + + +

0 0 2 0 1 0 1 1 2 1 3 1 1 2 3 2 4 2 4 2 3 2 1479 2 4 3 1479 3 5 3 5 4 1479 4 1265 4 5 5 1265 5 901 5 901 5 1265 5 1266 5 892 6 6 6 538 6 538 6 6 6 1262 6 538 6 1262 6 0 6 0 6 1262 6 2 6 1282 7 540 7 7 7 7 8 540 8 8 8 7 9 8 9 14 9 14 10 8 10 15 10 549 11 1259 11 9 11 549 12 9 12 543 12 543 13 9 13 10 13 543 14 10 14 11 14 11 15 10 15 13 15 11 16 13 16 12 16 12 17 13 17 14 17 12 18 14 18 15 18 606 19 605 19 16 19 16 20 605 20 1295 20 581 21 17 21 582 21 582 21 17 21 18 21 582 21 18 21 577 21 577 21 18 21 20 21 577 21 20 21 19 21 19 21 20 21 1297 21 17 22 581 22 21 22 17 23 21 23 1294 23 1294 24 21 24 22 24 1294 25 22 25 1291 25 1291 26 22 26 587 26 1291 26 587 26 23 26 23 27 587 27 586 27 23 28 586 28 24 28 25 29 1290 29 584 29 584 30 1290 30 26 30 584 31 26 31 585 31 585 32 26 32 27 32 585 33 27 33 29 33 29 34 27 34 28 34 29 35 28 35 586 35 586 36 28 36 24 36 1290 37 25 37 30 37 30 38 25 38 31 38 30 39 31 39 1289 39 1289 39 31 39 32 39 1289 40 32 40 1269 40 1269 41 32 41 612 41 1269 42 612 42 33 42 33 42 612 42 594 42 33 43 594 43 1316 43 1316 44 594 44 592 44 1252 45 34 45 35 45 35 46 34 46 588 46 35 47 588 47 36 47 36 48 588 48 563 48 44 49 37 49 1324 49 1324 49 37 49 1321 49 1321 21 37 21 38 21 38 21 37 21 595 21 38 21 595 21 40 21 40 21 595 21 39 21 39 50 42 50 40 50 40 50 42 50 41 50 41 6 42 6 43 6 43 6 42 6 533 6 43 6 533 6 1324 6 1324 6 533 6 44 6 45 21 47 21 46 21 46 21 47 21 48 21 46 21 48 21 1325 21 1325 21 48 21 597 21 52 49 603 49 49 49 49 49 603 49 50 49 49 49 50 49 45 49 45 49 50 49 47 49 1923 6 51 6 1922 6 1922 6 51 6 602 6 1922 6 602 6 52 6 52 6 602 6 603 6 53 21 532 21 1340 21 1340 21 532 21 54 21 1340 21 54 21 1338 21 1338 21 54 21 1210 21 616 51 1330 51 55 51 55 52 1330 52 1871 52 55 53 1871 53 615 53 615 54 1871 54 1335 54 615 33 1335 33 609 33 609 34 1335 34 56 34 609 55 56 55 607 55 607 55 56 55 1334 55 607 56 1334 56 57 56 57 57 1334 57 1333 57 57 58 1333 58 1210 58 1210 59 1333 59 1338 59 622 6 1329 6 623 6 623 6 1329 6 58 6 623 6 58 6 618 6 618 6 58 6 1332 6 618 6 1332 6 616 6 616 6 1332 6 1330 6 63 60 64 60 1327 60 63 61 1327 61 620 61 620 62 1327 62 59 62 620 63 59 63 60 63 60 64 59 64 61 64 60 65 61 65 62 65 62 66 61 66 1329 66 62 67 1329 67 622 67 69 68 1349 68 531 68 531 69 1349 69 1348 69 531 70 1348 70 63 70 63 71 1348 71 64 71 625 72 65 72 530 72 530 73 65 73 1343 73 530 74 1343 74 829 74 829 75 1343 75 1345 75 829 76 1345 76 826 76 826 77 1345 77 1347 77 826 78 1347 78 66 78 66 79 1347 79 1350 79 66 80 1350 80 830 80 830 81 1350 81 1351 81 830 82 1351 82 67 82 67 83 1351 83 68 83 67 84 68 84 69 84 69 84 68 84 1349 84 70 85 71 85 1360 85 1360 86 71 86 630 86 1360 87 630 87 1362 87 1362 88 630 88 1136 88 1136 89 78 89 1362 89 1362 90 78 90 1363 90 626 49 72 49 73 49 73 49 72 49 1357 49 626 91 73 91 74 91 626 92 74 92 627 92 627 64 74 64 1354 64 627 93 1354 93 75 93 75 94 1354 94 77 94 75 94 77 94 76 94 76 6 77 6 633 6 633 6 77 6 1352 6 633 6 1352 6 628 6 628 6 1352 6 1364 6 628 6 1364 6 78 6 78 6 1364 6 1363 6 1065 95 86 95 79 95 1065 96 79 96 1066 96 1066 97 79 97 1761 97 1066 98 1761 98 80 98 80 99 1761 99 82 99 80 100 82 100 81 100 81 101 82 101 1758 101 81 102 1758 102 83 102 83 103 1758 103 85 103 83 104 85 104 84 104 84 105 85 105 99 105 84 105 99 105 1084 105 1065 21 87 21 86 21 86 21 87 21 1762 21 88 106 98 106 89 106 88 107 89 107 90 107 90 108 89 108 91 108 90 109 91 109 93 109 93 110 91 110 92 110 93 110 92 110 1063 110 1063 111 92 111 95 111 1063 112 95 112 94 112 94 113 95 113 96 113 94 114 96 114 97 114 97 115 96 115 1762 115 97 116 1762 116 87 116 88 6 1084 6 98 6 98 6 1084 6 99 6 1341 117 604 117 108 117 100 118 1633 118 1632 118 100 118 1632 118 635 118 635 97 1632 97 1631 97 635 98 1631 98 102 98 102 119 1631 119 101 119 102 120 101 120 103 120 103 121 101 121 105 121 103 91 105 91 104 91 104 122 105 122 106 122 106 123 105 123 1336 123 106 124 1336 124 108 124 108 125 1336 125 107 125 108 126 107 126 1341 126 100 21 109 21 1633 21 1633 21 109 21 1786 21 111 127 119 127 1339 127 1339 128 119 128 110 128 111 129 1339 129 112 129 112 130 1339 130 1630 130 112 131 1630 131 113 131 1630 132 114 132 113 132 113 133 114 133 1629 133 113 134 1629 134 115 134 115 135 1629 135 116 135 115 135 116 135 117 135 117 113 116 113 118 113 117 114 118 114 636 114 636 136 118 136 1786 136 636 137 1786 137 109 137 119 6 604 6 110 6 110 6 604 6 1341 6 1177 138 120 138 121 138 1177 139 121 139 1181 139 1181 140 121 140 122 140 1181 141 122 141 1182 141 1182 142 122 142 1936 142 1182 142 1936 142 123 142 123 143 1936 143 124 143 123 143 124 143 125 143 125 144 124 144 1935 144 125 145 1935 145 1183 145 1183 146 1935 146 126 146 1183 147 126 147 127 147 128 148 1932 148 1934 148 128 148 1934 148 1178 148 1178 149 1934 149 130 149 1178 150 130 150 129 150 129 151 130 151 131 151 129 151 131 151 1179 151 1179 152 131 152 1933 152 1179 152 1933 152 132 152 132 153 1933 153 133 153 132 154 133 154 134 154 134 155 133 155 1937 155 134 155 1937 155 520 155 136 156 135 156 1927 156 136 157 1927 157 137 157 137 158 1927 158 138 158 137 159 138 159 1168 159 1168 160 138 160 1929 160 1168 161 1929 161 1173 161 1173 143 1929 143 1928 143 1173 143 1928 143 139 143 139 162 1928 162 140 162 139 163 140 163 1174 163 1174 146 140 146 141 146 1174 147 141 147 1175 147 143 148 142 148 144 148 143 148 144 148 146 148 146 164 144 164 145 164 146 165 145 165 1164 165 1164 151 145 151 1925 151 1164 151 1925 151 1165 151 1165 166 1925 166 147 166 1165 167 147 167 1167 167 1167 168 147 168 1930 168 1167 169 1930 169 149 169 149 170 1930 170 148 170 149 171 148 171 150 171 152 148 151 148 1488 148 152 172 1488 172 153 172 153 150 1488 150 1487 150 153 173 1487 173 641 173 641 174 1487 174 154 174 641 174 154 174 155 174 155 175 154 175 1491 175 155 175 1491 175 156 175 156 176 1491 176 157 176 156 153 157 153 158 153 158 177 157 177 1485 177 158 155 1485 155 159 155 1642 50 642 50 1484 50 1484 50 642 50 643 50 1484 50 643 50 1485 50 1485 50 643 50 159 50 652 148 1861 148 1662 148 652 172 1662 172 160 172 160 178 1662 178 1660 178 160 179 1660 179 161 179 161 174 1660 174 1659 174 161 174 1659 174 655 174 655 180 1659 180 1658 180 655 181 1658 181 162 181 162 182 1658 182 1657 182 162 183 1657 183 163 183 163 184 1657 184 1653 184 163 171 1653 171 656 171 179 185 1004 185 164 185 164 186 1004 186 1002 186 164 186 1002 186 165 186 165 187 1002 187 166 187 165 188 166 188 167 188 167 189 166 189 1001 189 167 189 1001 189 168 189 168 190 1001 190 1006 190 168 190 1006 190 169 190 169 191 1006 191 171 191 169 192 171 192 170 192 170 193 171 193 172 193 170 193 172 193 1386 193 1386 194 172 194 173 194 1386 195 173 195 175 195 175 196 173 196 174 196 175 196 174 196 1387 196 1387 197 174 197 176 197 1387 198 176 198 177 198 177 199 176 199 1005 199 177 200 1005 200 1388 200 1388 201 1005 201 178 201 1388 202 178 202 179 202 179 203 178 203 1004 203 191 185 180 185 1561 185 1561 186 180 186 181 186 1561 204 181 204 1564 204 1564 205 181 205 182 205 1564 188 182 188 1565 188 1565 206 182 206 183 206 1565 189 183 189 1573 189 1573 190 183 190 184 190 1573 207 184 207 185 207 185 191 184 191 858 191 185 191 858 191 1557 191 1557 208 858 208 857 208 1557 193 857 193 1563 193 1563 194 857 194 186 194 1563 194 186 194 187 194 187 209 186 209 188 209 187 196 188 196 1577 196 1577 198 188 198 854 198 1577 198 854 198 189 198 189 199 854 199 855 199 189 199 855 199 190 199 190 201 855 201 856 201 190 210 856 210 191 210 191 185 856 185 180 185 192 211 194 211 193 211 193 212 194 212 195 212 196 213 689 213 1676 213 1676 214 689 214 690 214 1676 215 690 215 197 215 197 216 690 216 198 216 197 217 198 217 1677 217 1677 218 198 218 199 218 686 219 200 219 201 219 201 220 200 220 202 220 201 221 202 221 203 221 203 222 202 222 205 222 203 223 205 223 204 223 204 224 205 224 1680 224 740 21 206 21 207 21 207 21 206 21 1699 21 207 21 1699 21 208 21 208 21 1699 21 1704 21 208 21 1704 21 209 21 209 21 1704 21 210 21 1683 6 755 6 211 6 211 6 755 6 754 6 211 6 754 6 212 6 212 6 754 6 213 6 212 6 213 6 1701 6 1701 6 213 6 214 6 215 225 216 225 789 225 789 226 216 226 1716 226 789 227 1716 227 777 227 777 90 1716 90 217 90 218 228 794 228 219 228 219 229 794 229 793 229 219 230 793 230 220 230 220 231 793 231 763 231 761 232 1536 232 221 232 761 143 221 143 766 143 766 233 221 233 1535 233 766 234 1535 234 767 234 767 235 1535 235 222 235 767 236 222 236 768 236 768 237 222 237 1538 237 768 237 1538 237 223 237 223 238 1538 238 224 238 223 239 224 239 769 239 769 174 224 174 220 174 769 240 220 240 763 240 1588 6 837 6 225 6 225 6 837 6 226 6 225 6 226 6 227 6 227 6 226 6 840 6 227 50 840 50 228 50 228 50 840 50 839 50 228 50 839 50 229 50 229 50 839 50 1224 50 229 50 1224 50 1587 50 1587 50 1224 50 230 50 1587 21 230 21 1585 21 1585 21 230 21 232 21 844 50 1323 50 841 50 841 50 1323 50 1322 50 841 50 1322 50 231 50 231 50 1322 50 1584 50 231 50 1584 50 232 50 232 50 1584 50 1585 50 847 21 233 21 234 21 234 21 233 21 1583 21 842 241 1578 241 235 241 842 242 235 242 843 242 843 243 235 243 237 243 843 244 237 244 236 244 236 158 237 158 1576 158 236 245 1576 245 238 245 238 142 1576 142 1582 142 238 142 1582 142 239 142 239 143 1582 143 240 143 239 143 240 143 848 143 848 246 240 246 1583 246 848 163 1583 163 233 163 1578 50 842 50 1562 50 1562 50 842 50 241 50 1562 50 241 50 1556 50 1556 50 241 50 859 50 1570 6 242 6 860 6 860 6 242 6 243 6 1569 50 849 50 1559 50 1559 50 849 50 850 50 1559 50 850 50 8143 50 8143 50 850 50 244 50 8143 247 244 247 1542 247 1542 248 244 248 772 248 1542 249 772 249 1540 249 1540 250 772 250 245 250 1540 251 245 251 7882 251 7882 252 245 252 246 252 8150 253 7882 253 757 253 757 254 7882 254 246 254 8150 255 757 255 1529 255 1529 256 757 256 247 256 1529 257 247 257 248 257 248 258 247 258 797 258 248 259 797 259 249 259 249 260 797 260 250 260 249 261 250 261 1516 261 1516 262 250 262 782 262 1516 263 782 263 251 263 251 264 782 264 800 264 7871 49 251 49 252 49 252 49 251 49 800 49 7871 265 252 265 1508 265 1508 266 252 266 803 266 1508 267 803 267 1503 267 1503 268 803 268 253 268 1503 269 253 269 1855 269 1855 270 253 270 254 270 1855 271 254 271 1853 271 1853 272 254 272 876 272 1853 273 876 273 877 273 1853 274 877 274 255 274 255 275 877 275 257 275 255 276 257 276 256 276 256 277 257 277 875 277 256 278 875 278 1852 278 1852 279 875 279 259 279 1852 280 259 280 258 280 258 281 259 281 874 281 258 282 874 282 1504 282 882 49 260 49 1237 49 1237 49 260 49 261 49 1237 49 261 49 872 49 872 49 261 49 1857 49 267 6 260 6 881 6 881 6 260 6 882 6 879 236 1500 236 1498 236 879 283 1498 283 262 283 262 237 1498 237 264 237 262 284 264 284 263 284 263 238 264 238 1497 238 263 285 1497 285 880 285 880 174 1497 174 265 174 880 240 265 240 1236 240 1236 286 265 286 1502 286 1236 175 1502 175 266 175 266 168 1502 168 267 168 266 183 267 183 881 183 891 49 1493 49 268 49 268 49 1493 49 1501 49 268 49 1501 49 879 49 879 49 1501 49 1500 49 884 21 883 21 269 21 269 21 883 21 1494 21 894 21 1480 21 270 21 270 21 1480 21 1486 21 270 21 1486 21 640 21 640 21 1486 21 271 21 640 21 271 21 638 21 638 21 271 21 1489 21 282 287 2099 287 912 287 912 288 2099 288 1476 288 912 289 1476 289 911 289 911 290 1476 290 272 290 911 291 272 291 909 291 909 291 272 291 274 291 909 292 274 292 273 292 273 293 274 293 1474 293 273 294 1474 294 275 294 275 294 1474 294 1472 294 275 295 1472 295 536 295 536 296 1472 296 276 296 536 297 276 297 537 297 537 297 276 297 1469 297 537 298 1469 298 277 298 277 299 1469 299 1478 299 277 300 1478 300 897 300 897 301 1478 301 278 301 897 302 278 302 280 302 280 303 278 303 279 303 280 304 279 304 281 304 281 304 279 304 1482 304 2099 305 282 305 1477 305 1477 306 282 306 920 306 1477 307 920 307 283 307 283 308 920 308 919 308 283 309 919 309 1460 309 1460 310 919 310 1218 310 1460 311 1218 311 284 311 284 312 1218 312 288 312 929 49 289 49 930 49 930 49 289 49 285 49 930 49 285 49 1200 49 1200 49 285 49 1690 49 1200 49 1690 49 286 49 286 49 1690 49 1685 49 286 49 1685 49 287 49 287 49 1685 49 1461 49 287 49 1461 49 288 49 288 49 1461 49 284 49 289 313 929 313 1898 313 1898 314 929 314 931 314 1898 315 931 315 291 315 291 315 931 315 290 315 291 316 290 316 292 316 292 317 290 317 935 317 292 318 935 318 2118 318 2118 319 935 319 936 319 2118 320 936 320 1247 320 1247 320 936 320 293 320 1247 321 293 321 1453 321 1453 321 293 321 294 321 1453 322 294 322 295 322 295 323 294 323 1098 323 295 324 1098 324 296 324 296 324 1098 324 298 324 296 325 298 325 297 325 297 325 298 325 299 325 297 326 299 326 301 326 301 327 299 327 300 327 301 328 300 328 302 328 302 328 300 328 304 328 302 329 304 329 303 329 303 330 304 330 305 330 303 331 305 331 1449 331 1449 332 305 332 1143 332 1449 333 1143 333 306 333 306 333 1143 333 1141 333 307 6 941 6 308 6 308 6 941 6 1137 6 308 6 1137 6 1939 6 1939 6 1137 6 309 6 1939 6 309 6 310 6 310 6 309 6 311 6 312 6 313 6 942 6 942 6 313 6 943 6 314 49 1435 49 315 49 315 49 1435 49 1436 49 315 49 1436 49 949 49 949 49 1436 49 1447 49 949 49 1447 49 950 49 950 49 1447 49 1446 49 316 21 964 21 1426 21 1426 21 964 21 1427 21 1434 334 968 334 317 334 1434 335 317 335 318 335 318 336 317 336 970 336 318 337 970 337 1432 337 1432 338 970 338 969 338 1432 339 969 339 319 339 319 340 969 340 320 340 319 341 320 341 321 341 321 342 320 342 322 342 321 343 322 343 1433 343 958 344 3972 344 323 344 323 344 3972 344 324 344 323 345 324 345 325 345 325 346 324 346 326 346 325 347 326 347 322 347 322 348 326 348 1433 348 3972 349 958 349 327 349 327 350 958 350 972 350 327 351 972 351 1422 351 1422 352 972 352 329 352 1422 353 329 353 328 353 328 353 329 353 973 353 328 354 973 354 1421 354 1421 355 973 355 706 355 1421 356 706 356 1419 356 1419 357 706 357 704 357 1419 358 704 358 330 358 330 359 704 359 331 359 330 360 331 360 1418 360 1418 361 331 361 332 361 1418 362 332 362 3948 362 3948 363 332 363 333 363 3948 364 333 364 1417 364 1417 365 333 365 334 365 1417 366 334 366 1410 366 1410 367 334 367 981 367 1410 368 981 368 4606 368 4606 369 981 369 693 369 4606 370 693 370 335 370 335 370 693 370 695 370 335 371 695 371 336 371 336 372 695 372 996 372 337 50 336 50 999 50 999 50 336 50 996 50 337 373 999 373 1000 373 337 374 1000 374 339 374 339 375 1000 375 338 375 339 376 338 376 340 376 340 377 338 377 992 377 340 377 992 377 1394 377 989 241 346 241 341 241 989 242 341 242 990 242 990 378 341 378 1398 378 990 379 1398 379 342 379 342 158 1398 158 1396 158 342 380 1396 380 994 380 994 142 1396 142 1395 142 994 381 1395 381 343 381 343 232 1395 232 1391 232 343 143 1391 143 987 143 987 382 1391 382 344 382 987 163 344 163 345 163 346 50 989 50 347 50 347 50 989 50 1007 50 347 50 1007 50 1385 50 1385 50 1007 50 1008 50 1385 50 1008 50 348 50 348 50 1008 50 1009 50 1016 178 349 178 350 178 1016 383 350 383 351 383 351 174 350 174 352 174 351 174 352 174 1014 174 1014 175 352 175 1381 175 1014 175 1381 175 353 175 353 384 1381 384 355 384 353 183 355 183 354 183 354 385 355 385 1390 385 354 386 1390 386 356 386 356 387 1390 387 348 387 356 379 348 379 1009 379 1921 50 1015 50 357 50 357 50 1015 50 598 50 357 50 598 50 358 50 358 50 598 50 596 50 358 50 596 50 359 50 359 50 596 50 1017 50 1380 50 1019 50 1919 50 1919 50 1019 50 1021 50 1919 50 1021 50 1918 50 1918 50 1021 50 360 50 1918 50 360 50 1379 50 1379 50 360 50 361 50 1379 50 361 50 362 50 362 50 361 50 1023 50 1024 21 363 21 523 21 523 21 363 21 1378 21 523 21 1378 21 1023 21 1023 21 1378 21 362 21 364 50 1589 50 836 50 836 50 1589 50 1590 50 836 50 1590 50 835 50 835 50 1590 50 1594 50 835 50 1594 50 365 50 365 50 1594 50 366 50 1595 6 831 6 1593 6 1593 6 831 6 832 6 1593 6 832 6 366 6 366 6 832 6 365 6 1346 388 827 388 825 388 831 389 1595 389 1596 389 831 390 1596 390 367 390 367 391 1596 391 368 391 367 392 368 392 822 392 822 393 368 393 824 393 824 394 368 394 369 394 824 395 369 395 825 395 825 396 369 396 1598 396 825 397 1598 397 1346 397 827 398 1346 398 828 398 828 399 1346 399 370 399 828 400 370 400 371 400 370 401 1601 401 371 401 371 402 1601 402 1600 402 371 403 1600 403 373 403 373 404 1600 404 372 404 373 405 372 405 374 405 374 406 372 406 375 406 375 407 372 407 1605 407 375 408 1605 408 376 408 1605 409 1604 409 376 409 376 410 1604 410 1603 410 376 411 1603 411 525 411 525 412 1603 412 1602 412 525 413 1602 413 378 413 379 21 819 21 377 21 377 21 819 21 820 21 377 21 820 21 1602 21 1602 21 820 21 378 21 819 50 379 50 818 50 818 50 379 50 1606 50 818 50 1606 50 380 50 380 50 1606 50 1608 50 380 50 1608 50 817 50 817 50 1608 50 1609 50 386 6 385 6 381 6 381 6 385 6 382 6 381 6 382 6 1609 6 1609 6 382 6 817 6 396 414 383 414 394 414 1612 415 384 415 1209 415 385 416 386 416 814 416 814 417 386 417 1610 417 814 418 1610 418 1209 418 1209 418 1610 418 387 418 1209 419 387 419 1612 419 384 420 1612 420 813 420 813 421 1612 421 389 421 813 422 389 422 388 422 388 423 389 423 390 423 388 424 390 424 391 424 391 425 390 425 392 425 391 426 392 426 810 426 810 427 392 427 393 427 810 428 393 428 394 428 394 428 393 428 395 428 394 429 395 429 396 429 383 430 396 430 397 430 397 431 396 431 1616 431 397 432 1616 432 398 432 398 433 1616 433 399 433 398 434 399 434 1070 434 1070 434 399 434 400 434 1070 435 400 435 1035 435 1035 436 400 436 1621 436 1035 437 1621 437 401 437 401 438 1621 438 402 438 401 439 402 439 404 439 402 409 403 409 404 409 404 440 403 440 1618 440 404 441 1618 441 807 441 807 412 1618 412 405 412 807 442 405 442 806 442 421 21 406 21 1623 21 1623 21 406 21 1044 21 1623 21 1044 21 405 21 405 21 1044 21 806 21 1375 50 407 50 1374 50 1374 50 407 50 1027 50 1374 50 1027 50 408 50 408 50 1027 50 409 50 408 21 409 21 1769 21 1769 21 409 21 1028 21 1769 21 1028 21 1371 21 1371 21 1028 21 1030 21 1368 443 410 443 411 443 1041 444 419 444 412 444 1041 445 412 445 1042 445 1042 446 412 446 1625 446 1042 447 1625 447 413 447 413 448 1625 448 1043 448 1043 449 1625 449 1365 449 1043 450 1365 450 1036 450 1365 451 414 451 1036 451 1036 452 414 452 1370 452 1036 388 1370 388 1037 388 1037 453 1370 453 415 453 1037 454 415 454 1039 454 1039 455 415 455 1033 455 1033 456 415 456 416 456 1033 457 416 457 411 457 411 458 416 458 1369 458 411 404 1369 404 1368 404 410 459 1368 459 1032 459 1032 460 1368 460 1366 460 1032 461 1366 461 1026 461 1366 462 417 462 1026 462 1026 463 417 463 418 463 1026 464 418 464 1031 464 1031 465 418 465 1371 465 1031 466 1371 466 1030 466 419 6 1041 6 1627 6 1627 6 1041 6 1040 6 1627 6 1040 6 420 6 420 6 1040 6 1047 6 420 50 1047 50 1624 50 1624 50 1047 50 1046 50 1624 50 1046 50 421 50 421 50 1046 50 406 50 1768 21 1056 21 422 21 422 21 1056 21 424 21 422 21 424 21 423 21 423 21 424 21 426 21 423 21 426 21 425 21 425 21 426 21 1059 21 1064 467 1756 467 1062 467 1062 468 1756 468 1902 468 1062 469 1902 469 1060 469 1060 470 1902 470 427 470 1060 471 427 471 1112 471 1112 472 427 472 428 472 1112 473 428 473 429 473 429 474 428 474 1815 474 429 475 1815 475 430 475 430 476 1815 476 431 476 430 477 431 477 1059 477 1059 478 431 478 425 478 1756 6 1064 6 1760 6 1760 6 1064 6 1068 6 1760 6 1068 6 432 6 432 6 1068 6 1069 6 1372 479 1029 479 433 479 433 480 1029 480 1052 480 433 481 1052 481 1771 481 1771 482 1052 482 1050 482 1029 483 1372 483 1025 483 1025 483 1372 483 1373 483 1025 484 1373 484 1034 484 1034 485 1373 485 434 485 1034 486 434 486 1367 486 435 487 1072 487 436 487 436 488 1072 488 437 488 436 489 437 489 438 489 438 490 437 490 439 490 438 491 439 491 1367 491 1367 492 439 492 440 492 1367 493 440 493 1034 493 1778 494 441 494 442 494 442 495 441 495 1081 495 445 21 447 21 443 21 443 21 447 21 1073 21 443 21 1073 21 1868 21 1868 21 1073 21 444 21 1868 21 444 21 441 21 441 21 444 21 1081 21 447 496 445 496 446 496 447 496 446 496 448 496 448 497 446 497 1775 497 448 498 1775 498 1074 498 1074 499 1775 499 449 499 1074 500 449 500 450 500 449 49 1774 49 450 49 450 49 1774 49 1076 49 1759 50 1067 50 1757 50 1757 50 1067 50 451 50 1757 50 451 50 452 50 452 50 451 50 453 50 452 50 453 50 454 50 454 50 453 50 1082 50 454 50 1082 50 1628 50 1628 50 1082 50 455 50 1628 6 455 6 1783 6 1783 6 455 6 634 6 1783 6 634 6 456 6 456 6 634 6 457 6 456 49 457 49 458 49 458 49 457 49 1089 49 458 49 1089 49 1787 49 1787 49 1089 49 1088 49 1787 49 1088 49 1789 49 1789 49 1088 49 459 49 1789 49 459 49 460 49 460 49 459 49 461 49 460 21 461 21 1755 21 1755 21 461 21 462 21 1755 21 462 21 1759 21 1759 21 462 21 1067 21 463 6 1797 6 1198 6 1198 6 1797 6 464 6 1198 6 464 6 1095 6 1095 6 464 6 1808 6 1095 6 1808 6 1096 6 1096 6 1808 6 1806 6 465 26 1101 26 1102 26 465 501 1102 501 466 501 466 28 1102 28 1093 28 466 28 1093 28 1805 28 1805 502 1093 502 467 502 1805 503 467 503 468 503 468 504 467 504 1096 504 468 505 1096 505 1806 505 469 506 470 506 1455 506 1455 507 470 507 471 507 1455 508 471 508 472 508 472 509 471 509 1099 509 472 510 1099 510 465 510 465 511 1099 511 1101 511 470 512 469 512 1091 512 1091 513 469 513 474 513 1091 514 474 514 473 514 473 514 474 514 1825 514 1791 515 1118 515 1117 515 1791 102 1117 102 475 102 475 516 1117 516 1106 516 475 120 1106 120 1245 120 1245 517 1106 517 1105 517 1245 162 1105 162 479 162 476 518 1810 518 477 518 477 519 1810 519 478 519 477 520 478 520 1105 520 1105 521 478 521 479 521 1810 144 476 144 480 144 1810 163 480 163 481 163 481 522 480 522 1120 522 481 522 1120 522 482 522 482 523 1120 523 1121 523 482 524 1121 524 483 524 473 525 1825 525 484 525 484 526 1825 526 485 526 484 527 485 527 1122 527 1122 527 485 527 1812 527 1122 528 1812 528 1121 528 1121 529 1812 529 483 529 1838 530 1131 530 1129 530 1838 531 1129 531 1839 531 1839 532 1129 532 1128 532 1839 533 1128 533 486 533 486 534 1128 534 1127 534 486 535 1127 535 487 535 487 536 1127 536 488 536 487 537 488 537 489 537 490 538 1831 538 1126 538 1126 539 1831 539 1833 539 1126 540 1833 540 488 540 488 541 1833 541 489 541 1831 542 490 542 491 542 491 543 490 543 492 543 491 544 492 544 493 544 493 545 492 545 1180 545 493 21 1180 21 1830 21 1830 21 1180 21 1139 21 1830 21 1139 21 1450 21 1450 21 1139 21 1140 21 1146 546 1823 546 494 546 494 546 1823 546 1822 546 494 547 1822 547 1144 547 1144 548 1822 548 1452 548 1144 549 1452 549 1142 549 1142 549 1452 549 495 549 1142 550 495 550 1140 550 1140 551 495 551 1450 551 496 285 1133 285 1134 285 496 552 1134 552 497 552 497 174 1134 174 499 174 497 174 499 174 498 174 498 175 499 175 1132 175 498 175 1132 175 1835 175 1801 553 1103 553 500 553 500 554 1103 554 1104 554 500 555 1104 555 501 555 501 556 1104 556 502 556 501 556 502 556 1802 556 1802 557 502 557 503 557 1802 558 503 558 504 558 504 559 503 559 1116 559 504 560 1116 560 506 560 506 561 1116 561 505 561 506 561 505 561 507 561 507 562 505 562 1113 562 507 563 1113 563 1792 563 1792 564 1113 564 508 564 1792 565 508 565 1793 565 1793 566 508 566 1108 566 1793 567 1108 567 1794 567 1794 568 1108 568 509 568 1794 569 509 569 1809 569 1809 570 509 570 1107 570 1809 571 1107 571 1800 571 1800 572 1107 572 510 572 1800 573 510 573 1801 573 1801 574 510 574 1103 574 1821 575 511 575 512 575 512 576 511 576 513 576 512 577 513 577 1818 577 1818 578 513 578 514 578 1818 579 514 579 1826 579 1826 580 514 580 517 580 515 581 516 581 1813 581 1813 582 516 582 1109 582 1813 583 1109 583 1821 583 1821 584 1109 584 511 584 515 585 518 585 516 585 516 585 518 585 1111 585 1826 586 517 586 1827 586 1827 587 517 587 1125 587 1827 588 1125 588 518 588 518 589 1125 589 1111 589 1075 590 664 590 654 590 932 590 930 590 1200 590 1094 590 519 590 926 590 134 590 520 590 629 590 513 590 1148 590 514 590 1142 590 521 590 1144 590 476 590 477 590 1123 590 463 590 1198 590 522 590 1111 590 1125 590 1124 590 1024 590 523 590 1022 590 931 590 927 590 290 590 919 590 916 590 1218 590 254 590 253 590 524 590 525 591 378 591 820 591 752 590 214 590 213 590 526 592 527 592 702 592 528 590 1227 590 1230 590 829 590 529 590 530 590 69 593 531 593 834 593 532 590 624 590 821 590 44 590 533 590 534 590 550 594 903 594 548 594 901 590 907 590 908 590 555 590 535 590 1243 590 612 590 32 590 905 590 610 590 593 590 612 590 4 590 5 590 900 590 275 590 536 590 900 590 900 590 536 590 537 590 900 590 537 590 4 590 4 590 537 590 895 590 4 590 895 590 1 590 892 590 538 590 893 590 893 590 538 590 0 590 12 595 15 595 539 595 539 590 15 590 8 590 539 590 8 590 1221 590 1221 590 8 590 540 590 1221 590 540 590 541 590 541 596 540 596 542 596 541 590 542 590 639 590 548 597 543 597 539 597 539 590 543 590 11 590 539 590 11 590 12 590 544 590 545 590 546 590 546 590 545 590 547 590 546 590 547 590 548 590 548 598 547 598 549 598 548 590 549 590 543 590 550 590 548 590 551 590 550 590 552 590 903 590 903 599 552 599 553 599 903 600 553 600 902 600 902 590 554 590 555 590 555 601 554 601 1219 601 1220 590 556 590 539 590 556 602 557 602 539 602 539 603 557 603 558 603 539 604 558 604 548 604 548 605 558 605 559 605 548 606 559 606 551 606 571 590 589 590 593 590 566 590 560 590 574 590 574 590 560 590 608 590 610 590 561 590 567 590 588 607 562 607 563 607 563 608 562 608 564 608 563 590 564 590 574 590 574 590 564 590 565 590 574 609 565 609 566 609 567 590 568 590 610 590 610 610 568 610 569 610 610 590 569 590 593 590 593 611 569 611 570 611 593 590 570 590 571 590 606 590 572 590 608 590 608 612 572 612 573 612 608 613 573 613 574 613 575 614 579 614 605 614 583 590 577 590 576 590 576 590 577 590 19 590 576 590 19 590 575 590 575 590 19 590 578 590 575 615 578 615 579 615 22 616 580 616 587 616 587 590 580 590 913 590 22 590 21 590 580 590 580 617 21 617 581 617 580 618 581 618 583 618 583 590 581 590 582 590 583 590 582 590 577 590 584 590 585 590 910 590 910 619 585 619 29 619 910 590 29 590 913 590 913 620 29 620 586 620 913 621 586 621 587 621 34 590 593 590 588 590 588 590 593 590 589 590 588 622 589 622 562 622 590 590 591 590 34 590 34 623 591 623 592 623 34 624 592 624 593 624 593 625 592 625 594 625 593 590 594 590 612 590 39 590 595 590 1226 590 1226 590 595 590 37 590 534 590 533 590 653 590 596 590 598 590 50 590 597 590 48 590 1013 590 1013 590 48 590 47 590 50 590 598 590 47 590 47 590 598 590 1015 590 47 590 1015 590 1013 590 1171 590 599 590 597 590 597 590 599 590 600 590 600 590 599 590 51 590 51 590 599 590 1176 590 51 590 1176 590 602 590 602 590 1176 590 601 590 602 590 601 590 603 590 54 590 108 590 1210 590 1210 626 108 626 604 626 605 590 606 590 575 590 575 590 606 590 608 590 575 590 608 590 607 590 607 590 608 590 609 590 560 590 561 590 608 590 608 590 561 590 610 590 608 590 610 590 609 590 609 590 610 590 615 590 905 627 611 627 612 627 612 628 611 628 613 628 612 590 613 590 610 590 610 590 613 590 614 590 610 629 614 629 615 629 615 590 614 590 535 590 615 590 535 590 55 590 55 590 535 590 555 590 55 590 555 590 616 590 616 630 555 630 617 630 616 590 617 590 618 590 618 590 617 590 619 590 531 631 63 631 834 631 834 632 63 632 620 632 834 590 620 590 621 590 621 633 620 633 60 633 60 590 62 590 621 590 621 590 62 590 622 590 621 634 622 634 619 634 619 590 622 590 623 590 619 590 623 590 618 590 821 590 624 590 529 590 529 590 624 590 625 590 529 635 625 635 530 635 1176 590 631 590 601 590 601 590 631 590 72 590 601 590 72 590 1018 590 1018 590 72 590 626 590 626 590 627 590 1018 590 1018 590 627 590 75 590 1018 590 75 590 76 590 628 636 78 636 1135 636 629 637 1136 637 1166 637 1166 590 1136 590 630 590 1166 590 630 590 1176 590 1176 590 630 590 71 590 1176 590 71 590 631 590 1135 590 632 590 628 590 628 590 632 590 1187 590 628 590 1187 590 633 590 457 590 634 590 1086 590 1086 590 634 590 455 590 1086 638 455 638 106 638 106 590 455 590 104 590 604 639 119 639 1210 639 1210 640 119 640 111 640 1210 590 111 590 1212 590 1212 641 111 641 112 641 1212 590 112 590 113 590 115 590 117 590 1203 590 100 590 635 590 1082 590 1082 642 635 642 102 642 1082 590 102 590 455 590 455 643 102 643 103 643 455 644 103 644 104 644 117 590 636 590 1203 590 1203 645 636 645 109 645 1203 646 109 646 100 646 637 590 644 590 152 590 152 590 153 590 637 590 637 647 153 647 638 647 637 590 638 590 670 590 670 590 638 590 885 590 639 590 640 590 159 590 159 590 640 590 158 590 153 590 641 590 638 590 638 590 641 590 155 590 638 590 155 590 640 590 640 590 155 590 156 590 640 648 156 648 158 648 646 590 541 590 642 590 642 590 541 590 639 590 642 590 639 590 643 590 643 590 639 590 159 590 644 590 637 590 645 590 645 590 637 590 1079 590 645 590 1079 590 650 590 646 649 647 649 541 649 541 590 647 590 648 590 541 590 648 590 1079 590 1079 650 648 650 649 650 1079 651 649 651 650 651 651 590 652 590 654 590 654 590 652 590 653 590 654 590 653 590 42 590 42 590 653 590 533 590 652 652 160 652 653 652 653 653 160 653 161 653 653 590 161 590 670 590 670 654 161 654 655 654 655 655 162 655 670 655 670 656 162 656 163 656 670 590 163 590 637 590 637 657 163 657 656 657 661 590 1079 590 657 590 657 590 1079 590 637 590 657 590 637 590 658 590 658 590 637 590 656 590 651 590 654 590 659 590 659 590 654 590 664 590 659 658 664 658 660 658 661 590 662 590 1079 590 1079 659 662 659 663 659 1079 660 663 660 664 660 664 661 663 661 665 661 664 662 665 662 660 662 878 590 1235 590 667 590 667 663 1235 663 666 663 666 590 1235 590 1229 590 666 664 1229 664 1228 664 667 665 668 665 878 665 878 590 668 590 669 590 878 590 669 590 670 590 670 666 669 666 671 666 670 590 671 590 653 590 1169 667 953 667 1170 667 1170 590 953 590 954 590 1169 590 1171 590 672 590 672 590 1171 590 673 590 672 668 673 668 681 668 681 590 673 590 678 590 955 590 674 590 675 590 675 590 674 590 676 590 675 590 676 590 961 590 961 669 676 669 677 669 961 590 677 590 1163 590 1163 670 677 670 679 670 1163 590 679 590 678 590 678 671 679 671 680 671 678 590 680 590 681 590 711 672 682 672 710 672 710 590 682 590 1163 590 682 590 683 590 1163 590 1163 673 683 673 684 673 1163 674 684 674 961 674 961 590 684 590 685 590 961 590 685 590 959 590 201 590 710 590 686 590 686 590 710 590 1163 590 686 590 1163 590 687 590 687 590 1163 590 688 590 690 675 689 675 691 675 199 676 198 676 982 676 982 590 198 590 690 590 982 590 690 590 981 590 690 590 691 590 981 590 981 677 691 677 692 677 981 590 692 590 693 590 693 678 692 678 694 678 693 590 694 590 695 590 695 679 694 679 696 679 695 680 696 680 697 680 697 590 194 590 695 590 695 681 194 681 192 681 695 682 192 682 998 682 698 590 985 590 699 590 699 590 985 590 700 590 527 590 701 590 702 590 702 683 701 683 703 683 702 684 703 684 199 684 332 590 331 590 704 590 717 590 705 590 706 590 706 685 705 685 707 685 706 686 707 686 704 686 704 687 707 687 975 687 203 688 204 688 708 688 709 590 712 590 717 590 201 590 203 590 710 590 710 590 203 590 715 590 710 590 715 590 711 590 711 590 715 590 956 590 712 590 713 590 717 590 717 689 713 689 714 689 717 690 714 690 705 690 203 590 708 590 715 590 715 691 708 691 716 691 715 590 716 590 717 590 717 692 716 692 718 692 717 693 718 693 709 693 1205 590 726 590 719 590 719 590 720 590 1205 590 1205 694 720 694 721 694 1205 695 721 695 732 695 732 696 721 696 723 696 732 590 723 590 722 590 722 590 723 590 724 590 1190 590 725 590 726 590 726 697 725 697 727 697 726 590 727 590 719 590 208 590 209 590 1197 590 1197 698 209 698 1191 698 1192 699 728 699 722 699 722 700 728 700 729 700 722 590 729 590 730 590 730 590 731 590 722 590 722 590 731 590 733 590 722 590 733 590 732 590 732 590 733 590 734 590 732 590 734 590 735 590 752 590 753 590 736 590 736 590 753 590 732 590 736 701 732 701 737 701 737 702 732 702 735 702 738 590 739 590 1200 590 740 590 207 590 741 590 741 590 207 590 1195 590 741 590 1195 590 742 590 743 590 286 590 745 590 745 590 286 590 744 590 745 590 744 590 746 590 743 590 747 590 286 590 286 703 747 703 748 703 286 590 748 590 1200 590 1200 704 748 704 749 704 1200 590 749 590 738 590 739 590 750 590 1200 590 1200 705 750 705 751 705 1200 706 751 706 1201 706 752 590 213 590 753 590 753 590 213 590 754 590 753 590 754 590 744 590 744 590 754 590 755 590 744 707 755 707 746 707 760 708 764 708 793 708 245 590 765 590 246 590 246 709 765 709 756 709 246 710 756 710 757 710 757 590 756 590 758 590 757 590 758 590 247 590 247 711 758 711 759 711 247 712 759 712 760 712 766 590 245 590 761 590 761 590 245 590 762 590 793 590 764 590 763 590 763 590 764 590 765 590 763 590 765 590 769 590 766 590 767 590 245 590 245 713 767 713 768 713 245 590 768 590 765 590 765 590 768 590 223 590 765 714 223 714 769 714 1240 590 770 590 1232 590 1232 715 770 715 771 715 1232 590 771 590 772 590 772 716 771 716 773 716 772 717 773 717 245 717 245 718 773 718 774 718 245 719 774 719 762 719 1239 590 789 590 777 590 1242 590 1241 590 775 590 775 590 1241 590 1239 590 775 590 1239 590 776 590 776 590 1239 590 777 590 250 590 796 590 780 590 778 590 779 590 799 590 250 590 780 590 782 590 782 720 780 720 781 720 782 721 781 721 783 721 783 590 784 590 782 590 782 722 784 722 785 722 782 723 785 723 798 723 1238 724 786 724 1239 724 1239 725 786 725 787 725 1239 590 787 590 789 590 789 726 787 726 788 726 789 727 788 727 215 727 215 728 788 728 799 728 215 590 799 590 790 590 790 590 799 590 779 590 795 590 791 590 247 590 247 729 791 729 792 729 760 590 793 590 247 590 247 590 793 590 794 590 247 730 794 730 795 730 796 590 250 590 792 590 792 590 250 590 797 590 792 731 797 731 247 731 798 590 778 590 782 590 782 590 778 590 799 590 782 590 799 590 800 590 800 732 799 732 801 732 800 590 801 590 252 590 252 733 801 733 802 733 252 590 802 590 803 590 803 734 802 734 804 734 803 735 804 735 1238 735 1238 590 804 590 805 590 1238 590 805 590 786 590 806 736 1044 736 807 736 807 590 1044 590 1045 590 807 737 1045 737 404 737 404 738 1045 738 808 738 404 590 808 590 401 590 1070 590 1035 590 809 590 1087 590 397 590 1071 590 1071 739 397 739 398 739 391 590 810 590 1090 590 1090 740 810 740 394 740 1090 590 394 590 1087 590 1087 741 394 741 811 741 1087 742 811 742 397 742 384 743 813 744 812 745 812 590 813 590 388 590 812 590 388 590 1207 590 814 590 1209 590 815 590 815 590 1209 590 1208 590 816 590 380 590 382 590 382 590 380 590 817 590 818 590 380 590 815 590 815 590 380 590 816 590 815 590 816 590 814 590 814 590 816 590 382 590 814 590 382 590 385 590 819 590 818 590 820 590 820 590 818 590 815 590 820 590 815 590 525 590 525 590 815 590 1208 590 525 746 1208 746 376 746 821 590 374 590 1208 590 1208 590 374 590 375 590 1208 590 375 590 376 590 367 747 822 747 823 747 823 590 822 590 824 590 823 590 824 590 66 590 66 590 824 590 825 590 66 590 825 590 826 590 826 748 825 748 827 748 826 590 827 590 829 590 829 749 827 749 828 749 829 590 828 590 529 590 529 750 828 750 371 750 529 590 371 590 821 590 821 751 371 751 373 751 821 752 373 752 374 752 831 753 367 753 833 753 833 590 367 590 823 590 833 590 823 590 67 590 67 590 823 590 66 590 67 754 66 754 830 754 831 590 833 590 832 590 832 590 833 590 835 590 832 590 835 590 365 590 67 755 69 755 833 755 833 590 69 590 834 590 833 590 834 590 835 590 835 590 834 590 836 590 226 590 837 590 621 590 621 590 837 590 834 590 834 590 837 590 364 590 834 590 364 590 836 590 621 590 838 590 226 590 226 590 838 590 839 590 226 590 839 590 840 590 231 590 1226 590 841 590 841 756 1226 756 37 756 841 590 37 590 844 590 842 590 843 590 534 590 534 757 843 757 236 757 534 758 236 758 238 758 844 759 239 759 848 759 37 590 44 590 844 590 844 760 44 760 534 760 844 590 534 590 239 590 239 590 534 590 238 590 845 590 846 590 847 590 847 761 846 761 844 761 847 590 844 590 233 590 233 762 844 762 848 762 183 763 182 763 1234 763 181 590 180 590 1231 590 1231 764 180 764 856 764 849 590 861 590 850 590 850 765 861 765 851 765 850 590 851 590 1234 590 1234 766 851 766 852 766 849 590 853 590 863 590 188 590 241 590 854 590 854 590 241 590 1231 590 854 767 1231 767 855 767 855 590 1231 590 856 590 188 768 186 768 241 768 241 769 186 769 857 769 241 590 857 590 859 590 859 770 857 770 858 770 859 590 858 590 864 590 864 771 858 771 184 771 243 590 861 590 860 590 860 590 861 590 849 590 860 590 849 590 862 590 862 590 849 590 863 590 184 590 183 590 864 590 864 590 183 590 1234 590 864 590 1234 590 865 590 865 590 1234 590 852 590 866 772 1232 772 867 772 867 590 1232 590 772 590 867 590 772 590 868 590 868 773 772 773 244 773 868 590 244 590 869 590 869 590 244 590 850 590 869 590 850 590 870 590 870 590 850 590 1234 590 870 774 1234 774 871 774 1237 590 872 590 524 590 524 775 872 775 873 775 524 590 873 590 254 590 254 590 873 590 874 590 254 776 874 776 876 776 875 777 257 777 877 777 876 590 874 590 877 590 877 778 874 778 259 778 877 779 259 779 875 779 268 590 879 590 878 590 878 780 879 780 262 780 878 590 262 590 1235 590 262 781 263 781 1235 781 1235 590 263 590 880 590 1235 590 880 590 1236 590 881 590 882 590 266 590 266 590 882 590 1237 590 883 590 884 590 885 590 885 782 884 782 886 782 885 783 886 783 670 783 670 784 886 784 887 784 670 590 887 590 888 590 888 785 889 785 670 785 670 786 889 786 890 786 670 590 890 590 878 590 878 787 890 787 891 787 878 590 891 590 268 590 542 590 892 590 639 590 639 788 892 788 893 788 639 590 893 590 640 590 640 590 893 590 270 590 1 590 895 590 0 590 0 590 895 590 896 590 0 590 896 590 893 590 893 590 896 590 894 590 893 590 894 590 270 590 537 789 277 789 895 789 895 790 277 790 897 790 895 590 897 590 896 590 896 590 897 590 280 590 896 590 280 590 894 590 894 590 280 590 281 590 894 791 281 791 898 791 909 792 273 792 899 792 899 590 273 590 275 590 899 590 275 590 908 590 908 590 275 590 900 590 908 590 900 590 901 590 901 793 900 793 5 793 902 590 555 590 903 590 903 590 555 590 1243 590 903 590 1243 590 904 590 904 590 1243 590 905 590 904 590 905 590 906 590 906 590 905 590 32 590 906 590 32 590 907 590 907 590 32 590 31 590 907 590 31 590 908 590 908 590 31 590 25 590 908 794 25 794 899 794 899 590 25 590 584 590 899 590 584 590 909 590 909 590 584 590 910 590 909 590 910 590 911 590 911 590 910 590 913 590 911 590 913 590 912 590 912 590 913 590 282 590 282 590 913 590 580 590 282 795 580 795 920 795 914 590 1215 590 915 590 915 590 1215 590 916 590 915 796 916 796 917 796 917 590 916 590 919 590 917 797 919 797 918 797 918 798 919 798 920 798 918 590 920 590 921 590 921 799 920 799 580 799 921 590 580 590 922 590 923 590 924 590 519 590 519 590 924 590 925 590 519 590 925 590 926 590 926 590 925 590 933 590 927 590 928 590 290 590 290 800 928 800 934 800 290 801 934 801 935 801 929 590 930 590 931 590 931 802 930 802 932 802 931 590 932 590 927 590 927 590 932 590 926 590 927 590 926 590 928 590 928 590 926 590 933 590 934 590 923 590 935 590 935 590 923 590 519 590 935 590 519 590 936 590 936 590 519 590 293 590 298 590 937 590 299 590 299 590 937 590 938 590 299 590 938 590 300 590 300 590 938 590 1145 590 300 590 1145 590 304 590 1142 590 1140 590 1143 590 939 590 940 590 941 590 941 590 940 590 1138 590 941 590 1138 590 1137 590 942 590 943 590 944 590 944 590 943 590 947 590 944 590 947 590 945 590 946 590 945 590 1170 590 1170 590 945 590 947 590 1170 590 947 590 1172 590 1172 590 947 590 311 590 1172 803 311 803 948 803 948 590 311 590 309 590 949 590 950 590 954 590 954 804 950 804 951 804 954 590 951 590 1170 590 1170 805 951 805 952 805 1170 590 952 590 946 590 953 806 955 806 954 806 954 590 955 590 675 590 954 590 675 590 949 590 949 590 675 590 315 590 956 590 972 590 957 590 957 807 972 807 958 807 957 590 958 590 959 590 959 590 958 590 323 590 959 590 323 590 961 590 961 808 323 808 325 808 961 809 325 809 965 809 960 810 962 810 961 810 961 811 962 811 963 811 961 590 963 590 675 590 675 787 963 787 314 787 675 590 314 590 315 590 964 590 316 590 965 590 965 812 316 812 966 812 965 813 966 813 961 813 961 814 966 814 967 814 961 590 967 590 960 590 970 590 317 590 968 590 322 815 320 815 969 815 969 816 970 816 322 816 322 817 970 817 968 817 322 590 968 590 325 590 325 590 968 590 971 590 325 590 971 590 965 590 956 590 715 590 972 590 972 590 715 590 717 590 972 590 717 590 329 590 329 590 717 590 706 590 329 590 706 590 973 590 334 590 333 590 332 590 199 590 982 590 702 590 702 590 982 590 974 590 702 818 974 818 977 818 975 590 976 590 704 590 704 590 976 590 526 590 704 590 526 590 332 590 332 590 526 590 702 590 332 590 702 590 334 590 334 590 702 590 977 590 977 590 978 590 334 590 334 819 978 819 979 819 334 590 979 590 981 590 981 820 979 820 980 820 981 590 980 590 982 590 982 821 980 821 983 821 982 822 983 822 974 822 988 823 991 823 984 823 988 590 984 590 985 590 985 824 984 824 986 824 985 825 986 825 997 825 343 590 987 590 996 590 1007 590 989 590 988 590 988 826 989 826 990 826 988 590 990 590 991 590 991 827 990 827 342 827 991 590 342 590 993 590 992 590 338 590 1000 590 342 828 994 828 993 828 993 829 994 829 343 829 993 590 343 590 995 590 995 830 343 830 996 830 995 590 996 590 997 590 997 831 996 831 695 831 997 590 695 590 985 590 985 590 695 590 998 590 985 590 998 590 700 590 987 832 345 832 996 832 996 833 345 833 992 833 996 590 992 590 999 590 999 590 992 590 1000 590 1003 834 1001 834 166 834 166 590 1002 590 1003 590 1003 835 1002 835 1004 835 1003 590 1004 590 988 590 988 836 1004 836 178 836 178 590 1005 590 988 590 988 837 1005 837 176 837 988 590 176 590 1007 590 1008 838 171 838 1006 838 176 590 174 590 1007 590 1007 839 174 839 173 839 1007 590 173 590 1008 590 1008 840 173 840 172 840 1008 841 172 841 171 841 1006 590 1001 590 1008 590 1008 590 1001 590 1003 590 1008 590 1003 590 1009 590 1009 590 1003 590 1013 590 353 590 354 590 1013 590 1013 842 354 842 356 842 1013 843 356 843 1009 843 1010 590 1011 590 1015 590 1015 590 1011 590 1012 590 353 590 1013 590 1014 590 1014 590 1013 590 1015 590 1014 590 1015 590 351 590 351 590 1015 590 1012 590 351 590 1012 590 1016 590 50 590 603 590 596 590 596 844 603 844 601 844 596 590 601 590 1017 590 1017 590 601 590 1018 590 1017 590 1018 590 1019 590 1019 590 1018 590 1021 590 1021 590 1018 590 1020 590 1021 590 1020 590 360 590 360 590 1020 590 1022 590 360 590 1022 590 361 590 361 590 1022 590 523 590 361 590 523 590 1023 590 1024 845 1048 845 407 845 407 590 1048 590 1051 590 407 590 1051 590 1027 590 1025 590 1032 590 1026 590 1025 846 1026 846 1029 846 409 590 1027 590 1028 590 1028 590 1027 590 1051 590 1028 590 1051 590 1030 590 1030 847 1051 847 1029 847 1030 848 1029 848 1031 848 1031 849 1029 849 1026 849 1032 590 1025 590 410 590 410 850 1025 850 1034 850 410 590 1034 590 411 590 1038 590 1033 590 439 590 439 851 1033 851 411 851 439 590 411 590 440 590 440 852 411 852 1034 852 1043 590 809 590 808 590 808 590 809 590 1035 590 808 590 1035 590 401 590 1043 590 1036 590 809 590 809 853 1036 853 1037 853 809 590 1037 590 1038 590 1038 854 1037 854 1039 854 1038 855 1039 855 1033 855 1040 590 1041 590 1045 590 1045 856 1041 856 1042 856 1045 590 1042 590 808 590 808 857 1042 857 413 857 808 590 413 590 1043 590 1044 590 406 590 1045 590 1045 590 406 590 1046 590 1045 590 1046 590 1040 590 1040 590 1046 590 1047 590 1053 590 1049 590 1048 590 1048 858 1049 858 1050 858 1048 590 1050 590 1051 590 1051 859 1050 859 1052 859 1051 860 1052 860 1029 860 1053 590 1048 590 1054 590 1054 590 1048 590 1057 590 1054 590 1057 590 1055 590 1055 590 1057 590 1056 590 1056 590 1057 590 1058 590 1056 590 1058 590 424 590 424 590 1058 590 1186 590 424 590 1186 590 426 590 426 590 1186 590 1059 590 1059 861 1186 861 1159 861 1059 862 1159 862 430 862 1112 863 1202 863 1060 863 1060 590 1202 590 1061 590 1060 590 1061 590 1062 590 1063 590 94 590 1064 590 1062 590 1061 590 1064 590 1064 590 1061 590 1085 590 1064 590 1085 590 1063 590 88 864 90 864 1085 864 1085 865 90 865 93 865 1085 866 93 866 1063 866 1066 590 80 590 1067 590 1067 867 80 867 81 867 1067 590 81 590 451 590 81 590 83 590 451 590 451 868 83 868 84 868 451 869 84 869 1084 869 94 870 97 870 1064 870 1064 871 97 871 87 871 1064 590 87 590 1065 590 1065 872 1066 872 1064 872 1064 590 1066 590 1067 590 1064 590 1067 590 1068 590 1068 590 1067 590 462 590 1068 590 462 590 1069 590 1069 590 462 590 461 590 1069 590 461 590 809 590 809 590 461 590 1071 590 809 590 1071 590 1070 590 1070 873 1071 873 398 873 439 590 437 590 1038 590 1038 874 437 874 1072 874 1038 590 1072 590 809 590 809 590 1072 590 1944 590 809 590 1944 590 1069 590 1222 590 1073 590 1223 590 1223 590 1073 590 447 590 1223 590 447 590 1225 590 1225 590 447 590 448 590 448 590 1074 590 1225 590 1225 875 1074 875 450 875 1225 590 450 590 1075 590 1075 590 450 590 1076 590 1075 590 1076 590 664 590 1076 590 1077 590 664 590 664 590 1077 590 1078 590 664 590 1078 590 1079 590 1079 590 1078 590 1080 590 1079 590 1080 590 541 590 541 876 1080 876 442 876 541 590 442 590 1221 590 1221 590 442 590 1081 590 1221 877 1081 877 1222 877 1222 590 1081 590 444 590 1222 590 444 590 1073 590 100 590 1082 590 1203 590 1203 590 1082 590 453 590 1203 590 453 590 1083 590 1083 590 453 590 451 590 1083 590 451 590 1085 590 1085 878 451 878 1084 878 1085 879 1084 879 88 879 1089 590 457 590 1207 590 1207 590 457 590 1086 590 1207 590 1086 590 54 590 54 590 1086 590 106 590 54 880 106 880 108 880 461 590 459 590 1071 590 1071 590 459 590 1088 590 1071 590 1088 590 1087 590 1087 590 1088 590 1089 590 1087 590 1089 590 1090 590 1090 590 1089 590 1207 590 1090 590 1207 590 391 590 391 590 1207 590 388 590 473 590 484 590 517 590 517 590 514 590 473 590 473 590 514 590 1148 590 473 590 1148 590 1091 590 1091 590 1148 590 1092 590 1091 590 1092 590 470 590 470 881 1092 881 1097 881 470 590 1097 590 471 590 467 882 1093 882 519 882 1093 883 1102 883 519 883 519 590 1102 590 1100 590 519 590 1100 590 293 590 293 590 1100 590 294 590 1094 590 1095 590 519 590 519 884 1095 884 1096 884 519 885 1096 885 467 885 1097 590 1098 590 471 590 471 590 1098 590 294 590 471 590 294 590 1099 590 1099 590 294 590 1100 590 1099 886 1100 886 1101 886 1101 887 1100 887 1102 887 1123 888 1103 888 510 888 508 590 1113 590 1124 590 1103 590 1123 590 1104 590 1104 590 1123 590 477 590 1104 590 477 590 502 590 502 590 477 590 1105 590 502 590 1105 590 503 590 503 889 1105 889 1106 889 503 890 1106 890 1116 890 510 590 1107 590 1123 590 1123 891 1107 891 509 891 1123 590 509 590 1124 590 1124 892 509 892 1108 892 1124 590 1108 590 508 590 511 893 1109 893 1110 893 1110 894 1109 894 516 894 1110 590 516 590 429 590 429 590 516 590 1111 590 429 590 1111 590 1112 590 1112 895 1111 895 1124 895 1112 590 1124 590 1202 590 1202 590 1124 590 1113 590 1202 590 1113 590 505 590 1119 590 1114 590 1202 590 1202 896 1114 896 1115 896 1116 590 1106 590 505 590 505 897 1106 897 1117 897 505 590 1117 590 1202 590 1202 898 1117 898 1118 898 1202 899 1118 899 1119 899 463 900 522 900 1115 900 1120 590 480 590 1121 590 1121 590 480 590 476 590 1121 901 476 901 1122 901 1122 590 476 590 1123 590 1122 590 1123 590 484 590 484 590 1123 590 1124 590 484 902 1124 902 517 902 517 590 1124 590 1125 590 1127 903 1184 903 488 903 488 590 1184 590 1126 590 1127 590 1128 590 1184 590 1184 590 1128 590 1129 590 1184 904 1129 904 1130 904 1132 590 499 590 1134 590 1129 590 1131 590 1130 590 1130 905 1131 905 1132 905 1130 590 1132 590 1133 590 1133 590 1132 590 1134 590 1180 590 492 590 629 590 629 906 492 906 490 906 1126 590 1184 590 490 590 490 590 1184 590 1135 590 490 590 1135 590 629 590 629 590 1135 590 78 590 629 590 78 590 1136 590 309 590 1137 590 948 590 948 590 1137 590 1138 590 948 590 1138 590 1139 590 1139 590 1138 590 940 590 1139 907 940 907 1140 907 1140 908 940 908 1141 908 1140 909 1141 909 1143 909 1142 590 1143 590 521 590 521 590 1143 590 305 590 521 590 305 590 1144 590 1144 910 305 910 304 910 1144 590 304 590 494 590 494 590 304 590 1145 590 494 911 1145 911 1146 911 1146 590 1145 590 938 590 1146 590 938 590 1188 590 429 590 430 590 1110 590 1110 590 430 590 1159 590 1110 590 1159 590 511 590 511 590 1159 590 1161 590 511 912 1161 912 513 912 513 590 1161 590 1147 590 513 913 1147 913 1148 913 1148 590 1147 590 1149 590 1148 590 1149 590 1092 590 1150 590 1130 590 1151 590 1151 914 1130 914 1161 914 1151 590 1161 590 1152 590 1185 590 1153 590 1159 590 1159 915 1153 915 1157 915 1154 590 1184 590 1155 590 1155 590 1184 590 1130 590 1155 590 1130 590 1156 590 1156 590 1130 590 1150 590 1157 916 1158 916 1159 916 1159 917 1158 917 1160 917 1159 590 1160 590 1161 590 1161 918 1160 918 1162 918 1161 919 1162 919 1152 919 597 590 1013 590 1171 590 1171 590 1013 590 1003 590 1171 590 1003 590 673 590 673 590 1003 590 988 590 673 590 988 590 678 590 678 590 988 590 985 590 678 590 985 590 1163 590 1163 590 985 590 698 590 1163 920 698 920 688 920 1172 921 1168 921 1173 921 146 922 1164 922 1176 922 1176 923 1164 923 1165 923 1176 924 1165 924 1166 924 1166 925 1165 925 1167 925 1166 926 1167 926 149 926 149 590 150 590 1166 590 1166 590 150 590 136 590 1166 590 136 590 1172 590 1172 927 136 927 137 927 1172 928 137 928 1168 928 1169 590 1170 590 1171 590 1171 590 1170 590 1172 590 1171 590 1172 590 599 590 599 929 1172 929 1173 929 599 930 1173 930 139 930 139 931 1174 931 599 931 599 932 1174 932 1175 932 599 590 1175 590 1176 590 1176 590 1175 590 143 590 1176 933 143 933 146 933 1177 590 1181 590 948 590 1178 590 129 590 1166 590 1166 934 129 934 1179 934 1166 590 1179 590 629 590 629 590 1179 590 132 590 629 935 132 935 134 935 1139 590 1180 590 948 590 948 590 1180 590 629 590 948 590 629 590 1177 590 1177 590 629 590 520 590 1181 936 1182 936 948 936 948 590 1182 590 123 590 948 590 123 590 1172 590 1172 937 123 937 125 937 125 590 1183 590 1172 590 1172 938 1183 938 127 938 1172 590 127 590 1166 590 1166 590 127 590 128 590 1166 939 128 939 1178 939 1154 940 1185 940 1184 940 1184 590 1185 590 1159 590 1184 590 1159 590 1135 590 1135 590 1159 590 1186 590 1135 590 1186 590 632 590 632 590 1186 590 1058 590 632 590 1058 590 1187 590 1187 590 1058 590 1057 590 1024 590 1022 590 1048 590 1048 590 1022 590 1020 590 1048 590 1020 590 1057 590 1057 590 1020 590 1018 590 1057 590 1018 590 1187 590 1187 590 1018 590 76 590 1187 590 76 590 633 590 298 941 1098 941 937 941 937 590 1098 590 1097 590 937 590 1097 590 938 590 938 590 1097 590 1092 590 938 590 1092 590 1188 590 1188 590 1092 590 1149 590 1189 590 1193 590 1190 590 1190 942 1193 942 1194 942 1190 943 1194 943 725 943 1191 590 1192 590 1197 590 1197 590 1192 590 722 590 1197 590 722 590 1193 590 1193 590 722 590 724 590 1193 944 724 944 1194 944 207 590 208 590 1195 590 1195 590 208 590 1197 590 1195 590 1197 590 1196 590 1196 590 1197 590 1193 590 1196 590 1193 590 1199 590 1199 590 1193 590 1189 590 1199 590 1189 590 522 590 1198 590 1095 590 522 590 522 590 1095 590 1094 590 522 590 1094 590 1199 590 1199 590 1094 590 926 590 1199 590 926 590 1196 590 1196 590 926 590 932 590 1196 590 932 590 1195 590 1195 590 932 590 1200 590 1195 945 1200 945 742 945 742 590 1200 590 1201 590 1115 590 522 590 1202 590 1202 590 522 590 1189 590 1202 590 1189 590 1061 590 1061 590 1189 590 1190 590 1061 590 1190 590 1085 590 1085 590 1190 590 726 590 1085 590 726 590 1083 590 1083 590 726 590 1205 590 1083 590 1205 590 1203 590 286 590 287 590 744 590 744 590 287 590 1204 590 744 590 1204 590 753 590 753 590 1204 590 1217 590 753 590 1217 590 732 590 732 590 1217 590 1216 590 732 590 1216 590 1205 590 1205 590 1216 590 1206 590 1205 590 1206 590 1203 590 1203 590 1206 590 1212 590 1203 590 1212 590 115 590 115 590 1212 590 113 590 54 946 532 946 1207 946 1207 590 532 590 821 590 1207 590 821 590 812 590 812 590 821 590 1208 590 812 590 1208 590 384 590 384 947 1208 947 1209 947 57 590 1210 590 1211 590 1211 590 1210 590 1212 590 1211 590 1212 590 1213 590 1213 590 1212 590 1206 590 1213 590 1206 590 1214 590 1214 590 1206 590 1216 590 1214 590 1216 590 1215 590 1215 590 1216 590 1217 590 1215 590 1217 590 916 590 916 590 1217 590 1204 590 916 590 1204 590 1218 590 1218 948 1204 948 287 948 1218 590 287 590 288 590 914 590 922 590 1215 590 1215 590 922 590 580 590 1215 590 580 590 1214 590 1214 590 580 590 583 590 1214 590 583 590 1213 590 1213 590 583 590 576 590 1213 590 576 590 1211 590 1211 590 576 590 575 590 1211 590 575 590 57 590 57 590 575 590 607 590 1219 590 1220 590 555 590 555 590 1220 590 539 590 555 590 539 590 617 590 617 590 539 590 1221 590 617 590 1221 590 619 590 619 590 1221 590 1222 590 619 590 1222 590 621 590 621 590 1222 590 1223 590 621 590 1223 590 838 590 838 590 1223 590 1225 590 838 590 1225 590 839 590 839 590 1225 590 1224 590 230 590 1224 590 232 590 232 590 1224 590 1225 590 232 590 1225 590 231 590 231 590 1225 590 1075 590 231 590 1075 590 1226 590 1226 590 1075 590 654 590 1226 949 654 949 39 949 39 590 654 590 42 590 671 950 528 950 653 950 653 590 528 590 1230 590 653 590 1230 590 534 590 534 590 1230 590 1231 590 534 590 1231 590 842 590 842 590 1231 590 241 590 1227 951 1228 951 1230 951 1230 590 1228 590 1229 590 1230 590 1229 590 1231 590 1231 590 1229 590 1234 590 1231 590 1234 590 181 590 181 590 1234 590 182 590 866 952 871 952 1232 952 1232 590 871 590 1234 590 1232 590 1234 590 1233 590 1233 590 1234 590 1229 590 1233 590 1229 590 524 590 524 590 1229 590 1235 590 524 590 1235 590 1237 590 1237 953 1235 953 1236 953 1237 954 1236 954 266 954 253 590 803 590 524 590 524 590 803 590 1238 590 524 590 1238 590 1233 590 1233 590 1238 590 1239 590 1233 590 1239 590 1232 590 1232 590 1239 590 1241 590 1232 590 1241 590 1240 590 1240 590 1241 590 1242 590 1268 955 611 955 1287 955 1287 956 611 956 905 956 1287 957 905 957 1270 957 1270 958 905 958 1243 958 1934 959 1932 959 1359 959 1244 960 1293 960 1884 960 506 961 507 961 1245 961 438 960 1773 960 436 960 1815 960 1814 960 431 960 1859 960 1544 960 1543 960 1857 960 261 960 1858 960 1460 960 1465 960 283 960 1460 960 284 960 1461 960 291 960 1246 960 1898 960 1453 960 1803 960 1247 960 310 960 1438 960 1443 960 1248 962 1663 962 1249 962 1419 963 330 963 1418 963 1250 960 1251 960 1410 960 412 960 419 960 1627 960 1252 960 35 960 1317 960 1297 960 20 960 1253 960 2 960 1262 960 1254 960 1282 960 7 960 1255 960 1255 960 7 960 14 960 1255 964 14 964 13 964 13 965 10 965 1255 965 1255 960 10 960 9 960 1255 966 9 966 1258 966 1256 960 1257 960 1261 960 9 960 1259 960 1258 960 1258 967 1259 967 1256 967 1258 960 1256 960 1260 960 1260 960 1256 960 1261 960 1254 960 1262 960 1263 960 1263 968 1262 968 6 968 1263 960 6 960 1777 960 1481 960 1264 960 3 960 1478 960 1469 960 1479 960 1479 969 1469 969 1265 969 1265 970 1470 970 1266 970 1266 960 1470 960 1471 960 1266 960 1471 960 1267 960 1287 971 1289 971 1268 971 1268 972 1289 972 1269 972 1270 973 1870 973 1869 973 1284 960 1274 960 1285 960 1271 960 1272 960 1869 960 1869 974 1272 974 1273 974 1274 960 1275 960 1285 960 1285 975 1275 975 1276 975 1285 976 1276 976 1258 976 1258 977 1276 977 1277 977 1277 960 1278 960 1258 960 1258 978 1278 978 1279 978 1258 960 1279 960 1255 960 1255 979 1279 979 1280 979 1255 980 1280 980 1283 980 6 981 1281 981 1777 981 1777 960 1281 960 1282 960 1777 960 1282 960 1776 960 1776 982 1282 982 1255 982 1776 960 1255 960 1869 960 1869 960 1255 960 1283 960 1869 983 1283 983 1271 983 1273 960 1284 960 1869 960 1869 960 1284 960 1285 960 1869 984 1285 984 1270 984 1270 960 1285 960 1286 960 1270 985 1286 985 1287 985 1287 960 1286 960 1288 960 1287 960 1288 960 1289 960 1289 986 1288 986 1267 986 1289 987 1267 987 30 987 30 960 1267 960 1471 960 30 960 1471 960 1290 960 1290 960 1471 960 1473 960 1290 960 1473 960 26 960 24 988 28 988 1292 988 1292 960 28 960 27 960 1294 960 1291 960 1293 960 1293 960 1291 960 1292 960 1292 989 1291 989 23 989 1292 990 23 990 24 990 1244 960 18 960 1293 960 1293 960 18 960 17 960 1293 991 17 991 1294 991 16 960 1295 960 1888 960 1888 992 1295 992 1296 992 1888 993 1296 993 1887 993 1297 960 1253 960 1887 960 1298 994 1299 994 1300 994 1300 960 1299 960 1318 960 1300 960 1318 960 1301 960 16 960 1888 960 1302 960 1302 960 1888 960 1299 960 1302 960 1299 960 1303 960 1303 960 1299 960 1298 960 1303 960 1298 960 1304 960 1298 995 1305 995 1304 995 1304 996 1305 996 1306 996 1304 960 1306 960 36 960 36 960 1306 960 1307 960 36 960 1307 960 35 960 35 997 1307 997 1308 997 35 960 1308 960 1317 960 1317 998 1308 998 1309 998 1317 999 1309 999 1310 999 1310 960 1311 960 1317 960 1317 960 1311 960 1312 960 1317 1000 1312 1000 1318 1000 1318 960 1312 960 1313 960 1318 960 1313 960 1301 960 1314 960 1315 960 1316 960 1316 960 1315 960 1252 960 1316 1001 1252 1001 33 1001 33 960 1252 960 1317 960 33 960 1317 960 1269 960 1269 960 1317 960 1318 960 1269 1002 1318 1002 1268 1002 1661 960 1319 960 41 960 41 960 1319 960 40 960 41 960 43 960 1579 960 1579 960 43 960 1324 960 40 960 1319 960 38 960 38 960 1319 960 1320 960 38 960 1320 960 1321 960 1321 1003 1320 1003 1322 1003 1321 960 1322 960 1324 960 1324 960 1322 960 1323 960 1324 1004 1323 1004 1579 1004 1325 960 1326 960 1924 960 1924 960 1326 960 1923 960 59 1005 1327 1005 1328 1005 1328 960 1327 960 1591 960 1331 960 58 960 1865 960 1865 960 58 960 1329 960 1865 1006 1329 1006 1328 1006 1328 960 1329 960 61 960 1328 960 61 960 59 960 1871 1007 1330 1007 1331 1007 1331 960 1330 960 1332 960 1331 960 1332 960 58 960 1338 960 1333 960 1337 960 1337 960 1333 960 1334 960 1337 960 1334 960 1888 960 1888 960 1334 960 56 960 1888 960 56 960 1299 960 1299 1008 56 1008 1335 1008 1299 960 1335 960 1318 960 107 960 1336 960 1782 960 1337 960 1889 960 1338 960 1338 1009 1889 1009 1630 1009 1338 1010 1630 1010 1339 1010 1339 960 110 960 1338 960 1338 960 110 960 1341 960 1338 960 1341 960 1340 960 1341 960 107 960 1340 960 1340 960 107 960 1782 960 1340 960 1782 960 53 960 53 960 1782 960 1614 960 1342 960 1599 960 65 960 65 960 1599 960 1344 960 65 1011 1344 1011 1343 1011 1343 960 1344 960 1345 960 1346 960 1598 960 1350 960 1350 1012 1598 1012 1597 1012 1344 960 370 960 1345 960 1345 1013 370 1013 1346 1013 1345 960 1346 960 1347 960 1347 960 1346 960 1350 960 1327 1014 64 1014 1591 1014 1591 1015 64 1015 1348 1015 1591 960 1348 960 1592 960 1592 1016 1348 1016 1349 1016 1592 1017 1349 1017 1597 1017 1597 960 1349 960 68 960 1597 960 68 960 1350 960 1350 960 68 960 1351 960 1916 960 1352 960 1353 960 1353 960 1352 960 77 960 1353 960 77 960 1355 960 1355 1018 77 1018 1354 1018 1354 960 74 960 1355 960 1355 1019 74 1019 73 1019 1355 960 73 960 1356 960 1356 960 73 960 1357 960 1356 960 1357 960 1926 960 1357 960 1358 960 1926 960 1926 960 1358 960 70 960 1926 960 70 960 1359 960 1359 960 70 960 1360 960 1359 960 1360 960 1832 960 1832 1020 1360 1020 1362 1020 1832 960 1362 960 1361 960 1361 960 1362 960 1363 960 1361 960 1363 960 1916 960 1916 960 1363 960 1364 960 1916 960 1364 960 1352 960 1365 960 1619 960 414 960 414 960 1619 960 1620 960 1373 960 1366 960 434 960 434 1021 1366 1021 1368 1021 434 960 1368 960 1367 960 1367 960 1368 960 1369 960 1367 960 1369 960 438 960 438 1022 1369 1022 416 1022 438 960 416 960 1773 960 1773 1023 416 1023 415 1023 1773 960 415 960 1620 960 1620 1024 415 1024 1370 1024 1620 960 1370 960 414 960 433 1025 1371 1025 1372 1025 1372 1026 1371 1026 418 1026 1372 1027 418 1027 1373 1027 1373 1028 418 1028 417 1028 1373 960 417 960 1366 960 408 960 1769 960 1374 960 1374 960 1769 960 1376 960 1374 960 1376 960 1375 960 1375 960 1376 960 363 960 1376 960 1770 960 363 960 363 960 1770 960 1377 960 363 960 1377 960 1378 960 1378 960 1377 960 1379 960 1378 960 1379 960 362 960 1380 960 1919 960 359 960 359 960 1919 960 1355 960 359 960 1355 960 358 960 358 960 1355 960 1356 960 1920 960 1390 960 355 960 355 960 1381 960 1920 960 1920 1029 1381 1029 352 1029 1920 960 352 960 1921 960 1921 1030 352 1030 350 1030 1382 960 1383 960 1384 960 1384 1031 1383 1031 1921 1031 1384 960 1921 960 349 960 349 960 1921 960 350 960 169 1032 170 1032 1385 1032 1385 1033 170 1033 1386 1033 1385 960 1386 960 347 960 347 1034 1386 1034 175 1034 347 1035 175 1035 1387 1035 164 960 1943 960 179 960 179 960 1943 960 1389 960 179 960 1389 960 1388 960 1388 1036 1389 1036 177 1036 164 960 165 960 1943 960 1943 1037 165 1037 167 1037 1943 1038 167 1038 168 1038 1390 960 1920 960 348 960 348 960 1920 960 1943 960 348 960 1943 960 1385 960 1385 1039 1943 1039 168 1039 1385 1040 168 1040 169 1040 1387 960 177 960 347 960 347 1041 177 1041 1389 1041 347 960 1389 960 346 960 1394 1042 344 1042 1391 1042 1399 960 1389 960 1392 960 1392 960 1389 960 1942 960 1392 960 1942 960 1393 960 1393 960 1942 960 1403 960 339 960 340 960 337 960 337 1043 340 1043 1394 1043 337 960 1394 960 336 960 336 960 1394 960 1391 960 336 1044 1391 1044 1395 1044 335 960 336 960 1404 960 1404 960 336 960 1395 960 1404 960 1395 960 1397 960 1397 1045 1395 1045 1396 1045 1397 960 1396 960 1399 960 1399 1046 1396 1046 1398 1046 1399 960 1398 960 1389 960 1389 960 1398 960 341 960 1389 960 341 960 346 960 1679 960 1400 960 1942 960 1942 960 1400 960 1401 960 1401 960 1402 960 1942 960 1942 960 1402 960 335 960 1942 960 335 960 1403 960 1403 960 335 960 1404 960 1402 960 1405 960 335 960 335 1047 1405 1047 193 1047 335 1048 193 1048 195 1048 195 960 1406 960 335 960 335 1049 1406 1049 1407 1049 335 960 1407 960 4606 960 4606 1050 1407 1050 1408 1050 4606 960 1408 960 1410 960 1410 1051 1408 1051 1409 1051 1410 1052 1409 1052 1675 1052 1410 1053 1251 1053 1417 1053 1417 960 1251 960 1411 960 1417 1054 1411 1054 1415 1054 1250 960 1410 960 1413 960 1413 960 1410 960 1412 960 1413 960 1412 960 1414 960 1414 960 1412 960 1416 960 1414 960 1416 960 1415 960 1415 960 1416 960 1417 960 1417 960 1416 960 1418 960 1417 960 1418 960 3948 960 1421 1055 1419 1055 1420 1055 1422 960 328 960 1421 960 1420 1056 1248 1056 1421 1056 1421 960 1248 960 1249 960 1421 960 1249 960 1422 960 1422 960 1249 960 1744 960 1422 960 1744 960 327 960 1749 960 1423 960 1431 960 1424 1057 1749 1057 1425 1057 1425 960 1749 960 1437 960 1425 1058 1437 1058 1435 1058 1426 960 1427 960 1428 960 1428 960 1427 960 1423 960 1428 1059 1423 1059 1429 1059 1429 1060 1423 1060 1749 1060 1429 960 1749 960 1430 960 1430 1061 1749 1061 1424 1061 324 960 1749 960 326 960 326 960 1749 960 1431 960 326 960 1431 960 1433 960 1433 960 1431 960 1434 960 319 960 321 960 1432 960 1432 1062 321 1062 1433 1062 1432 960 1433 960 318 960 318 1063 1433 1063 1434 1063 1435 960 1437 960 1436 960 1436 960 1437 960 1445 960 1436 960 1445 960 1447 960 313 960 312 960 1438 960 1438 1064 312 1064 1439 1064 1438 960 1439 960 1443 960 1443 960 1439 960 1440 960 1443 960 1440 960 1441 960 1441 1065 1442 1065 1443 1065 1443 1066 1442 1066 1444 1066 1443 960 1444 960 1445 960 1445 1067 1444 1067 1446 1067 1445 960 1446 960 1447 960 1829 960 1448 960 307 960 1829 1068 307 1068 1938 1068 302 960 303 960 1451 960 1451 960 303 960 1449 960 1451 960 1449 960 1450 960 1450 960 495 960 1451 960 1451 960 495 960 1452 960 1451 960 1452 960 302 960 302 960 1452 960 1909 960 302 960 1909 960 301 960 297 960 1911 960 296 960 296 960 1911 960 1454 960 296 960 1454 960 295 960 295 960 1454 960 1453 960 1453 960 1454 960 1455 960 1453 960 1455 960 1803 960 1247 960 1803 960 2118 960 2118 960 1803 960 1804 960 2118 960 1804 960 292 960 1903 960 1900 960 1456 960 1456 960 1900 960 1246 960 1456 960 1246 960 1457 960 1457 960 1246 960 291 960 1457 960 291 960 1458 960 1458 1069 291 1069 292 1069 1458 960 292 960 1459 960 1459 1070 292 1070 1804 1070 1459 960 1804 960 1904 960 1899 960 285 960 289 960 1465 960 1460 960 1885 960 1885 1071 1460 1071 1461 1071 1885 960 1461 960 1685 960 1293 960 1462 960 1884 960 1884 960 1462 960 1463 960 1884 960 1463 960 1464 960 1885 960 1884 960 1465 960 1465 960 1884 960 1464 960 1465 960 1464 960 283 960 283 960 1464 960 1466 960 283 1072 1466 1072 1477 1072 1477 960 1466 960 1467 960 1477 960 1467 960 1293 960 1293 960 1467 960 1468 960 1293 960 1468 960 1462 960 274 960 272 960 1475 960 1475 1073 272 1073 1476 1073 1265 960 1469 960 1470 960 1470 960 1469 960 276 960 1470 960 276 960 1471 960 1471 1074 276 1074 1472 1074 1471 960 1472 960 1473 960 1473 960 1472 960 1474 960 1473 960 1474 960 26 960 26 1075 1474 1075 274 1075 26 1076 274 1076 27 1076 27 960 274 960 1475 960 27 960 1475 960 1292 960 1292 960 1475 960 1476 960 1292 960 1476 960 1293 960 1293 960 1476 960 2099 960 1293 1077 2099 1077 1477 1077 279 960 278 960 1481 960 1481 960 278 960 1478 960 1481 960 1478 960 1264 960 1264 960 1478 960 1479 960 1264 960 1479 960 3 960 1486 960 1480 960 1481 960 279 960 1481 960 1482 960 1482 960 1481 960 1480 960 1482 1078 1480 1078 1483 1078 1263 960 1484 960 1485 960 3 960 2 960 1481 960 1481 960 2 960 1254 960 1481 960 1254 960 1486 960 1486 960 1254 960 1263 960 1486 960 1263 960 271 960 271 960 1263 960 1485 960 1487 960 1488 960 1489 960 1489 960 1488 960 1634 960 1489 960 1634 960 1490 960 1485 1079 157 1079 271 1079 271 1080 157 1080 1491 1080 271 1081 1491 1081 1489 1081 1489 960 1491 960 154 960 1489 960 154 960 1487 960 1492 960 1655 960 1654 960 1493 1082 1495 1082 1499 1082 269 960 1494 960 1656 960 1656 960 1494 960 1490 960 1499 960 1495 960 1654 960 1654 1083 1495 1083 1496 1083 1654 1084 1496 1084 1492 1084 1498 1085 1858 1085 264 1085 264 960 1858 960 1497 960 1498 1086 1500 1086 1499 1086 1499 960 1500 960 1501 960 1499 960 1501 960 1493 960 260 960 267 960 261 960 261 1087 267 1087 1502 1087 261 960 1502 960 1858 960 1858 960 1502 960 265 960 1858 960 265 960 1497 960 1856 1088 1503 1088 1855 1088 1852 960 258 960 1504 960 1521 960 1516 960 1505 960 1505 1089 1516 1089 251 1089 1505 1090 251 1090 1506 1090 1506 960 251 960 7871 960 1506 1091 7871 1091 1507 1091 1507 1092 7871 1092 1508 1092 1507 960 1508 960 1850 960 1509 1093 1511 1093 1510 1093 1510 1094 1511 1094 1512 1094 1510 1095 1512 1095 1850 1095 1850 960 1512 960 1513 960 1850 960 1513 960 1507 960 1514 1096 1515 1096 1516 1096 249 1097 1516 1097 1524 1097 1522 1098 1519 1098 1521 1098 1515 960 1517 960 1516 960 1516 1099 1517 1099 1518 1099 1516 1100 1518 1100 1524 1100 1521 960 1519 960 1516 960 1516 1101 1519 1101 1520 1101 1516 1102 1520 1102 1514 1102 1509 960 1716 960 1521 960 1521 1103 1716 1103 216 1103 1521 1104 216 1104 1522 1104 218 960 219 960 1523 960 1523 960 219 960 1529 960 1524 960 1525 960 249 960 249 960 1525 960 1526 960 249 960 1526 960 248 960 248 1105 1526 1105 1527 1105 248 960 1527 960 1529 960 1529 1106 1527 1106 1528 1106 1529 960 1528 960 1523 960 1537 960 1540 960 1530 960 1530 1107 1540 1107 7882 1107 1530 960 7882 960 8150 960 219 960 1534 960 1529 960 1529 1108 1534 1108 1531 1108 1529 1109 1531 1109 8150 1109 8150 960 1531 960 1532 960 8150 960 1532 960 1530 960 220 960 1537 960 219 960 219 1110 1537 1110 1533 1110 219 1111 1533 1111 1534 1111 1535 960 221 960 1540 960 1540 1112 221 1112 1536 1112 220 1113 224 1113 1537 1113 1537 1114 224 1114 1538 1114 1537 960 1538 960 1540 960 1540 1115 1538 1115 222 1115 1540 1116 222 1116 1535 1116 1536 1117 1539 1117 1540 1117 1540 1118 1539 1118 1541 1118 1540 960 1541 960 1542 960 1542 1119 1541 1119 1549 1119 1543 960 1544 960 1545 960 1545 960 1544 960 1555 960 1545 960 1555 960 1550 960 1552 960 1559 960 1546 960 1546 960 1559 960 1547 960 1547 960 1559 960 8143 960 1547 960 8143 960 1548 960 1548 960 8143 960 1542 960 1548 960 1542 960 1555 960 1555 960 1542 960 1549 960 1555 1120 1549 1120 1550 1120 1546 960 1551 960 1552 960 1552 960 1551 960 1553 960 1552 960 1553 960 1555 960 1555 960 1553 960 1554 960 1555 960 1554 960 1548 960 1556 960 1575 960 1557 960 1556 960 1557 960 1562 960 189 1121 190 1121 1560 1121 242 960 1569 960 1558 960 1558 960 1569 960 1559 960 1558 960 1559 960 1571 960 190 960 191 960 1560 960 1560 1122 191 1122 1561 1122 1560 960 1561 960 1552 960 1557 960 1563 960 1562 960 1562 1123 1563 1123 187 1123 1562 1124 187 1124 1577 1124 1561 960 1564 960 1552 960 1552 1125 1564 1125 1565 1125 1552 1126 1565 1126 1573 1126 1566 960 1567 960 1568 960 1568 1127 1567 1127 1569 1127 1568 1128 1569 1128 1570 1128 1570 960 1569 960 242 960 1571 1129 1559 1129 1572 1129 1572 960 1559 960 1552 960 1572 960 1552 960 1574 960 1574 1130 1552 1130 1573 1130 1574 960 1573 960 1575 960 1575 1131 1573 1131 185 1131 1575 1132 185 1132 1557 1132 1576 960 237 960 1579 960 1577 960 189 960 1562 960 1562 1041 189 1041 1560 1041 1562 960 1560 960 1578 960 1578 960 1560 960 1579 960 1578 960 1579 960 235 960 235 960 1579 960 237 960 1580 960 1581 960 1323 960 1323 1133 1581 1133 234 1133 1576 960 1579 960 1582 960 1582 960 1579 960 1323 960 1582 960 1323 960 240 960 240 960 1323 960 234 960 240 960 234 960 1583 960 1584 960 1586 960 1585 960 1585 960 1586 960 1864 960 1585 960 1864 960 1587 960 1587 960 1864 960 229 960 227 960 228 960 225 960 225 960 228 960 1863 960 225 960 1863 960 1588 960 1588 960 1863 960 1328 960 1588 1134 1328 1134 1589 1134 1589 960 1328 960 1591 960 1589 960 1591 960 1590 960 1590 960 1591 960 1592 960 1590 960 1592 960 1594 960 1594 960 1592 960 1593 960 1594 960 1593 960 366 960 1595 960 1593 960 1596 960 1596 960 1593 960 1592 960 1596 960 1592 960 368 960 368 960 1592 960 1597 960 368 960 1597 960 369 960 369 960 1597 960 1598 960 1599 960 1613 960 1605 960 1605 960 372 960 1599 960 1599 960 372 960 1600 960 1599 960 1600 960 1344 960 1344 1135 1600 1135 1601 1135 1344 1136 1601 1136 370 1136 377 960 1602 960 1611 960 1611 960 1602 960 1603 960 1611 1137 1603 1137 1613 1137 1613 1138 1603 1138 1604 1138 1613 960 1604 960 1605 960 1606 960 379 960 377 960 377 960 1611 960 1606 960 1606 960 1611 960 1607 960 1606 960 1607 960 1608 960 1608 960 1607 960 381 960 1608 960 381 960 1609 960 386 960 381 960 1610 960 1610 960 381 960 1607 960 1610 960 1607 960 387 960 387 960 1607 960 1611 960 387 960 1611 960 1612 960 1612 960 1611 960 1613 960 1612 1139 1613 1139 389 1139 1615 960 1788 960 1617 960 390 960 1874 960 392 960 392 960 1874 960 1614 960 392 960 1614 960 393 960 393 960 1614 960 1615 960 393 960 1615 960 395 960 395 1140 1615 1140 1617 1140 1622 960 399 960 1788 960 1788 1141 399 1141 1616 1141 1788 1142 1616 1142 1617 1142 405 960 1618 960 1626 960 1626 1143 1618 1143 1619 1143 1618 1144 403 1144 1619 1144 1619 960 403 960 402 960 1619 960 402 960 1620 960 1620 1145 402 1145 1621 1145 1620 960 1621 960 1622 960 1622 1146 1621 1146 400 1146 1622 1147 400 1147 399 1147 405 960 1626 960 1623 960 1623 960 1626 960 1624 960 1623 960 1624 960 421 960 1365 960 1625 960 1619 960 1619 1148 1625 1148 412 1148 1619 960 412 960 1626 960 1626 960 412 960 1627 960 1626 960 1627 960 1624 960 1624 960 1627 960 420 960 1336 960 105 960 1628 960 1628 960 105 960 101 960 1628 960 101 960 454 960 1786 960 118 960 1785 960 118 1149 116 1149 1785 1149 1785 960 116 960 1629 960 1785 960 1629 960 1889 960 1889 960 1629 960 114 960 1889 1150 114 1150 1630 1150 101 960 1631 960 454 960 454 1151 1631 1151 1632 1151 454 1152 1632 1152 1633 1152 1488 1153 151 1153 1634 1153 1634 960 151 960 1635 960 1634 960 1635 960 1649 960 1649 960 1635 960 1636 960 1649 1154 1636 1154 1637 1154 1637 960 1638 960 1649 960 1649 1155 1638 1155 1639 1155 1649 1156 1639 1156 1777 1156 1639 960 1640 960 1777 960 1777 1157 1640 1157 1641 1157 1777 960 1641 960 1263 960 1263 1158 1641 1158 1642 1158 1263 960 1642 960 1484 960 1644 960 1643 960 1647 960 1644 960 1647 960 1862 960 1643 960 1645 960 1647 960 1647 1159 1645 1159 1646 1159 1647 1160 1646 1160 1649 1160 1646 960 1648 960 1649 960 1649 960 1648 960 1650 960 1649 960 1650 960 1634 960 1634 1161 1650 1161 1651 1161 1634 960 1651 960 1652 960 1653 960 1657 960 1654 960 1652 960 1653 960 1634 960 1634 960 1653 960 1654 960 1634 960 1654 960 1490 960 1490 1162 1654 1162 1655 1162 1490 1163 1655 1163 1656 1163 1657 960 1658 960 1654 960 1654 1164 1658 1164 1659 1164 1654 1165 1659 1165 1661 1165 1659 960 1660 960 1661 960 1661 1166 1660 1166 1662 1166 1661 960 1662 960 1319 960 1319 1167 1662 1167 1861 1167 1663 960 1664 960 1249 960 1249 1168 1664 1168 1665 1168 1249 1169 1665 1169 1666 1169 1666 1170 1667 1170 1249 1170 1249 1171 1667 1171 1668 1171 1249 960 1668 960 1744 960 1744 1172 1668 1172 1669 1172 1744 1173 1669 1173 1670 1173 1678 960 1671 960 1416 960 1416 1174 1671 1174 1672 1174 1416 960 1672 960 1418 960 1418 1175 1672 1175 1673 1175 1418 1176 1673 1176 1419 1176 1419 960 1673 960 1674 960 1419 960 1674 960 1420 960 1675 960 196 960 1410 960 1410 1177 196 1177 1676 1177 1410 960 1676 960 1412 960 1412 960 1676 960 197 960 1412 960 197 960 1416 960 1416 960 197 960 1677 960 1416 960 1677 960 1678 960 1682 960 1679 960 1941 960 1670 960 1680 960 1744 960 1744 1178 1680 1178 205 1178 1744 960 205 960 1681 960 1681 960 205 960 202 960 1681 960 202 960 1941 960 1941 960 202 960 200 960 1941 960 200 960 1682 960 1683 960 211 960 1684 960 1684 960 211 960 1880 960 1684 960 1880 960 1886 960 1685 1179 1693 1179 1686 1179 1688 960 1690 960 1687 960 1687 960 1690 960 1698 960 1688 960 1689 960 1690 960 1690 960 1689 960 1691 960 1690 960 1691 960 1685 960 1685 1180 1691 1180 1692 1180 1685 1181 1692 1181 1693 1181 206 960 1694 960 1695 960 1695 1182 1694 1182 1696 1182 1695 960 1696 960 1690 960 1690 1183 1696 1183 1697 1183 1690 1184 1697 1184 1698 1184 206 960 1695 960 1699 960 1699 960 1695 960 1700 960 1699 960 1700 960 1704 960 212 960 1701 960 1878 960 1878 960 1701 960 1876 960 1877 960 1709 960 1711 960 1703 960 1708 960 1702 960 1703 960 1702 960 1714 960 210 960 1704 960 1705 960 1705 960 1704 960 1700 960 1705 960 1700 960 1706 960 1706 1185 1700 1185 1702 1185 1706 960 1702 960 1707 960 1707 960 1702 960 1708 960 1709 960 1710 960 1711 960 1711 1186 1710 1186 1712 1186 1711 960 1712 960 1702 960 1702 1187 1712 1187 1713 1187 1702 960 1713 960 1714 960 1510 960 1860 960 1715 960 1509 960 1510 960 1716 960 1716 960 1510 960 1715 960 1716 960 1715 960 217 960 1721 960 1858 960 1718 960 1498 960 1499 960 1858 960 1858 960 1499 960 1717 960 1858 960 1717 960 1718 960 1718 1188 1719 1188 1721 1188 1721 1189 1719 1189 1720 1189 1721 960 1720 960 1722 960 1722 1190 1720 1190 1723 1190 1722 960 1723 960 1661 960 1661 1191 1723 1191 1724 1191 1661 960 1724 960 1654 960 1654 960 1724 960 1725 960 1654 960 1725 960 1499 960 1499 1192 1725 1192 1726 1192 1499 1193 1726 1193 1717 1193 1736 960 1739 960 1727 960 1727 1190 1739 1190 1728 1190 1727 960 1728 960 1941 960 1941 1194 1728 1194 1729 1194 1941 960 1729 960 1749 960 1749 960 1729 960 1730 960 1749 960 1730 960 1437 960 1730 960 1731 960 1437 960 1437 1195 1731 1195 1732 1195 1437 960 1732 960 1445 960 1445 1196 1732 1196 1733 1196 1445 960 1733 960 1443 960 1443 1197 1733 1197 1734 1197 1443 960 1734 960 1735 960 1735 1198 1734 1198 1737 1198 1735 960 1737 960 1736 960 1736 1199 1737 1199 1738 1199 1736 1200 1738 1200 1739 1200 1748 960 1740 960 1749 960 1749 960 1740 960 1741 960 1749 1201 1741 1201 1941 1201 1941 1202 1741 1202 1742 1202 1941 960 1742 960 1681 960 1681 1203 1742 1203 1743 1203 1681 1204 1743 1204 1744 1204 1744 960 1743 960 1745 960 1744 960 1745 960 327 960 327 1205 1745 1205 1746 1205 327 960 1746 960 3972 960 3972 1206 1746 1206 1747 1206 3972 1207 1747 1207 324 1207 324 1208 1747 1208 1748 1208 324 1209 1748 1209 1749 1209 1750 1210 1711 1210 1751 1210 1751 960 1711 960 1702 960 1751 960 1702 960 1752 960 1752 960 1702 960 1896 960 1891 960 1875 960 1753 960 1891 960 1753 960 1892 960 1892 960 1753 960 1754 960 1892 960 1754 960 1893 960 460 960 1755 960 1760 960 1760 960 1755 960 1759 960 1762 960 96 960 1756 960 96 960 95 960 1756 960 1756 1211 95 1211 92 1211 1756 960 92 960 1763 960 1763 960 92 960 91 960 99 1212 85 1212 1757 1212 1757 1213 85 1213 1758 1213 1757 960 1758 960 1759 960 1758 960 82 960 1759 960 1759 960 82 960 1761 960 1759 960 1761 960 1760 960 1760 1214 1761 1214 79 1214 1760 960 79 960 1756 960 1756 1215 79 1215 86 1215 1756 960 86 960 1762 960 91 960 89 960 1763 960 1763 1216 89 1216 98 1216 1763 960 98 960 99 960 1816 960 1827 960 518 960 1915 960 423 960 1914 960 1914 960 423 960 425 960 431 1217 1814 1217 425 1217 425 960 1814 960 1764 960 425 1218 1764 1218 1914 1218 1765 1219 1766 1219 1908 1219 1766 960 1767 960 1908 960 1908 960 1767 960 1768 960 1908 1220 1768 1220 1915 1220 1915 960 1768 960 422 960 1915 960 422 960 423 960 1769 960 1371 960 1376 960 1376 960 1371 960 433 960 1376 960 433 960 1770 960 1770 1221 433 1221 1771 1221 1770 1222 1771 1222 1907 1222 1622 960 432 960 1620 960 1620 960 432 960 1772 960 1620 960 1772 960 1773 960 1773 960 1772 960 435 960 1773 1223 435 1223 436 1223 1868 960 441 960 1776 960 1647 960 1781 960 1586 960 1586 960 1781 960 1774 960 1586 960 1774 960 1864 960 1864 960 1774 960 449 960 1864 1224 449 1224 1775 1224 1775 960 446 960 1864 960 1864 1225 446 1225 445 1225 1864 960 445 960 1866 960 1776 960 441 960 1777 960 1777 960 441 960 1778 960 1777 1226 1778 1226 1649 1226 1649 960 1778 960 1779 960 1649 960 1779 960 1647 960 1647 960 1779 960 1780 960 1647 960 1780 960 1781 960 1336 1227 1628 1227 1782 1227 1782 960 1628 960 1783 960 1782 960 1783 960 1614 960 1614 960 1783 960 456 960 1614 960 456 960 1615 960 99 960 1757 960 1763 960 1763 960 1757 960 452 960 1763 960 452 960 1784 960 1784 960 452 960 454 960 1784 960 454 960 1785 960 1785 960 454 960 1633 960 1785 960 1633 960 1786 960 456 960 458 960 1615 960 1615 960 458 960 1787 960 1615 960 1787 960 1788 960 1788 960 1787 960 1789 960 1788 960 1789 960 1622 960 1622 960 1789 960 460 960 1622 960 460 960 432 960 432 960 460 960 1760 960 1245 960 507 960 475 960 1794 960 1809 960 1816 960 1799 960 1790 960 1796 960 1796 1228 1790 1228 1791 1228 1796 960 1791 960 475 960 475 960 507 960 1796 960 1796 1229 507 1229 1792 1229 1796 960 1792 960 1816 960 1816 1230 1792 1230 1793 1230 1816 960 1793 960 1794 960 1807 960 464 960 1795 960 1795 960 464 960 1797 960 1795 960 1797 960 1796 960 1796 1231 1797 1231 1798 1231 1796 1232 1798 1232 1799 1232 1809 960 1800 960 1811 960 1811 1233 1800 1233 1801 1233 1811 1234 1801 1234 500 1234 478 1235 501 1235 479 1235 479 1236 501 1236 1802 1236 479 1237 1802 1237 1245 1237 1245 1238 1802 1238 504 1238 1245 1239 504 1239 506 1239 1455 1240 472 1240 1803 1240 1803 1241 472 1241 465 1241 1803 960 465 960 1804 960 1804 1242 465 1242 466 1242 1804 1243 466 1243 1805 1243 1805 960 468 960 1804 960 1804 1244 468 1244 1806 1244 1804 960 1806 960 1807 960 1807 960 1806 960 1808 960 1807 960 1808 960 464 960 1825 960 474 960 1912 960 1912 960 474 960 469 960 1809 960 1811 960 1816 960 1816 960 1811 960 485 960 1816 960 485 960 1827 960 1810 960 1811 960 478 960 478 960 1811 960 500 960 478 1245 500 1245 501 1245 481 960 482 960 1810 960 1810 1246 482 1246 483 1246 1810 1247 483 1247 1811 1247 1811 960 483 960 1812 960 1811 960 1812 960 485 960 1821 960 1764 960 1813 960 1813 960 1764 960 1814 960 1813 960 1814 960 515 960 515 960 1814 960 1815 960 515 960 1815 960 518 960 518 1248 1815 1248 428 1248 518 1249 428 1249 1816 1249 1816 1250 428 1250 427 1250 1816 960 427 960 1796 960 1824 960 1817 960 1819 960 1819 960 1817 960 1820 960 1818 960 1819 960 512 960 512 1251 1819 1251 1820 1251 512 1252 1820 1252 1821 1252 1821 960 1820 960 1846 960 1821 960 1846 960 1764 960 1452 1253 1822 1253 1909 1253 1909 960 1822 960 1823 960 1909 960 1823 960 1910 960 1910 960 1823 960 1824 960 1910 960 1824 960 1912 960 1912 1254 1824 1254 1819 1254 1912 1255 1819 1255 1825 1255 1825 960 1819 960 1818 960 1825 960 1818 960 485 960 485 1256 1818 1256 1826 1256 485 1257 1826 1257 1827 1257 486 1258 487 1258 1828 1258 486 960 1828 960 1839 960 1449 960 306 960 1450 960 1450 1259 306 1259 1829 1259 1450 960 1829 960 1830 960 1830 960 1829 960 1938 960 1830 960 1938 960 493 960 493 1260 1938 1260 1940 1260 493 1261 1940 1261 491 1261 491 960 1940 960 1832 960 491 960 1832 960 1831 960 1831 960 1832 960 1361 960 1831 1262 1361 1262 1833 1262 1833 960 1361 960 1828 960 1833 960 1828 960 489 960 489 1263 1828 1263 487 1263 497 1264 498 1264 496 1264 496 960 498 960 1835 960 496 960 1835 960 1834 960 1834 1265 1835 1265 1838 1265 1913 960 1836 960 1828 960 1828 1266 1836 1266 1837 1266 1838 960 1839 960 1834 960 1834 1267 1839 1267 1828 1267 1834 960 1828 960 1840 960 1840 960 1828 960 1837 960 1840 1268 1841 1268 1834 1268 1834 1269 1841 1269 1842 1269 1834 960 1842 960 1846 960 1846 1270 1842 1270 1843 1270 1846 1271 1843 1271 1844 1271 1844 960 1845 960 1846 960 1846 1272 1845 1272 1847 1272 1846 960 1847 960 1764 960 1764 1273 1847 1273 1848 1273 1764 1274 1848 1274 1849 1274 1508 960 1503 960 1850 960 1850 960 1503 960 1856 960 1850 960 1856 960 1510 960 1510 960 1856 960 1851 960 256 960 1852 960 255 960 255 960 1852 960 1504 960 255 960 1504 960 1853 960 1853 960 1504 960 1854 960 1853 960 1854 960 1855 960 1855 960 1854 960 1857 960 1855 960 1857 960 1856 960 1856 960 1857 960 1858 960 1856 960 1858 960 1851 960 1851 960 1858 960 1721 960 41 960 1579 960 1661 960 1661 960 1579 960 1560 960 1661 960 1560 960 1722 960 1722 960 1560 960 1552 960 1722 960 1552 960 1721 960 1721 960 1552 960 1555 960 1721 960 1555 960 1851 960 1851 960 1555 960 1544 960 1851 960 1544 960 1510 960 1510 960 1544 960 1859 960 1510 1275 1859 1276 1860 1277 1861 960 1862 960 1319 960 1319 960 1862 960 1647 960 1319 960 1647 960 1320 960 1320 960 1647 960 1586 960 1320 960 1586 960 1322 960 1322 960 1586 960 1584 960 228 960 229 960 1863 960 1863 960 229 960 1864 960 1863 960 1864 960 1328 960 1328 960 1864 960 1866 960 1328 960 1866 960 1865 960 1865 960 1866 960 1867 960 1865 960 1867 960 1331 960 445 960 443 960 1866 960 1866 960 443 960 1868 960 1866 960 1868 960 1867 960 1867 960 1868 960 1776 960 1867 960 1776 960 1331 960 1331 960 1776 960 1869 960 1331 960 1869 960 1871 960 1871 960 1869 960 1870 960 1871 960 1870 960 1335 960 1335 960 1870 960 1872 960 1335 1278 1872 1278 1318 1278 1318 960 1872 960 1873 960 1318 960 1873 960 1268 960 1342 960 53 960 1599 960 1599 960 53 960 1614 960 1599 960 1614 960 1613 960 1613 960 1614 960 1874 960 1613 960 1874 960 389 960 389 960 1874 960 390 960 1890 960 1711 960 1891 960 1891 1279 1711 1279 1750 1279 1891 960 1750 960 1875 960 1876 960 1877 960 1878 960 1878 1280 1877 1280 1711 1280 1878 960 1711 960 1881 960 1881 960 1711 960 1890 960 1881 960 1890 960 1879 960 211 960 212 960 1880 960 1880 960 212 960 1878 960 1880 960 1878 960 1883 960 1883 960 1878 960 1881 960 1883 960 1881 960 1882 960 1882 960 1881 960 1879 960 1882 960 1879 960 1253 960 20 960 18 960 1253 960 1253 960 18 960 1244 960 1253 960 1244 960 1882 960 1882 960 1244 960 1884 960 1882 960 1884 960 1883 960 1883 960 1884 960 1885 960 1883 960 1885 960 1880 960 1880 960 1885 960 1685 960 1880 1281 1685 1281 1886 1281 1886 1282 1685 1282 1686 1282 1887 960 1253 960 1888 960 1888 960 1253 960 1879 960 1888 960 1879 960 1337 960 1337 960 1879 960 1890 960 1337 960 1890 960 1889 960 1889 960 1890 960 1891 960 1889 960 1891 960 1785 960 1785 960 1891 960 1892 960 1785 960 1892 960 1784 960 1784 960 1892 960 1893 960 1784 960 1893 960 1763 960 1690 960 285 960 1695 960 1695 960 285 960 1899 960 1695 960 1899 960 1700 960 1700 960 1899 960 1894 960 1700 960 1894 960 1702 960 1702 960 1894 960 1895 960 1702 960 1895 960 1896 960 1896 960 1895 960 1893 960 1896 1283 1893 1283 1897 1283 1897 960 1893 960 1754 960 289 960 1898 960 1899 960 1899 960 1898 960 1246 960 1899 960 1246 960 1894 960 1894 960 1246 960 1900 960 1894 960 1900 960 1895 960 1895 960 1900 960 1905 960 1895 960 1905 960 1893 960 1893 960 1905 960 1901 960 1893 960 1901 960 1763 960 1763 960 1901 960 1906 960 1763 960 1906 960 1756 960 1756 960 1906 960 1902 960 1903 960 1904 960 1900 960 1900 960 1904 960 1804 960 1900 960 1804 960 1905 960 1905 960 1804 960 1807 960 1905 960 1807 960 1901 960 1901 960 1807 960 1795 960 1901 960 1795 960 1906 960 1906 960 1795 960 1796 960 1906 960 1796 960 1902 960 1902 960 1796 960 427 960 1907 960 1765 960 1770 960 1770 960 1765 960 1908 960 1770 960 1908 960 1377 960 1377 960 1908 960 1917 960 1377 960 1917 960 1379 960 1379 960 1917 960 1918 960 301 960 1909 960 297 960 297 960 1909 960 1910 960 297 960 1910 960 1911 960 1911 960 1910 960 1912 960 1911 960 1912 960 1454 960 1454 1284 1912 1284 469 1284 1454 960 469 960 1455 960 1849 960 1913 960 1764 960 1764 960 1913 960 1828 960 1764 960 1828 960 1914 960 1914 960 1828 960 1361 960 1914 960 1361 960 1915 960 1915 960 1361 960 1916 960 1915 960 1916 960 1908 960 1908 960 1916 960 1353 960 1908 960 1353 960 1917 960 1917 960 1353 960 1355 960 1917 960 1355 960 1918 960 1918 960 1355 960 1919 960 142 960 1926 960 144 960 144 960 1926 960 145 960 46 960 1920 960 45 960 45 1285 1920 1285 1921 1285 45 960 1921 960 49 960 49 960 1921 960 357 960 49 960 357 960 52 960 52 960 357 960 358 960 52 1286 358 1286 1922 1286 1922 960 358 960 1356 960 1922 960 1356 960 1923 960 1923 960 1356 960 1926 960 1923 960 1926 960 1924 960 1924 960 1926 960 142 960 1924 960 142 960 141 960 145 960 1926 960 1925 960 1925 960 1926 960 1359 960 1925 960 1359 960 147 960 138 960 1927 960 1931 960 1931 1287 1927 1287 135 1287 141 960 140 960 1924 960 1924 1288 140 1288 1928 1288 1924 960 1928 960 1931 960 1931 1289 1928 1289 1929 1289 1931 1290 1929 1290 138 1290 135 960 148 960 1359 960 1359 1291 148 1291 1930 1291 1359 960 1930 960 147 960 135 960 1359 960 1931 960 1931 960 1359 960 1932 960 1931 960 1932 960 126 960 133 1292 1933 1292 1832 1292 1832 960 1933 960 131 960 1832 1293 131 1293 1359 1293 1359 1294 131 1294 130 1294 1359 1295 130 1295 1934 1295 126 1296 1935 1296 1931 1296 1931 1297 1935 1297 124 1297 1931 1298 124 1298 1940 1298 1940 1299 124 1299 1936 1299 1940 960 1936 960 122 960 122 1300 121 1300 1940 1300 1940 1301 121 1301 120 1301 1940 960 120 960 1832 960 1832 960 120 960 1937 960 1832 1302 1937 1302 133 1302 307 960 308 960 1938 960 1938 960 308 960 1939 960 1938 960 1939 960 1940 960 1940 960 1939 960 310 960 1940 960 310 960 1931 960 1931 960 310 960 1443 960 1931 960 1443 960 1924 960 1924 960 1443 960 1735 960 1924 960 1735 960 1325 960 1679 1303 1942 1303 1941 1303 1941 960 1942 960 1389 960 1941 960 1389 960 1727 960 1727 960 1389 960 1943 960 1727 960 1943 960 1736 960 1736 960 1943 960 1920 960 1736 960 1920 960 1735 960 1735 960 1920 960 46 960 1735 960 46 960 1325 960 432 49 1069 49 1772 49 1772 49 1069 49 1944 49 1772 49 1944 49 435 49 435 49 1944 49 1072 49 2185 1304 1952 1304 1945 1304 1945 1305 1952 1305 2550 1305 1945 1306 2550 1306 1946 1306 1946 1307 2550 1307 2551 1307 1946 1308 2551 1308 2180 1308 2180 1308 2551 1308 1947 1308 2180 1309 1947 1309 1948 1309 1948 1310 1947 1310 1949 1310 1948 1311 1949 1311 2179 1311 2179 1312 1949 1312 1950 1312 2181 1313 1953 1313 2545 1313 2181 1314 2545 1314 1951 1314 1951 1315 2545 1315 2548 1315 1951 1316 2548 1316 2182 1316 2182 1317 2548 1317 2546 1317 2182 1318 2546 1318 2187 1318 2187 1319 2546 1319 1952 1319 2187 1320 1952 1320 2185 1320 1953 1321 2181 1321 1954 1321 1954 1321 2181 1321 1955 1321 1954 1322 1955 1322 2563 1322 2563 1323 1955 1323 2189 1323 1956 1324 1957 1324 2502 1324 2502 1325 1957 1325 2559 1325 2502 1326 2559 1326 1958 1326 1958 1327 2559 1327 2558 1327 1958 1328 2558 1328 2496 1328 2496 1329 2558 1329 2557 1329 1959 50 2193 50 1960 50 1960 50 2193 50 1961 50 1960 50 1961 50 2820 50 2820 50 1961 50 1962 50 2820 50 1962 50 1963 50 1963 50 1962 50 1964 50 2505 1330 2823 1330 2821 1330 2505 1331 2821 1331 1965 1331 1965 1332 2821 1332 1966 1332 1965 1333 1966 1333 1967 1333 1967 1334 1966 1334 1969 1334 1967 1335 1969 1335 1968 1335 1968 1336 1969 1336 2819 1336 1968 1337 2819 1337 1970 1337 1970 1338 2819 1338 1971 1338 1970 1339 1971 1339 2507 1339 2507 1340 1971 1340 1972 1340 2507 1341 1972 1341 2508 1341 2509 50 2508 50 1973 50 1973 50 2508 50 1972 50 2509 1342 1973 1342 1974 1342 2509 1343 1974 1343 2510 1343 2510 1344 1974 1344 1975 1344 2510 1344 1975 1344 2511 1344 2511 1345 1975 1345 1976 1345 2511 1346 1976 1346 2512 1346 2512 1347 1976 1347 1977 1347 2512 1348 1977 1348 2514 1348 2514 1349 1977 1349 1978 1349 2514 1349 1978 1349 2165 1349 2165 1350 1978 1350 1979 1350 2165 1351 1979 1351 2166 1351 1980 1352 1981 1352 2208 1352 2208 1353 1981 1353 1982 1353 2208 1354 1982 1354 2209 1354 2209 1354 1982 1354 2575 1354 2209 1355 2575 1355 2176 1355 2176 1355 2575 1355 2574 1355 2176 1356 2574 1356 2199 1356 2199 1357 2574 1357 2571 1357 2216 49 1983 49 2515 49 2515 49 1983 49 1984 49 2515 49 1984 49 2516 49 2516 49 1984 49 1985 49 2516 49 1985 49 2210 49 2210 49 1985 49 1986 49 2504 1358 1988 1358 1987 1358 1987 1359 1988 1359 2830 1359 1987 1360 2830 1360 1989 1360 1989 1361 2830 1361 2828 1361 1989 1362 2828 1362 2218 1362 2218 1363 2828 1363 1990 1363 2218 1364 1990 1364 1991 1364 1991 1364 1990 1364 2592 1364 2587 6 2223 6 1992 6 1992 6 2223 6 1993 6 1992 6 1993 6 1994 6 1994 6 1993 6 1995 6 1997 1342 1996 1342 1998 1342 1997 1365 1998 1365 2428 1365 2428 1366 1998 1366 1999 1366 2428 1367 1999 1367 2000 1367 2000 1368 1999 1368 2002 1368 2000 1369 2002 1369 2001 1369 2001 1370 2002 1370 2912 1370 2001 1371 2912 1371 2003 1371 2003 1372 2912 1372 2004 1372 2003 1373 2004 1373 2005 1373 2005 1374 2004 1374 2910 1374 2005 1351 2910 1351 2014 1351 1997 50 2006 50 1996 50 1996 50 2006 50 2012 50 2013 1330 2907 1330 2007 1330 2013 1375 2007 1375 2422 1375 2422 1376 2007 1376 2008 1376 2422 1376 2008 1376 2423 1376 2423 1377 2008 1377 2909 1377 2423 1378 2909 1378 2009 1378 2009 1379 2909 1379 2908 1379 2009 1380 2908 1380 2011 1380 2011 1381 2908 1381 2010 1381 2011 1381 2010 1381 2425 1381 2425 1382 2010 1382 2012 1382 2425 1341 2012 1341 2006 1341 2013 49 2014 49 2907 49 2907 49 2014 49 2910 49 2015 50 2016 50 2017 50 2017 50 2016 50 2609 50 2245 1383 2629 1383 2173 1383 2173 1384 2629 1384 2019 1384 2173 1385 2019 1385 2018 1385 2018 1386 2019 1386 2020 1386 2018 1387 2020 1387 2438 1387 2438 1388 2020 1388 2628 1388 2021 1389 2232 1389 2022 1389 2174 1390 2611 1390 2023 1390 2023 1391 2611 1391 2024 1391 2023 1392 2024 1392 2022 1392 2022 1393 2024 1393 2622 1393 2022 1394 2622 1394 2021 1394 2232 1395 2021 1395 2618 1395 2232 1396 2618 1396 2025 1396 2025 1397 2618 1397 2619 1397 2025 1398 2619 1398 2231 1398 2231 1399 2619 1399 2026 1399 2231 1400 2026 1400 2027 1400 2027 1401 2026 1401 2616 1401 2027 1402 2616 1402 2028 1402 2625 1403 2242 1403 2626 1403 2626 1404 2242 1404 2243 1404 2626 1405 2243 1405 2616 1405 2616 1405 2243 1405 2028 1405 2641 1406 2258 1406 2640 1406 2640 1407 2258 1407 2260 1407 2640 1408 2260 1408 2638 1408 2638 1409 2260 1409 2262 1409 2659 21 2272 21 2660 21 2660 21 2272 21 2271 21 2660 21 2271 21 2661 21 2661 21 2271 21 2029 21 2030 1410 2644 1410 2439 1410 2439 1410 2644 1410 2642 1410 2439 1411 2642 1411 2031 1411 2031 1412 2642 1412 2032 1412 2031 1413 2032 1413 2274 1413 2274 1414 2032 1414 2033 1414 2274 1415 2033 1415 2275 1415 2275 1416 2033 1416 2654 1416 2646 49 2034 49 2427 49 2427 49 2034 49 2249 49 2061 1417 2680 1417 2447 1417 2447 1417 2680 1417 2679 1417 2447 1418 2679 1418 2446 1418 2446 1418 2679 1418 2035 1418 2446 1419 2035 1419 2303 1419 2303 1420 2035 1420 2036 1420 2303 1421 2036 1421 2037 1421 2037 1422 2036 1422 2682 1422 2037 1423 2682 1423 2038 1423 2038 1424 2682 1424 2688 1424 2038 1425 2688 1425 2299 1425 2299 1426 2688 1426 2687 1426 2299 1427 2687 1427 2301 1427 2301 1428 2687 1428 2039 1428 2301 1429 2039 1429 2302 1429 2302 1429 2039 1429 2685 1429 2302 1430 2685 1430 2040 1430 2040 1431 2685 1431 2684 1431 2040 1432 2684 1432 2041 1432 2041 1433 2684 1433 2042 1433 2041 1434 2042 1434 2297 1434 2297 1435 2042 1435 2043 1435 2297 1436 2043 1436 2044 1436 2044 1437 2043 1437 2045 1437 2044 1438 2045 1438 2046 1438 2046 1439 2045 1439 2544 1439 2046 1440 2544 1440 2294 1440 2294 1441 2544 1441 2902 1441 2294 1442 2902 1442 2047 1442 2047 1443 2902 1443 2048 1443 2047 1444 2048 1444 2049 1444 2049 1445 2048 1445 2692 1445 2049 1446 2692 1446 2050 1446 2050 1446 2692 1446 2052 1446 2050 1447 2052 1447 2051 1447 2051 1447 2052 1447 2053 1447 2051 1448 2053 1448 2054 1448 2054 1449 2053 1449 2678 1449 2054 1450 2678 1450 2314 1450 2314 1451 2678 1451 2677 1451 2314 1452 2677 1452 2315 1452 2315 1453 2677 1453 2675 1453 2315 1454 2675 1454 2055 1454 2055 1455 2675 1455 2824 1455 2055 1456 2824 1456 2309 1456 2309 1457 2824 1457 2056 1457 2309 1458 2056 1458 2057 1458 2057 1459 2056 1459 2059 1459 2057 1460 2059 1460 2058 1460 2058 1460 2059 1460 2833 1460 2058 1461 2833 1461 2306 1461 2306 1462 2833 1462 2060 1462 2306 1463 2060 1463 2308 1463 2308 1464 2060 1464 2681 1464 2308 1465 2681 1465 2061 1465 2061 1466 2681 1466 2680 1466 2521 1467 2062 1467 2739 1467 2740 1468 2523 1468 2741 1468 2741 1469 2523 1469 2522 1469 2741 1470 2522 1470 2739 1470 2739 1471 2522 1471 2063 1471 2739 1472 2063 1472 2521 1472 2069 1473 2064 1473 2065 1473 2065 1474 2064 1474 2573 1474 2065 1475 2573 1475 2197 1475 2197 1476 2573 1476 2066 1476 2197 1477 2066 1477 2067 1477 2067 1478 2066 1478 2576 1478 2067 1479 2576 1479 2068 1479 2068 1480 2576 1480 2577 1480 2068 1481 2577 1481 2521 1481 2521 1482 2577 1482 2062 1482 2064 1483 2069 1483 2200 1483 2070 1484 2071 1484 2202 1484 2202 1485 2071 1485 2569 1485 2202 1486 2569 1486 2200 1486 2200 1487 2569 1487 2572 1487 2200 1488 2572 1488 2064 1488 2264 49 2072 49 2073 49 2073 49 2072 49 2074 49 2073 49 2074 49 2267 49 2267 49 2074 49 2880 49 2267 49 2880 49 2075 49 2075 49 2880 49 2076 49 2075 49 2076 49 2461 49 2461 49 2076 49 2884 49 2461 49 2884 49 2194 49 2194 49 2884 49 2583 49 2194 49 2583 49 2204 49 2204 49 2583 49 2581 49 2204 49 2581 49 2070 49 2070 49 2581 49 2071 49 2079 1489 2639 1489 2078 1489 2072 1490 2264 1490 2077 1490 2077 1491 2264 1491 2253 1491 2077 1492 2253 1492 2078 1492 2078 1493 2253 1493 2251 1493 2078 1494 2251 1494 2079 1494 2639 1495 2079 1495 2080 1495 2080 1496 2079 1496 2261 1496 2080 144 2261 144 2081 144 2081 1497 2261 1497 2259 1497 2081 1498 2259 1498 2083 1498 2086 1499 2650 1499 2082 1499 2082 1500 2650 1500 2651 1500 2082 1501 2651 1501 2083 1501 2083 1502 2651 1502 2632 1502 2083 1503 2632 1503 2081 1503 2087 21 2084 21 2240 21 2240 21 2084 21 2612 21 2240 21 2612 21 2236 21 2236 21 2612 21 2911 21 2236 21 2911 21 2085 21 2085 21 2911 21 2643 21 2085 21 2643 21 2086 21 2086 21 2643 21 2650 21 2087 1504 2088 1504 2084 1504 2084 1505 2088 1505 2623 1505 2093 1506 2091 1506 2617 1506 2093 1507 2617 1507 2233 1507 2233 1508 2617 1508 2624 1508 2233 1509 2624 1509 2234 1509 2234 1510 2624 1510 2623 1510 2234 1511 2623 1511 2088 1511 2094 1512 2620 1512 2621 1512 2094 1513 2621 1513 2089 1513 2089 1514 2621 1514 2090 1514 2089 1515 2090 1515 2092 1515 2092 1516 2090 1516 2091 1516 2092 1517 2091 1517 2093 1517 2620 1518 2094 1518 2736 1518 2736 1519 2094 1519 2333 1519 2736 1520 2333 1520 2095 1520 2095 1521 2333 1521 2332 1521 2095 1522 2332 1522 2096 1522 2096 1523 2332 1523 2097 1523 2096 1524 2097 1524 2098 1524 2098 1525 2097 1525 2334 1525 2735 1526 2098 1526 2101 1526 2101 1527 2098 1527 2334 1527 2102 1528 2099 1528 2338 1528 2338 1528 2099 1528 2100 1528 2338 1529 2100 1529 2101 1529 2101 1530 2100 1530 2735 1530 2099 21 2102 21 2103 21 2103 21 2102 21 2104 21 2103 21 2104 21 2721 21 2721 21 2104 21 2105 21 2105 1531 2346 1531 2721 1531 2721 1531 2346 1531 2106 1531 2106 50 2346 50 2897 50 2897 50 2346 50 2345 50 2897 50 2345 50 2896 50 2896 50 2345 50 2495 50 2896 50 2495 50 2887 50 2887 50 2495 50 2454 50 2887 50 2454 50 2107 50 2107 50 2454 50 2108 50 2107 50 2108 50 2774 50 2774 50 2108 50 2109 50 2774 50 2109 50 2110 50 2110 50 2109 50 2388 50 2110 50 2388 50 2111 50 2111 50 2388 50 2463 50 2111 50 2463 50 2838 50 2838 50 2463 50 2168 50 2838 50 2168 50 2112 50 2112 50 2168 50 2347 50 2115 1532 2717 1532 2350 1532 2350 1533 2717 1533 2716 1533 2350 1534 2716 1534 2349 1534 2349 1535 2716 1535 2113 1535 2349 1536 2113 1536 2347 1536 2347 1537 2113 1537 2112 1537 2717 6 2115 6 2114 6 2114 6 2115 6 2116 6 2114 6 2116 6 2118 6 2118 6 2116 6 2117 6 2118 1538 2117 1538 2718 1538 2718 1539 2117 1539 2351 1539 2718 1540 2351 1540 2714 1540 2714 1541 2351 1541 2119 1541 2714 1542 2119 1542 2120 1542 2120 1543 2119 1543 2121 1543 2120 1544 2121 1544 2123 1544 2123 1545 2121 1545 2122 1545 2712 1546 2123 1546 2353 1546 2353 1547 2123 1547 2122 1547 2355 1548 2132 1548 2124 1548 2124 1549 2132 1549 2125 1549 2124 1550 2125 1550 2357 1550 2357 1551 2125 1551 2126 1551 2357 1552 2126 1552 2352 1552 2352 1553 2126 1553 2127 1553 2352 1554 2127 1554 2353 1554 2353 1555 2127 1555 2712 1555 2186 1556 2128 1556 2547 1556 2186 1557 2547 1557 2129 1557 2129 1558 2547 1558 2130 1558 2129 1559 2130 1559 2131 1559 2131 1560 2130 1560 2132 1560 2131 1561 2132 1561 2355 1561 2139 1562 2140 1562 2133 1562 2133 1563 2140 1563 2134 1563 2133 1564 2134 1564 2135 1564 2135 1565 2134 1565 2553 1565 2135 1566 2553 1566 2183 1566 2183 1566 2553 1566 2136 1566 2183 1567 2136 1567 2137 1567 2137 1567 2136 1567 2552 1567 2137 1568 2552 1568 2184 1568 2184 1568 2552 1568 2138 1568 2184 1569 2138 1569 2186 1569 2186 1570 2138 1570 2128 1570 2139 1571 2361 1571 2140 1571 2140 1572 2361 1572 2810 1572 2810 6 2361 6 2813 6 2813 6 2361 6 2527 6 2813 6 2527 6 2141 6 2141 6 2527 6 2525 6 2141 6 2525 6 2142 6 2142 6 2525 6 2143 6 2142 6 2143 6 2740 6 2740 6 2143 6 2523 6 2144 21 2371 21 2145 21 2145 21 2371 21 2146 21 2145 21 2146 21 2147 21 2147 21 2146 21 2372 21 2147 21 2372 21 2148 21 2148 21 2372 21 2149 21 2150 6 2764 6 2152 6 2152 6 2764 6 2151 6 2152 6 2151 6 2381 6 2381 6 2151 6 2153 6 2381 6 2153 6 2154 6 2154 6 2153 6 2767 6 2484 1573 2155 1573 2156 1573 2156 1574 2155 1574 2157 1574 2156 1575 2157 1575 2486 1575 2486 1576 2157 1576 2158 1576 2486 1577 2158 1577 2159 1577 2159 1578 2158 1578 2863 1578 2159 1579 2863 1579 2489 1579 2489 1580 2863 1580 2862 1580 2489 1581 2862 1581 2160 1581 2160 1582 2862 1582 2855 1582 2160 1583 2855 1583 2487 1583 2487 1584 2855 1584 2857 1584 2487 1585 2857 1585 2488 1585 2488 1586 2857 1586 2161 1586 2488 1587 2161 1587 2162 1587 2162 1588 2161 1588 2859 1588 2162 1589 2859 1589 2483 1589 2483 1590 2859 1590 2861 1590 2483 1591 2861 1591 2482 1591 2482 1592 2861 1592 2163 1592 2482 1593 2163 1593 2164 1593 2164 1594 2163 1594 2854 1594 2164 1595 2854 1595 2484 1595 2484 1596 2854 1596 2155 1596 2165 960 2166 960 2513 960 2433 960 2431 960 2167 960 2347 960 2168 960 2348 960 2344 960 2169 960 2104 960 2521 960 2063 960 2522 960 2170 960 2221 960 2304 960 2046 960 2296 960 2044 960 2171 960 2172 960 2311 960 2018 960 2244 960 2173 960 2174 960 2023 960 2240 960 2504 1597 1987 1597 2217 1597 2175 960 2330 960 2213 960 2176 960 2198 960 2209 960 1995 960 1993 960 2459 960 1964 960 1962 960 2177 960 1964 960 2177 960 2519 960 2360 960 2178 960 2526 960 2526 1598 2178 1598 2520 1598 2180 960 1948 960 2360 960 2360 960 1948 960 2179 960 2360 1599 2179 1599 2178 1599 2133 960 2135 960 2180 960 2180 1600 2135 1600 2183 1600 2180 1601 2183 1601 1946 1601 1946 960 2183 960 1945 960 2181 960 1951 960 2356 960 2356 1602 1951 1602 2182 1602 2183 960 2137 960 1945 960 1945 1603 2137 1603 2184 1603 1945 1604 2184 1604 2185 1604 2185 960 2184 960 2186 960 2185 960 2186 960 2187 960 2187 960 2186 960 2182 960 2355 960 2356 960 2131 960 2131 1605 2356 1605 2182 1605 2131 960 2182 960 2129 960 2129 1606 2182 1606 2186 1606 2188 960 2189 960 2356 960 2356 1607 2189 1607 1955 1607 2356 1608 1955 1608 2181 1608 1958 960 2496 960 2190 960 2506 960 1961 960 2513 960 2513 960 1961 960 2193 960 2502 960 2191 960 1956 960 1956 960 2191 960 2513 960 1956 960 2513 960 2192 960 2192 1609 2513 1609 2193 1609 2196 1610 2194 1610 2195 1610 2195 960 2194 960 2204 960 2195 1611 2204 1611 2207 1611 1995 960 2459 960 2196 960 2067 960 2209 960 2197 960 2197 960 2209 960 2198 960 2197 960 2198 960 2065 960 2065 960 2198 960 2176 960 2065 960 2176 960 2069 960 2069 1612 2176 1612 2199 1612 2069 960 2199 960 2200 960 2200 1613 2199 1613 2201 1613 2200 960 2201 960 2202 960 2202 1614 2201 1614 2203 1614 2202 960 2203 960 2070 960 2070 1615 2203 1615 2205 1615 2070 960 2205 960 2204 960 2204 960 2205 960 2206 960 2204 1616 2206 1616 2207 1616 2068 960 1980 960 2067 960 2067 1617 1980 1617 2208 1617 2067 1618 2208 1618 2209 1618 2175 960 2213 960 2215 960 2210 1619 2211 1619 2524 1619 2524 1620 2211 1620 2212 1620 2524 960 2212 960 2213 960 2213 960 2212 960 2214 960 2213 1621 2214 1621 2215 1621 2515 960 2517 960 2216 960 2216 960 2517 960 2310 960 2216 960 2310 960 2219 960 1987 960 1989 960 2217 960 2217 960 1989 960 2218 960 2217 960 2218 960 2310 960 2310 960 2218 960 1991 960 2310 1622 1991 1622 2219 1622 2503 960 2307 960 2220 960 2220 960 2307 960 2304 960 2304 1623 2221 1623 2220 1623 2220 960 2221 960 2222 960 2220 960 2222 960 2223 960 2223 960 2222 960 2224 960 2223 960 2224 960 1993 960 1993 1624 2224 1624 2225 1624 1993 960 2225 960 2459 960 3311 960 3310 960 2227 960 3307 1625 3306 1625 2226 1625 2226 1626 3306 1626 3302 1626 2226 960 3302 960 2354 960 3311 960 2227 960 3313 960 3302 960 3304 960 2354 960 2354 1627 3304 1627 3305 1627 2354 1628 3305 1628 2348 1628 2348 1629 3305 1629 3315 1629 2348 1630 3315 1630 3314 1630 2351 1631 3308 1631 2230 1631 3310 960 3309 960 2227 960 2227 1632 3309 1632 2228 1632 2227 960 2228 960 2229 960 3307 960 2226 960 2230 960 2230 960 2226 960 2119 960 2230 1633 2119 1633 2351 1633 2231 960 2027 960 2429 960 2429 1634 2027 1634 2028 1634 2022 1635 2088 1635 2023 1635 2023 960 2088 960 2087 960 2023 960 2087 960 2240 960 2429 1636 2089 1636 2231 1636 2231 960 2089 960 2092 960 2231 960 2092 960 2025 960 2025 1637 2092 1637 2093 1637 2025 960 2093 960 2232 960 2232 960 2093 960 2233 960 2232 960 2233 960 2022 960 2022 1638 2233 1638 2234 1638 2022 960 2234 960 2088 960 2438 960 2235 960 2421 960 2016 960 2015 960 2236 960 2015 960 2237 960 2236 960 2236 1639 2237 1639 2238 1639 2236 1640 2238 1640 2240 1640 2240 960 2238 960 2239 960 2240 1641 2239 1641 2174 1641 2242 960 2241 960 2430 960 2242 960 2430 960 2243 960 2173 960 2244 960 2245 960 2245 960 2244 960 2442 960 2245 1642 2442 1642 2246 1642 2247 1643 2426 1643 2085 1643 2247 1644 2085 1644 2248 1644 2248 960 2085 960 2086 960 2248 1645 2086 1645 2255 1645 2427 960 2249 960 2424 960 2424 1646 2249 1646 2250 1646 2424 1647 2250 1647 2030 1647 2262 960 2251 960 2252 960 2252 1648 2251 1648 2253 1648 2252 960 2253 960 2254 960 2255 1649 2086 1649 2256 1649 2256 960 2086 960 2082 960 2256 960 2082 960 2257 960 2257 960 2082 960 2083 960 2257 960 2083 960 2258 960 2258 1650 2083 1650 2259 1650 2258 1651 2259 1651 2260 1651 2260 960 2259 960 2261 960 2260 960 2261 960 2262 960 2262 1652 2261 1652 2079 1652 2262 1653 2079 1653 2251 1653 2254 960 2253 960 2263 960 2263 1654 2253 1654 2264 1654 2263 960 2264 960 2265 960 2265 960 2264 960 2073 960 2265 960 2073 960 2266 960 2267 960 2268 960 2073 960 2073 1655 2268 1655 2269 1655 2073 1656 2269 1656 2266 1656 2444 960 2276 960 2277 960 2277 960 2270 960 2444 960 2444 1657 2270 1657 2029 1657 2444 960 2029 960 2443 960 2443 960 2029 960 2271 960 2443 960 2271 960 2272 960 2439 960 2031 960 2273 960 2273 960 2031 960 2274 960 2273 960 2274 960 2276 960 2276 1658 2274 1658 2275 1658 2276 1659 2275 1659 2277 1659 2190 960 2498 960 2485 960 2286 960 2190 960 2278 960 2278 960 2190 960 2485 960 2278 960 2485 960 2279 960 2279 1660 2485 1660 2280 1660 2281 960 2458 960 2282 960 2282 960 2458 960 2283 960 2311 960 2172 960 2284 960 2284 1661 2172 1661 2285 1661 2284 1662 2285 1662 2440 1662 2441 1663 2440 1663 2413 1663 2286 960 2287 960 2190 960 2190 1664 2287 1664 2288 1664 2190 960 2288 960 2291 960 2291 1665 2288 1665 2289 1665 2289 960 2290 960 2291 960 2291 1666 2290 1666 2292 1666 2291 960 2292 960 2311 960 2311 1667 2292 1667 2293 1667 2311 960 2293 960 2171 960 2046 960 2294 960 2295 960 2295 960 2294 960 2284 960 2424 960 2300 960 2302 960 2044 960 2296 960 2297 960 2297 960 2296 960 2437 960 2297 1668 2437 1668 2041 1668 2041 960 2437 960 2421 960 2041 960 2421 960 2040 960 2037 960 2038 960 2298 960 2298 960 2038 960 2299 960 2298 960 2299 960 2300 960 2300 960 2299 960 2301 960 2300 960 2301 960 2302 960 2303 960 2037 960 2444 960 2318 960 2304 960 2447 960 2057 1669 2058 1669 2305 1669 2305 960 2058 960 2306 960 2305 960 2306 960 2307 960 2307 1670 2306 1670 2308 1670 2307 960 2308 960 2304 960 2304 1671 2308 1671 2061 1671 2304 1672 2061 1672 2447 1672 2309 960 2310 960 2513 960 2309 960 2513 960 2055 960 2294 1673 2047 1673 2284 1673 2284 1674 2047 1674 2049 1674 2284 960 2049 960 2311 960 2311 1675 2049 1675 2312 1675 2311 960 2312 960 2291 960 2291 1676 2312 1676 2051 1676 2291 960 2051 960 2190 960 2190 1677 2051 1677 2054 1677 2190 960 2054 960 2313 960 2313 960 2054 960 2314 960 2313 960 2314 960 2315 960 2445 960 2325 960 2318 960 2318 1678 2325 1678 2316 1678 2316 1679 2317 1679 2318 1679 2318 960 2317 960 2319 960 2318 960 2319 960 2304 960 2304 960 2319 960 2320 960 2304 1680 2320 1680 2170 1680 2329 960 2321 960 2460 960 2460 960 2321 960 2322 960 2460 960 2322 960 2462 960 2462 1681 2322 1681 2323 1681 2462 960 2323 960 2445 960 2445 1662 2323 1662 2324 1662 2445 1682 2324 1682 2325 1682 2225 960 2326 960 2459 960 2459 960 2326 960 2327 960 2459 960 2327 960 2460 960 2460 1683 2327 1683 2328 1683 2460 1684 2328 1684 2329 1684 2521 960 2213 960 2068 960 2068 960 2213 960 2330 960 2068 1685 2330 1685 1980 1685 2335 960 2332 960 2331 960 2331 960 2332 960 2333 960 2331 960 2333 960 2429 960 2429 960 2333 960 2094 960 2429 1686 2094 1686 2089 1686 2337 960 2334 960 2335 960 2335 960 2334 960 2097 960 2335 960 2097 960 2332 960 2169 960 3295 960 2432 960 2336 960 2338 960 2337 960 2337 960 2338 960 2101 960 2337 1687 2101 1687 2334 1687 2336 960 2339 960 2338 960 2338 1688 2339 1688 2340 1688 2338 1689 2340 1689 2102 1689 3295 960 2341 960 2432 960 2432 1690 2341 1690 2342 1690 2432 960 2342 960 2337 960 2337 1691 2342 1691 3294 1691 2337 1692 3294 1692 2336 1692 2340 1693 2343 1693 2102 1693 2102 1694 2343 1694 3297 1694 2102 960 3297 960 2104 960 2104 1695 3297 1695 3296 1695 2104 1696 3296 1696 2344 1696 2432 960 2345 960 2346 960 2169 960 2432 960 2104 960 2104 960 2432 960 2346 960 2104 960 2346 960 2105 960 2347 960 2348 960 2349 960 3314 1697 3313 1697 2348 1697 2348 960 3313 960 2227 960 2348 960 2227 960 2349 960 2349 960 2227 960 2229 960 2349 1698 2229 1698 2350 1698 2350 960 2229 960 2116 960 2350 960 2116 960 2115 960 2228 1699 3308 1699 2229 1699 2229 1700 3308 1700 2351 1700 2229 960 2351 960 2116 960 2116 1701 2351 1701 2117 1701 2352 960 2353 960 2354 960 2354 1702 2353 1702 2122 1702 2354 960 2122 960 2226 960 2226 1703 2122 1703 2121 1703 2226 960 2121 960 2119 960 2355 960 2124 960 2356 960 2356 960 2124 960 2357 960 2356 960 2357 960 2358 960 2358 960 2357 960 2352 960 2358 960 2352 960 2359 960 2359 960 2352 960 2354 960 2180 960 2360 960 2133 960 2133 1704 2360 1704 2361 1704 2133 1705 2361 1705 2139 1705 2481 960 2362 960 2492 960 2470 960 2363 960 2472 960 2371 1706 2364 1706 2471 1706 2471 1707 2364 1707 2469 1707 2150 1708 2152 1708 2365 1708 2365 960 2152 960 2455 960 2365 960 2455 960 2366 960 2366 1709 2455 1709 2367 1709 2363 960 2368 960 2472 960 2472 1710 2368 1710 2369 1710 2472 960 2369 960 2370 960 2371 960 2471 960 2146 960 2146 960 2471 960 2374 960 2146 960 2374 960 2372 960 2149 960 2372 960 2373 960 2373 960 2372 960 2374 960 2373 960 2374 960 2375 960 2375 1711 2374 1711 2376 1711 2451 1712 2377 1712 2109 1712 2109 1713 2377 1713 2378 1713 2109 960 2378 960 2388 960 2388 1714 2378 1714 2379 1714 2388 1715 2379 1715 2389 1715 2383 1716 2380 1716 2394 1716 2394 1717 2380 1717 2391 1717 2452 960 2381 960 2154 960 2448 1718 2450 1718 2382 1718 2383 960 2384 960 2380 960 2380 1719 2384 1719 2376 1719 2380 960 2376 960 2385 960 2385 1720 2376 1721 2374 1722 2385 960 2374 960 2386 960 2386 1723 2374 1723 2388 1723 2386 1724 2388 1724 2387 1724 2387 960 2388 960 2389 960 2382 1725 2390 1725 2448 1725 2448 1726 2390 1726 2392 1726 2448 960 2392 960 2391 960 2391 1727 2392 1727 2393 1727 2391 960 2393 960 2394 960 2154 960 2395 960 2452 960 2452 1728 2395 1728 2396 1728 2452 960 2396 960 2450 960 2400 1729 2430 1729 2397 1729 2397 960 2430 960 2398 960 2418 960 2416 960 2399 960 2400 960 2401 960 2430 960 2430 1730 2401 1730 2402 1730 2430 1731 2402 1732 2416 1733 2416 1734 2402 1734 2403 1734 2416 1735 2403 1735 2399 1735 2399 960 2404 960 2418 960 2418 1736 2404 1736 2405 1736 2418 960 2405 960 2412 960 2412 1737 2405 1737 2406 1737 2412 1738 2406 1738 2410 1738 2411 960 2407 960 2441 960 2441 1739 2407 1739 2408 1739 2441 960 2408 960 2398 960 2398 1740 2408 1740 2409 1740 2398 1741 2409 1741 2397 1741 2410 960 2411 960 2412 960 2412 1742 2411 1742 2441 1742 2412 960 2441 960 2458 960 2458 960 2441 960 2413 960 2458 1743 2413 1743 2283 1743 2414 960 2529 960 2416 960 2416 1744 2529 1744 2415 1744 2416 1745 2415 1745 2431 1745 2415 960 2530 960 2431 960 2431 1746 2530 1746 2532 1746 2431 960 2532 960 2167 960 2167 1747 2532 1747 2533 1747 2167 1748 2533 1748 2436 1748 2535 960 2456 960 2417 960 2457 1749 2538 1749 2412 1749 2412 1750 2538 1750 2419 1750 2412 960 2419 960 2418 960 2418 1751 2419 1751 2420 1751 2418 960 2420 960 2416 960 2416 1752 2420 1752 2528 1752 2416 1753 2528 1753 2414 1753 1997 1754 2428 1754 2085 1754 2005 960 2014 960 2236 960 2236 960 2014 960 2421 960 2236 960 2421 960 2016 960 2016 1755 2421 1755 2235 1755 2014 960 2013 960 2421 960 2421 960 2013 960 2422 960 2421 1756 2422 1756 2423 1756 2302 960 2040 960 2424 960 2424 960 2040 960 2421 960 2424 960 2421 960 2009 960 2009 960 2421 960 2423 960 2009 1757 2011 1757 2424 1757 2424 1758 2011 1758 2425 1758 2424 1759 2425 1759 2006 1759 2426 1760 2427 1760 2085 1760 2085 960 2427 960 2424 960 2085 960 2424 960 1997 960 1997 960 2424 960 2006 960 2428 1761 2000 1761 2085 1761 2085 1762 2000 1762 2001 1762 2085 960 2001 960 2236 960 2236 1763 2001 1763 2003 1763 2236 1764 2003 1764 2005 1764 2028 1765 2243 1765 2429 1765 2429 960 2243 960 2430 960 2429 960 2430 960 2331 960 2331 960 2430 960 2416 960 2331 960 2416 960 2335 960 2335 960 2416 960 2431 960 2335 960 2431 960 2337 960 2337 960 2431 960 2433 960 2337 960 2433 960 2432 960 2345 960 2432 960 2434 960 2434 960 2432 960 2433 960 2434 960 2433 960 2435 960 2435 960 2433 960 2167 960 2435 960 2167 960 2417 960 2417 960 2167 960 2436 960 2417 1766 2436 1766 2535 1766 2046 960 2295 960 2296 960 2296 960 2295 960 2442 960 2296 960 2442 960 2437 960 2437 960 2442 960 2244 960 2437 960 2244 960 2421 960 2421 960 2244 960 2018 960 2421 960 2018 960 2438 960 2037 1767 2298 1767 2444 1767 2444 960 2298 960 2300 960 2444 960 2300 960 2276 960 2276 960 2300 960 2424 960 2276 960 2424 960 2273 960 2273 960 2424 960 2030 960 2273 960 2030 960 2439 960 2440 960 2441 960 2284 960 2284 960 2441 960 2398 960 2284 960 2398 960 2295 960 2295 960 2398 960 2430 960 2295 960 2430 960 2442 960 2442 1768 2430 1769 2241 1770 2442 960 2241 960 2246 960 2443 960 2462 960 2444 960 2444 960 2462 960 2445 960 2444 960 2445 960 2303 960 2303 960 2445 960 2318 960 2303 960 2318 960 2446 960 2446 960 2318 960 2447 960 2448 960 2449 960 2450 960 2450 1771 2449 1771 2451 1771 2450 960 2451 960 2452 960 2452 1772 2451 1772 2109 1772 2452 960 2109 960 2108 960 2152 960 2381 960 2455 960 2455 960 2381 960 2452 960 2455 960 2452 960 2453 960 2453 960 2452 960 2108 960 2453 960 2108 960 2454 960 2362 960 2367 960 2492 960 2492 1773 2367 1773 2455 1773 2492 960 2455 960 2493 960 2493 960 2455 960 2453 960 2493 960 2453 960 2494 960 2494 960 2453 960 2454 960 2494 960 2454 960 2495 960 2456 960 2457 960 2417 960 2417 960 2457 960 2412 960 2417 960 2412 960 2491 960 2491 960 2412 960 2458 960 2491 960 2458 960 2485 960 2485 960 2458 960 2281 960 2485 1774 2281 1774 2280 1774 2196 1775 2459 1775 2194 1775 2194 960 2459 960 2460 960 2194 960 2460 960 2461 960 2461 960 2460 960 2462 960 2461 960 2462 960 2075 960 2075 960 2462 960 2443 960 2075 960 2443 960 2267 960 2267 960 2443 960 2272 960 2267 1776 2272 1776 2268 1776 2463 960 2388 960 2501 960 2501 960 2388 960 2374 960 2501 960 2374 960 2464 960 2464 960 2374 960 2471 960 2464 960 2471 960 2500 960 2465 960 2466 960 2472 960 2472 1777 2466 1777 2467 1777 2472 1778 2467 1778 2468 1778 2469 1779 2470 1779 2471 1779 2471 960 2470 960 2472 960 2471 960 2472 960 2500 960 2500 960 2472 960 2468 960 2500 1780 2468 1780 2475 1780 2476 1781 2499 1781 2473 1781 2473 960 2499 960 2500 960 2473 960 2500 960 2474 960 2474 960 2500 960 2475 960 2476 960 2477 960 2499 960 2499 1782 2477 1782 2478 1782 2499 960 2478 960 2490 960 2490 1783 2478 1783 2479 1783 2490 1784 2479 1784 2480 1784 2480 1785 2465 1785 2490 1785 2490 1786 2465 1786 2472 1786 2490 960 2472 960 2492 960 2492 960 2472 960 2370 960 2492 1787 2370 1787 2481 1787 2164 960 2498 960 2482 960 2482 1788 2498 1789 2499 1790 2482 960 2499 960 2483 960 2483 960 2499 960 2162 960 2164 960 2484 960 2498 960 2498 1791 2484 1791 2156 1791 2498 960 2156 960 2485 960 2485 1792 2156 1792 2486 1792 2485 1793 2486 1793 2159 1793 2489 960 2160 960 2490 960 2490 1794 2160 1794 2487 1794 2490 960 2487 960 2499 960 2499 1795 2487 1795 2488 1795 2499 1796 2488 1796 2162 1796 2159 960 2489 960 2485 960 2485 1797 2489 1797 2490 1797 2485 960 2490 960 2491 960 2491 960 2490 960 2492 960 2491 960 2492 960 2417 960 2417 960 2492 960 2493 960 2417 960 2493 960 2435 960 2435 960 2493 960 2494 960 2435 960 2494 960 2434 960 2434 960 2494 960 2495 960 2434 960 2495 960 2345 960 2496 1798 2497 1798 2190 1798 2190 960 2497 960 2188 960 2190 1799 2188 1800 2498 1801 2498 960 2188 960 2356 960 2498 960 2356 960 2499 960 2499 960 2356 960 2358 960 2499 960 2358 960 2500 960 2500 960 2358 960 2359 960 2500 960 2359 960 2464 960 2464 960 2359 960 2354 960 2464 960 2354 960 2501 960 2501 960 2354 960 2348 960 2501 960 2348 960 2463 960 2463 960 2348 960 2168 960 2315 1802 2055 1802 2313 1802 2313 960 2055 960 2513 960 2313 960 2513 960 2190 960 2190 960 2513 960 2191 960 2190 960 2191 960 1958 960 1958 960 2191 960 2502 960 2503 1803 2504 1803 2307 1803 2307 960 2504 960 2217 960 2307 960 2217 960 2305 960 2305 960 2217 960 2310 960 2305 960 2310 960 2057 960 2057 960 2310 960 2309 960 2513 960 2166 960 2506 960 2506 960 2166 960 2505 960 2506 960 2505 960 1965 960 1970 960 2517 960 1968 960 1968 960 2517 960 2506 960 1968 960 2506 960 1967 960 1967 960 2506 960 1965 960 1970 1804 2507 1804 2517 1804 2517 1805 2507 1805 2508 1805 2517 960 2508 960 2310 960 2310 960 2508 960 2509 960 2310 1806 2509 1806 2510 1806 2510 1807 2511 1807 2310 1807 2310 1808 2511 1808 2512 1808 2310 960 2512 960 2513 960 2513 1809 2512 1809 2514 1809 2513 1810 2514 1810 2165 1810 2515 960 2516 960 2517 960 2517 960 2516 960 2518 960 2517 960 2518 960 2506 960 2506 960 2518 960 2177 960 2506 960 2177 960 1961 960 1961 960 2177 960 1962 960 2516 960 2210 960 2518 960 2518 960 2210 960 2524 960 2518 960 2524 960 2177 960 2177 960 2524 960 2526 960 2177 960 2526 960 2519 960 2519 960 2526 960 2520 960 2521 960 2522 960 2213 960 2213 960 2522 960 2523 960 2213 960 2523 960 2524 960 2524 960 2523 960 2143 960 2524 960 2143 960 2526 960 2526 960 2143 960 2525 960 2526 960 2525 960 2360 960 2360 960 2525 960 2527 960 2360 960 2527 960 2361 960 2528 1811 2539 1811 2414 1811 2414 1812 2539 1812 2798 1812 2414 1813 2798 1813 2529 1813 2529 1814 2798 1814 2801 1814 2529 1815 2801 1815 2415 1815 2415 1816 2801 1816 2803 1816 2415 1817 2803 1817 2530 1817 2530 1818 2803 1818 2531 1818 2530 1819 2531 1819 2532 1819 2532 1820 2531 1820 2797 1820 2532 1821 2797 1821 2533 1821 2533 1822 2797 1822 2436 1822 2436 1823 2797 1823 2534 1823 2436 1824 2534 1824 2535 1824 2534 1824 2874 1824 2535 1824 2535 1825 2874 1825 2536 1825 2535 1826 2536 1826 2456 1826 2456 1827 2536 1827 2808 1827 2456 1828 2808 1828 2457 1828 2457 1829 2808 1829 2806 1829 2457 1830 2806 1830 2538 1830 2538 1831 2806 1831 2537 1831 2538 1832 2537 1832 2419 1832 2419 1833 2537 1833 2420 1833 2420 1833 2537 1833 2805 1833 2420 1834 2805 1834 2528 1834 2528 1835 2805 1835 2804 1835 2528 1836 2804 1836 2539 1836 2157 1837 2155 1837 2860 1837 2540 590 2713 590 2858 590 2817 590 2816 590 2818 590 2874 590 2534 590 2885 590 2541 590 2542 590 2761 590 2573 590 2543 590 2066 590 2106 590 2897 590 2726 590 2705 590 2694 590 2693 590 2707 590 2882 590 2881 590 2045 590 2901 590 2544 590 2578 590 2570 590 2569 590 1981 590 2566 590 2738 590 1950 590 1949 590 2811 590 2548 590 2545 590 2549 590 2550 590 1952 590 2128 590 2128 1838 1952 1838 2546 1838 2128 590 2546 590 2547 590 2547 1839 2546 1839 2548 1839 2547 590 2548 590 2130 590 2130 590 2548 590 2549 590 2130 1840 2549 1840 2132 1840 2132 590 2549 590 2125 590 2128 590 2138 590 2550 590 2550 1841 2138 1841 2552 1841 2550 590 2552 590 2551 590 2551 1842 2552 1842 2136 1842 2551 1843 2136 1843 1947 1843 1947 1844 2136 1844 2553 1844 1947 1845 2553 1845 2134 1845 1963 590 2554 590 2812 590 2812 1846 2554 1846 2555 1846 2812 590 2555 590 2811 590 2811 1847 2555 1847 2556 1847 2811 590 2556 590 1950 590 2557 590 2558 590 2826 590 2826 590 2558 590 2559 590 2826 590 2559 590 2560 590 2560 590 2559 590 1957 590 1957 1848 2561 1848 2560 1848 2560 1849 2561 1849 1959 1849 2560 590 1959 590 2822 590 2822 590 1959 590 1960 590 2822 590 1960 590 2820 590 2545 590 1953 590 2549 590 2549 590 1953 590 1954 590 2549 590 1954 590 2860 590 2827 590 2825 590 2562 590 2562 590 2825 590 2860 590 2562 1850 2860 1850 2563 1850 2563 590 2860 590 1954 590 2564 590 2815 590 2814 590 2565 1851 1986 1851 2816 1851 2566 590 2567 590 2738 590 2738 590 2567 590 2568 590 2738 1852 2568 1852 2564 1852 2066 590 2543 590 2576 590 2569 590 2570 590 2572 590 2572 1853 2570 1853 2571 1853 2572 590 2571 590 2064 590 2064 1854 2571 1854 2573 1854 2573 590 2571 590 2574 590 2573 590 2574 590 2543 590 2543 590 2574 590 2575 590 2543 590 2575 590 2576 590 2576 1855 2575 1855 1982 1855 2576 590 1982 590 2577 590 2578 590 2569 590 2579 590 2579 1856 2569 1856 2071 1856 2579 590 2071 590 2580 590 2580 590 2071 590 2581 590 2580 590 2581 590 2582 590 2883 590 1992 590 1994 590 2583 590 2584 590 2581 590 2581 1857 2584 1857 2585 1857 2581 1858 2585 1858 2582 1858 2586 590 2588 590 2587 590 2587 1859 2588 1859 2698 1859 2698 590 2702 590 2589 590 2589 590 2702 590 2831 590 2589 590 2831 590 1988 590 1988 590 2831 590 2830 590 1984 590 1983 590 2591 590 1983 590 2590 590 2591 590 2591 1860 2590 1860 2592 1860 2591 590 2592 590 2829 590 2829 590 2592 590 1990 590 2829 590 1990 590 2828 590 2606 1861 2593 1861 2719 1861 2719 1862 2594 1862 2720 1862 2720 1863 2594 1863 2595 1863 2596 1864 2597 1864 2715 1864 2715 1865 2597 1865 2598 1865 2715 590 2598 590 2601 590 2601 1866 2598 1866 2599 1866 2601 1867 2599 1867 2600 1867 2600 1868 2602 1868 2601 1868 2601 590 2602 590 2603 590 2601 590 2603 590 2718 590 2718 1869 2603 1869 2605 1869 2718 590 2605 590 2604 590 2604 1870 2605 1870 2607 1870 2604 590 2607 590 2606 590 2606 590 2607 590 2608 590 2606 1871 2608 1871 2593 1871 2017 590 2609 590 2898 590 2898 1872 2609 1872 2610 1872 2898 1873 2610 1873 2628 1873 2024 590 2611 590 2612 590 2612 590 2611 590 2613 590 2612 1874 2613 1874 2911 1874 2911 1875 2613 1875 2614 1875 2911 1876 2614 1876 2615 1876 2616 590 2026 590 2627 590 2627 1877 2026 1877 2619 1877 2622 590 2617 590 2021 590 2021 1878 2617 1878 2091 1878 2021 590 2091 590 2618 590 2618 1879 2091 1879 2619 1879 2620 590 2627 590 2621 590 2621 590 2627 590 2619 590 2621 590 2619 590 2090 590 2090 590 2619 590 2091 590 2612 590 2084 590 2024 590 2024 1880 2084 1880 2623 1880 2024 590 2623 590 2622 590 2622 590 2623 590 2624 590 2622 590 2624 590 2617 590 2892 1881 2625 1881 2627 1881 2627 1882 2625 1882 2626 1882 2627 590 2626 590 2616 590 2628 590 2020 590 2899 590 2899 590 2020 590 2019 590 2899 590 2019 590 2900 590 2900 590 2019 590 2629 590 2658 590 2880 590 2630 590 2630 590 2880 590 2074 590 2630 1883 2074 1883 2631 1883 2631 590 2074 590 2634 590 2651 590 2633 590 2632 590 2632 1884 2633 1884 2641 1884 2634 590 2074 590 2635 590 2635 590 2074 590 2072 590 2635 1885 2072 1885 2636 1885 2636 1886 2072 1886 2077 1886 2636 590 2077 590 2637 590 2637 1887 2077 1887 2078 1887 2637 590 2078 590 2638 590 2638 590 2078 590 2639 590 2638 1888 2639 1888 2640 1888 2640 590 2639 590 2080 590 2640 590 2080 590 2641 590 2641 590 2080 590 2081 590 2641 1889 2081 1889 2632 1889 2643 1890 2647 1890 2648 1890 2642 590 2644 590 2903 590 2643 590 2648 590 2650 590 2644 590 2645 590 2903 590 2903 1891 2645 1891 2034 1891 2903 590 2034 590 2643 590 2643 590 2034 590 2646 590 2643 1892 2646 1892 2647 1892 2648 1893 2649 1893 2650 1893 2650 1894 2649 1894 2652 1894 2650 590 2652 590 2651 590 2651 590 2652 590 2653 590 2651 590 2653 590 2633 590 2642 590 2905 590 2032 590 2032 590 2905 590 2033 590 2033 590 2905 590 2654 590 2654 590 2905 590 2655 590 2654 590 2655 590 2656 590 2656 590 2655 590 2657 590 2657 590 2655 590 2906 590 2657 1895 2906 1895 2661 1895 2658 1896 2659 1896 2878 1896 2878 590 2659 590 2660 590 2878 590 2660 590 2661 590 2662 590 2663 590 2888 590 2663 590 2664 590 2889 590 2889 1897 2664 1897 2689 1897 2864 1898 2665 1898 2865 1898 2866 590 2666 590 2867 590 2867 1899 2666 1899 2667 1899 2867 1900 2667 1900 2872 1900 2852 590 2825 590 2668 590 2668 590 2825 590 2669 590 2668 590 2669 590 2674 590 2690 590 2671 590 2670 590 2670 1901 2671 1901 2672 1901 2670 590 2672 590 2669 590 2669 1902 2672 1902 2673 1902 2669 590 2673 590 2674 590 2824 1903 2675 1903 2676 1903 2676 590 2675 590 2677 590 2676 590 2677 590 2825 590 2825 1904 2677 1904 2678 1904 2825 590 2678 590 2669 590 2059 590 2056 590 2591 590 2591 590 2056 590 2560 590 2695 590 2035 590 2693 590 2693 1905 2035 1905 2679 1905 2693 590 2679 590 2702 590 2702 1906 2679 1906 2680 1906 2702 590 2680 590 2831 590 2831 1907 2680 1907 2681 1907 2831 590 2681 590 2832 590 2832 590 2681 590 2060 590 2832 590 2060 590 2833 590 2906 590 2682 590 2695 590 2695 1908 2682 1908 2036 1908 2695 1909 2036 1909 2035 1909 2901 590 2045 590 2683 590 2045 590 2043 590 2683 590 2683 590 2043 590 2042 590 2683 590 2042 590 2898 590 2898 1910 2042 1910 2684 1910 2898 590 2684 590 2903 590 2903 1911 2684 1911 2685 1911 2903 590 2685 590 2904 590 2904 590 2685 590 2039 590 2904 590 2039 590 2686 590 2686 590 2039 590 2687 590 2686 590 2687 590 2688 590 2902 590 2890 590 2048 590 2048 590 2890 590 2889 590 2048 590 2889 590 2670 590 2670 590 2889 590 2689 590 2670 1912 2689 1912 2690 1912 2678 590 2053 590 2669 590 2669 1913 2053 1913 2691 1913 2669 590 2691 590 2670 590 2670 1914 2691 1914 2692 1914 2670 1915 2692 1915 2048 1915 2693 590 2694 590 2695 590 2695 590 2694 590 2696 590 2695 590 2696 590 2879 590 2588 590 2697 590 2698 590 2698 590 2697 590 2699 590 2698 590 2699 590 2702 590 2702 1916 2699 1916 2700 1916 2700 590 2701 590 2702 590 2702 1902 2701 1902 2703 1902 2702 590 2703 590 2693 590 2693 1901 2703 1901 2704 1901 2693 590 2704 590 2705 590 2587 590 1992 590 2586 590 2586 590 1992 590 2883 590 2586 590 2883 590 2706 590 2706 590 2883 590 2711 590 2707 590 2708 590 2882 590 2882 590 2708 590 2709 590 2882 590 2709 590 2883 590 2883 1917 2709 1917 2710 1917 2883 1918 2710 1918 2711 1918 2712 590 2127 590 2540 590 2540 590 2127 590 2126 590 2540 590 2126 590 2713 590 2713 590 2126 590 2125 590 2718 590 2714 590 2601 590 2601 590 2714 590 2120 590 2601 590 2120 590 2715 590 2715 590 2120 590 2123 590 2716 590 2717 590 2114 590 2118 590 2718 590 2114 590 2114 590 2718 590 2604 590 2114 590 2604 590 2716 590 2716 590 2604 590 2606 590 2716 590 2606 590 2113 590 2719 590 2720 590 2606 590 2606 590 2720 590 2112 590 2606 1919 2112 1919 2113 1919 2106 1920 2726 1920 2721 1920 2729 590 2722 590 2726 590 2894 590 2100 590 2724 590 2721 590 2726 590 2103 590 2103 590 2726 590 2722 590 2103 1921 2722 1921 2723 1921 2724 590 2725 590 2894 590 2894 1922 2725 1922 2727 1922 2894 1923 2727 1923 2726 1923 2726 1924 2727 1924 2728 1924 2726 1925 2728 1925 2729 1925 2723 1926 2730 1926 2103 1926 2103 1927 2730 1927 2731 1927 2103 590 2731 590 2099 590 2731 1928 2732 1928 2099 1928 2099 1929 2732 1929 2733 1929 2099 1930 2733 1930 2100 1930 2100 1931 2733 1931 2734 1931 2100 1932 2734 1932 2724 1932 2096 1933 2098 1933 2894 1933 2894 1934 2098 1934 2735 1934 2894 590 2735 590 2100 590 2620 590 2736 590 2627 590 2627 590 2736 590 2095 590 2627 590 2095 590 2893 590 2893 590 2095 590 2096 590 2893 590 2096 590 2737 590 2737 590 2096 590 2894 590 2738 590 2741 590 2739 590 1982 590 1981 590 2577 590 2577 1935 1981 1935 2738 1935 2577 590 2738 590 2062 590 2062 590 2738 590 2739 590 2564 590 2814 590 2738 590 2738 590 2814 590 2740 590 2738 590 2740 590 2741 590 2140 1936 2811 1936 2134 1936 2134 590 2811 590 1949 590 2134 590 1949 590 1947 590 2744 590 2742 590 2745 590 2764 590 2743 590 2765 590 2744 1937 2745 1937 2870 1937 2144 590 2145 590 2746 590 2746 590 2145 590 2836 590 2746 590 2836 590 2747 590 2747 590 2836 590 2835 590 2743 590 2748 590 2765 590 2765 1938 2748 1938 2749 1938 2765 1939 2749 1939 2869 1939 2749 1940 2750 1940 2869 1940 2869 1941 2750 1941 2751 1941 2869 1942 2751 1942 2871 1942 2756 1943 2779 1943 2757 1943 2769 590 2147 590 2148 590 2541 590 2761 590 2762 590 2772 590 2774 590 2752 590 2752 590 2774 590 2110 590 2752 590 2110 590 2753 590 2753 590 2110 590 2754 590 2755 1944 2766 1944 2763 1944 2756 590 2757 590 2758 590 2758 590 2757 590 2759 590 2758 590 2759 590 2761 590 2761 1945 2759 1945 2760 1945 2761 1946 2760 1946 2762 1946 2755 590 2763 590 2542 590 2764 590 2765 590 2151 590 2151 590 2765 590 2763 590 2151 590 2763 590 2153 590 2153 590 2763 590 2766 590 2153 1947 2766 1947 2767 1947 2148 590 2768 590 2769 590 2769 1948 2768 1948 2770 1948 2769 1949 2770 1949 2771 1949 2772 590 2773 590 2774 590 2774 1950 2773 1950 2775 1950 2774 1951 2775 1951 2763 1951 2776 590 2769 590 2777 590 2777 590 2769 590 2771 590 2777 1952 2771 1952 2756 1952 2756 1953 2771 1953 2778 1953 2756 1954 2778 1954 2779 1954 2763 590 2775 590 2542 590 2542 1955 2775 1955 2780 1955 2542 1956 2780 1956 2761 1956 2789 590 2781 590 2788 590 2782 590 2783 590 2784 590 2782 1957 2784 1957 2799 1957 2783 590 2785 590 2784 590 2784 1958 2785 1958 2786 1958 2784 1959 2786 1959 2781 1959 2781 1960 2786 1960 2787 1960 2781 1961 2787 1961 2788 1961 2788 1962 2790 1962 2789 1962 2789 1963 2790 1963 2791 1963 2789 590 2791 590 2888 590 2888 1964 2791 1964 2792 1964 2800 590 2807 590 2796 590 2792 1965 2793 1965 2888 1965 2888 1966 2793 1966 2794 1966 2888 1967 2794 1967 2807 1967 2807 1968 2794 1968 2795 1968 2807 1969 2795 1969 2796 1969 2797 1970 2531 1970 2802 1970 2800 1971 2798 1971 2539 1971 2798 590 2800 590 2801 590 2796 590 2799 590 2800 590 2800 590 2799 590 2784 590 2800 590 2784 590 2801 590 2801 590 2784 590 2802 590 2801 590 2802 590 2803 590 2803 590 2802 590 2531 590 2539 590 2804 590 2800 590 2800 1972 2804 1972 2805 1972 2800 590 2805 590 2807 590 2807 1973 2805 1973 2537 1973 2537 590 2806 590 2807 590 2807 1974 2806 1974 2808 1974 2807 590 2808 590 2809 590 2809 1975 2808 1975 2536 1975 2140 1976 2810 1976 2811 1976 2811 590 2810 590 2813 590 2811 590 2813 590 2812 590 2812 590 2813 590 2141 590 2812 590 2141 590 2814 590 2814 590 2141 590 2142 590 2814 590 2142 590 2740 590 2815 590 2565 590 2814 590 2814 590 2565 590 2816 590 2814 590 2816 590 2812 590 2812 590 2816 590 2817 590 2812 590 2817 590 1963 590 1974 590 1973 590 2591 590 2591 590 1973 590 2818 590 2591 590 2818 590 1984 590 1984 590 2818 590 2816 590 1984 590 2816 590 1985 590 1985 590 2816 590 1986 590 1973 590 1972 590 2818 590 2818 1977 1972 1977 1971 1977 2818 590 1971 590 2819 590 2822 1978 1969 1978 1966 1978 1978 590 1977 590 2560 590 2560 1979 1977 1979 1976 1979 2560 590 1976 590 2591 590 2591 1980 1976 1980 1975 1980 2591 590 1975 590 1974 590 2819 1981 1969 1981 2818 1981 2818 590 1969 590 2822 590 2818 590 2822 590 2817 590 2817 590 2822 590 2820 590 2817 590 2820 590 1963 590 1966 590 2821 590 2822 590 2822 1982 2821 1982 2823 1982 2822 590 2823 590 2560 590 2560 590 2823 590 1979 590 2560 1983 1979 1983 1978 1983 2056 1984 2824 1984 2560 1984 2560 590 2824 590 2676 590 2560 590 2676 590 2826 590 2826 590 2676 590 2825 590 2826 590 2825 590 2557 590 2557 590 2825 590 2827 590 2828 590 2830 590 2829 590 2829 590 2830 590 2831 590 2829 590 2831 590 2591 590 2591 590 2831 590 2832 590 2591 590 2832 590 2059 590 2059 1985 2832 1985 2833 1985 2111 590 2769 590 2110 590 2110 1986 2769 1986 2776 1986 2110 1987 2776 1987 2754 1987 2145 590 2147 590 2836 590 2836 590 2147 590 2769 590 2836 590 2769 590 2834 590 2834 590 2769 590 2111 590 2834 590 2111 590 2838 590 2742 1988 2835 1988 2745 1988 2745 1989 2835 1989 2836 1989 2745 590 2836 590 2837 590 2837 590 2836 590 2834 590 2837 590 2834 590 2720 590 2720 590 2834 590 2838 590 2720 590 2838 590 2112 590 2851 590 2839 590 2858 590 2845 590 2840 590 2842 590 2842 1990 2840 1990 2841 1990 2842 1991 2841 1991 2843 1991 2595 1864 2596 1864 2720 1864 2720 590 2596 590 2715 590 2720 590 2715 590 2837 590 2837 590 2715 590 2842 590 2837 590 2842 590 2745 590 2745 590 2842 590 2843 590 2745 1992 2843 1992 2844 1992 2123 1993 2712 1993 2715 1993 2715 1994 2712 1994 2540 1994 2715 590 2540 590 2842 590 2842 590 2540 590 2858 590 2842 590 2858 590 2845 590 2845 590 2858 590 2839 590 2844 590 2846 590 2745 590 2745 1995 2846 1995 2847 1995 2745 590 2847 590 2856 590 2847 590 2848 590 2856 590 2856 1996 2848 1996 2849 1996 2856 590 2849 590 2858 590 2858 1997 2849 1997 2850 1997 2858 1998 2850 1998 2851 1998 2852 590 2853 590 2825 590 2825 1999 2853 1999 2665 1999 2825 590 2665 590 2860 590 2860 590 2665 590 2864 590 2860 590 2864 590 2157 590 2155 2000 2854 2000 2860 2000 2860 2001 2854 2001 2163 2001 2860 2002 2163 2002 2861 2002 2855 590 2856 590 2857 590 2857 590 2856 590 2858 590 2857 590 2858 590 2161 590 2161 590 2858 590 2859 590 2125 590 2549 590 2713 590 2713 590 2549 590 2860 590 2713 590 2860 590 2858 590 2858 2003 2860 2003 2861 2003 2858 2004 2861 2004 2859 2004 2855 590 2862 590 2856 590 2856 2005 2862 2005 2863 2005 2856 2006 2863 2006 2864 2006 2864 2007 2863 2007 2158 2007 2864 2008 2158 2008 2157 2008 2865 590 2866 590 2864 590 2864 590 2866 590 2867 590 2864 590 2867 590 2856 590 2856 590 2867 590 2868 590 2856 590 2868 590 2745 590 2745 590 2868 590 2869 590 2745 590 2869 590 2870 590 2870 590 2869 590 2871 590 2872 590 2662 590 2867 590 2867 590 2662 590 2888 590 2867 590 2888 590 2868 590 2868 590 2888 590 2807 590 2868 590 2807 590 2869 590 2869 590 2807 590 2809 590 2869 590 2809 590 2765 590 2765 590 2809 590 2873 590 2765 590 2873 590 2763 590 2763 590 2873 590 2876 590 2763 590 2876 590 2774 590 2774 590 2876 590 2107 590 2536 590 2874 590 2809 590 2809 590 2874 590 2885 590 2809 590 2885 590 2873 590 2873 590 2885 590 2875 590 2873 590 2875 590 2876 590 2876 590 2875 590 2877 590 2876 590 2877 590 2107 590 2107 590 2877 590 2887 590 2661 590 2906 590 2878 590 2878 590 2906 590 2695 590 2878 590 2695 590 2881 590 2881 2009 2695 2009 2879 2009 2881 590 2879 590 2707 590 2658 590 2878 590 2880 590 2880 590 2878 590 2881 590 2880 590 2881 590 2076 590 2076 590 2881 590 2882 590 2076 590 2882 590 2884 590 2884 590 2882 590 2883 590 2884 590 2883 590 2583 590 2583 2010 2883 2010 1994 2010 2583 2011 1994 2011 2584 2011 2534 590 2797 590 2885 590 2885 590 2797 590 2802 590 2885 590 2802 590 2875 590 2875 590 2802 590 2886 590 2875 590 2886 590 2877 590 2877 590 2886 590 2895 590 2877 590 2895 590 2887 590 2887 590 2895 590 2896 590 2663 590 2889 590 2888 590 2888 590 2889 590 2890 590 2888 590 2890 590 2789 590 2789 590 2890 590 2900 590 2789 590 2900 590 2781 590 2629 590 2891 590 2900 590 2900 590 2891 590 2892 590 2900 2012 2892 2012 2781 2012 2781 590 2892 590 2627 590 2781 590 2627 590 2784 590 2784 590 2627 590 2893 590 2784 590 2893 590 2802 590 2802 590 2893 590 2737 590 2802 590 2737 590 2886 590 2886 590 2737 590 2894 590 2886 590 2894 590 2895 590 2895 590 2894 590 2726 590 2895 590 2726 590 2896 590 2896 590 2726 590 2897 590 2628 590 2899 590 2898 590 2898 590 2899 590 2900 590 2898 590 2900 590 2683 590 2683 590 2900 590 2890 590 2683 590 2890 590 2901 590 2901 590 2890 590 2902 590 2901 590 2902 590 2544 590 2642 590 2903 590 2905 590 2905 590 2903 590 2904 590 2905 590 2904 590 2655 590 2655 590 2904 590 2686 590 2655 590 2686 590 2906 590 2906 590 2686 590 2688 590 2906 590 2688 590 2682 590 2898 2013 2007 2013 2907 2013 1999 590 1998 590 2643 590 2643 2014 1998 2014 1996 2014 2643 590 1996 590 2903 590 2903 590 1996 590 2012 590 2903 2015 2012 2015 2010 2015 2010 590 2908 590 2903 590 2903 2016 2908 2016 2909 2016 2903 590 2909 590 2898 590 2898 2017 2909 2017 2008 2017 2898 2018 2008 2018 2007 2018 2615 590 2017 590 2911 590 2911 590 2017 590 2898 590 2911 590 2898 590 2910 590 2910 590 2898 590 2907 590 2910 2019 2004 2019 2911 2019 2911 2020 2004 2020 2912 2020 2911 2021 2912 2021 2643 2021 2643 2022 2912 2022 2002 2022 2643 2023 2002 2023 1999 2023 3150 2024 2913 2024 3541 2024 3150 2025 3541 2025 2914 2025 2914 2026 3541 2026 2915 2026 2914 2027 2915 2027 2916 2027 2916 2028 2915 2028 3540 2028 2916 2029 3540 2029 2917 2029 2917 2030 3540 2030 3539 2030 2917 2031 3539 2031 2919 2031 2919 2032 3539 2032 2918 2032 2919 2032 2918 2032 2920 2032 2920 2033 2918 2033 3538 2033 2920 2034 3538 2034 2921 2034 2921 2035 3538 2035 2922 2035 2921 2036 2922 2036 2923 2036 2924 2037 2925 2037 2927 2037 2924 2038 2927 2038 2926 2038 2926 2039 2927 2039 2928 2039 2926 2040 2928 2040 2929 2040 2929 2041 2928 2041 2930 2041 2929 2041 2930 2041 3145 2041 3145 2042 2930 2042 2931 2042 3145 2043 2931 2043 3146 2043 3146 2044 2931 2044 3537 2044 3146 2045 3537 2045 3147 2045 3147 2046 3537 2046 3536 2046 3147 2047 3536 2047 3148 2047 3777 2048 2932 2048 3778 2048 3778 2049 2932 2049 3362 2049 3778 2050 3362 2050 2933 2050 2933 2051 3362 2051 2934 2051 2933 2052 2934 2052 2935 2052 2935 2053 2934 2053 3108 2053 2935 2054 3108 2054 3497 2054 3497 2055 3108 2055 3201 2055 3497 2056 3201 2056 2936 2056 2936 2057 3201 2057 2937 2057 2936 2058 2937 2058 2938 2058 2938 2059 2937 2059 3949 2059 2938 2060 3949 2060 3762 2060 3762 2061 3949 2061 3213 2061 3762 2062 3213 2062 3760 2062 3760 2063 3213 2063 2939 2063 3760 368 2939 368 2940 368 2940 369 2939 369 3946 369 2940 2064 3946 2064 2941 2064 2941 2065 3946 2065 2942 2065 2941 2066 2942 2066 2943 2066 2943 2067 2942 2067 3093 2067 2943 2068 3093 2068 2944 2068 2944 2069 3093 2069 3095 2069 2944 2070 3095 2070 3753 2070 3753 2070 3095 2070 3084 2070 3753 2071 3084 2071 2945 2071 2945 2072 3084 2072 3004 2072 2945 2073 3004 2073 3752 2073 3752 2074 3004 2074 4239 2074 2347 2075 3450 2075 3223 2075 3223 2076 3450 2076 3615 2076 3223 2077 3615 2077 3224 2077 3224 579 3615 579 2946 579 3224 2078 2946 2078 3225 2078 3225 2079 2946 2079 2947 2079 3225 2080 2947 2080 3220 2080 3220 2081 2947 2081 2948 2081 3220 2082 2948 2082 3219 2082 3219 2083 2948 2083 2949 2083 3219 2084 2949 2084 2950 2084 2950 2085 2949 2085 2951 2085 2950 2086 2951 2086 2952 2086 2952 475 2951 475 3749 475 2346 50 2953 50 3059 50 3059 50 2953 50 3747 50 3059 50 3747 50 3056 50 3056 50 3747 50 2954 50 3056 50 2954 50 3066 50 3066 50 2954 50 2955 50 3066 50 2955 50 2347 50 2347 50 2955 50 3450 50 2953 2087 2346 2087 3746 2087 3746 2088 2346 2088 2956 2088 3746 2089 2956 2089 3744 2089 3744 2090 2956 2090 3232 2090 3744 2091 3232 2091 3592 2091 3592 2092 3232 2092 3244 2092 3592 2093 3244 2093 3590 2093 3590 2094 3244 2094 2957 2094 3590 2095 2957 2095 3741 2095 3741 2096 2957 2096 3251 2096 3741 2097 3251 2097 2958 2097 2958 33 3251 33 2959 33 2960 2098 2962 2098 2961 2098 2961 2099 2962 2099 3255 2099 2961 2100 3255 2100 3459 2100 3459 2101 3255 2101 2963 2101 3459 2102 2963 2102 2964 2102 2964 2102 2963 2102 7873 2102 2964 2103 7873 2103 3734 2103 3734 2104 7873 2104 3079 2104 3734 2105 3079 2105 3735 2105 3735 2106 3079 2106 3259 2106 3735 2107 3259 2107 2965 2107 2965 2108 3259 2108 8513 2108 2965 2083 8513 2083 2966 2083 2966 2109 8513 2109 2967 2109 2966 2110 2967 2110 3729 2110 3729 2078 2967 2078 8505 2078 3729 2111 8505 2111 3723 2111 3723 2112 8505 2112 3172 2112 3723 2113 3172 2113 3568 2113 3568 2114 3172 2114 3163 2114 3568 2115 3163 2115 3565 2115 3565 2116 3163 2116 3164 2116 3565 2117 3164 2117 3562 2117 3562 2118 3164 2118 3386 2118 3562 2119 3386 2119 3800 2119 3800 2120 3386 2120 2968 2120 3800 2121 2968 2121 2969 2121 2969 2122 2968 2122 3273 2122 2969 2123 3273 2123 2970 2123 2970 2124 3273 2124 3272 2124 2970 2125 3272 2125 2971 2125 2971 2126 3272 2126 3267 2126 2971 2127 3267 2127 2972 2127 2972 2128 3267 2128 3277 2128 2972 2129 3277 2129 3700 2129 3700 2130 3277 2130 2973 2130 3700 2131 2973 2131 3698 2131 3698 2132 2973 2132 2974 2132 3698 2133 2974 2133 2975 2133 2975 2134 2974 2134 3377 2134 2975 2135 3377 2135 2976 2135 2976 2135 3377 2135 2977 2135 2976 2136 2977 2136 2978 2136 2978 2137 2977 2137 3229 2137 2978 2138 3229 2138 2979 2138 2979 2138 3229 2138 2980 2138 3291 2139 3697 2139 3292 2139 3292 2140 3697 2140 3696 2140 3292 2141 3696 2141 2981 2141 2981 2142 3696 2142 2982 2142 3697 2143 3291 2143 3685 2143 3685 2144 3291 2144 2983 2144 3685 2145 2983 2145 3687 2145 3687 2146 2983 2146 3300 2146 3687 2147 3300 2147 3680 2147 3680 2148 3300 2148 3299 2148 2987 49 2984 49 3152 49 3152 49 2984 49 3679 49 3152 49 3679 49 3151 49 3151 49 3679 49 2985 49 3151 49 2985 49 3298 49 3298 49 2985 49 2986 49 3298 49 2986 49 3299 49 3299 49 2986 49 3680 49 2984 2149 2987 2149 3666 2149 3666 2150 2987 2150 3303 2150 3666 2151 3303 2151 3667 2151 3667 2152 3303 2152 2988 2152 3667 2153 2988 2153 3662 2153 3662 2154 2988 2154 3000 2154 3605 2155 3293 2155 3611 2155 3611 2156 3293 2156 2989 2156 3611 2157 2989 2157 3580 2157 3580 2158 2989 2158 3237 2158 3282 2159 3602 2159 2990 2159 2990 293 3602 293 3601 293 2990 2160 3601 2160 2991 2160 2991 2161 3601 2161 3576 2161 3827 2162 3320 2162 3618 2162 3618 2163 3320 2163 2992 2163 2993 2164 2995 2164 2994 2164 2994 2165 2995 2165 3321 2165 2994 2166 3321 2166 3617 2166 3617 2167 3321 2167 2996 2167 2997 590 3369 590 3190 590 3342 590 2998 590 2999 590 3000 590 2988 590 3001 590 3282 590 2990 590 3002 590 3237 590 2989 590 3003 590 2956 590 3002 590 3232 590 2346 590 3059 590 3373 590 4239 590 3004 590 3045 590 2939 590 3210 590 3104 590 4233 590 4232 590 3396 590 3005 590 3006 590 3189 590 3375 590 3007 590 3143 590 3008 590 3009 590 3202 590 3208 2168 3010 2168 3100 2168 3011 590 3033 590 3218 590 3012 590 3391 590 3383 590 3013 2169 3381 2169 3278 2169 3014 590 3250 590 3015 590 3015 590 3250 590 3379 590 3015 2170 3379 2170 3016 2170 3016 590 3379 590 3380 590 3012 2171 3383 2171 3017 2171 3254 590 3018 590 3019 590 3019 2172 3018 2172 3020 2172 3019 590 3020 590 3384 590 3249 590 3021 590 3252 590 3383 590 3385 590 3017 590 3017 590 3385 590 3027 590 3017 2173 3027 2173 3024 2173 3021 2174 3022 2174 3252 2174 3252 2175 3022 2175 3023 2175 3252 590 3023 590 3025 590 3025 2176 3023 2176 3024 2176 3025 590 3024 590 3026 590 3026 590 3024 590 3027 590 3372 590 3028 590 3029 590 3029 2177 3028 2177 3030 2177 3032 2178 3031 2178 3355 2178 3032 590 3355 590 3033 590 3034 2179 3035 2179 3036 2179 3047 2180 3037 2180 3217 2180 3367 590 3368 590 3038 590 3038 590 3039 590 3045 590 3045 2181 3039 2181 3049 2181 3046 2182 3034 2182 3045 2182 3011 2183 3218 2183 3040 2183 3041 590 3042 590 3049 590 3049 2184 3042 2184 3043 2184 3049 2185 3043 2185 3045 2185 3045 590 3043 590 3044 590 3045 2186 3044 2186 3046 2186 3037 590 3047 590 3049 590 3049 590 3047 590 3048 590 3049 2187 3048 2187 3041 2187 3312 590 3138 590 3051 590 3051 590 3138 590 3050 590 3051 590 3050 590 3052 590 3373 590 3053 590 3050 590 3050 2188 3053 2188 3054 2188 3050 590 3054 590 3052 590 3068 2189 3055 2189 3066 2189 3066 590 3055 590 3056 590 3055 2190 3057 2190 3056 2190 3056 590 3057 590 3058 590 3056 590 3058 590 3059 590 3059 2191 3058 2191 3060 2191 3059 2192 3060 2192 3373 2192 3373 590 3060 590 3061 590 3373 590 3061 590 3053 590 3222 590 3001 590 2347 590 3062 590 3063 590 3001 590 3001 590 3063 590 3064 590 3001 590 3064 590 2347 590 2347 2193 3064 2193 3065 2193 2347 590 3065 590 3066 590 3066 2194 3065 2194 3067 2194 3066 590 3067 590 3068 590 3175 590 3069 590 3176 590 3069 590 3070 590 3176 590 3176 2195 3070 2195 3071 2195 3176 590 3071 590 3019 590 3019 2196 3071 2196 3072 2196 3019 590 3072 590 3256 590 3080 2197 3073 2197 3074 2197 2963 2198 3258 2198 3075 2198 2963 2199 3075 2199 7873 2199 3075 590 3076 590 7873 590 7873 2200 3076 2200 3077 2200 7873 2201 3077 2201 3079 2201 3079 2202 3077 2202 3078 2202 3079 2203 3078 2203 3080 2203 3081 590 3082 590 3092 590 3092 2204 3082 2204 3127 2204 3127 590 3082 590 3083 590 3127 590 3083 590 3214 590 3095 2205 3085 2205 3084 2205 3084 2206 3085 2206 3086 2206 3086 2207 3087 2207 3084 2207 3084 590 3087 590 3088 590 3084 590 3088 590 3004 590 3004 2208 3088 2208 3089 2208 3004 2209 3089 2209 3045 2209 3045 590 3089 590 3090 590 3045 590 3090 590 3092 590 3092 2210 3090 2210 3091 2210 3092 2211 3091 2211 3081 2211 3214 2212 3094 2212 3093 2212 3093 2213 3094 2213 3096 2213 3093 2214 3096 2214 3095 2214 3095 2215 3096 2215 3097 2215 3095 2216 3097 2216 3085 2216 3098 590 3099 590 3104 590 3100 590 3101 590 3210 590 3210 2217 3101 2217 3102 2217 3102 2218 3103 2218 3210 2218 3210 590 3103 590 3105 590 3210 590 3105 590 3104 590 3104 2219 3105 2219 3106 2219 3104 2220 3106 2220 3098 2220 3008 590 3202 590 3107 590 3107 590 3201 590 3109 590 3109 2221 3201 2221 3108 2221 3109 590 3108 590 3110 590 3110 590 3108 590 2934 590 3110 590 2934 590 3111 590 3112 590 3113 590 3365 590 3365 590 3113 590 3114 590 3365 2222 3114 2222 3200 2222 3115 590 3116 590 3118 590 3118 2223 3116 2223 3117 2223 3118 590 3117 590 3365 590 3365 2224 3117 2224 3119 2224 3365 2225 3119 2225 3112 2225 3120 2226 3360 2226 3121 2226 3121 590 3360 590 3359 590 3092 590 3122 590 3359 590 3359 2227 3122 2227 3123 2227 3359 2228 3123 2228 3121 2228 3099 590 3124 590 3104 590 3104 2229 3124 2229 3125 2229 3104 590 3125 590 3127 590 3127 2230 3125 2230 3126 2230 3126 2231 3128 2231 3127 2231 3127 2232 3128 2232 3129 2232 3127 590 3129 590 3092 590 3092 2233 3129 2233 3130 2233 3092 590 3130 590 3122 590 3301 590 3149 590 3134 590 3050 590 3133 590 3374 590 3142 2234 3131 2234 3050 2234 3050 2235 3131 2235 3132 2235 3050 2236 3132 2236 3133 2236 3134 590 3135 590 3301 590 3301 2237 3135 2237 3136 2237 3301 2238 3136 2238 3138 2238 3138 590 3136 590 3137 590 3137 590 3139 590 3138 590 3138 2239 3139 2239 3140 2239 3138 590 3140 590 3050 590 3050 2240 3140 2240 3141 2240 3050 590 3141 590 3142 590 2926 2241 2929 2241 3144 2241 3375 590 3143 590 3144 590 3144 590 3143 590 2924 590 3144 2242 2924 2242 2926 2242 3145 590 3146 590 3151 590 3151 2243 3146 2243 3147 2243 3151 2244 3147 2244 3148 2244 2923 590 3149 590 2921 590 2921 590 3149 590 3301 590 2921 590 3301 590 2920 590 2920 2245 3301 2245 2919 2245 3148 590 3150 590 3151 590 3151 2246 3150 2246 2914 2246 3151 590 2914 590 3152 590 3152 2247 2914 2247 2916 2247 3152 2248 2916 2248 2917 2248 3154 2249 3153 2249 3161 2249 3154 590 3161 590 3163 590 3005 590 3156 590 3155 590 3155 590 3156 590 3387 590 3157 2250 3158 2250 3386 2250 3386 590 3158 590 3159 590 3386 2251 3159 2251 3160 2251 3161 2252 3162 2252 3163 2252 3163 2253 3162 2253 3165 2253 3163 590 3165 590 3164 590 3164 2254 3165 2254 3166 2254 3164 2255 3166 2255 3386 2255 3386 2256 3166 2256 3167 2256 3386 2257 3167 2257 3157 2257 3169 590 3168 590 3182 590 3169 590 3182 590 3183 590 3261 590 3170 590 3264 590 3264 590 3170 590 3171 590 3163 590 3172 590 3154 590 3154 590 3172 590 3264 590 3154 590 3264 590 3173 590 3173 590 3264 590 3171 590 3173 2258 3171 2258 3174 2258 3073 590 3175 590 3074 590 3074 590 3175 590 3176 590 3074 590 3176 590 3177 590 3177 590 3176 590 3178 590 3177 2259 3179 2259 3074 2259 3074 2260 3179 2260 3180 2260 3074 590 3180 590 3182 590 3182 2261 3180 2261 3181 2261 3182 2262 3181 2262 3183 2262 3382 590 3184 590 3185 590 3185 2263 3186 2263 3382 2263 3382 2264 3186 2264 3187 2264 3382 590 3187 590 3176 590 3176 2265 3187 2265 3188 2265 3176 590 3188 590 3178 590 3005 590 3189 590 3156 590 3156 2266 3189 2266 3184 2266 3156 590 3184 590 3388 590 3190 590 3369 590 3393 590 3393 590 3369 590 3029 590 3393 590 3029 590 3395 590 3029 590 3191 590 3395 590 3395 590 3191 590 3196 590 3395 590 3196 590 3396 590 3396 590 4232 590 3192 590 3192 2267 4232 2267 3193 2267 3192 2268 3193 2268 4230 2268 4230 2269 3194 2269 3364 2269 3364 2270 3194 2270 4236 2270 4236 2271 4234 2271 3364 2271 3364 590 4234 590 3195 590 3364 590 3195 590 3196 590 3196 590 3195 590 4228 590 4228 590 3197 590 3196 590 3196 2272 3197 2272 3198 2272 3196 2273 3198 2273 3396 2273 3396 2274 3198 2274 3199 2274 3396 2275 3199 2275 4233 2275 4230 590 3364 590 3192 590 3192 590 3364 590 3363 590 3192 590 3363 590 3397 590 3362 590 3365 590 2934 590 2934 590 3365 590 3200 590 2934 2276 3200 2276 3111 2276 3107 590 3202 590 3201 590 3201 590 3202 590 3207 590 3201 590 3207 590 2937 590 2937 590 3207 590 3213 590 2937 2277 3213 2277 3949 2277 3206 590 3203 590 3207 590 3207 590 3203 590 3204 590 4244 590 3205 590 3213 590 3213 2278 3205 2278 2939 2278 3212 590 3206 590 3210 590 3210 590 3206 590 3207 590 3210 590 3207 590 3100 590 3100 590 3207 590 3202 590 3100 590 3202 590 3208 590 3208 590 3202 590 3009 590 3205 2279 3209 2279 2939 2279 2939 2280 3209 2280 3211 2280 2939 2281 3211 2281 3210 2281 3210 2282 3211 2282 4240 2282 3210 2283 4240 2283 3212 2283 3204 590 4115 590 3207 590 3207 2284 4115 2284 4114 2284 3207 590 4114 590 3213 590 3213 2285 4114 2285 4113 2285 3213 2286 4113 2286 4244 2286 3214 590 3093 590 3127 590 3127 2287 3093 2287 2942 2287 3127 590 2942 590 3104 590 3104 2288 2942 2288 3946 2288 3104 590 3946 590 2939 590 3034 590 3036 590 3045 590 3045 590 3036 590 3215 590 3045 2289 3215 2289 4239 2289 2950 590 2952 590 3047 590 3033 590 3355 590 3218 590 3218 590 3355 590 3357 590 3218 2290 3357 2290 3216 2290 3217 590 3040 590 3047 590 3047 2291 3040 2291 3218 2291 3047 590 3218 590 2950 590 2950 590 3218 590 3216 590 2950 2292 3216 2292 3219 2292 3219 590 3216 590 3221 590 3219 590 3221 590 3220 590 3827 590 3337 590 3320 590 3320 590 3337 590 3340 590 3221 590 3336 590 3220 590 3220 2293 3336 2293 3337 2293 3220 590 3337 590 3225 590 3225 590 3337 590 3827 590 2347 590 3223 590 3222 590 3222 590 3223 590 3224 590 3222 590 3224 590 3321 590 3321 590 3224 590 3225 590 3321 2294 3225 2294 2996 2294 2996 590 3225 590 3827 590 3244 590 3232 590 3234 590 3241 590 3229 590 3226 590 3226 590 3229 590 2977 590 3226 590 2977 590 3227 590 2980 590 3229 590 3228 590 3228 590 3229 590 3241 590 3228 2295 3241 2295 3230 2295 3230 590 3241 590 3231 590 3002 590 2990 590 3232 590 3232 590 2990 590 2991 590 3232 590 2991 590 3234 590 3234 2296 2991 2296 3233 2296 3234 2297 3233 2297 3235 2297 3235 590 3233 590 3236 590 3235 2298 3236 2298 3237 2298 3003 2299 3238 2299 3237 2299 3237 2300 3238 2300 3239 2300 3237 2301 3239 2301 3235 2301 3235 2302 3239 2302 3240 2302 3235 590 3240 590 3241 590 3241 2303 3240 2303 3242 2303 3241 2304 3242 2304 3231 2304 3234 590 3243 590 3244 590 3244 590 3243 590 3245 590 3244 590 3245 590 2957 590 2957 590 3245 590 3246 590 2957 590 3246 590 3251 590 3251 2305 3246 2305 3247 2305 3251 590 3247 590 3250 590 3250 2306 3247 2306 3248 2306 3250 590 3248 590 3379 590 3014 590 3249 590 3250 590 3250 590 3249 590 3252 590 3250 590 3252 590 3251 590 3251 590 3252 590 2959 590 3253 590 3254 590 2962 590 2962 590 3254 590 3019 590 2962 590 3019 590 3255 590 3255 2307 3019 2307 3256 2307 3255 2308 3256 2308 2963 2308 2963 590 3256 590 3257 590 2963 590 3257 590 3258 590 3080 590 3074 590 3079 590 3079 590 3074 590 3182 590 3079 590 3182 590 3259 590 3259 590 3182 590 2967 590 3259 2309 2967 2309 8513 2309 3260 590 3262 590 3264 590 3168 590 3261 590 3182 590 3182 590 3261 590 3264 590 3182 590 3264 590 2967 590 2967 590 3264 590 3262 590 2967 2310 3262 2310 8353 2310 8353 590 8501 590 2967 590 2967 2311 8501 2311 3263 2311 2967 2312 3263 2312 8505 2312 3263 590 8506 590 8505 590 8505 2313 8504 2313 3172 2313 3172 2314 8504 2314 8502 2314 3172 2315 8502 2315 8500 2315 8500 590 8510 590 3172 590 3172 590 8510 590 8509 590 3172 590 8509 590 3264 590 3264 590 8509 590 8508 590 3264 2316 8508 2316 3260 2316 3270 590 2968 590 3386 590 3276 2317 3275 2317 3268 2317 3265 590 3266 590 3267 590 3267 2318 3266 2318 3275 2318 3268 2319 3269 2319 3276 2319 3276 590 3269 590 8514 590 3276 590 8514 590 3270 590 3270 590 8514 590 8398 590 3270 590 8398 590 8397 590 8397 2320 3271 2320 3270 2320 3270 2321 3271 2321 3272 2321 3270 590 3272 590 2968 590 2968 2322 3272 2322 3273 2322 3271 2323 8396 2323 3272 2323 3272 2324 8396 2324 8395 2324 3272 590 8395 590 3267 590 3267 2325 8395 2325 3274 2325 3267 2326 3274 2326 3265 2326 3275 2327 3276 2327 3267 2327 3267 590 3276 590 3390 590 3267 590 3390 590 3277 590 3277 590 3390 590 2973 590 2973 590 3390 590 3278 590 2973 590 3278 590 2974 590 2974 590 3278 590 3378 590 2974 590 3378 590 3377 590 3293 590 3280 590 3279 590 3279 2328 3280 2328 3281 2328 2346 590 3373 590 2956 590 2956 590 3373 590 3279 590 2956 590 3279 590 3002 590 3002 2329 3279 2329 3281 2329 3002 2330 3281 2330 3282 2330 3293 2331 3283 2331 2989 2331 2989 2332 3283 2332 3284 2332 2989 2333 3284 2333 3285 2333 3285 590 3286 590 2989 590 2989 2334 3286 2334 3287 2334 2989 590 3287 590 3003 590 3003 2335 3287 2335 3288 2335 3003 590 3288 590 3289 590 3289 2336 3288 2336 3290 2336 2983 2337 3291 2337 3279 2337 3279 590 3291 590 3292 590 3279 590 3292 590 3293 590 3293 590 3292 590 2981 590 3293 2338 2981 2338 3283 2338 3300 590 2983 590 2340 590 2339 590 2336 590 3376 590 3376 2339 2336 2339 3294 2339 3376 2340 3294 2340 2342 2340 2342 2341 2341 2341 3373 2341 3373 2342 2341 2342 3295 2342 3373 590 3295 590 3279 590 3279 2343 3295 2343 2169 2343 3279 2344 2169 2344 2344 2344 2344 590 3296 590 3279 590 3279 2345 3296 2345 3297 2345 3279 590 3297 590 2983 590 2983 2346 3297 2346 2343 2346 2983 2347 2343 2347 2340 2347 3298 590 3299 590 3300 590 2917 590 2919 590 3152 590 3152 590 2919 590 3301 590 3152 590 3301 590 2987 590 2987 590 3301 590 3303 590 3306 590 2988 590 3302 590 3302 2348 2988 2348 3303 2348 3302 590 3303 590 3304 590 3304 590 3303 590 3301 590 3304 590 3301 590 3305 590 3306 2349 3307 2349 2988 2349 2988 2350 3307 2350 3308 2350 2988 590 3308 590 3001 590 3001 2351 3308 2351 3309 2351 3001 2352 3309 2352 3310 2352 3310 590 3311 590 3001 590 3001 590 3311 590 3138 590 3001 590 3138 590 3062 590 3062 590 3138 590 3312 590 3311 590 3313 590 3138 590 3138 2353 3313 2353 3314 2353 3138 2354 3314 2354 3301 2354 3301 2355 3314 2355 3315 2355 3301 2356 3315 2356 3305 2356 3000 590 3001 590 3316 590 3316 590 3001 590 3317 590 3316 2357 3317 2357 3329 2357 3329 590 3317 590 3318 590 3329 590 3318 590 3340 590 3340 590 3318 590 3319 590 3340 2358 3319 2358 3320 2358 3321 590 2995 590 3222 590 3222 2359 2995 2359 3322 2359 3222 2360 3322 2360 3001 2360 3001 2361 3322 2361 3323 2361 3001 2362 3323 2362 3317 2362 3324 590 3325 590 3334 590 3334 2363 3325 2363 3332 2363 3340 2364 3333 2364 3326 2364 3326 590 3327 590 3340 590 3340 2365 3327 2365 3328 2365 3340 2366 3328 2366 3329 2366 3329 2367 3328 2367 3330 2367 3329 2368 3330 2368 3331 2368 3332 590 3333 590 3334 590 3334 590 3333 590 3340 590 3334 590 3340 590 3335 590 3336 590 3338 590 3337 590 3337 590 3338 590 3339 590 3337 590 3339 590 3340 590 3340 2369 3339 2369 3346 2369 3371 590 3370 590 3341 590 3341 590 3370 590 2998 590 3341 590 2998 590 3344 590 3344 590 2998 590 3342 590 3344 2370 3342 2370 3343 2370 3343 590 3345 590 3344 590 3344 2371 3345 2371 3347 2371 3344 590 3347 590 3346 590 3346 2372 3347 2372 3348 2372 3346 2373 3348 2373 3340 2373 3340 2374 3348 2374 3349 2374 3340 590 3349 590 3335 590 3248 590 3350 590 3379 590 3379 590 3350 590 3351 590 3379 2375 3351 2375 3227 2375 3227 2376 3351 2376 3352 2376 3227 590 3352 590 3226 590 3341 590 3353 590 3371 590 3371 2377 3353 2377 3354 2377 3371 590 3354 590 3355 590 3355 590 3354 590 3356 590 3355 590 3356 590 3357 590 3038 590 3045 590 3367 590 3367 590 3045 590 3092 590 3367 590 3092 590 3358 590 3358 590 3092 590 3359 590 3358 590 3359 590 3366 590 3366 590 3359 590 3360 590 3366 590 3360 590 3118 590 3118 2378 3360 2378 3361 2378 3118 590 3361 590 3115 590 2932 590 3397 590 3362 590 3362 590 3397 590 3363 590 3362 590 3363 590 3365 590 3365 590 3363 590 3364 590 3365 590 3364 590 3118 590 3118 590 3364 590 3196 590 3118 590 3196 590 3366 590 3366 590 3196 590 3191 590 3366 590 3191 590 3358 590 3358 590 3191 590 3029 590 3358 590 3029 590 3367 590 3367 590 3029 590 3030 590 3367 590 3030 590 3368 590 2997 590 3370 590 3369 590 3369 590 3370 590 3371 590 3369 590 3371 590 3029 590 3029 590 3371 590 3355 590 3029 590 3355 590 3372 590 3372 590 3355 590 3031 590 2342 590 3373 590 3376 590 3376 590 3373 590 3050 590 3376 590 3050 590 3144 590 3144 2379 3050 2379 3374 2379 3144 2380 3374 2380 3375 2380 2340 590 2339 590 3300 590 3300 590 2339 590 3376 590 3300 590 3376 590 3298 590 3298 590 3376 590 3144 590 3298 590 3144 590 3151 590 3151 2381 3144 2381 2929 2381 3151 2382 2929 2382 3145 2382 2977 590 3377 590 3227 590 3227 590 3377 590 3378 590 3227 590 3378 590 3379 590 3379 590 3378 590 3278 590 3379 590 3278 590 3380 590 3380 590 3278 590 3381 590 3184 590 3382 590 3388 590 3388 590 3382 590 3176 590 3388 590 3176 590 3389 590 3389 590 3176 590 3019 590 3389 590 3019 590 3383 590 3383 2383 3019 2383 3384 2383 3383 2384 3384 2384 3385 2384 3160 590 3387 590 3386 590 3386 590 3387 590 3156 590 3386 590 3156 590 3270 590 3270 590 3156 590 3388 590 3270 590 3388 590 3276 590 3276 590 3388 590 3389 590 3276 590 3389 590 3390 590 3390 590 3389 590 3383 590 3390 590 3383 590 3278 590 3278 590 3383 590 3391 590 3278 590 3391 590 3013 590 3392 2385 3393 2385 3394 2385 3394 2386 3393 2386 3395 2386 3394 2387 3395 2387 3795 2387 3795 2388 3395 2388 3396 2388 3795 2389 3396 2389 3789 2389 3789 2390 3396 2390 3192 2390 3789 2391 3192 2391 3779 2391 3779 2392 3192 2392 3397 2392 3779 2393 3397 2393 3777 2393 3777 2394 3397 2394 2932 2394 2947 960 3627 960 2948 960 2960 960 2961 960 3737 960 2975 960 3699 960 3698 960 3579 960 2978 960 2979 960 3398 960 3690 960 3695 960 3694 960 2982 960 3696 960 3725 960 3399 960 3724 960 3724 960 3400 960 3720 960 3503 960 3401 960 3504 960 3402 960 3460 960 3459 960 3453 960 3403 960 2955 960 3668 2395 3448 2395 3528 2395 3820 960 3404 960 3826 960 3405 960 3406 960 3736 960 3809 960 3407 960 3701 960 3701 2396 3407 2396 3408 2396 3701 2397 3408 2397 3804 2397 3808 2398 3595 2398 3409 2398 3804 2399 3424 2399 3737 2399 3737 2400 3424 2400 3410 2400 3737 960 3410 960 3405 960 3408 960 3411 960 3804 960 3804 960 3411 960 3412 960 3804 960 3412 960 3424 960 3424 2401 3412 2401 3422 2401 3420 960 3413 960 3415 960 3413 960 3414 960 3415 960 3415 2402 3414 2402 3416 2402 3415 2403 3416 2403 3594 2403 3594 960 3416 960 3417 960 3594 960 3417 960 3418 960 3415 960 3419 960 3420 960 3420 2404 3419 2404 3421 2404 3420 960 3421 960 3422 960 3422 2405 3421 2405 3423 2405 3422 2406 3423 2406 3424 2406 3425 2407 3426 2407 3817 2407 3427 960 3645 960 3428 960 3428 960 3645 960 3649 960 3428 2408 3649 2408 3429 2408 3429 960 3649 960 3430 960 3431 2409 3432 2409 3433 2409 3438 2410 3442 2410 3439 2410 3432 960 3434 960 3433 960 3433 2411 3434 2411 3435 2411 3433 960 3435 960 3436 960 3436 2412 3435 2412 3438 2412 3436 960 3438 960 3437 960 3437 960 3438 960 3439 960 3751 960 3440 960 3472 960 3472 960 3440 960 3441 960 3472 960 3441 960 3445 960 3438 960 3443 960 3442 960 3442 960 3443 960 3472 960 3442 960 3472 960 3444 960 3444 960 3472 960 3445 960 3814 960 3533 960 3446 960 3446 960 3533 960 3528 960 3446 2413 3528 2413 3447 2413 3447 960 3528 960 3448 960 3449 2414 3668 2414 3663 2414 3449 960 3663 960 3614 960 2955 960 3403 960 3450 960 2954 960 3451 960 2955 960 2955 2415 3451 2415 3452 2415 2955 2416 3452 2416 3453 2416 3454 960 3748 960 3812 960 3454 2417 3812 2417 3813 2417 3747 960 3455 960 2954 960 2954 2418 3455 2418 3456 2418 2954 2419 3456 2419 3451 2419 3457 960 3458 960 3803 960 3803 2420 3458 2420 3544 2420 3459 960 3460 960 2961 960 2961 2421 3460 2421 3461 2421 2961 960 3461 960 3737 960 3543 960 3462 960 3552 960 3552 960 3462 960 3463 960 3463 960 3464 960 3734 960 3734 2422 3464 2422 3465 2422 3734 960 3465 960 2964 960 3465 960 3466 960 2964 960 2964 2423 3466 2423 3467 2423 2964 2424 3467 2424 3459 2424 3459 960 3467 960 3468 960 3459 2425 3468 2425 3402 2425 3469 960 3470 960 3510 960 3470 960 3471 960 3510 960 3510 2426 3471 2426 3473 2426 3510 960 3473 960 3472 960 3472 2427 3473 2427 3474 2427 3472 960 3474 960 3754 960 3475 2428 3478 2428 3753 2428 3753 960 3478 960 2944 960 3476 2429 3477 2429 3513 2429 3478 960 3479 960 2944 960 2944 2430 3479 2430 3480 2430 2944 960 3480 960 2943 960 2943 2431 3480 2431 3481 2431 2943 2432 3481 2432 3476 2432 3482 960 3484 960 3483 960 3494 2433 3491 2433 3484 2433 3494 960 3484 960 3818 960 3822 960 3485 960 3823 960 3823 2434 3485 2434 3486 2434 3823 2435 3486 2435 3487 2435 3487 2436 3488 2436 3823 2436 3823 960 3488 960 3489 960 3823 960 3489 960 3494 960 3490 960 3491 960 3492 960 3492 960 3491 960 3494 960 3492 2437 3494 2437 3493 2437 3493 960 3494 960 3489 960 3495 960 3496 960 3775 960 3775 2438 3496 2438 3776 2438 3497 960 3498 960 2935 960 2935 2439 3498 2439 3499 2439 2935 960 3499 960 2933 960 2933 2440 3499 2440 3821 2440 3500 2441 3501 2441 3758 2441 3758 2442 3501 2442 3502 2442 3758 2443 3502 2443 3756 2443 3757 960 3503 960 3771 960 3771 2444 3503 2444 3504 2444 3771 960 3504 960 3774 960 3774 960 3504 960 3505 960 3774 960 3505 960 3775 960 3775 960 3505 960 3506 960 3775 2445 3506 2445 3495 2445 3483 960 3507 960 3482 960 3482 2446 3507 2446 3508 2446 3482 960 3508 960 3510 960 3510 2447 3508 2447 3509 2447 3510 2448 3509 2448 3512 2448 3477 960 3469 960 3513 960 3513 960 3469 960 3510 960 3513 960 3510 960 3511 960 3511 960 3510 960 3512 960 3511 960 3514 960 3513 960 3513 2449 3514 2449 3515 2449 3513 960 3515 960 3758 960 3758 2450 3515 2450 3516 2450 3758 2451 3516 2451 3500 2451 3811 960 3517 960 3518 960 3518 2452 3519 2452 3811 2452 3811 2453 3519 2453 3520 2453 3811 2454 3520 2454 3533 2454 3520 960 3521 960 3533 960 3533 2455 3521 2455 3522 2455 3533 2456 3522 2456 3531 2456 3523 2457 3524 2457 3525 2457 3525 960 3524 960 3527 960 3525 960 3527 960 3526 960 3526 2458 3527 2458 3528 2458 3526 960 3528 960 3529 960 3529 960 3528 960 3530 960 3531 960 3532 960 3533 960 3533 960 3532 960 3534 960 3533 960 3534 960 3528 960 3528 2459 3534 2459 3535 2459 3528 2460 3535 2460 3530 2460 2931 2461 2930 2461 2985 2461 2985 2462 2930 2462 2928 2462 2985 2463 2928 2463 3811 2463 3811 2464 2928 2464 2927 2464 3811 960 2927 960 3517 960 3517 2465 2927 2465 2925 2465 2913 960 3536 960 2985 960 2985 2466 3536 2466 3537 2466 2985 2467 3537 2467 2931 2467 3524 960 2922 960 3527 960 3527 2468 2922 2468 3538 2468 3527 2469 3538 2469 2918 2469 3539 960 3540 960 3679 960 3679 2470 3540 2470 2915 2470 3679 960 2915 960 2985 960 2985 2471 2915 2471 3541 2471 2985 2472 3541 2472 2913 2472 3554 960 3542 960 3552 960 3552 960 3542 960 3803 960 3552 960 3803 960 3543 960 3543 960 3803 960 3544 960 3542 960 3545 960 3803 960 3803 2473 3545 2473 3575 2473 3803 960 3575 960 3572 960 3546 960 3547 960 3550 960 3550 2474 3547 2474 3548 2474 3548 2475 3549 2475 3550 2475 3550 2476 3549 2476 3551 2476 3550 960 3551 960 3552 960 3552 2477 3551 2477 3553 2477 3552 2478 3553 2478 3554 2478 3400 960 3555 960 3720 960 3720 2479 3555 2479 3556 2479 3720 2480 3556 2480 3721 2480 3801 2481 3557 2481 3558 2481 3558 960 3559 960 3801 960 3801 2482 3559 2482 3560 2482 3801 960 3560 960 3713 960 3714 2483 3561 2483 3562 2483 3562 2484 3561 2484 3563 2484 3563 2485 3564 2485 3562 2485 3562 2486 3564 2486 3566 2486 3562 960 3566 960 3565 960 3565 2487 3566 2487 3567 2487 3565 960 3567 960 3568 960 3568 2488 3567 2488 3569 2488 3568 2489 3569 2489 3726 2489 3570 960 3571 960 3573 960 3573 960 3571 960 3572 960 3573 2490 3572 2490 3574 2490 3574 960 3572 960 3575 960 3577 960 3611 960 3580 960 3576 960 3601 960 3745 960 3577 960 3580 960 3589 960 3592 960 3578 960 3744 960 3744 2491 3578 2491 3742 2491 3598 960 2976 960 3596 960 3596 960 2976 960 2978 960 3596 2492 2978 2492 3584 2492 3584 960 2978 960 3579 960 3584 2493 3579 2493 3582 2493 3587 960 3580 960 3581 960 3587 960 3581 960 3742 960 3582 960 3583 960 3584 960 3584 2494 3583 2494 3585 2494 3584 960 3585 960 3587 960 3587 2495 3585 2495 3586 2495 3587 2496 3586 2496 3580 2496 3580 2497 3586 2497 3588 2497 3580 2498 3588 2498 3589 2498 3741 2499 3740 2499 3590 2499 3590 960 3740 960 3591 960 3590 960 3591 960 3592 960 3592 2500 3591 2500 3593 2500 3592 960 3593 960 3578 960 3739 960 3594 960 3808 960 3808 960 3594 960 3418 960 3808 2501 3418 2501 3595 2501 3596 960 3597 960 3598 960 3598 960 3597 960 3599 960 3598 960 3599 960 3808 960 3808 960 3599 960 3600 960 3808 960 3600 960 3739 960 3601 960 3602 960 3745 960 3745 960 3602 960 3603 960 3745 960 3603 960 3695 960 3695 960 3603 960 3604 960 3695 2502 3604 2502 3605 2502 3577 2503 3606 2503 3607 2503 3613 2504 3608 2504 3611 2504 3611 960 3608 960 3605 960 3607 2505 3609 2505 3577 2505 3577 2506 3609 2506 3610 2506 3577 960 3610 960 3611 960 3611 2507 3610 2507 3612 2507 3611 2508 3612 2508 3613 2508 3403 960 3614 960 3450 960 3450 960 3614 960 3663 960 3450 960 3663 960 3615 960 3615 960 3663 960 3616 960 3615 960 3616 960 2946 960 2946 960 3616 960 2947 960 3616 960 2994 960 2947 960 2947 2509 2994 2509 3617 2509 2947 960 3617 960 3627 960 3627 2510 3617 2510 3618 2510 3627 960 3618 960 2992 960 3661 960 3619 960 3660 960 3660 960 3619 960 3657 960 3660 960 3657 960 3620 960 3621 960 3622 960 3663 960 3663 960 3622 960 3623 960 3663 2511 3623 2511 3616 2511 3616 960 3623 960 2993 960 3616 960 2993 960 2994 960 3632 960 3630 960 3624 960 3624 960 3630 960 3625 960 3624 960 3625 960 3815 960 3626 960 3627 960 3657 960 3657 960 3627 960 2992 960 3657 960 2992 960 3620 960 3628 960 3630 960 3629 960 3629 960 3630 960 3632 960 3629 960 3632 960 3631 960 3631 960 3632 960 3638 960 3633 960 3634 960 3657 960 3657 2512 3634 2512 3635 2512 3657 960 3635 960 3626 960 3626 2513 3635 2513 3636 2513 3626 2514 3636 2514 3632 2514 3632 2515 3636 2515 3637 2515 3632 2516 3637 2516 3638 2516 3649 960 3639 960 3815 960 3815 960 3639 960 3640 960 3815 960 3640 960 3624 960 3626 960 3641 960 3627 960 3627 960 3641 960 3642 960 3627 960 3642 960 2948 960 2948 2517 3642 2517 3643 2517 2948 960 3643 960 2949 960 2949 960 3643 960 3644 960 2949 960 3644 960 2951 960 2951 2518 3644 2518 3646 2518 2951 960 3646 960 3645 960 3645 2519 3646 2519 3647 2519 3645 960 3647 960 3649 960 3649 960 3647 960 3648 960 3649 960 3648 960 3639 960 3650 2520 3659 2520 3657 2520 3650 960 3657 960 3651 960 3651 960 3657 960 3619 960 3651 2521 3619 2521 3652 2521 3653 2522 3654 2522 3655 2522 3655 2523 3654 2523 3633 2523 3655 960 3633 960 3656 960 3656 960 3633 960 3657 960 3656 960 3657 960 3658 960 3658 2524 3657 2524 3659 2524 3660 2525 3621 2525 3661 2525 3661 960 3621 960 3663 960 3661 960 3663 960 3662 960 3662 2526 3663 2526 3667 2526 3663 2527 3669 2527 3664 2527 3674 2528 3527 2528 3665 2528 3665 960 3527 960 3666 960 3665 960 3666 960 3673 960 3673 2529 3666 2529 3667 2529 3668 960 3528 960 3663 960 3663 960 3528 960 3678 960 3663 2530 3678 2530 3669 2530 3664 960 3670 960 3663 960 3663 2531 3670 2531 3671 2531 3663 2532 3671 2532 3667 2532 3667 2533 3671 2533 3672 2533 3667 2534 3672 2534 3673 2534 3674 960 3675 960 3527 960 3527 2535 3675 2535 3676 2535 3527 960 3676 960 3528 960 3528 2536 3676 2536 3677 2536 3528 2537 3677 2537 3678 2537 2918 960 3539 960 3527 960 3527 960 3539 960 3679 960 3527 960 3679 960 3666 960 3666 960 3679 960 2984 960 2986 960 3810 960 3680 960 3680 960 3810 960 3687 960 3695 960 3690 960 3812 960 3681 960 3682 960 3685 960 3685 2538 3682 2538 3683 2538 3685 2539 3683 2539 3695 2539 3695 2540 3683 2540 3684 2540 3695 2541 3684 2541 3398 2541 3681 960 3685 960 3686 960 3686 2542 3685 2542 3687 2542 3686 960 3687 960 3688 960 3688 960 3687 960 3810 960 3688 960 3810 960 3689 960 3690 960 3691 960 3812 960 3812 2543 3691 2543 3692 2543 3812 2544 3692 2544 3810 2544 3810 2545 3692 2545 3693 2545 3810 2546 3693 2546 3689 2546 3608 960 3694 960 3605 960 3605 960 3694 960 3696 960 3605 960 3696 960 3695 960 3695 960 3696 960 3697 960 3695 2547 3697 2547 3685 2547 3698 960 3699 960 3700 960 3700 960 3699 960 3701 960 3700 960 3701 960 2972 960 3712 960 3806 960 3805 960 3807 960 3702 960 2971 960 2971 2548 3702 2548 3703 2548 2971 2549 3703 2549 2970 2549 3703 2550 3704 2550 2970 2550 2970 2551 3704 2551 3705 2551 2970 960 3705 960 3709 960 3709 2552 3705 2552 3706 2552 3709 960 3706 960 3707 960 3707 2553 3708 2553 3709 2553 3709 960 3708 960 3710 960 3709 960 3710 960 3805 960 3805 960 3710 960 3711 960 3805 960 3711 960 3712 960 3800 960 3801 960 3562 960 3562 960 3801 960 3713 960 3562 960 3713 960 3714 960 3719 2554 3715 2554 3720 2554 3720 2555 3715 2555 3716 2555 3720 2556 3716 2556 3717 2556 3718 960 3719 960 2966 960 2966 2557 3719 2557 3720 2557 2966 960 3720 960 3550 960 3550 960 3720 960 3721 960 3550 2558 3721 2558 3546 2558 3722 960 3727 960 3723 960 3717 960 3722 960 3720 960 3720 960 3722 960 3723 960 3720 960 3723 960 3724 960 3724 960 3723 960 3568 960 3724 960 3568 960 3725 960 3725 960 3568 960 3726 960 3727 960 3728 960 3723 960 3723 2559 3728 2559 3730 2559 3723 2560 3730 2560 3729 2560 3730 960 3731 960 3729 960 3729 2561 3731 2561 3732 2561 3729 960 3732 960 2966 960 2966 2562 3732 2562 3733 2562 2966 2563 3733 2563 3718 2563 3463 960 3734 960 3552 960 3552 2564 3734 2564 3735 2564 3552 960 3735 960 3550 960 3550 2565 3735 2565 2965 2565 3550 2566 2965 2566 2966 2566 3405 960 3736 960 3737 960 3737 960 3736 960 3738 960 3737 2567 3738 2567 2960 2567 3739 960 3740 960 3594 960 3594 960 3740 960 3741 960 3594 960 3741 960 3415 960 3415 960 3741 960 2958 960 3581 2568 3743 2568 3742 2568 3742 2569 3743 2569 3576 2569 3742 960 3576 960 3744 960 3744 960 3576 960 3745 960 3744 960 3745 960 3746 960 3746 960 3745 960 3695 960 3746 960 3695 960 2953 960 2953 960 3695 960 3812 960 2953 960 3812 960 3747 960 3747 960 3812 960 3748 960 3747 2570 3748 2570 3455 2570 3427 960 3431 960 3645 960 3645 960 3431 960 3433 960 3645 960 3433 960 2951 960 2951 960 3433 960 3749 960 3750 960 3751 960 3752 960 3752 960 3751 960 3472 960 3752 960 3472 960 2945 960 2945 960 3472 960 3754 960 2945 2571 3754 2571 3753 2571 3753 960 3754 960 3755 960 3753 960 3755 960 3475 960 3760 960 3758 960 3771 960 3771 960 3758 960 3756 960 3771 2572 3756 2572 3757 2572 3476 2573 3513 2573 2943 2573 2943 960 3513 960 3758 960 2943 960 3758 960 2941 960 2941 960 3758 960 3760 960 2941 960 3760 960 2940 960 3759 2574 3765 2574 3774 2574 3762 960 3760 960 3761 960 3761 960 3763 960 3762 960 3762 2575 3763 2575 3764 2575 3762 2576 3764 2576 3773 2576 3765 2577 3766 2577 3774 2577 3774 2578 3766 2578 3767 2578 3774 960 3767 960 3771 960 3771 2579 3767 2579 3768 2579 3768 960 3769 960 3771 960 3771 2580 3769 2580 3770 2580 3771 960 3770 960 3760 960 3760 2581 3770 2581 3772 2581 3760 2582 3772 2582 3761 2582 2936 2583 2938 2583 3762 2583 3773 960 3759 960 3762 960 3762 960 3759 960 3774 960 3762 960 3774 960 2936 960 2936 960 3774 960 3775 960 2936 960 3775 960 3497 960 3497 960 3775 960 3776 960 3497 2584 3776 2584 3498 2584 3779 960 3777 960 3778 960 3794 960 3781 960 3824 960 3786 960 3790 960 3784 960 3790 960 3789 960 3784 960 3784 2585 3789 2585 3779 2585 3784 960 3779 960 3780 960 3780 960 3779 960 3778 960 3780 960 3778 960 2933 960 3781 2586 3782 2586 3824 2586 3824 960 3782 960 3783 960 3824 960 3783 960 3784 960 3784 960 3783 960 3785 960 3784 960 3785 960 3786 960 3791 960 3795 960 3787 960 3787 2587 3795 2587 3789 2587 3787 960 3789 960 3788 960 3788 960 3789 960 3790 960 3791 960 3792 960 3795 960 3795 2588 3792 2588 3793 2588 3795 2589 3793 2589 3794 2589 3794 960 3824 960 3795 960 3795 960 3824 960 3825 960 3795 960 3825 960 3394 960 3394 960 3825 960 3392 960 3392 960 3825 960 3817 960 3392 960 3817 960 3796 960 3796 960 3817 960 3797 960 3796 960 3797 960 3816 960 3557 960 3801 960 3571 960 3571 960 3801 960 3798 960 3571 960 3798 960 3572 960 3572 960 3798 960 3799 960 3572 960 3799 960 3803 960 2969 2590 2970 2590 3800 2590 3800 960 2970 960 3709 960 3800 960 3709 960 3801 960 3801 960 3709 960 3805 960 3801 960 3805 960 3798 960 3798 960 3805 960 3802 960 3798 960 3802 960 3799 960 3461 960 3457 960 3737 960 3737 960 3457 960 3803 960 3737 960 3803 960 3804 960 3804 960 3803 960 3799 960 3804 960 3799 960 3701 960 3701 960 3799 960 3802 960 3701 960 3802 960 2972 960 2972 960 3802 960 3805 960 2972 960 3805 960 2971 960 2971 960 3805 960 3806 960 2971 2591 3806 2591 3807 2591 2975 960 2976 960 3699 960 3699 960 2976 960 3598 960 3699 960 3598 960 3701 960 3701 960 3598 960 3808 960 3701 960 3808 960 3809 960 3809 960 3808 960 3409 960 2986 960 2985 960 3810 960 3810 960 2985 960 3811 960 3810 960 3811 960 3812 960 3812 960 3811 960 3533 960 3812 960 3533 960 3813 960 3813 2592 3533 2592 3814 2592 3625 2593 3816 2593 3815 2593 3815 960 3816 960 3797 960 3815 960 3797 960 3649 960 3649 960 3797 960 3817 960 3649 960 3817 960 3430 960 3430 960 3817 960 3426 960 3484 960 3482 960 3818 960 3818 960 3482 960 3510 960 3818 960 3510 960 3819 960 3819 960 3510 960 3472 960 3819 960 3472 960 3826 960 3826 960 3472 960 3443 960 3826 960 3443 960 3820 960 3821 2594 3822 2594 2933 2594 2933 960 3822 960 3823 960 2933 960 3823 960 3780 960 3780 960 3823 960 3494 960 3780 960 3494 960 3784 960 3784 960 3494 960 3818 960 3784 960 3818 960 3824 960 3824 960 3818 960 3819 960 3824 960 3819 960 3825 960 3825 960 3819 960 3826 960 3825 960 3826 960 3817 960 3817 960 3826 960 3404 960 3817 2595 3404 2595 3425 2595 2996 2596 3827 2596 3617 2596 3617 2597 3827 2597 3618 2597 4458 2598 4069 2598 3828 2598 3828 2598 4069 2598 4079 2598 3828 2599 4079 2599 3829 2599 3829 2600 4079 2600 3830 2600 4081 2601 4454 2601 3831 2601 3831 2602 4454 2602 3833 2602 3831 2603 3833 2603 3832 2603 3832 2604 3833 2604 3834 2604 3832 2605 3834 2605 4393 2605 4393 2606 3834 2606 3835 2606 4074 2607 4448 2607 4072 2607 4072 2608 4448 2608 3836 2608 4072 2609 3836 2609 3837 2609 3837 2610 3836 2610 4450 2610 3837 2611 4450 2611 4067 2611 4067 2612 4450 2612 4634 2612 4067 2613 4634 2613 4066 2613 4066 2614 4634 2614 4633 2614 4066 2615 4633 2615 3838 2615 3838 2616 4633 2616 4443 2616 3838 2617 4443 2617 3840 2617 3838 2618 3840 2618 3839 2618 3839 2619 3840 2619 3842 2619 3839 2620 3842 2620 3841 2620 3841 2621 3842 2621 3843 2621 3841 2621 3843 2621 3844 2621 3844 2622 3843 2622 4704 2622 3844 2623 4704 2623 3845 2623 4456 2624 3846 2624 4457 2624 4457 2625 3846 2625 4415 2625 4457 2626 4415 2626 3847 2626 3847 2627 4415 2627 3848 2627 3847 2628 3848 2628 4704 2628 4704 2628 3848 2628 3845 2628 3849 2629 3860 2629 4710 2629 4710 2630 3860 2630 3850 2630 3851 2631 3852 2631 3853 2631 3851 2632 3853 2632 4413 2632 4413 2633 3853 2633 3854 2633 4413 2634 3854 2634 3856 2634 3856 2635 3854 2635 3855 2635 3856 2635 3855 2635 3857 2635 3857 2636 3855 2636 3858 2636 3857 2637 3858 2637 4407 2637 4407 2638 3858 2638 3859 2638 4407 2639 3859 2639 4408 2639 4408 2640 3859 2640 4705 2640 4408 2641 4705 2641 4409 2641 4409 2642 4705 2642 3850 2642 4409 2642 3850 2642 3860 2642 3861 2643 4442 2643 3862 2643 3862 2644 4442 2644 3863 2644 3862 2645 3863 2645 4097 2645 4097 2646 3863 2646 3864 2646 4097 2647 3864 2647 4095 2647 4095 2648 3864 2648 3865 2648 4095 2649 3865 2649 3866 2649 3866 2650 3865 2650 3867 2650 4109 2651 4483 2651 3868 2651 3868 2652 4483 2652 4716 2652 3868 2653 4716 2653 3869 2653 3869 2654 4716 2654 4717 2654 3869 2655 4717 2655 3870 2655 3870 2655 4717 2655 3871 2655 3872 2656 3877 2656 3874 2656 3874 2657 3877 2657 3873 2657 3874 2658 3873 2658 4107 2658 4107 2659 3873 2659 3875 2659 4107 2660 3875 2660 4111 2660 4111 2661 3875 2661 3876 2661 4221 2662 4481 2662 3880 2662 3877 2663 3872 2663 3878 2663 3878 2664 3872 2665 3879 2666 3878 2667 3879 2667 3880 2667 3880 2668 3879 2668 4218 2668 3880 2662 4218 2662 4221 2662 4481 2669 4221 2669 4476 2669 4476 2670 4221 2670 4222 2670 4476 2671 4222 2671 4477 2671 4477 2672 4222 2672 3881 2672 4514 2673 4122 2673 3884 2673 4128 2674 3882 2674 3883 2674 3883 2674 3882 2674 3885 2674 3883 2675 3885 2675 3884 2675 3884 2676 3885 2676 4516 2676 3884 2677 4516 2677 4514 2677 4131 2678 4130 2678 3886 2678 3886 2679 4130 2679 3887 2679 4129 2680 4517 2680 4509 2680 4129 2680 4509 2680 3888 2680 3888 2681 4509 2681 3887 2681 3888 2681 3887 2681 4130 2681 4135 2682 3889 2682 4134 2682 4134 2683 3889 2683 4519 2683 4134 2684 4519 2684 4347 2684 4347 2685 4519 2685 4518 2685 4347 2686 4518 2686 4129 2686 4129 2687 4518 2687 4517 2687 3890 2688 4520 2688 4777 2688 3890 2688 4777 2688 4133 2688 4133 2689 4777 2689 4776 2689 4133 2690 4776 2690 3891 2690 3891 2691 4776 2691 3889 2691 3891 2692 3889 2692 4135 2692 4520 2693 3890 2693 3892 2693 3892 2694 3890 2694 3893 2694 3892 2695 3893 2695 4521 2695 4521 2696 3893 2696 4336 2696 4533 2697 3894 2697 4530 2697 4530 2698 3894 2698 3895 2698 4530 2699 3895 2699 4528 2699 4528 2700 3895 2700 4145 2700 4151 2701 4527 2701 3896 2701 4528 2702 4145 2702 3897 2702 3897 2703 4145 2703 3898 2703 3897 2704 3898 2704 3896 2704 3896 2704 3898 2704 3899 2704 3896 2701 3899 2701 4151 2701 4522 2705 3900 2705 3901 2705 3901 2706 3900 2706 4150 2706 4522 2707 3901 2707 4524 2707 4524 2708 3901 2709 4152 2710 4524 2711 4152 2712 4525 2713 4152 2714 3902 2715 4525 2716 4525 2717 3902 2717 3903 2717 4525 2718 3903 2718 4768 2718 4768 2719 3903 2719 3904 2719 4768 2720 3904 2720 3905 2720 3905 2721 3904 2721 4548 2721 4548 2722 3904 2722 3906 2722 4548 2723 3906 2723 4547 2723 4547 2723 3906 2723 4160 2723 4142 2724 3907 2724 3908 2724 3908 2725 3907 2725 3909 2725 3908 2726 3909 2726 4155 2726 4155 2727 3909 2727 4543 2727 4155 2728 4543 2728 4156 2728 4156 2728 4543 2728 3910 2728 4537 2729 3911 2729 4139 2729 4537 2730 4139 2730 4538 2730 4538 2731 4139 2731 4138 2731 4538 2731 4138 2731 4541 2731 4541 2732 4138 2732 3913 2732 4541 2733 3913 2733 3912 2733 3912 2734 3913 2734 4143 2734 3912 2735 4143 2735 4542 2735 4537 2736 4536 2736 3911 2736 3911 2736 4536 2736 4140 2736 4196 2737 4566 2737 3914 2737 3914 2738 4566 2738 4590 2738 3914 2739 4590 2739 4352 2739 4352 2740 4590 2740 4567 2740 4352 2741 4567 2741 4351 2741 4351 2742 4567 2742 3915 2742 4351 2743 3915 2743 3917 2743 3917 2744 3915 2744 3916 2744 3917 2745 3916 2745 4182 2745 4182 2746 3916 2746 3918 2746 4182 2747 3918 2747 4184 2747 4184 2748 3918 2748 4574 2748 4184 2749 4574 2749 3919 2749 3919 2750 4574 2750 4573 2750 3919 2751 4573 2751 4186 2751 4186 2752 4573 2752 4572 2752 4186 2753 4572 2753 3920 2753 3920 2754 4572 2754 4570 2754 3920 2755 4570 2755 3921 2755 3921 2756 4570 2756 4569 2756 3921 2757 4569 2757 4189 2757 4189 2758 4569 2758 3922 2758 4189 2759 3922 2759 4190 2759 4190 2760 3922 2760 3923 2760 4190 2761 3923 2761 4191 2761 4191 2762 3923 2762 3924 2762 4191 2763 3924 2763 4181 2763 4181 2764 3924 2764 4575 2764 4181 2765 4575 2766 3925 2767 3925 2768 4575 2768 3926 2768 3925 2769 3926 2769 4198 2769 4198 2770 3926 2770 4583 2770 4198 2771 4583 2771 3927 2771 3927 2772 4583 2772 4582 2772 3927 2773 4582 2773 3928 2773 3928 2774 4582 2774 3929 2774 3928 2775 3929 2775 4199 2775 4199 2776 3929 2776 4563 2776 4199 2777 4563 2777 4200 2777 4200 2778 4563 2778 4562 2778 4200 2779 4562 2779 3930 2779 3930 2780 4562 2780 3931 2780 3930 2781 3931 2781 3932 2781 3932 2782 3931 2782 3933 2782 3932 2783 3933 2783 4197 2783 4197 2784 3933 2784 4720 2784 4197 2785 4720 2785 4403 2785 4403 2786 4720 2786 3934 2786 4403 2787 3934 2787 4193 2787 4193 2788 3934 2788 3935 2788 4193 2789 3935 2789 4194 2789 4194 2790 3935 2790 3936 2790 4194 2791 3936 2791 4195 2791 4195 2792 3936 2792 4564 2792 4195 2793 4564 2793 4196 2793 4196 2794 4564 2794 4566 2794 4440 2795 4239 2795 3937 2795 3937 2796 4239 2796 4237 2796 3937 2797 4237 2797 3939 2797 3939 2798 4237 2798 3938 2798 3939 2799 3938 2799 4764 2799 4764 2800 3938 2800 4358 2800 4764 2801 4358 2801 3940 2801 3940 2802 4358 2802 3941 2802 3940 2803 3941 2803 4669 2803 4669 2804 3941 2804 4288 2804 4669 2805 4288 2805 3942 2805 3942 2806 4288 2806 4369 2806 3942 2807 4369 2807 4723 2807 4723 2808 4369 2808 3943 2808 4723 2809 3943 2809 4608 2809 4608 2810 3943 2810 4061 2810 4608 2811 4061 2811 336 2811 336 2812 4061 2812 3095 2812 3946 2813 4606 2813 3944 2813 3944 2814 4606 2814 4605 2814 3944 2815 4605 2815 3945 2815 3945 2816 4605 2816 4607 2816 3945 2817 4607 2817 3095 2817 3095 2818 4607 2818 336 2818 4606 2819 3946 2819 3947 2819 3947 2820 3946 2820 4242 2820 3947 2821 4242 2821 3948 2821 3948 2822 4242 2822 3949 2822 3948 2823 3949 2823 4603 2823 4603 2823 3949 2823 3950 2823 4603 2824 3950 2824 3951 2824 3951 2825 3950 2825 4247 2825 3951 2826 4247 2826 4604 2826 4604 2827 4247 2827 4246 2827 4604 2828 4246 2828 3952 2828 3952 2829 4246 2829 3953 2829 3952 2830 3953 2830 3954 2830 3952 2831 3954 2831 3956 2831 3956 2832 3954 2832 3955 2832 3956 2833 3955 2833 3957 2833 4248 2834 3961 2834 4249 2834 4249 2835 3961 2835 4602 2835 4249 2836 4602 2836 4250 2836 4250 2837 4602 2837 3958 2837 4250 2838 3958 2838 4252 2838 4252 2838 3958 2838 3959 2838 4252 2839 3959 2839 3955 2839 3955 2840 3959 2840 3957 2840 3967 2841 3968 2841 3960 2841 3967 2842 3960 2842 4077 2842 4077 2843 3960 2843 4445 2843 4077 2843 4445 2843 3962 2843 3962 2844 4445 2844 3961 2844 3962 2845 3961 2845 4248 2845 4256 2846 3963 2846 4255 2846 4255 2847 3963 2847 3964 2847 4255 2848 3964 2848 4068 2848 4068 2849 3964 2849 4452 2849 4068 2850 4452 2850 4071 2850 4071 2851 4452 2851 4451 2851 4071 2852 4451 2852 4073 2852 4073 2852 4451 2852 3965 2852 4073 2853 3965 2853 3966 2853 3966 2854 3965 2854 4449 2854 3966 2855 4449 2855 3967 2855 3967 2855 4449 2855 3968 2855 3972 2856 4231 2856 3969 2856 3969 2857 4231 2857 3970 2857 3969 2858 3970 2858 4609 2858 4609 2859 3970 2859 3971 2859 4231 2860 3972 2860 4229 2860 4229 2861 3972 2861 3973 2861 4229 2862 3973 2862 4227 2862 4227 2863 3973 2863 4625 2863 4625 2864 4623 2864 4227 2864 4227 2865 4623 2865 4226 2865 4226 2866 4623 2866 3974 2866 3974 2867 4623 2867 3975 2867 3974 2868 3975 2868 3976 2868 3976 2869 3975 2869 3977 2869 3976 2870 3977 2870 3978 2870 3978 2871 3977 2871 3979 2871 3978 2872 3979 2872 3980 2872 3980 2873 3979 2873 3981 2873 3980 2874 3981 2874 4511 2874 3980 2875 4511 2875 3982 2875 3982 2876 4511 2876 3984 2876 3982 2877 3984 2877 3983 2877 3983 2878 3984 2878 3985 2878 3983 2879 3985 2879 4123 2879 4123 2880 3985 2880 3986 2880 4123 2881 3986 2881 3987 2881 3987 2882 3986 2882 3988 2882 3987 2883 3988 2883 4124 2883 4124 2884 3988 2884 3991 2884 4124 2885 3991 2885 3989 2885 4127 2886 3989 2886 3990 2886 3990 2887 3989 2887 3991 2887 4127 2888 3990 2888 3992 2888 3992 2889 3990 2889 4515 2889 3992 2890 4515 2890 4324 2890 4324 2891 4515 2891 4505 2891 4324 2892 4505 2892 3993 2892 3993 2893 4505 2893 4793 2893 3993 2894 4793 2894 4147 2894 4147 2894 4793 2894 3997 2894 4534 2895 3994 2895 3995 2895 4147 2896 3997 2897 3996 2898 3996 2899 3997 2900 3998 2901 3996 2902 3998 2902 3995 2902 3995 2903 3998 2903 3999 2903 3995 2895 3999 2895 4534 2895 4531 2904 4000 2904 4532 2904 4532 2905 4000 2905 4149 2905 4532 2906 4149 2906 4534 2906 4534 2906 4149 2906 3994 2906 4000 2907 4531 2907 4529 2907 4006 2908 4002 2908 4001 2908 4001 2909 4002 2909 4003 2909 4001 2910 4003 2910 4529 2910 4529 2911 4003 2911 4004 2911 4529 2912 4004 2912 4000 2912 4002 2913 4006 2913 4005 2913 4005 2914 4006 2914 4523 2914 4005 2915 4523 2915 4367 2915 4367 2916 4523 2916 4007 2916 4367 2917 4007 2917 4366 2917 4366 2918 4007 2918 4008 2918 4366 2919 4008 2919 4009 2919 4009 2920 4008 2920 4771 2920 4009 2921 4771 2921 4364 2921 4364 2922 4771 2922 4480 2922 4364 2923 4480 2923 4084 2923 4084 2924 4480 2924 4011 2924 4084 2925 4011 2925 4010 2925 4010 2926 4011 2926 4472 2926 4012 2927 4015 2927 4088 2927 4010 2928 4472 2928 4089 2928 4089 2929 4472 2929 4013 2929 4089 2930 4013 2930 4088 2930 4088 2931 4013 2931 4014 2931 4088 2932 4014 2932 4012 2932 4015 2933 4012 2933 4062 2933 4062 2934 4012 2934 4016 2934 4062 2935 4016 2935 4098 2935 4098 2936 4016 2937 4017 2938 4098 2939 4017 2939 4099 2939 4099 2940 4017 2940 4018 2940 4099 2941 4018 2941 4019 2941 4019 2942 4018 2942 4631 2942 4019 2943 4631 2943 4063 2943 4063 2943 4631 2943 4632 2943 4063 2944 4632 2944 4020 2944 4701 2945 4026 2945 4630 2945 4630 2945 4026 2945 4418 2945 4630 2946 4418 2946 4020 2946 4020 2947 4418 2947 4021 2947 4020 2948 4021 2948 4063 2948 4022 2949 4023 2949 4024 2949 4024 2950 4023 2950 4423 2950 4024 2951 4423 2951 4025 2951 4025 2952 4423 2952 4421 2952 4025 2953 4421 2953 4700 2953 4700 2954 4421 2954 4420 2954 4700 2955 4420 2955 4701 2955 4701 2956 4420 2956 4026 2956 4027 2957 4257 2957 4028 2957 4028 2958 4257 2958 4029 2958 4028 2959 4029 2959 4677 2959 4677 2960 4029 2960 4274 2960 4677 2961 4274 2961 4030 2961 4030 2962 4274 2962 4275 2962 4264 2963 4651 2963 4031 2963 4031 2964 4651 2964 4652 2964 4031 2965 4652 2965 4032 2965 4032 2966 4652 2966 4653 2966 4032 2967 4653 2967 4277 2967 4277 2968 4653 2968 4655 2968 4033 2969 4034 2969 4373 2969 4373 2969 4034 2969 4263 2969 4303 2970 4046 2970 4035 2970 4035 2971 4046 2971 4683 2971 4035 2972 4683 2972 4036 2972 4036 2973 4683 2973 4682 2973 4036 2974 4682 2974 4299 2974 4299 2975 4682 2975 4037 2975 4299 2976 4037 2976 4038 2976 4038 2977 4037 2977 4680 2977 4038 2978 4680 2978 4300 2978 4300 2979 4680 2979 4679 2979 4300 2980 4679 2980 4304 2980 4304 2981 4679 2981 4305 2981 4305 2982 4679 2982 4689 2982 4305 2983 4689 2983 4308 2983 4689 2984 4688 2984 4308 2984 4308 2985 4688 2985 4039 2985 4308 2986 4039 2986 4040 2986 4040 2987 4039 2987 4685 2987 4040 2988 4685 2988 4309 2988 4309 2989 4685 2989 4041 2989 4309 2990 4041 2990 4042 2990 4042 2991 4041 2991 4043 2991 4042 2992 4043 2992 4301 2992 4301 2993 4043 2993 4044 2993 4044 2994 4043 2994 4045 2994 4044 2995 4045 2995 4303 2995 4303 2996 4045 2996 4684 2996 4303 2997 4684 2997 4046 2997 4370 2998 4735 2998 4047 2998 4047 2970 4735 2970 4734 2970 4047 2999 4734 2999 4049 2999 4049 3000 4734 3000 4048 3000 4049 3001 4048 3001 4371 3001 4371 3002 4048 3002 4050 3002 4371 3003 4050 3003 4372 3003 4372 3004 4050 3004 4731 3004 4372 3005 4731 3005 4052 3005 4052 3006 4731 3006 4051 3006 4052 3007 4051 3007 4053 3007 4053 3008 4051 3008 4730 3008 4053 3009 4730 3009 4054 3009 4054 3010 4730 3010 4055 3010 4054 3011 4055 3011 4375 3011 4375 3012 4055 3012 4056 3012 4375 3013 4056 3013 4058 3013 4058 3014 4056 3014 4057 3014 4058 3015 4057 3015 4059 3015 4059 3016 4057 3016 4729 3016 4059 3017 4729 3017 4060 3017 4060 3018 4729 3018 4728 3018 4060 3019 4728 3019 4370 3019 4370 3020 4728 3020 4735 3020 4341 3021 4340 3021 4311 3021 3095 960 4061 960 4398 960 4098 3022 4096 3022 4062 3022 4063 3023 4021 3023 4418 3023 4155 960 4154 960 3908 960 4347 3024 4136 3024 4134 3024 4100 960 4064 960 4101 960 4094 960 4085 960 4084 960 3881 960 4222 960 4363 960 3845 3025 3848 3025 4417 3025 3845 960 4417 960 3844 960 3841 960 4065 960 3839 960 3839 960 4065 960 4422 960 4067 960 4066 960 4422 960 4422 3026 4066 3026 3838 3026 4422 3027 3838 3027 3839 3027 4255 960 4068 960 4067 960 4067 960 4068 960 4071 960 4067 3028 4071 3028 3837 3028 3837 960 4071 960 4072 960 4069 960 4070 960 4078 960 4078 3029 4070 3029 4076 3029 4071 960 4073 960 4072 960 4072 3030 4073 3030 3966 3030 4072 960 3966 960 4074 960 4074 3031 3966 3031 3967 3031 4074 960 3967 960 4075 960 4075 960 3967 960 4076 960 4248 960 4078 960 3962 960 3962 960 4078 960 4076 960 3962 3032 4076 3032 4077 3032 4077 3033 4076 3033 3967 3033 4395 960 3830 960 4078 960 4078 3034 3830 3034 4079 3034 4078 3035 4079 3035 4069 3035 3832 3036 4393 3036 4400 3036 4414 960 4415 960 4080 960 4080 960 4415 960 3846 960 3831 960 4082 960 4081 960 4081 960 4082 960 4080 960 4081 960 4080 960 4083 960 4083 960 4080 960 3846 960 4084 960 4085 960 4364 960 4364 3037 4085 3037 4086 3037 4364 3038 4086 3038 4087 3038 3881 960 4363 960 4087 960 4095 3039 3866 3039 4015 3039 4015 3040 3866 3040 4088 3040 4088 960 3866 960 4090 960 4088 960 4090 960 4089 960 4089 3041 4090 3041 4091 3041 4089 3042 4091 3042 4010 3042 4010 3043 4091 3043 4092 3043 4010 960 4092 960 4084 960 4084 3044 4092 3044 4093 3044 4084 3045 4093 3045 4094 3045 4015 960 4062 960 4095 960 4095 3046 4062 3046 4096 3046 4095 960 4096 960 4097 960 4097 3047 4096 3047 4098 3047 4097 960 4098 960 3862 960 3862 3048 4098 3048 4099 3048 3862 3049 4099 3049 3861 3049 3861 960 4099 960 4019 960 3870 960 4103 960 4419 960 4100 3050 4101 3050 4102 3050 4103 960 4104 960 4419 960 4419 3051 4104 3051 4105 3051 4419 3052 4105 3052 4101 3052 4101 3053 4105 3053 4106 3053 4101 3054 4106 3054 4102 3054 3872 3055 3874 3055 4401 3055 4401 960 3874 960 4107 960 4401 3056 4107 3056 4402 3056 4402 960 4107 960 4111 960 3868 3057 4108 3057 4109 3057 4109 960 4108 960 4402 960 4109 960 4402 960 4110 960 4110 960 4402 960 4111 960 3879 960 4112 960 4218 960 4218 960 4112 960 4215 960 4254 3058 3203 3058 4398 3058 4398 960 3203 960 3206 960 4398 960 3206 960 3212 960 4240 3059 3211 3059 4241 3059 4241 3060 3211 3060 3209 3060 4113 3061 4114 3061 4245 3061 4245 3062 4114 3062 4115 3062 4245 960 4115 960 4254 960 4254 3063 4115 3063 3204 3063 4254 3064 3204 3064 3203 3064 3950 3065 4244 3065 4117 3065 3209 960 3205 960 4241 960 4241 3066 3205 3066 4243 3066 4241 960 4243 960 4116 960 4113 960 4245 960 4117 960 4117 3067 4245 3067 4247 3067 4117 3068 4247 3068 3950 3068 4120 960 4119 960 4118 960 4118 3069 4119 3069 4336 3069 3989 960 3883 960 3884 960 4118 3070 3982 3070 4120 3070 4120 960 3982 960 3983 960 4120 3071 3983 3071 4121 3071 4121 3072 3983 3072 4123 3072 4121 3073 4123 3073 4122 3073 4122 960 4123 960 3987 960 4122 960 3987 960 3884 960 3884 960 3987 960 4124 960 3884 960 4124 960 3989 960 4125 3074 3992 3074 4126 3074 4126 3075 3992 3075 4324 3075 4126 960 4324 960 4132 960 3989 960 4127 960 3883 960 3883 3076 4127 3076 3992 3076 3883 960 3992 960 4128 960 4128 960 3992 960 4125 960 4129 960 3888 960 4187 960 4187 960 3888 960 4130 960 4187 960 4130 960 4324 960 4324 960 4130 960 4131 960 4324 3077 4131 3077 4132 3077 3890 3078 4133 3078 4338 3078 3890 960 4338 960 3893 960 4134 3079 4136 3079 4135 3079 4135 960 4136 960 4137 960 4135 960 4137 960 3891 960 3913 960 4138 960 3993 960 3993 3080 4138 3080 4139 3080 3911 3081 4140 3081 4321 3081 4321 960 4140 960 4141 960 4321 3082 4141 3082 4142 3082 3913 3083 3993 3083 4143 3083 4143 960 3993 960 4147 960 4143 960 4147 960 4144 960 4003 960 3898 960 4004 960 4004 3084 3898 3084 4145 3084 4144 960 4147 960 4146 960 4146 3085 4147 3085 3996 3085 4146 3086 3996 3086 4148 3086 4148 3087 3996 3087 3995 3087 4148 3088 3995 3088 3894 3088 3894 3089 3995 3089 3994 3089 3894 960 3994 960 3895 960 3895 3090 3994 3090 4149 3090 3895 960 4149 960 4145 960 4145 3091 4149 3091 4000 3091 4145 3092 4000 3092 4004 3092 4152 960 3901 960 4005 960 4005 960 3901 960 4150 960 4005 960 4150 960 4002 960 4002 3093 4150 3093 4151 3093 4002 960 4151 960 4003 960 4003 3094 4151 3094 3899 3094 4003 3095 3899 3095 3898 3095 4152 960 4005 960 3902 960 3902 960 4005 960 4367 960 3902 960 4367 960 3903 960 4348 3096 4160 3096 4153 3096 4153 960 4160 960 3906 960 4153 3097 3906 3097 3904 3097 4154 960 4155 960 4157 960 4155 960 4156 960 4157 960 4157 3098 4156 3098 4158 3098 4157 3099 4158 3099 4348 3099 4348 3100 4158 3100 4159 3100 4348 3101 4159 3101 4160 3101 4400 3102 4396 3102 4377 3102 4165 960 4362 960 4166 960 4161 960 4400 960 4162 960 4162 3103 4400 3103 4377 3103 4162 960 4377 960 4163 960 4163 960 4377 960 4164 960 4165 960 4166 960 4310 960 4302 3104 4349 3104 4167 3104 4161 3105 4168 3105 4400 3105 4400 3106 4168 3106 4169 3106 4400 960 4169 960 4170 960 4170 3107 4169 3107 4171 3107 4171 3108 4172 3108 4170 3108 4170 960 4172 960 4173 960 4170 960 4173 960 4174 960 4174 960 4173 960 4175 960 4175 3109 4176 3109 4174 3109 4174 3110 4176 3110 4177 3110 4174 3111 4177 3111 4178 3111 4178 3112 4177 3112 4179 3112 4178 3113 4179 3113 4349 3113 4191 3114 4181 3114 4180 3114 4180 960 4181 960 4178 960 3917 3115 4182 3115 4183 3115 4183 3116 4182 3116 4184 3116 4183 960 4184 960 4185 960 4184 960 3919 960 4185 960 4185 960 3919 960 4186 960 4185 3117 4186 3117 4321 3117 4321 960 4186 960 3920 960 4321 3118 3920 3118 4187 3118 4187 3119 3920 3119 3921 3119 4187 3120 3921 3120 4188 3120 4188 960 3921 960 4189 960 4188 960 4189 960 4346 960 4346 960 4189 960 4190 960 4346 960 4190 960 4191 960 4351 960 3917 960 4348 960 3914 960 4204 960 4215 960 4403 3121 4193 3121 4192 3121 4192 960 4193 960 4194 960 4192 3122 4194 3122 4112 3122 4112 960 4194 960 4195 960 4112 3123 4195 3123 4215 3123 4215 3124 4195 3124 4196 3124 4215 960 4196 960 3914 960 4197 960 4402 960 4080 960 4197 3125 4080 3125 3932 3125 4181 960 3925 960 4178 960 4178 960 3925 960 4198 960 4178 3126 4198 3126 4174 3126 4174 960 4198 960 3927 960 4174 960 3927 960 4170 960 4170 3127 3927 3127 3928 3127 4170 960 3928 960 4400 960 4400 3128 3928 3128 4199 3128 4400 3129 4199 3129 4399 3129 4399 960 4199 960 4200 960 4399 3130 4200 3130 3930 3130 4212 3131 4201 3131 4204 3131 4204 3132 4201 3132 4202 3132 4214 960 4215 960 4203 960 4203 960 4215 960 4204 960 4203 960 4204 960 4205 960 4205 960 4204 960 4202 960 4206 960 4208 960 4207 960 4207 3133 4208 3133 4209 3133 4207 960 4209 960 4365 960 4365 3134 4209 3134 4210 3134 4365 960 4210 960 4212 960 4212 3135 4210 3135 4211 3135 4212 3136 4211 3136 4201 3136 4206 960 4207 960 4213 960 4213 960 4207 960 4363 960 4213 3137 4363 3137 4225 3137 4214 3138 4216 3138 4215 3138 4215 3139 4216 3139 4217 3139 4215 960 4217 960 4218 960 4218 3140 4217 3140 4219 3140 4218 3141 4219 3141 4221 3141 4221 3142 4219 3142 4220 3142 4221 960 4220 960 4222 960 4222 3143 4220 3143 4223 3143 4222 960 4223 960 4363 960 4363 960 4223 960 4224 960 4363 960 4224 960 4225 960 4063 960 4101 960 4019 960 4019 960 4101 960 4064 960 4019 960 4064 960 3861 960 4339 960 3976 960 4337 960 4337 960 3976 960 3978 960 4337 3144 3978 3144 4118 3144 4118 3145 3978 3145 3980 3145 4118 3146 3980 3146 3982 3146 4235 3147 4226 3147 4339 3147 4339 960 4226 960 3974 960 4339 960 3974 960 3976 960 3194 3148 4229 3148 4235 3148 4235 3149 4229 3149 4227 3149 4235 3150 4227 3150 4226 3150 3197 960 4228 960 4238 960 3194 960 4230 960 4229 960 4229 3151 4230 3151 3193 3151 4229 960 3193 960 4231 960 3193 960 4232 960 4231 960 4231 3152 4232 3152 4233 3152 4231 3153 4233 3153 3970 3153 4233 960 3199 960 3970 960 3970 3154 3199 3154 3198 3154 3970 960 3198 960 3197 960 4228 960 3195 960 4238 960 4238 3155 3195 3155 4234 3155 4238 3156 4234 3156 4235 3156 4235 960 4234 960 4236 960 4235 3157 4236 3157 3194 3157 4238 3158 4237 3158 4239 3158 3197 3159 4238 3159 3970 3159 3970 3160 4238 3160 4239 3160 3970 3161 4239 3161 3971 3161 3095 960 4398 960 3945 960 3212 960 4240 960 4398 960 4398 960 4240 960 4241 960 4398 960 4241 960 3945 960 3945 960 4241 960 4116 960 3945 960 4116 960 3944 960 3944 3162 4116 3162 4242 3162 3944 960 4242 960 3946 960 4243 3163 4244 3163 4116 3163 4116 3164 4244 3164 3950 3164 4116 960 3950 960 4242 960 4242 3165 3950 3165 3949 3165 4252 3166 3955 3166 4254 3166 3955 960 3954 960 4254 960 4254 3167 3954 3167 3953 3167 4254 960 3953 960 4245 960 4245 960 3953 960 4246 960 4245 960 4246 960 4247 960 4248 960 4249 960 4078 960 4078 960 4249 960 4250 960 4078 960 4250 960 4251 960 4251 960 4250 960 4252 960 4251 3168 4252 3168 4253 3168 4253 960 4252 960 4254 960 4067 3169 4422 3169 4255 3169 4255 3170 4422 3170 4023 3170 4255 3171 4023 3171 4256 3171 4257 960 4258 960 4272 960 4258 960 4259 960 4272 960 4272 3172 4259 3172 4260 3172 4272 960 4260 960 4269 960 4261 960 4262 960 4359 960 4261 3173 4359 3173 4263 3173 4264 3174 4031 3174 4265 3174 4265 3175 4031 3175 4356 3175 4265 960 4356 960 4266 960 4266 3176 4356 3176 4360 3176 4260 960 4267 960 4269 960 4269 3177 4267 3177 4268 3177 4269 3178 4268 3178 4373 3178 4278 960 4270 960 4271 960 4271 3179 4270 3179 4273 3179 4285 960 4278 960 4283 960 4257 3180 4272 3180 4029 3180 4029 960 4272 960 4271 960 4029 3181 4271 3181 4274 3181 4274 3182 4271 3182 4273 3182 4274 3183 4273 3183 4275 3183 4288 3184 4276 3184 4286 3184 4355 3185 4032 3185 4277 3185 4283 960 4278 960 4279 960 4279 960 4278 960 4271 960 4279 960 4271 960 4280 960 4280 960 4271 960 4369 960 4280 960 4369 960 4291 960 4295 3186 4353 3186 4292 3186 4295 3187 4296 3187 4281 3187 4281 3188 4296 3188 4282 3188 4281 3189 4282 3189 4283 3189 4283 3190 4282 3190 4284 3190 4283 3191 4284 3191 4285 3191 4286 3192 4287 3192 4288 3192 4288 3193 4287 3193 4289 3193 4288 960 4289 960 4369 960 4369 3194 4289 3194 4290 3194 4369 3195 4290 3195 4291 3195 4292 3196 4293 3196 4295 3196 4295 3197 4293 3197 4294 3197 4295 3198 4294 3198 4296 3198 4277 3199 4297 3199 4355 3199 4355 3200 4297 3200 4298 3200 4355 3201 4298 3201 4353 3201 4306 960 4315 960 4300 960 4035 960 4036 960 4338 960 4338 3202 4036 3202 4299 3202 4338 960 4299 960 4315 960 4315 3203 4299 3203 4038 3203 4315 3204 4038 3204 4300 3204 4309 960 4042 960 4302 960 4302 3205 4042 3205 4301 3205 4302 960 4301 960 4350 960 4350 3206 4301 3206 4044 3206 4350 960 4044 960 4338 960 4338 3207 4044 3207 4303 3207 4338 3208 4303 3208 4035 3208 4300 960 4304 960 4306 960 4306 3209 4304 3209 4305 3209 4306 960 4305 960 4307 960 4307 3210 4305 3210 4308 3210 4307 3211 4308 3211 4040 3211 4040 960 4309 960 4307 960 4307 3212 4309 3212 4302 3212 4307 3213 4302 3213 4166 3213 4166 960 4302 960 4167 960 4166 3214 4167 3214 4310 3214 4340 960 4426 960 4311 960 4311 3215 4426 3215 4312 3215 4311 3216 4312 3216 4345 3216 4313 960 4314 960 4315 960 4315 3217 4314 3217 4425 3217 4315 960 4425 960 4340 960 4340 3218 4425 3218 4316 3218 4340 3219 4316 3219 4426 3219 4344 3220 4428 3220 4431 3220 4432 960 4317 960 4307 960 4307 3221 4317 3221 4433 3221 4307 960 4433 960 4306 960 4306 3222 4433 3222 4318 3222 4306 960 4318 960 4315 960 4315 3223 4318 3223 4435 3223 4315 3224 4435 3224 4313 3224 4322 3225 4319 3225 3993 3225 4330 960 4320 960 4321 960 4321 960 4320 960 4323 960 4139 960 3911 960 3993 960 3993 3226 3911 3226 4321 3226 3993 3227 4321 3227 4322 3227 4322 960 4321 960 4323 960 4331 3228 4324 3228 4325 3228 4325 3229 4324 3229 3993 3229 4325 3230 3993 3230 4326 3230 4326 3231 3993 3231 4319 3231 4335 960 4327 960 4187 960 4187 3232 4327 3232 4328 3232 4187 960 4328 960 4321 960 4321 960 4328 960 4329 960 4321 960 4329 960 4330 960 4331 960 4332 960 4324 960 4324 960 4332 960 4333 960 4324 3233 4333 3233 4187 3233 4187 3234 4333 3234 4334 3234 4187 960 4334 960 4335 960 4336 960 3893 960 4118 960 4118 960 3893 960 4338 960 4118 960 4338 960 4337 960 4337 960 4338 960 4315 960 4337 960 4315 960 4339 960 4339 960 4315 960 4340 960 4339 960 4340 960 4235 960 4235 960 4340 960 4341 960 4235 960 4341 960 4238 960 4237 3235 4238 3235 4342 3235 4342 960 4238 960 4341 960 4342 3236 4341 3236 4343 3236 4343 960 4341 960 4311 960 4343 960 4311 960 4344 960 4344 960 4311 960 4345 960 4344 3237 4345 3237 4428 3237 4191 3238 4180 3238 4346 3238 4346 3239 4180 3239 4137 3239 4346 960 4137 960 4188 960 4188 3240 4137 3240 4136 3240 4188 960 4136 960 4187 960 4187 960 4136 960 4347 960 4187 960 4347 960 4129 960 3917 960 4183 960 4348 960 4348 3241 4183 3241 4185 3241 4348 960 4185 960 4157 960 4157 3242 4185 3242 4321 3242 4157 960 4321 960 4154 960 4154 3243 4321 3243 4142 3243 4154 960 4142 960 3908 960 4349 960 4302 960 4178 960 4178 3244 4302 3244 4350 3244 4178 960 4350 960 4180 960 4180 3245 4350 3245 4338 3245 4180 960 4338 960 4137 960 4137 960 4338 960 4133 960 4137 960 4133 960 3891 960 4153 960 4365 960 4348 960 4348 960 4365 960 4212 960 4348 960 4212 960 4351 960 4351 3246 4212 3246 4204 3246 4351 3247 4204 3247 4352 3247 4352 960 4204 960 3914 960 4295 960 4354 960 4353 960 4353 3248 4354 3248 4276 3248 4353 960 4276 960 4355 960 4355 3249 4276 3249 4288 3249 4355 3250 4288 3250 3941 3250 4031 960 4032 960 4356 960 4356 3251 4032 3251 4355 3251 4356 3252 4355 3252 4357 3252 4357 3253 4355 3253 3941 3253 4357 3254 3941 3254 4358 3254 4262 960 4360 960 4359 960 4359 960 4360 960 4356 960 4359 3255 4356 3255 4387 3255 4387 3256 4356 3256 4357 3256 4387 3257 4357 3257 4361 3257 4361 960 4357 960 4358 960 4361 3258 4358 3258 3938 3258 4431 3259 4432 3259 4344 3259 4344 3260 4432 3260 4307 3260 4344 3261 4307 3261 4385 3261 4385 960 4307 960 4166 960 4385 3262 4166 3262 4377 3262 4377 3263 4166 3263 4362 3263 4377 3264 4362 3264 4164 3264 4087 3265 4363 3265 4364 3265 4364 960 4363 960 4207 960 4364 960 4207 960 4009 960 4009 3266 4207 3266 4365 3266 4009 960 4365 960 4366 960 4366 3267 4365 3267 4153 3267 4366 960 4153 960 4367 960 4367 3268 4153 3268 3904 3268 4367 3269 3904 3269 3903 3269 4269 960 4374 960 4272 960 4272 960 4374 960 4397 960 4272 3270 4397 3270 4271 3270 4271 960 4397 960 4368 960 4271 960 4368 960 4369 960 4369 960 4368 960 3943 960 4390 3271 4370 3271 4047 3271 4390 960 4047 960 4386 960 4386 3272 4047 3272 4049 3272 4386 3273 4049 3273 4371 3273 4371 3274 4372 3274 4386 3274 4386 3275 4372 3275 4269 3275 4386 3276 4269 3276 4359 3276 4359 960 4269 960 4373 960 4359 3277 4373 3277 4263 3277 4372 960 4052 960 4269 960 4269 960 4052 960 4053 960 4269 3278 4053 3278 4374 3278 4374 3279 4053 3279 4054 3279 4374 3280 4054 3280 4375 3280 4375 3281 4058 3281 4374 3281 4374 3282 4058 3282 4059 3282 4374 3283 4059 3283 4390 3283 4390 3284 4059 3284 4060 3284 4390 3285 4060 3285 4370 3285 4396 3286 4383 3286 4376 3286 4396 3287 4376 3287 4377 3287 4377 3288 4376 3288 4378 3288 4377 3289 4378 3289 4379 3289 4392 960 4380 960 4390 960 4390 3290 4380 3290 4381 3290 4390 960 4381 960 4396 960 4396 3291 4381 3291 4382 3291 4396 3292 4382 3292 4383 3292 4379 3293 4384 3293 4377 3293 4377 3294 4384 3294 4386 3294 4377 3295 4386 3295 4385 3295 4385 3296 4386 3296 4359 3296 4385 3297 4359 3297 4344 3297 4344 3298 4359 3298 4387 3298 4344 960 4387 960 4343 960 4343 960 4387 960 4361 960 4343 3299 4361 3299 4342 3299 4342 3300 4361 3300 3938 3300 4342 3301 3938 3301 4237 3301 4384 3302 4388 3302 4386 3302 4386 3303 4388 3303 4389 3303 4386 3304 4389 3304 4390 3304 4390 3305 4389 3305 4391 3305 4390 3306 4391 3306 4392 3306 4393 960 4394 960 4400 960 4400 3307 4394 3307 4395 3307 4400 960 4395 960 4396 960 4396 3308 4395 3308 4078 3308 4396 960 4078 960 4390 960 4390 960 4078 960 4251 960 4390 960 4251 960 4374 960 4374 960 4251 960 4253 960 4374 960 4253 960 4397 960 4397 960 4253 960 4254 960 4397 960 4254 960 4368 960 4368 960 4254 960 4398 960 4368 960 4398 960 3943 960 3943 960 4398 960 4061 960 3930 3309 3932 3309 4399 3309 4399 960 3932 960 4080 960 4399 3310 4080 3310 4400 3310 4400 960 4080 960 4082 960 4400 3311 4082 3311 3832 3311 3832 960 4082 960 3831 960 3879 3312 3872 3312 4112 3312 4112 3313 3872 3313 4401 3313 4112 3310 4401 3310 4192 3310 4192 960 4401 960 4402 960 4192 3314 4402 3314 4403 3314 4403 3315 4402 3315 4197 3315 4404 960 4108 960 4405 960 4405 960 4108 960 4414 960 4405 960 4414 960 4406 960 4406 960 4414 960 4410 960 4413 960 3856 960 4402 960 4402 3316 3856 3316 3857 3316 4402 3317 3857 3317 4080 3317 4080 3318 3857 3318 4407 3318 4080 960 4407 960 4408 960 4408 960 4409 960 4080 960 4080 3319 4409 3319 3860 3319 4080 960 3860 960 4414 960 4414 3320 3860 3320 3849 3320 4414 3321 3849 3321 4410 3321 4404 3322 4411 3322 4108 3322 4108 960 4411 960 4412 960 4108 960 4412 960 4402 960 4402 3323 4412 3323 3851 3323 4402 960 3851 960 4413 960 3868 3324 3869 3324 4108 3324 4108 3325 3869 3325 4416 3325 4108 960 4416 960 4414 960 4414 960 4416 960 4417 960 4414 3326 4417 3326 4415 3326 4415 3327 4417 3327 3848 3327 3869 960 3870 960 4416 960 4416 960 3870 960 4419 960 4416 3328 4419 3328 4417 3328 4417 960 4419 960 4065 960 4417 960 4065 960 3844 960 3844 960 4065 960 3841 960 4063 3329 4418 3329 4101 3329 4101 3330 4418 3330 4026 3330 4101 3331 4026 3331 4419 3331 4419 960 4026 960 4420 960 4419 3332 4420 3332 4065 3332 4065 960 4420 960 4421 960 4065 960 4421 960 4422 960 4422 960 4421 960 4423 960 4422 3333 4423 3333 4023 3333 4435 2970 4687 2970 4313 2970 4313 3000 4687 3000 4686 3000 4313 3001 4686 3001 4314 3001 4314 2973 4686 2973 4691 2973 4314 2974 4691 2974 4425 2974 4425 3004 4691 3004 4424 3004 4425 3004 4424 3004 4316 3004 4316 3334 4424 3334 4693 3334 4316 3007 4693 3007 4426 3007 4426 3335 4693 3335 4427 3335 4426 3336 4427 3336 4312 3336 4312 3337 4427 3337 4345 3337 4345 3338 4427 3338 4429 3338 4345 3339 4429 3339 4428 3339 4429 3340 4438 3340 4428 3340 4428 3341 4438 3341 4430 3341 4428 3342 4430 3342 4431 3342 4431 3343 4430 3343 4698 3343 4431 3344 4698 3344 4432 3344 4432 3345 4698 3345 4696 3345 4432 3346 4696 3346 4317 3346 4317 3347 4696 3347 4434 3347 4317 3348 4434 3348 4433 3348 4433 3349 4434 3349 4318 3349 4318 3350 4434 3350 4694 3350 4318 3351 4694 3351 4435 3351 4435 3352 4694 3352 4436 3352 4435 2999 4436 2999 4687 2999 4736 3353 4750 3353 4733 3353 4437 3354 4718 3354 4715 3354 4438 590 4429 590 4773 590 4439 590 4027 590 4028 590 4016 3355 4469 3355 4017 3355 4440 3356 3937 3356 4610 3356 4767 3357 4441 3357 4770 3357 3923 3358 4568 3358 3924 3358 4567 590 4594 590 4765 590 3909 3359 4784 3359 4543 3359 4442 3360 4464 3360 4629 3360 4443 3361 4633 3361 4699 3361 4446 590 4444 590 4459 590 4602 3362 3961 3362 4459 3362 4459 3363 3961 3363 4445 3363 4459 3364 4445 3364 4446 3364 4446 3365 4445 3365 3960 3365 4446 3366 3960 3366 4447 3366 4447 3367 3960 3367 3968 3367 4447 590 3968 590 4448 590 4448 3368 3968 3368 3836 3368 3968 590 4449 590 3836 590 3836 590 4449 590 3965 590 3836 3369 3965 3369 4450 3369 4450 3370 3965 3370 4451 3370 4450 590 4451 590 4634 590 4634 3371 4451 3371 4452 3371 4634 3372 4452 3372 3964 3372 4704 590 3843 590 4453 590 4453 590 3843 590 3842 590 4453 590 3842 590 4699 590 4699 3373 3842 3373 3840 3373 4699 3374 3840 3374 4443 3374 3835 590 3834 590 4721 590 4721 590 3834 590 3833 590 4721 590 3833 590 4714 590 4714 3375 3833 3375 4454 3375 4454 590 4455 590 4714 590 4714 3376 4455 3376 4456 3376 4714 590 4456 590 4708 590 4708 590 4456 590 4457 590 4708 590 4457 590 3847 590 4444 590 4458 590 4459 590 4459 3377 4458 3377 3828 3377 4459 3378 3828 3378 4751 3378 4460 590 4743 590 4461 590 4461 590 4743 590 4751 590 4461 590 4751 590 3829 590 3829 3379 4751 3379 3828 3379 4462 3380 4463 3380 4703 3380 4703 3381 4463 3381 4702 3381 4464 590 4465 590 4629 590 4629 590 4465 590 4466 590 4629 3382 4466 3382 4462 3382 4467 590 3871 590 4718 590 4631 3383 4018 3383 3863 3383 3863 3384 4018 3384 3864 3384 4013 3385 4468 3385 4014 3385 4014 3386 4468 3386 3867 3386 4018 3387 4017 3387 3864 3387 3864 3388 4017 3388 4469 3388 3864 590 4469 590 3865 590 3865 3389 4469 3389 4016 3389 3865 590 4016 590 3867 590 3867 590 4016 590 4012 590 3867 3390 4012 3390 4014 3390 4478 590 4470 590 4011 590 4011 3391 4470 3391 4471 3391 4011 3392 4471 3392 4472 3392 4472 3393 4471 3393 4473 3393 4472 3394 4473 3394 4013 3394 4013 3395 4473 3395 4474 3395 4013 3396 4474 3396 4468 3396 4475 3397 4476 3397 4477 3397 4478 590 4011 590 4479 590 4479 590 4011 590 4480 590 4479 590 4480 590 4772 590 4599 3398 4482 3398 4481 3398 4481 3399 4482 3399 3880 3399 3880 3400 4587 3400 3878 3400 3878 590 4587 590 4565 590 3878 590 4565 590 3877 590 3877 3401 4565 3401 3873 3401 4716 3402 4483 3402 4486 3402 3875 590 4484 590 3876 590 3876 590 4484 590 4486 590 3876 590 4486 590 4485 590 4485 590 4486 590 4483 590 4487 3403 4488 3403 4489 3403 4489 3404 4488 3404 4492 3404 4489 3405 4492 3405 4719 3405 4487 590 4489 590 4490 590 4490 3406 4489 3406 4504 3406 4490 590 4504 590 4491 590 4492 590 4493 590 4719 590 4719 3407 4493 3407 4494 3407 4719 3408 4494 3408 4497 3408 4497 3409 4494 3409 4495 3409 4497 3410 4495 3410 4496 3410 4496 590 4498 590 4497 590 4497 3411 4498 3411 4499 3411 4497 3412 4499 3412 4603 3412 4603 3413 4499 3413 4500 3413 4603 590 4500 590 4502 590 4502 3414 4500 3414 4501 3414 4502 590 4501 590 4504 590 4504 3415 4501 3415 4503 3415 4504 3416 4503 3416 4491 3416 4801 3417 4509 3417 4517 3417 4507 590 4505 590 4506 590 4506 3418 4505 3418 4515 3418 4506 3419 4515 3419 3882 3419 3882 590 4515 590 3885 590 4507 590 4508 590 4505 590 4505 3420 4508 3420 3886 3420 4505 590 3886 590 4801 590 4801 590 3886 590 3887 590 4801 3421 3887 3421 4509 3421 4510 590 4512 590 4626 590 4510 3422 4626 3422 4521 3422 3981 3423 4626 3423 4511 3423 4511 590 4626 590 4512 590 4511 3424 4512 3424 3984 3424 3984 3425 4512 3425 3985 3425 4512 590 4513 590 3985 590 3985 3426 4513 3426 4514 3426 3985 3427 4514 3427 3986 3427 3986 590 4514 590 4516 590 4515 590 3990 590 3885 590 3885 590 3990 590 3991 590 3885 590 3991 590 4516 590 4516 590 3991 590 3988 590 4516 590 3988 590 3986 590 4517 3428 4518 3428 4782 3428 4782 590 4518 590 4519 590 4782 590 4519 590 4778 590 4778 3429 4519 3429 3889 3429 4777 590 4520 590 4626 590 4626 3430 4520 3430 3892 3430 4626 3431 3892 3431 4521 3431 3900 590 4522 590 4523 590 4523 3432 4522 3432 4524 3432 4523 3433 4524 3433 4007 3433 4007 3434 4524 3434 4525 3434 4007 3435 4525 3435 4768 3435 3998 3436 4526 3436 3999 3436 3999 3437 4526 3437 4533 3437 3900 590 4523 590 4527 590 4527 590 4523 590 4006 590 4527 3438 4006 3438 3896 3438 3896 590 4006 590 4001 590 3896 590 4001 590 3897 590 3897 3439 4001 3439 4529 3439 3897 3440 4529 3440 4528 3440 4528 3441 4529 3441 4531 3441 4528 3442 4531 3442 4530 3442 4530 3443 4531 3443 4532 3443 4530 590 4532 590 4533 590 4533 3444 4532 3444 4534 3444 4533 3445 4534 3445 3999 3445 3909 590 3907 590 4571 590 3907 590 4535 590 4571 590 4571 3446 4535 3446 4536 3446 4571 590 4536 590 4793 590 4793 590 4536 590 4537 590 4793 3447 4537 3447 4538 3447 3997 3448 4539 3448 3998 3448 3998 3449 4539 3449 4540 3449 3998 3450 4540 3450 4526 3450 4538 590 4541 590 4793 590 4793 3451 4541 3451 3912 3451 4793 3452 3912 3452 3997 3452 3997 3453 3912 3453 4542 3453 3997 3454 4542 3454 4539 3454 4543 590 4784 590 3910 590 3910 3455 4784 3455 4544 3455 3910 3456 4544 3456 4545 3456 4545 590 4544 590 4546 590 4546 590 4544 590 4786 590 4546 3457 4786 3457 4547 3457 4768 3458 3905 3458 4769 3458 4769 3459 3905 3459 4548 3459 4769 590 4548 590 4547 590 4759 3460 4549 3460 4760 3460 4549 590 4550 590 4578 590 4578 3461 4550 3461 4579 3461 4741 3462 4742 3462 4755 3462 4551 590 4552 590 4554 590 4554 3463 4552 3463 4553 3463 4554 3464 4553 3464 4758 3464 4555 590 4743 590 4556 590 4556 590 4743 590 4581 590 4556 590 4581 590 4557 590 4580 590 4558 590 4577 590 4577 3465 4558 3465 4559 3465 4577 3466 4559 3466 4581 3466 4581 590 4559 590 4560 590 4581 590 4560 590 4557 590 3933 590 3931 590 4561 590 4561 3467 3931 3467 4562 3467 4561 590 4562 590 4743 590 4743 3468 4562 3468 4563 3468 4743 590 4563 590 4581 590 3934 590 4720 590 4486 590 4486 3469 4720 3469 4714 3469 4722 590 3936 590 3935 590 3936 590 4722 590 4564 590 4564 3470 4722 3470 4565 3470 4564 3471 4565 3471 4566 3471 4566 590 4565 590 4587 590 4566 3472 4587 3472 4590 3472 4786 3473 3916 3473 4765 3473 4765 3474 3916 3474 3915 3474 4765 590 3915 590 4567 590 4568 3475 3923 3475 4783 3475 3923 3476 3922 3476 4783 3476 4783 590 3922 590 4569 590 4783 590 4569 590 4801 590 4801 590 4569 590 4570 590 4801 3477 4570 3477 4571 3477 4571 3478 4570 3478 4572 3478 4571 590 4572 590 4785 590 4785 590 4572 590 4573 590 4785 3479 4573 3479 4787 3479 4787 590 4573 590 4574 590 4787 3480 4574 3480 3918 3480 4575 590 4576 590 3926 590 3926 590 4576 590 4578 590 3926 3481 4578 3481 4577 3481 4577 3482 4578 3482 4579 3482 4577 3483 4579 3483 4580 3483 4563 590 3929 590 4581 590 4581 3484 3929 3484 4582 3484 4581 590 4582 590 4577 590 4577 590 4582 590 4583 590 4577 590 4583 590 3926 590 4594 590 4584 590 4585 590 4482 3485 4586 3485 3880 3485 3880 3486 4586 3486 4588 3486 3880 3487 4588 3487 4587 3487 4587 3488 4588 3488 4589 3488 4587 590 4589 590 4591 590 4567 590 4590 590 4594 590 4594 590 4590 590 4587 590 4594 590 4587 590 4584 590 4584 3489 4587 3489 4591 3489 4585 590 4592 590 4594 590 4594 590 4592 590 4593 590 4594 3490 4593 3490 4765 3490 4765 3491 4593 3491 4595 3491 4765 590 4595 590 4766 590 4767 590 4596 590 4441 590 4441 3492 4596 3492 4597 3492 4441 3493 4597 3493 4475 3493 4475 3494 4597 3494 4598 3494 4475 590 4598 590 4601 590 4481 3495 4476 3495 4599 3495 4599 590 4476 590 4475 590 4599 590 4475 590 4600 590 4600 3496 4475 3496 4601 3496 3957 3497 3959 3497 4736 3497 4736 590 3959 590 3958 590 4736 3498 3958 3498 4750 3498 4750 590 3958 590 4602 590 4603 590 3951 590 4497 590 4497 3499 3951 3499 4604 3499 4497 590 4604 590 4719 590 4719 3500 4604 3500 3952 3500 4719 3501 3952 3501 3956 3501 4605 590 4606 590 3947 590 3948 590 4603 590 3947 590 3947 3502 4603 3502 4502 3502 3947 3503 4502 3503 4605 3503 4605 3504 4502 3504 4504 3504 4605 3505 4504 3505 4607 3505 4607 590 4504 590 336 590 336 590 4504 590 4489 590 336 590 4489 590 4608 590 4440 3506 4610 3506 4609 3506 4618 590 4611 590 4610 590 4624 590 3973 590 4622 590 4609 590 4610 590 3969 590 3969 590 4610 590 4611 590 3969 3507 4611 3507 4612 3507 4612 3508 4613 3508 3969 3508 3969 590 4613 590 4614 590 3969 590 4614 590 3972 590 4622 590 4615 590 4624 590 4624 3509 4615 3509 4616 3509 4624 590 4616 590 4610 590 4610 3510 4616 3510 4617 3510 4610 3511 4617 3511 4618 3511 4614 590 4619 590 3972 590 3972 3512 4619 3512 4620 3512 3972 3513 4620 3513 3973 3513 3973 3514 4620 3514 4621 3514 3973 3515 4621 3515 4622 3515 3975 590 4623 590 4624 590 4624 3516 4623 3516 4625 3516 4624 3517 4625 3517 3973 3517 3981 3518 3979 3518 4626 3518 4626 590 3979 590 3977 590 4626 3519 3977 3519 4627 3519 4627 590 3977 590 3975 590 4627 3520 3975 3520 4628 3520 4628 590 3975 590 4624 590 4629 590 4630 590 4020 590 3863 3521 4442 3521 4631 3521 4631 590 4442 590 4629 590 4631 3522 4629 3522 4632 3522 4632 3523 4629 3523 4020 3523 4462 3524 4703 3524 4629 3524 4629 3525 4703 3525 4701 3525 4629 3526 4701 3526 4630 3526 3963 3527 4699 3527 3964 3527 3964 3528 4699 3528 4633 3528 3964 3529 4633 3529 4634 3529 4651 590 4635 590 4642 590 4033 3530 4636 3530 4732 3530 4636 3531 4637 3531 4732 3531 4732 3532 4637 3532 4638 3532 4732 590 4638 590 4726 590 4726 3533 4638 3533 4639 3533 4726 3534 4639 3534 4439 3534 4640 3535 4645 3535 4034 3535 4635 590 4641 590 4642 590 4642 3536 4641 3536 4643 3536 4642 590 4643 590 4640 590 4640 3537 4643 3537 4644 3537 4640 3538 4644 3538 4645 3538 4661 3539 4646 3539 3942 3539 3942 3540 4646 3540 4647 3540 3942 3541 4647 3541 4669 3541 4669 590 4647 590 4648 590 4669 3542 4648 3542 4667 3542 4650 3543 4654 3543 4671 3543 4649 590 4675 590 4665 590 4650 3544 4671 3544 4675 3544 4651 590 4642 590 4652 590 4652 590 4642 590 4671 590 4652 3545 4671 3545 4653 3545 4653 590 4671 590 4654 590 4653 590 4654 590 4655 590 4656 3546 4657 3546 4678 3546 4678 3547 4657 3547 4658 3547 4678 590 4658 590 3942 590 3942 3548 4658 3548 4659 3548 3942 3549 4659 3549 4661 3549 4661 3550 4659 3550 4660 3550 4661 590 4660 590 4662 590 4663 590 4664 590 4672 590 4649 590 4665 590 4666 590 4667 590 4668 590 4669 590 4669 590 4668 590 4670 590 4669 590 4670 590 4671 590 4663 590 4672 590 4665 590 4665 3551 4672 3551 4673 3551 4665 3552 4673 3552 4666 3552 4664 3553 4663 3553 4660 3553 4660 3554 4663 3554 4674 3554 4660 3555 4674 3555 4662 3555 4671 590 4670 590 4675 590 4675 3556 4670 3556 4676 3556 4675 3557 4676 3557 4665 3557 4439 3558 4028 3558 4726 3558 4726 590 4028 590 4677 590 4726 3559 4677 3559 4678 3559 4678 3560 4677 3560 4030 3560 4678 590 4030 590 4656 590 4689 3561 4679 3561 4681 3561 4681 3562 4679 3562 4680 3562 4775 3563 4779 3563 4046 3563 4680 590 4037 590 4681 590 4681 3564 4037 3564 4682 3564 4681 3565 4682 3565 4779 3565 4779 3566 4682 3566 4683 3566 4779 3567 4683 3567 4046 3567 4046 590 4684 590 4775 590 4775 3568 4684 3568 4045 3568 4775 590 4045 590 4760 590 4760 3569 4045 3569 4043 3569 4043 3570 4041 3570 4760 3570 4760 3571 4041 3571 4685 3571 4760 3572 4685 3572 4695 3572 4685 590 4039 590 4695 590 4695 3573 4039 3573 4688 3573 4695 590 4688 590 4690 590 4427 590 4693 590 4692 590 4690 3574 4686 3574 4687 3574 4686 590 4690 590 4691 590 4688 590 4689 590 4690 590 4690 590 4689 590 4681 590 4690 3575 4681 3575 4691 3575 4691 590 4681 590 4692 590 4691 590 4692 590 4424 590 4424 590 4692 590 4693 590 4687 590 4436 590 4690 590 4690 3576 4436 3576 4694 3576 4690 590 4694 590 4695 590 4695 3577 4694 3577 4434 3577 4434 590 4696 590 4695 590 4695 3578 4696 3578 4698 3578 4695 590 4698 590 4697 590 4697 3579 4698 3579 4430 3579 3963 590 4022 590 4699 590 4699 3580 4022 3580 4024 3580 4699 590 4024 590 4453 590 4453 3581 4024 3581 4025 3581 4453 590 4025 590 4703 590 4703 590 4025 590 4700 590 4703 590 4700 590 4701 590 4702 590 4467 590 4703 590 4703 3582 4467 3582 4718 3582 4703 590 4718 590 4453 590 4453 590 4718 590 4437 590 4453 3583 4437 3583 4704 3583 4714 590 4705 590 3859 590 4706 590 4707 590 4708 590 4713 590 4706 590 4715 590 4715 590 4706 590 4708 590 4715 3584 4708 3584 4437 3584 4437 3585 4708 3585 3847 3585 4437 590 3847 590 4704 590 4707 590 4709 590 4708 590 4708 3586 4709 3586 4710 3586 4708 590 4710 590 4714 590 4714 590 4710 590 3850 590 4714 590 3850 590 4705 590 3852 590 4711 590 4715 590 4715 3587 4711 3587 4712 3587 4715 3588 4712 3588 4713 3588 3859 590 3858 590 4714 590 4714 3589 3858 3589 3855 3589 4714 590 3855 590 4486 590 4486 3590 3855 3590 3854 3590 4486 3591 3854 3591 3853 3591 3853 590 3852 590 4486 590 4486 3592 3852 3592 4715 3592 4486 590 4715 590 4716 590 4716 3593 4715 3593 4718 3593 4716 3594 4718 3594 4717 3594 4717 590 4718 590 3871 590 4723 590 4608 590 4724 590 4724 590 4608 590 4489 590 4724 590 4489 590 4725 590 4725 590 4489 590 4719 590 4725 590 4719 590 4727 590 4720 3595 3933 3595 4714 3595 4714 590 3933 590 4561 590 4714 590 4561 590 4721 590 4721 590 4561 590 4743 590 4721 590 4743 590 3835 590 3835 590 4743 590 4460 590 3875 3596 3873 3596 4484 3596 4484 3597 3873 3597 4565 3597 4484 590 4565 590 4486 590 4486 590 4565 590 4722 590 4486 3598 4722 3598 3934 3598 3934 3599 4722 3599 3935 3599 3942 590 4723 590 4678 590 4678 590 4723 590 4724 590 4678 590 4724 590 4726 590 4726 3600 4724 3600 4725 3600 4726 590 4725 590 4732 590 4732 590 4725 590 4727 590 4732 590 4727 590 4051 590 4051 590 4727 590 4730 590 4728 590 4729 590 4733 590 4057 590 4056 590 4727 590 4727 590 4056 590 4055 590 4727 3601 4055 3601 4730 3601 4051 3602 4731 3602 4732 3602 4732 3603 4731 3603 4050 3603 4732 590 4050 590 4756 590 4050 590 4048 590 4756 590 4756 3604 4048 3604 4734 3604 4756 590 4734 590 4733 590 4733 3605 4734 3605 4735 3605 4733 3606 4735 3606 4728 3606 3956 590 3957 590 4719 590 4719 590 3957 590 4736 590 4719 3607 4736 3607 4727 3607 4727 590 4736 590 4733 590 4727 590 4733 590 4057 590 4057 590 4733 590 4729 590 4737 590 4745 590 4751 590 4740 3608 4741 3608 4738 3608 4738 590 4741 590 4756 590 4738 590 4756 590 4739 590 4740 3609 4737 3609 4741 3609 4741 3610 4737 3610 4751 3610 4741 3611 4751 3611 4742 3611 4742 590 4751 590 4743 590 4742 590 4743 590 4744 590 4744 590 4743 590 4555 590 4745 590 4746 590 4751 590 4751 3612 4746 3612 4747 3612 4751 3613 4747 3613 4752 3613 4754 590 4748 590 4756 590 4756 3614 4748 3614 4749 3614 4756 3615 4749 3615 4739 3615 4602 590 4459 590 4750 590 4750 3616 4459 3616 4751 3616 4750 590 4751 590 4733 590 4733 3617 4751 3617 4752 3617 4733 590 4752 590 4756 590 4756 3618 4752 3618 4753 3618 4756 3619 4753 3619 4754 3619 4755 590 4551 590 4741 590 4741 3620 4551 3620 4554 3620 4741 590 4554 590 4756 590 4756 3621 4554 3621 4757 3621 4756 3622 4757 3622 4732 3622 4732 590 4757 590 4640 590 4732 590 4640 590 4033 590 4033 590 4640 590 4034 590 4758 590 4759 590 4554 590 4554 590 4759 590 4760 590 4554 590 4760 590 4757 590 4757 590 4760 590 4695 590 4757 3623 4695 3623 4640 3623 4640 590 4695 590 4697 590 4640 590 4697 590 4642 590 4642 590 4697 590 4761 590 4642 590 4761 590 4671 590 4671 590 4761 590 4762 590 4671 590 4762 590 4669 590 4669 590 4762 590 3940 590 4430 3624 4438 3624 4697 3624 4697 590 4438 590 4773 590 4697 590 4773 590 4761 590 4761 590 4773 590 4774 590 4761 590 4774 590 4762 590 4762 3625 4774 3625 4763 3625 4762 590 4763 590 3940 590 3940 590 4763 590 4764 590 4547 590 4786 590 4769 590 4769 590 4786 590 4765 590 4769 590 4765 590 4770 590 4770 3626 4765 3626 4766 3626 4770 3627 4766 3627 4767 3627 4768 590 4769 590 4007 590 4007 590 4769 590 4770 590 4007 590 4770 590 4008 590 4008 590 4770 590 4441 590 4008 590 4441 590 4771 590 4771 3628 4441 3628 4475 3628 4771 3629 4475 3629 4480 3629 4480 590 4475 590 4477 590 4480 3630 4477 3630 4772 3630 4429 3631 4427 3631 4773 3631 4773 590 4427 590 4692 590 4773 590 4692 590 4774 590 4774 590 4692 590 4780 590 4774 590 4780 590 4763 590 4763 3632 4780 3632 4781 3632 4763 3633 4781 3633 4764 3633 4764 590 4781 590 3939 590 4549 3634 4578 3634 4760 3634 4760 590 4578 590 4576 590 4760 590 4576 590 4775 590 4775 3635 4576 3635 4778 3635 4775 3636 4778 3636 4779 3636 3889 590 4776 590 4778 590 4778 3637 4776 3637 4777 3637 4778 590 4777 590 4779 590 4779 590 4777 590 4626 590 4779 3638 4626 3638 4681 3638 4681 3639 4626 3639 4627 3639 4681 590 4627 590 4692 590 4692 590 4627 590 4628 590 4692 590 4628 590 4780 590 4780 590 4628 590 4624 590 4780 590 4624 590 4781 590 4781 590 4624 590 4610 590 4781 590 4610 590 3939 590 3939 590 4610 590 3937 590 4517 590 4782 590 4801 590 4801 3640 4782 3640 4778 3640 4801 590 4778 590 4783 590 4783 3641 4778 3641 4576 3641 4783 590 4576 590 4568 590 4568 3642 4576 3642 4575 3642 4568 590 4575 590 3924 590 3909 590 4571 590 4784 590 4784 3643 4571 3643 4785 3643 4784 590 4785 590 4544 590 4544 3644 4785 3644 4787 3644 4544 590 4787 590 4786 590 4786 3645 4787 3645 3918 3645 4786 3646 3918 3646 3916 3646 4505 3647 4788 3647 4793 3647 4793 3648 4788 3648 4789 3648 4793 3649 4789 3649 4791 3649 4571 590 4790 590 4796 590 4791 3650 4792 3650 4793 3650 4793 3651 4792 3651 4794 3651 4793 3652 4794 3652 4571 3652 4571 590 4794 590 4795 590 4571 590 4795 590 4790 590 4796 590 4797 590 4571 590 4571 3653 4797 3653 4798 3653 4571 3654 4798 3654 4801 3654 4801 3655 4798 3655 4799 3655 4801 3656 4799 3656 4800 3656 4800 590 4802 590 4801 590 4801 590 4802 590 4803 590 4801 590 4803 590 4505 590 4505 3657 4803 3657 4804 3657 4505 3658 4804 3658 4788 3658 5452 3659 5075 3659 4805 3659 4805 3660 5075 3660 5074 3660 4805 3661 5074 3661 5746 3661 5746 3662 5074 3662 4806 3662 5746 3663 4806 3663 4807 3663 4807 3664 4806 3664 5332 3664 4810 3665 4809 3665 4808 3665 4810 3665 4808 3665 5454 3665 5454 3666 4808 3666 5075 3666 5454 3666 5075 3666 5452 3666 4809 3667 4810 3667 5077 3667 5077 3668 4810 3668 4811 3668 5077 3669 4811 3669 4812 3669 4812 3670 4811 3670 5439 3670 4812 3671 5439 3671 4816 3671 4816 3672 5439 3672 5438 3672 4813 3673 5073 3673 5072 3673 4813 3674 5072 3674 4814 3674 4814 3675 5072 3675 5071 3675 4814 3676 5071 3676 4815 3676 4815 3677 5071 3677 5070 3677 4815 3678 5070 3678 5440 3678 5440 3679 5070 3679 4816 3679 5440 3679 4816 3679 5438 3679 5444 3680 4826 3680 4817 3680 4817 3681 4826 3681 5068 3681 4817 3682 5068 3682 4818 3682 4818 3682 5068 3682 4819 3682 4818 3683 4819 3683 5607 3683 5607 3684 4819 3684 5069 3684 5607 3685 5069 3685 4820 3685 4820 3686 5069 3686 4821 3686 4820 3687 4821 3687 4813 3687 4813 3687 4821 3687 5073 3687 4822 3688 5078 3688 4823 3688 4822 3689 4823 3689 4824 3689 4824 3690 4823 3690 4825 3690 4824 3691 4825 3691 5443 3691 5443 3692 4825 3692 5066 3692 5443 3692 5066 3692 5447 3692 5447 3693 5066 3693 4826 3693 5447 3694 4826 3694 5444 3694 5078 3695 4822 3695 4827 3695 4827 3696 4822 3696 4829 3696 4827 3697 4829 3697 4828 3697 4828 3698 4829 3698 4830 3698 4831 3699 5327 3699 5326 3699 4831 3700 5326 3700 4832 3700 4832 3701 5326 3701 5325 3701 4832 3702 5325 3702 4833 3702 4833 3703 5325 3703 5316 3703 4833 3704 5316 3704 5751 3704 5751 3705 5316 3705 4834 3705 5751 3706 4834 3706 5752 3706 5752 3707 4834 3707 4835 3707 5752 3708 4835 3708 4836 3708 4836 3709 4835 3709 4837 3709 4836 3710 4837 3710 5757 3710 5469 3711 4839 3711 4838 3711 4838 3712 4839 3712 4840 3712 4838 3713 4840 3713 4841 3713 4841 3714 4840 3714 4842 3714 4841 3715 4842 3715 5461 3715 5461 3716 4842 3716 5086 3716 5461 3717 5086 3717 5462 3717 5462 3718 5086 3718 5090 3718 5467 3719 5096 3719 5099 3719 4843 3720 5389 3720 4844 3720 4844 3721 5389 3721 5458 3721 4843 3722 4844 3722 5100 3722 5100 3723 4844 3723 5455 3723 5100 3724 5455 3724 5099 3724 5099 3725 5455 3725 5457 3725 5099 3726 5457 3726 5467 3726 5103 3727 4845 3727 5101 3727 5101 3727 4845 3727 5437 3727 5101 3728 5437 3728 5389 3728 5389 3729 5437 3729 5458 3729 4846 3730 5105 3730 4847 3730 4847 3730 5105 3730 4849 3730 4847 3731 4849 3731 4848 3731 4848 3732 4849 3732 4851 3732 4848 3733 4851 3733 4850 3733 4850 3734 4851 3734 5106 3734 4852 3735 4853 3735 5764 3735 5764 3736 4853 3736 4854 3736 5764 3737 4854 3737 5765 3737 5765 3738 4854 3738 5108 3738 5765 3739 5108 3739 5773 3739 5773 3739 5108 3739 4855 3739 5503 3740 5142 3740 4856 3740 4856 3741 5142 3741 4857 3741 4856 3742 4857 3742 5696 3742 5696 3743 4857 3743 5140 3743 5696 3744 5140 3744 5697 3744 5697 3745 5140 3745 5123 3745 4860 3746 4859 3746 5137 3746 4860 3747 5137 3747 4858 3747 4858 3748 5137 3748 5393 3748 4858 3748 5393 3748 5504 3748 5504 3749 5393 3749 5142 3749 5504 3750 5142 3750 5503 3750 4859 3751 4860 3751 5138 3751 5138 3752 4860 3752 5682 3752 5138 3753 5682 3753 4861 3753 4861 3753 5682 3753 5491 3753 5494 3754 4866 3754 4862 3754 5494 3755 4862 3755 5493 3755 5493 3756 4862 3756 4863 3756 5493 3757 4863 3757 5492 3757 5492 3758 4863 3758 4864 3758 5492 3759 4864 3759 4865 3759 4865 3760 4864 3760 4861 3760 4865 3761 4861 3761 5491 3761 4866 3762 5494 3762 5496 3762 5499 3763 5126 3763 4867 3763 4867 3764 5126 3764 5134 3764 4867 3765 5134 3765 5496 3765 5496 3766 5134 3766 4868 3766 5496 3767 4868 3767 4866 3767 5502 3768 5128 3768 5127 3768 5502 3769 5127 3769 5497 3769 5497 3770 5127 3770 4869 3770 5497 3770 4869 3770 4870 3770 4870 3771 4869 3771 5124 3771 4870 3772 5124 3772 4871 3772 4871 3773 5124 3773 5126 3773 4871 3774 5126 3774 5499 3774 5502 3775 5501 3775 5128 3775 5128 3776 5501 3776 4872 3776 5146 3777 5511 3777 5151 3777 5151 3778 5511 3778 4874 3778 5151 3779 4874 3779 4873 3779 4873 3780 4874 3780 5513 3780 5157 3781 4875 3781 5671 3781 5671 3782 4875 3782 4876 3782 4876 3783 4875 3783 5156 3783 4876 3784 5156 3784 4877 3784 4877 3785 5156 3785 5155 3785 4877 3785 5155 3785 5701 3785 5701 3786 5155 3786 5435 3786 5435 3787 5155 3787 5153 3787 5435 3788 5153 3788 5523 3788 5523 3789 5153 3789 4878 3789 5523 3790 4878 3790 4879 3790 4879 3791 4878 3791 4880 3791 5165 3792 4881 3792 5526 3792 4879 3793 4880 3793 5525 3793 5525 3794 4880 3795 4882 3796 5525 3797 4882 3797 5526 3797 5526 3798 4882 3798 5164 3798 5526 3792 5164 3792 5165 3792 5143 3799 4884 3799 4883 3799 4883 3799 4884 3799 5515 3799 5143 3800 4883 3800 4885 3800 4885 3801 4883 3801 5519 3801 4885 3802 5519 3802 5144 3802 5519 3803 4886 3803 5144 3803 5144 3804 4886 3804 5520 3804 5144 3805 5520 3805 5385 3805 5385 3806 5520 3806 4887 3806 5385 3807 4887 3807 5166 3807 5166 3808 4887 3808 5167 3808 5167 3809 4887 3809 4888 3809 5167 3810 4888 3810 5165 3810 5165 3811 4888 3811 4881 3811 4920 3812 4889 3812 5547 3812 5547 3813 4889 3813 4890 3813 5547 3814 4890 3814 5704 3814 5704 3815 4890 3815 4891 3815 5704 3816 4891 3816 4892 3816 4892 3817 4891 3817 4893 3817 4892 3818 4893 3818 5698 3818 5698 3819 4893 3819 4894 3819 5698 3820 4894 3820 5544 3820 5544 3821 4894 3821 5200 3821 5544 3822 5200 3822 4895 3822 4895 3822 5200 3822 5198 3822 4895 3823 5198 3823 4896 3823 4896 3824 5198 3824 4897 3824 4896 141 4897 141 4898 141 4898 3825 4897 3825 4899 3825 4898 3826 4899 3826 4900 3826 4900 3827 4899 3827 4901 3827 4900 3828 4901 3828 5546 3828 5546 3829 4901 3829 5196 3829 5546 3830 5196 3830 4902 3830 4902 3831 5196 3831 4903 3831 4902 3832 4903 3832 4904 3832 4904 3833 4903 3833 4905 3833 4904 3834 4905 3834 5691 3834 5691 3835 4905 3835 4907 3835 5691 3836 4907 3836 4906 3836 4906 3837 4907 3837 4908 3837 4906 3838 4908 3838 5550 3838 5550 3839 4908 3839 4909 3839 5550 3840 4909 3840 4911 3840 4911 3840 4909 3840 4910 3840 4911 3841 4910 3841 5551 3841 5551 3842 4910 3842 4912 3842 5551 3843 4912 3843 5553 3843 5553 3844 4912 3844 5204 3844 5553 3845 5204 3845 5554 3845 5554 3846 5204 3846 5186 3846 5554 3847 5186 3847 4913 3847 4913 3848 5186 3848 5184 3848 4913 3849 5184 3849 4914 3849 4914 3850 5184 3850 4916 3850 4914 3851 4916 3851 4915 3851 4915 3852 4916 3852 5183 3852 4915 3853 5183 3853 5549 3853 5549 3854 5183 3854 5189 3854 5549 3855 5189 3855 5750 3855 5750 3856 5189 3856 5188 3856 5750 3857 5188 3857 4917 3857 4917 3858 5188 3858 5335 3858 4917 3859 5335 3859 4918 3859 4918 3860 5335 3860 5194 3860 4918 3861 5194 3861 4919 3861 4919 3862 5194 3862 5191 3862 4919 3863 5191 3863 4920 3863 4920 3864 5191 3864 4889 3864 12150 3865 4921 3865 4922 3865 4922 3866 4921 3866 5732 3866 4922 3867 5732 3867 4923 3867 4923 3868 5732 3868 5715 3868 4923 3869 5715 3869 4924 3869 4924 3870 5715 3870 5712 3870 4924 3871 5712 3871 5377 3871 5377 3872 5712 3872 5708 3872 5377 3873 5708 3873 5376 3873 5376 3874 5708 3874 5707 3874 5376 3875 5707 3875 5336 3875 5336 3876 5707 3876 5630 3876 5336 3877 5630 3877 5341 3877 5341 3878 5630 3878 5745 3878 5341 3879 5745 3879 4925 3879 4925 3880 5745 3880 4926 3880 4925 3881 4926 3881 5234 3881 5234 3882 4926 3882 10346 3882 10693 3883 4921 3883 11540 3883 11540 3884 4921 3884 12150 3884 11537 3885 10700 3885 4927 3885 4927 3886 10700 3886 4928 3886 4927 3887 4928 3887 11540 3887 11540 3888 4928 3888 10693 3888 4929 3889 4930 3889 5239 3889 5239 3890 4930 3890 5585 3890 5239 3891 5585 3891 11537 3891 11537 3892 5585 3892 10700 3892 4937 3893 5582 3893 5580 3893 4937 3894 5580 3894 5248 3894 5248 3895 5580 3895 4930 3895 5248 3896 4930 3896 4929 3896 5132 3897 4931 3897 4932 3897 4932 3898 4931 3898 4933 3898 4932 3899 4933 3899 4934 3899 4934 3900 4933 3900 4935 3900 4934 3901 4935 3901 4936 3901 4936 3901 4935 3901 5583 3901 4936 3902 5583 3902 4937 3902 4937 3903 5583 3903 5582 3903 4931 3904 5132 3904 4939 3904 4931 3905 4939 3905 4938 3905 4938 3906 4939 3906 5133 3906 4938 3906 5133 3906 4940 3906 4940 3907 5133 3907 5130 3907 4940 3908 5130 3908 4941 3908 4941 3909 5130 3909 5131 3909 4941 3910 5131 3910 5495 3910 5495 3911 5131 3911 5136 3911 5495 3912 5136 3912 4942 3912 4942 3913 5136 3913 5135 3913 4942 3914 5135 3914 4943 3914 5498 3915 4943 3915 4944 3915 4944 3916 4943 3916 5135 3916 5498 3917 4944 3917 4945 3917 4945 3918 4944 3918 5125 3918 4945 3919 5125 3919 5676 3919 5676 3920 5125 3920 4946 3920 5676 3921 4946 3921 5434 3921 5434 3922 4946 3922 5411 3922 5434 3923 5411 3923 4948 3923 4948 3924 5411 3924 4949 3924 4947 3925 5512 3925 4952 3925 4948 3926 4949 3926 4950 3926 4950 3926 4949 3926 5160 3926 4950 3927 5160 3927 4952 3927 4952 3928 5160 3928 4951 3928 4952 3929 4951 3929 4947 3929 4956 3930 4953 3930 4954 3930 4954 3931 4953 3931 4955 3931 4954 3932 4955 3932 4947 3932 4947 3933 4955 3933 5512 3933 4953 3934 4956 3934 4961 3934 4957 3935 4958 3935 4960 3935 4960 3936 4958 3936 4959 3936 4960 3937 4959 3937 4961 3937 4961 3938 4959 3938 5508 3938 4961 3939 5508 3939 4953 3939 4958 3940 4957 3940 5514 3940 5514 3941 4957 3941 5148 3941 5514 3942 5148 3942 4962 3942 4962 3943 5148 3943 5145 3943 4962 3944 5145 3944 4963 3944 4963 3945 5145 3945 4965 3945 4963 3946 4965 3946 4964 3946 4964 3947 4965 3947 5386 3947 4964 3948 5386 3948 5456 3948 5456 3949 5386 3949 5388 3949 5456 3950 5388 3950 5468 3950 5468 3951 5388 3951 5098 3951 5468 3952 5098 3952 4966 3952 4966 3953 5098 3953 5097 3953 5091 3954 4973 3954 4968 3954 4966 3955 5097 3955 5464 3955 5464 3956 5097 3956 4967 3956 5464 3957 4967 3957 4968 3957 4968 3958 4967 3958 5092 3958 4968 3959 5092 3959 5091 3959 5253 3960 4974 3960 4969 3960 4969 3961 4974 3961 5576 3961 4969 3962 5576 3962 4971 3962 4971 3963 5576 3963 4970 3963 4971 3964 4970 3964 5087 3964 5087 3965 4970 3965 5459 3965 5087 3966 5459 3966 5089 3966 5089 3967 5459 3967 4972 3967 5089 3968 4972 3968 5091 3968 5091 3969 4972 3969 4973 3969 4974 3970 5253 3970 4975 3970 5254 3971 5769 3971 5252 3971 5252 3972 5769 3973 4976 3974 5252 3975 4976 3975 4975 3975 4975 3976 4976 3976 4977 3976 4975 3970 4977 3970 4974 3970 5310 3977 4978 3977 5311 3977 5311 3978 4978 3978 4979 3978 5311 3979 4979 3979 4981 3979 4981 3980 4979 3980 4980 3980 4981 3981 4980 3981 4983 3981 4983 3982 4980 3982 4982 3982 4983 3983 4982 3983 5254 3983 5254 3983 4982 3983 5769 3983 5227 3984 4984 3984 5228 3984 5228 3985 4984 3985 5600 3985 5228 3986 5600 3986 11525 3986 11525 3987 5600 3987 4987 3987 5602 3988 4988 3988 4985 3988 4985 3989 4988 3989 5225 3989 4985 3990 5225 3990 5603 3990 5603 3991 5225 3991 4986 3991 5603 3992 4986 3992 5599 3992 5599 3993 4986 3993 5229 3993 5599 3994 5229 3994 4987 3994 4987 3995 5229 3995 11525 3995 5349 3996 4988 3996 4989 3996 4989 3997 4988 3997 5602 3997 5448 3998 4992 3998 5604 3998 5604 3999 4992 3999 5224 3999 5604 4000 5224 4000 5605 4000 5605 4001 5224 4001 4990 4001 5605 4002 4990 4002 5601 4002 5601 4003 4990 4003 5223 4003 5601 4004 5223 4004 4989 4004 4989 4005 5223 4005 5349 4005 5446 4006 5065 4006 4991 4006 5446 4007 4991 4007 5450 4007 5450 4008 4991 4008 5067 4008 5450 4009 5067 4009 5449 4009 5449 4010 5067 4010 4992 4010 5449 4011 4992 4011 5448 4011 4993 4012 5308 4012 5608 4012 5608 4013 5308 4013 4994 4013 5608 4014 4994 4014 5442 4014 5442 4015 4994 4015 4996 4015 5442 4016 4996 4016 4995 4016 4995 4017 4996 4017 4998 4017 4995 4018 4998 4018 4997 4018 4997 4019 4998 4019 4999 4019 4997 4020 4999 4020 5445 4020 5445 4021 4999 4021 5000 4021 5445 4022 5000 4022 5446 4022 5446 4023 5000 4023 5065 4023 5001 4024 5288 4024 5002 4024 5002 4025 5288 4025 5003 4025 5002 4026 5003 4026 5626 4026 5626 4027 5003 4027 5289 4027 5626 4028 5289 4028 5627 4028 5627 4029 5289 4029 5004 4029 5005 4030 5641 4030 5639 4030 5005 4031 5639 4031 5278 4031 5278 4032 5639 4032 5007 4032 5278 4032 5007 4032 5006 4032 5006 4033 5007 4033 5008 4033 5006 4034 5008 4034 5280 4034 5280 4035 5008 4035 5635 4035 5280 4036 5635 4036 5009 4036 5009 4037 5635 4037 5638 4037 5009 4038 5638 4038 5010 4038 5010 4039 5638 4039 5637 4039 5010 4040 5637 4040 5277 4040 5277 4041 5637 4041 5627 4041 5277 4042 5627 4042 5004 4042 5265 4043 5619 4043 5266 4043 5266 4044 5619 4044 5011 4044 5266 4045 5011 4045 5270 4045 5270 4046 5011 4046 5013 4046 5270 4047 5013 4047 5012 4047 5012 4048 5013 4048 5014 4048 5255 4049 5015 4049 5719 4049 5719 4049 5015 4049 5016 4049 5033 4050 5296 4050 5645 4050 5645 4051 5296 4051 5017 4051 5645 2998 5017 2998 5019 2998 5019 2997 5017 2997 5018 2997 5019 2970 5018 2970 5647 2970 5647 3000 5018 3000 5021 3000 5647 3001 5021 3001 5020 3001 5020 3002 5021 3002 5022 3002 5020 2974 5022 2974 5023 2974 5023 2975 5022 2975 5024 2975 5023 4052 5024 4052 5648 4052 5648 4053 5024 4053 5025 4053 5025 4054 5024 4054 5294 4054 5025 4055 5294 4055 5026 4055 5294 4056 5295 4056 5026 4056 5026 4057 5295 4057 5300 4057 5026 4058 5300 4058 5027 4058 5027 4059 5300 4059 5029 4059 5027 4060 5029 4060 5028 4060 5028 3341 5029 3341 5299 3341 5028 4061 5299 4061 5652 4061 5652 3343 5299 3343 5031 3343 5652 3344 5031 3344 5030 3344 5030 4062 5031 4062 5032 4062 5032 4063 5031 4063 5297 4063 5032 4064 5297 4064 5033 4064 5033 4065 5297 4065 5034 4065 5033 3347 5034 3347 5296 3347 5044 4066 5366 4066 5035 4066 5035 3347 5366 3347 5359 3347 5035 4067 5359 4067 5036 4067 5036 4068 5359 4068 5361 4068 5036 4069 5361 4069 5727 4069 5727 4070 5361 4070 5360 4070 5727 4071 5360 4071 5037 4071 5037 4072 5360 4072 5038 4072 5037 4073 5038 4073 5039 4073 5039 4074 5038 4074 5040 4074 5039 4075 5040 4075 5736 4075 5736 4076 5040 4076 5370 4076 5736 4077 5370 4077 5041 4077 5041 4078 5370 4078 5042 4078 5041 4079 5042 4079 5738 4079 5738 4080 5042 4080 5369 4080 5738 4058 5369 4058 5733 4058 5733 4081 5369 4081 5372 4081 5733 4060 5372 4060 5734 4060 5734 3341 5372 3341 5368 3341 5734 3342 5368 3342 5043 3342 5043 4082 5368 4082 5045 4082 5043 4083 5045 4083 5044 4083 5044 3345 5045 3345 5366 3345 5059 3346 5357 3346 5046 3346 5046 3347 5357 3347 5355 3347 5046 3348 5355 3348 5047 3348 5047 3020 5355 3020 5048 3020 5047 2998 5048 2998 5049 2998 5049 2999 5048 2999 5346 2999 5049 2970 5346 2970 5721 2970 5721 3000 5346 3000 5345 3000 5721 3001 5345 3001 5050 3001 5050 2973 5345 2973 5051 2973 5050 2974 5051 2974 5052 2974 5052 3004 5051 3004 5354 3004 5052 3004 5354 3004 5722 3004 5722 3334 5354 3334 5348 3334 5722 3007 5348 3007 5053 3007 5053 3335 5348 3335 5054 3335 5053 3336 5054 3336 5055 3336 5055 4084 5054 4084 5056 4084 5055 4084 5056 4084 5723 4084 5723 3341 5056 3341 5344 3341 5723 3342 5344 3342 5058 3342 5058 3343 5344 3343 5057 3343 5058 3344 5057 3344 5059 3344 5059 3345 5057 3345 5357 3345 5350 4085 5371 4085 5358 4085 5314 590 5312 590 5060 590 5378 590 5427 590 5390 590 4929 590 5239 590 5247 590 5061 590 5062 590 5396 590 12150 590 4922 590 5396 590 5222 590 5063 590 5387 590 4905 590 5399 590 4907 590 5153 3596 5402 3596 4878 3596 4839 4086 5081 4086 5083 4086 5073 590 4821 590 5309 590 4825 590 4823 590 5064 590 5068 4087 4826 4087 5065 4087 5065 3426 4826 3426 5066 3426 5065 590 5066 590 4991 590 4991 4088 5066 4088 4825 4088 4991 4089 4825 4089 5067 4089 5067 590 4825 590 5064 590 5067 3423 5064 3423 4992 3423 4992 3518 5064 3518 5224 3518 5065 4090 5000 4090 5068 4090 5068 590 5000 590 4999 590 5068 590 4999 590 4819 590 4819 4091 4999 4091 4998 4091 4819 590 4998 590 5069 590 5069 590 4998 590 4996 590 5069 590 4996 590 4994 590 4816 590 5070 590 5314 590 5314 4092 5070 4092 5071 4092 5314 590 5071 590 5309 590 5309 4093 5071 4093 5072 4093 5309 590 5072 590 5073 590 5332 590 4806 590 5330 590 5330 590 4806 590 5074 590 5330 4094 5074 4094 5076 4094 5076 590 5074 590 5075 590 5075 590 4808 590 5076 590 5076 3421 4808 3421 4809 3421 5076 4095 4809 4095 5317 4095 5317 4096 4809 4096 5077 4096 5317 590 5077 590 4812 590 4823 3422 5078 3422 5064 3422 5064 3431 5078 3431 4827 3431 5064 590 4827 590 5367 590 5333 590 5185 590 5079 590 5079 4097 5185 4097 5367 4097 5079 590 5367 590 4828 590 4828 590 5367 590 4827 590 5085 4098 5080 4098 5312 4098 5312 590 5080 590 5774 590 5312 590 5774 590 5060 590 5081 4099 5082 4099 5083 4099 5083 4100 5082 4100 5084 4100 5083 4101 5084 4101 5085 4101 4969 4102 4971 4102 4840 4102 4840 590 4971 590 4842 590 4842 4103 4971 4103 5088 4103 4842 590 5088 590 5086 590 4971 4104 5087 4104 5088 4104 5088 590 5087 590 5089 590 5088 590 5089 590 5086 590 5086 4105 5089 4105 5091 4105 5086 590 5091 590 5090 590 5090 3441 5091 3441 5092 3441 5090 4106 5092 4106 5093 4106 5093 3439 5092 3439 4967 3439 5093 590 4967 590 5094 590 5094 4107 4967 4107 5095 4107 5095 590 4967 590 5097 590 5095 590 5097 590 5096 590 5096 590 5097 590 5098 590 5096 590 5098 590 5099 590 5388 4108 4843 4108 5098 4108 5098 4109 4843 4109 5100 4109 5098 4110 5100 4110 5099 4110 5389 4111 5387 4111 5101 4111 5101 4112 5387 4112 5063 4112 5101 4113 5063 4113 5103 4113 5103 4114 5063 4114 5102 4114 5103 590 5102 590 5206 590 5206 590 5208 590 5104 590 5104 590 5208 590 5192 590 5104 3456 5192 3456 5105 3456 5105 590 5192 590 4849 590 4851 590 5334 590 5106 590 5106 590 5334 590 5315 590 5106 590 5315 590 5107 590 5774 590 4855 590 5060 590 5060 590 4855 590 5108 590 5060 590 5108 590 4854 590 5121 4115 5232 4115 5233 4115 5109 590 5110 590 5111 590 5109 590 5111 590 5232 590 5351 4116 5112 4116 5353 4116 5353 3509 5112 3509 5113 3509 5353 590 5113 590 5226 590 5226 4117 5113 4117 5114 4117 5226 4118 5114 4118 5115 4118 5115 590 5116 590 5226 590 5226 4119 5116 4119 5117 4119 5226 590 5117 590 5229 590 5229 4120 5117 4120 5118 4120 5229 4121 5118 4121 5230 4121 5230 4122 5118 4122 5119 4122 5230 590 5119 590 5233 590 5233 590 5119 590 5120 590 5233 590 5120 590 5121 590 5129 4123 5122 4123 5123 4123 4869 4124 4946 4124 5124 4124 5124 590 4946 590 5125 590 5124 590 5125 590 5126 590 5126 590 5125 590 5134 590 4869 590 5127 590 4946 590 4946 4125 5127 4125 5128 4125 4946 590 5128 590 5129 590 5129 4126 5128 4126 4872 4126 5129 3376 4872 3376 5122 3376 4864 590 4863 590 5249 590 4864 590 5249 590 4861 590 4863 4127 4862 4127 5130 4127 5130 4128 4862 4128 4866 4128 5130 590 4866 590 5131 590 5131 4129 4866 4129 4868 4129 5132 590 5249 590 4939 590 4939 4130 5249 4130 4863 4130 4939 590 4863 590 5133 590 5133 590 4863 590 5130 590 5125 590 4944 590 5134 590 5134 4131 4944 4131 5135 4131 5134 4132 5135 4132 4868 4132 4868 4133 5135 4133 5136 4133 4868 4134 5136 4134 5131 4134 5137 590 4859 590 5249 590 5249 4135 4859 4135 5138 4135 5249 3377 5138 3377 4861 3377 5123 590 5140 590 5139 590 5139 590 5140 590 4857 590 5139 590 4857 590 5141 590 5141 4136 4857 4136 5142 4136 4884 590 5143 590 5148 590 5148 4137 5143 4137 4885 4137 5148 590 4885 590 5145 590 5145 4138 4885 4138 5144 4138 5145 4139 5144 4139 5385 4139 5160 590 5162 590 4951 590 4951 4140 5162 4140 5146 4140 4884 590 5148 590 5147 590 5147 4141 5148 4141 4957 4141 5147 590 4957 590 5149 590 5149 4142 4957 4142 4960 4142 5149 590 4960 590 5150 590 5150 4143 4960 4143 4961 4143 5150 590 4961 590 4873 590 4873 3390 4961 3390 4956 3390 4873 4144 4956 4144 5151 4144 5151 590 4956 590 4954 590 5151 590 4954 590 5146 590 5146 590 4954 590 4947 590 5146 590 4947 590 4951 590 5411 4145 5152 4145 5154 4145 5153 590 5155 590 5401 590 5411 590 5154 590 4949 590 5155 590 5156 590 5401 590 5401 4146 5156 4146 4875 4146 5401 590 4875 590 5411 590 5411 4147 4875 4147 5157 4147 5411 4148 5157 4148 5152 4148 5154 590 5158 590 4949 590 4949 4149 5158 4149 5159 4149 4949 590 5159 590 5160 590 5160 4150 5159 4150 5161 4150 5160 4151 5161 4151 5162 4151 4878 590 5402 590 4880 590 4880 4152 5402 4152 5163 4152 4880 4153 5163 4153 4882 4153 4882 590 5163 590 5164 590 5164 590 5163 590 5195 590 5164 590 5195 590 5165 590 5385 4154 5166 4154 5168 4154 5168 4155 5166 4155 5167 4155 5168 590 5167 590 5165 590 5169 590 5170 590 5298 590 5170 4156 5171 4156 5201 4156 5201 4157 5171 4157 5202 4157 5172 4158 5173 4158 5374 4158 5374 4159 5173 4159 5174 4159 5175 590 5362 590 5176 590 5176 590 5362 590 5363 590 5365 590 5185 590 5177 590 5177 4160 5185 4160 5187 4160 5177 590 5187 590 5178 590 5203 4161 5179 4161 5180 4161 5180 590 5179 590 5181 590 5180 4162 5181 4162 5187 4162 5187 3465 5181 3465 5182 3465 5187 590 5182 590 5178 590 5183 4163 4916 4163 5331 4163 5331 590 4916 590 5184 590 5331 4164 5184 4164 5185 4164 5185 590 5184 590 5186 590 5185 4165 5186 4165 5187 4165 5188 590 5189 590 5315 590 5315 4166 5189 4166 5076 4166 5382 4167 4891 4167 5190 4167 5190 590 4891 590 4890 590 5190 590 4890 590 5208 590 5208 4168 4890 4168 4889 4168 5208 590 4889 590 5192 590 5192 590 4889 590 5191 590 5192 590 5191 590 5193 590 5193 4169 5191 4169 5194 4169 5193 4170 5194 4170 5335 4170 5195 4171 4894 4171 5382 4171 5382 4172 4894 4172 4893 4172 5382 4173 4893 4173 4891 4173 5399 590 4905 590 5398 590 4905 590 4903 590 5398 590 5398 4174 4903 4174 5196 4174 5398 590 5196 590 5129 590 5129 4175 5196 4175 4901 4175 5129 4176 4901 4176 5401 4176 5401 590 4901 590 4899 590 5401 3598 4899 3598 5197 3598 5197 590 4899 590 4897 590 5197 590 4897 590 5199 590 5199 4177 4897 4177 5198 4177 5199 590 5198 590 5200 590 4908 4178 5400 4178 4909 4178 4909 590 5400 590 5201 590 4909 590 5201 590 5180 590 5180 4179 5201 4179 5202 4179 5180 590 5202 590 5203 590 5186 590 5204 590 5187 590 5187 590 5204 590 4912 590 5187 590 4912 590 5180 590 5180 3484 4912 3484 4910 3484 5180 4180 4910 4180 4909 4180 5102 590 5205 590 5206 590 5206 4181 5205 4181 5207 4181 5206 4182 5207 4182 5208 4182 5208 590 5207 590 5212 590 5209 590 5190 590 5210 590 5210 590 5190 590 5208 590 5210 4183 5208 4183 5211 4183 5211 590 5208 590 5212 590 5209 590 5213 590 5190 590 5190 3488 5213 3488 5214 3488 5190 590 5214 590 5382 590 5382 4184 5214 4184 5215 4184 5382 4185 5215 4185 5383 4185 5216 590 5384 590 5218 590 5218 4186 5384 4186 5217 4186 5217 3496 5219 3496 5218 3496 5218 590 5219 590 5220 590 5218 590 5220 590 5387 590 5387 4187 5220 4187 5221 4187 5387 3492 5221 3492 5222 3492 5349 590 5223 590 5350 590 5350 4188 5223 4188 4990 4188 5350 4189 4990 4189 5371 4189 5371 590 4990 590 5224 590 5229 590 4986 590 5226 590 5226 4190 4986 4190 5225 4190 5226 590 5225 590 5353 590 5353 4191 5225 4191 4988 4191 5231 590 5227 590 5228 590 11525 590 5229 590 5228 590 5228 590 5229 590 5230 590 5228 4192 5230 4192 5231 4192 5231 4193 5230 4193 5233 4193 5231 590 5233 590 5235 590 5232 590 5111 590 5233 590 5233 4194 5111 4194 5234 4194 5233 4195 5234 4195 5235 4195 12150 590 5396 590 11540 590 11540 4196 5396 4196 4927 4196 4927 4197 5396 4197 5062 4197 4927 4198 5062 4198 5242 4198 5239 4199 11537 4199 5246 4199 5247 4200 5236 4200 5396 4200 5396 4201 5236 4201 5237 4201 5396 3404 5237 3404 5061 3404 5246 4202 5238 4202 5239 4202 5239 590 5238 590 5240 590 5239 590 5240 590 5247 590 5247 4203 5240 4203 5241 4203 5247 3407 5241 3407 5236 3407 5242 590 5243 590 4927 590 4927 4204 5243 4204 5244 4204 4927 4205 5244 4205 11537 4205 11537 4206 5244 4206 5245 4206 11537 4207 5245 4207 5246 4207 4936 4208 4937 4208 5247 4208 5247 4209 4937 4209 5248 4209 5247 3501 5248 3501 4929 3501 5132 4210 4932 4210 5249 4210 5249 590 4932 590 4934 590 5249 4211 4934 4211 5250 4211 5250 590 4934 590 4936 590 5250 4212 4936 4212 5251 4212 5251 590 4936 590 5247 590 5083 4213 5252 4213 4975 4213 4840 590 4839 590 4969 590 4969 4214 4839 4214 5083 4214 4969 590 5083 590 5253 590 5253 4215 5083 4215 4975 4215 5085 590 5312 590 5083 590 5083 590 5312 590 5254 590 5083 4216 5254 4216 5252 4216 5308 590 5309 590 4994 590 4994 590 5309 590 4821 590 4994 590 4821 590 5069 590 5255 590 5257 590 5256 590 5256 3538 5257 3538 5342 3538 5288 4217 5258 4217 5260 4217 5258 590 5259 590 5260 590 5260 3533 5259 3533 5261 3533 5260 590 5261 590 5262 590 5261 590 5263 590 5262 590 5262 4218 5263 4218 5264 4218 5262 4219 5264 4219 5015 4219 5265 590 5266 590 5267 590 5267 590 5266 590 5343 590 5267 590 5343 590 5268 590 5268 590 5343 590 5269 590 5339 4220 5270 4220 5012 4220 5271 590 5376 590 5272 590 5272 590 5376 590 5336 590 5272 4221 5336 4221 5273 4221 5273 590 5336 590 5274 590 5012 590 5275 590 5339 590 5339 4222 5275 4222 5276 4222 5339 4223 5276 4223 5337 4223 5274 590 5336 590 5286 590 5286 590 5336 590 5338 590 5286 4224 5338 4224 5285 4224 5009 4225 5010 4225 5290 4225 5290 4226 5010 4226 5277 4226 5278 4227 5006 4227 5279 4227 5279 4228 5006 4228 5280 4228 5279 4229 5280 4229 5009 4229 5278 590 5279 590 5005 590 5005 4230 5279 4230 5281 4230 5005 590 5281 590 5283 590 5283 590 5281 590 5282 590 5283 590 5282 590 5285 590 5285 4231 5282 4231 5284 4231 5285 4232 5284 4232 5286 4232 5271 4233 5287 4233 5376 4233 5376 4234 5287 4234 5291 4234 5376 4235 5291 4235 5290 4235 5288 4236 5260 4236 5003 4236 5003 590 5260 590 5290 590 5003 4237 5290 4237 5289 4237 5289 590 5290 590 5277 590 5289 4238 5277 4238 5004 4238 5290 4239 5291 4239 5009 4239 5009 4240 5291 4240 5292 4240 5009 4241 5292 4241 5279 4241 5392 4242 5293 4242 5296 4242 5394 4243 5024 4243 5022 4243 5022 590 5021 590 5394 590 5394 4244 5021 4244 5018 4244 5394 3617 5018 3617 5293 3617 5293 3613 5018 3613 5017 3613 5293 3612 5017 3612 5296 3612 5294 590 5302 590 5295 590 5295 4245 5302 4245 5301 4245 5296 4246 5034 4246 5392 4246 5392 4247 5034 4247 5297 4247 5392 590 5297 590 5298 590 5298 4248 5297 4248 5031 4248 5031 590 5299 590 5298 590 5298 4249 5299 4249 5029 4249 5298 4250 5029 4250 5301 4250 5301 4251 5029 4251 5300 4251 5301 4252 5300 4252 5295 4252 5425 590 5424 590 5391 590 5420 4253 5302 4253 5394 4253 5394 590 5302 590 5294 590 5394 4254 5294 4254 5024 4254 5424 590 5421 590 5391 590 5391 590 5421 590 5303 590 5391 590 5303 590 5394 590 5394 4255 5303 4255 5304 4255 5394 4256 5304 4256 5420 4256 5420 4257 5432 4257 5302 4257 5302 4258 5432 4258 5305 4258 5302 590 5305 590 5301 590 5301 4259 5305 4259 5430 4259 5430 590 5429 590 5301 590 5301 4260 5429 4260 5306 4260 5301 4261 5306 4261 5307 4261 5307 4262 5306 4262 5428 4262 5308 4263 5310 4263 5309 4263 5309 4264 5310 4264 5311 4264 5309 4265 5311 4265 5314 4265 5314 590 5311 590 4981 590 5314 4266 4981 4266 5312 4266 5312 590 4981 590 4983 590 5312 4267 4983 4267 5254 4267 4816 590 5314 590 5313 590 5313 4268 5314 4268 5060 4268 5313 4269 5060 4269 5328 4269 5328 590 5060 590 4854 590 5328 590 4854 590 5315 590 5315 4270 4854 4270 4853 4270 5315 3446 4853 3446 5107 3446 5325 590 5315 590 5316 590 5316 590 5315 590 5076 590 5316 590 5076 590 4834 590 4834 4271 5076 4271 4835 4271 5317 590 5318 590 5319 590 5319 4272 5320 4272 5317 4272 5317 590 5320 590 5321 590 5317 590 5321 590 5076 590 5076 590 5321 590 4837 590 5076 4273 4837 4273 4835 4273 5322 590 5323 590 5328 590 5328 4274 5323 4274 5324 4274 5324 590 5318 590 5328 590 5328 4275 5318 4275 5317 4275 5328 4276 5317 4276 5313 4276 5313 590 5317 590 4812 590 5313 590 4812 590 4816 590 5325 590 5326 590 5315 590 5315 4277 5326 4277 5327 4277 5315 590 5327 590 5328 590 5328 590 5327 590 5329 590 5328 4278 5329 4278 5322 4278 5189 590 5183 590 5076 590 5076 590 5183 590 5331 590 5076 590 5331 590 5330 590 5330 590 5331 590 5185 590 5330 4279 5185 4279 5332 4279 5332 590 5185 590 5333 590 4851 3359 4849 3359 5334 3359 5334 590 4849 590 5192 590 5334 4280 5192 4280 5315 4280 5315 590 5192 590 5193 590 5315 590 5193 590 5188 590 5188 590 5193 590 5335 590 5341 590 5339 590 5336 590 5336 4281 5339 4281 5337 4281 5336 4282 5337 4282 5338 4282 5266 590 5270 590 5343 590 5343 4283 5270 4283 5339 4283 5343 590 5339 590 5340 590 5340 590 5339 590 5341 590 5340 590 5341 590 4925 590 5342 590 5269 590 5256 590 5256 590 5269 590 5343 590 5256 590 5343 590 5352 590 5352 4284 5343 4284 5340 4284 5352 590 5340 590 5111 590 5111 590 5340 590 4925 590 5111 4285 4925 4285 5234 4285 5057 590 5344 590 5358 590 5051 4286 5345 4286 5256 4286 5256 4287 5345 4287 5346 4287 5256 590 5346 590 5356 590 5056 590 5054 590 5347 590 5347 4288 5054 4288 5348 4288 5347 4289 5348 4289 5354 4289 4988 4290 5349 4290 5353 4290 5353 4291 5349 4291 5350 4291 5353 590 5350 590 5347 590 5347 590 5350 590 5358 590 5347 4292 5358 4292 5056 4292 5056 590 5358 590 5344 590 5110 590 5351 590 5111 590 5111 4293 5351 4293 5353 4293 5111 590 5353 590 5352 590 5352 590 5353 590 5347 590 5352 590 5347 590 5256 590 5256 4294 5347 4294 5354 4294 5256 4295 5354 4295 5051 4295 5346 590 5048 590 5356 590 5356 4296 5048 4296 5355 4296 5356 4297 5355 4297 5358 4297 5358 4298 5355 4298 5357 4298 5358 4299 5357 4299 5057 4299 5359 590 5366 590 5367 590 5361 590 5362 590 5360 590 5360 590 5362 590 5356 590 5360 590 5356 590 5038 590 5361 590 5359 590 5362 590 5362 590 5359 590 5367 590 5362 4300 5367 4300 5363 4300 5363 4301 5367 4301 5185 4301 5363 590 5185 590 5364 590 5364 590 5185 590 5365 590 5366 590 5045 590 5367 590 5367 3567 5045 3567 5368 3567 5367 3566 5368 3566 5372 3566 5369 590 5042 590 5358 590 5358 3562 5042 3562 5370 3562 5358 4302 5370 4302 5356 4302 5356 4303 5370 4303 5040 4303 5356 4304 5040 4304 5038 4304 5224 590 5064 590 5371 590 5371 4305 5064 4305 5367 4305 5371 590 5367 590 5358 590 5358 3565 5367 3565 5372 3565 5358 3564 5372 3564 5369 3564 5175 4306 5172 4306 5362 4306 5362 590 5172 590 5374 590 5362 590 5374 590 5356 590 5356 590 5374 590 5373 590 5356 590 5373 590 5256 590 5256 590 5373 590 5262 590 5256 4307 5262 4307 5255 4307 5255 4308 5262 4308 5015 4308 5174 4309 5169 4309 5374 4309 5374 590 5169 590 5298 590 5374 4310 5298 4310 5373 4310 5373 590 5298 590 5301 590 5373 4311 5301 4311 5262 4311 5262 590 5301 590 5307 590 5262 590 5307 590 5260 590 5260 590 5307 590 5375 590 5260 590 5375 590 5290 590 5290 4312 5375 4312 5380 4312 5290 590 5380 590 5376 590 5376 590 5380 590 5377 590 5428 4313 5378 4313 5307 4313 5307 590 5378 590 5390 590 5307 590 5390 590 5375 590 5375 590 5390 590 5379 590 5375 4314 5379 4314 5380 4314 5380 4315 5379 4315 5381 4315 5380 590 5381 590 5377 590 5377 590 5381 590 4924 590 5165 590 5195 590 5168 590 5168 4316 5195 4316 5382 4316 5168 4317 5382 4317 5216 4317 5216 4318 5382 4318 5383 4318 5216 590 5383 590 5384 590 5385 590 5168 590 5145 590 5145 590 5168 590 5216 590 5145 590 5216 590 4965 590 4965 590 5216 590 5218 590 4965 590 5218 590 5386 590 5386 590 5218 590 5387 590 5386 590 5387 590 5388 590 5388 590 5387 590 5389 590 5388 4319 5389 4319 4843 4319 5427 590 5425 590 5390 590 5390 590 5425 590 5391 590 5390 4320 5391 4320 5379 4320 5379 590 5391 590 5395 590 5379 3632 5395 3632 5381 3632 5381 590 5395 590 5397 590 5381 590 5397 590 4924 590 4924 590 5397 590 4923 590 5170 590 5201 590 5298 590 5298 590 5201 590 5400 590 5298 590 5400 590 5392 590 5392 4321 5400 4321 5141 4321 5392 4322 5141 4322 5293 4322 5142 590 5393 590 5141 590 5141 4323 5393 4323 5137 4323 5141 590 5137 590 5293 590 5293 590 5137 590 5249 590 5293 4324 5249 4324 5394 4324 5394 590 5249 590 5250 590 5394 590 5250 590 5391 590 5391 590 5250 590 5251 590 5391 590 5251 590 5395 590 5395 590 5251 590 5247 590 5395 4325 5247 4325 5397 4325 5397 590 5247 590 5396 590 5397 590 5396 590 4923 590 4923 590 5396 590 4922 590 5123 590 5139 590 5129 590 5129 4326 5139 4326 5141 4326 5129 590 5141 590 5398 590 5398 4327 5141 4327 5400 4327 5398 590 5400 590 5399 590 5399 4328 5400 4328 4908 4328 5399 590 4908 590 4907 590 5153 590 5401 590 5402 590 5402 4329 5401 4329 5197 4329 5402 590 5197 590 5163 590 5163 590 5197 590 5199 590 5163 590 5199 590 5195 590 5195 4330 5199 4330 5200 4330 5195 590 5200 590 4894 590 5414 590 5403 590 5401 590 5401 4331 5403 4331 5404 4331 5401 4332 5404 4332 5129 4332 5129 590 5404 590 5405 590 5129 590 5405 590 5415 590 5411 4333 5406 4333 5407 4333 5406 590 5411 590 5408 590 5408 590 5411 590 4946 590 5408 590 4946 590 5409 590 5407 590 5410 590 5411 590 5411 4334 5410 4334 5412 4334 5411 590 5412 590 5401 590 5401 590 5412 590 5413 590 5401 4335 5413 4335 5414 4335 5415 590 5416 590 5129 590 5129 590 5416 590 5417 590 5129 590 5417 590 4946 590 4946 4336 5417 4336 5418 4336 4946 4337 5418 4337 5409 4337 5663 3348 5420 3348 5419 3348 5419 4338 5420 4338 5304 4338 5419 4339 5304 4339 5657 4339 5657 4340 5304 4340 5303 4340 5657 4341 5303 4341 5422 4341 5422 4342 5303 4342 5421 4342 5422 4343 5421 4343 5423 4343 5423 4344 5421 4344 5424 4344 5423 4345 5424 4345 5654 4345 5654 4346 5424 4346 5425 4346 5654 4347 5425 4347 5426 4347 5426 4348 5425 4348 5689 4348 5689 4349 5425 4349 5427 4349 5689 4055 5427 4055 5690 4055 5427 4056 5378 4056 5690 4056 5690 3335 5378 3335 5428 3335 5690 4350 5428 4350 5659 4350 5659 4351 5428 4351 5306 4351 5659 4084 5306 4084 5716 4084 5716 4352 5306 4352 5429 4352 5716 4061 5429 4061 5660 4061 5660 3343 5429 3343 5430 3343 5660 3344 5430 3344 5662 3344 5662 4353 5430 4353 5431 4353 5431 4354 5430 4354 5305 4354 5431 4355 5305 4355 5663 4355 5663 4356 5305 4356 5432 4356 5663 3347 5432 3347 5420 3347 5684 4357 5658 4357 5655 4357 5672 960 5433 960 5434 960 10346 4358 4926 4358 5592 4358 4974 960 4977 960 4976 960 5563 960 5476 960 5475 960 5543 960 5530 960 5541 960 5523 960 5522 960 5435 960 5696 4359 5694 4359 4856 4359 5436 960 5577 960 5768 960 5461 4360 5460 4360 4841 4360 5458 960 5437 960 5480 960 5438 960 5439 960 5767 960 4815 960 5771 960 4814 960 4814 4361 5771 4361 5441 4361 5438 960 5767 960 5440 960 5607 4362 4820 4362 5441 4362 5441 4363 4820 4363 4813 4363 5441 4364 4813 4364 4814 4364 5608 4365 5442 4365 5607 4365 5607 4366 5442 4366 4995 4366 5607 960 4995 960 4818 960 4818 4367 4995 4367 4817 4367 4822 960 4824 960 5741 960 5741 4368 4824 4368 5443 4368 4995 960 4997 960 4817 960 4817 4369 4997 4369 5445 4369 4817 4370 5445 4370 5444 4370 5444 960 5445 960 5446 960 5444 960 5446 960 5447 960 5447 4371 5446 4371 5443 4371 5448 4372 5741 4372 5449 4372 5449 4373 5741 4373 5443 4373 5449 960 5443 960 5450 960 5450 4374 5443 4374 5446 4374 5740 960 4830 960 5741 960 5741 4375 4830 4375 4829 4375 5741 4376 4829 4376 4822 4376 5746 960 4807 960 5555 960 5753 960 4811 960 5453 960 5453 4377 4811 4377 4810 4377 4805 960 5451 960 5452 960 5452 4378 5451 4378 5453 4378 5452 960 5453 960 5454 960 5454 960 5453 960 4810 960 4844 960 5456 960 5455 960 5455 960 5456 960 5468 960 5455 960 5468 960 5457 960 5458 960 5480 960 4844 960 4970 960 4841 960 5459 960 5459 960 4841 960 5460 960 5459 4379 5460 4379 4972 4379 4972 4380 5460 4381 5461 4382 4972 4383 5461 4383 4973 4383 4973 4384 5461 4384 5462 4384 4973 4385 5462 4385 4968 4385 4968 3084 5462 3084 5463 3084 4968 960 5463 960 5464 960 5464 3095 5463 3095 5465 3095 5464 960 5465 960 4966 960 4966 4386 5465 4386 5466 4386 4966 960 5466 960 5468 960 5468 4387 5466 4387 5467 4387 5468 4388 5467 4388 5457 4388 5576 960 5469 960 4970 960 4970 960 5469 960 4838 960 4970 960 4838 960 4841 960 5436 960 5768 960 5472 960 5773 4389 5772 4389 5770 4389 5770 4390 5772 4390 5470 4390 5770 4391 5470 4391 5768 4391 5768 4392 5470 4392 5471 4392 5768 4393 5471 4393 5472 4393 4846 960 4847 960 5748 960 5748 960 4847 960 4848 960 5748 960 4848 960 5762 960 5762 4394 4848 4394 4850 4394 5764 960 5473 960 4852 960 4852 960 5473 960 5762 960 4852 960 5762 960 5474 960 5474 960 5762 960 4850 960 5747 4395 5548 4395 5478 4395 5478 960 5548 960 5475 960 5475 960 5476 960 5478 960 5478 4396 5476 4396 5477 4396 5478 960 5477 960 4845 960 4845 4397 5477 4397 5479 4397 4845 960 5479 960 5437 960 5437 4398 5479 4398 5571 4398 5437 4399 5571 4399 5480 4399 5593 960 10706 960 5489 960 5489 960 10706 960 10710 960 5485 960 5488 960 5592 960 5592 4400 5488 4400 5481 4400 5592 3155 5481 3155 5482 3155 5483 960 10707 960 5484 960 5484 4401 10707 4401 5486 4401 5484 960 5486 960 5485 960 5485 4402 5486 4402 5487 4402 5485 3157 5487 3157 5488 3157 5599 4403 5598 4403 5490 4403 10710 960 10709 960 5489 960 5489 4404 10709 4404 5597 4404 5489 960 5597 960 5595 960 5483 960 5484 960 5490 960 5490 4405 5484 4405 5603 4405 5490 4406 5603 4406 5599 4406 5492 4407 4865 4407 5579 4407 5579 4408 4865 4408 5491 4408 4943 4409 4867 4409 5496 4409 5579 4410 4938 4410 5492 4410 5492 4411 4938 4411 4940 4411 5492 4412 4940 4412 5493 4412 5493 4413 4940 4413 4941 4413 5493 960 4941 960 5494 960 5494 4414 4941 4414 5495 4414 5494 960 5495 960 5496 960 5496 4415 5495 4415 4942 4415 5496 4416 4942 4416 4943 4416 4871 960 4945 960 4870 960 4870 960 4945 960 5676 960 4870 4417 5676 4417 5497 4417 4943 4418 5498 4418 4867 4418 4867 4419 5498 4419 4945 4419 4867 960 4945 960 5499 960 5499 960 4945 960 4871 960 5697 960 5500 960 5695 960 5695 4420 5500 4420 5501 4420 5695 4421 5501 4421 5676 4421 5676 4422 5501 4422 5502 4422 5676 4423 5502 4423 5497 4423 4860 960 4858 960 5646 960 4860 960 5646 960 5682 960 4856 960 5694 960 5503 960 5503 960 5694 960 5703 960 5503 960 5703 960 5504 960 5505 960 5670 960 5434 960 5505 960 5434 960 5506 960 5506 4424 5434 4424 4948 4424 5506 960 4948 960 5507 960 5671 4425 4876 4425 5668 4425 5668 4426 4876 4426 4877 4426 5668 4427 4877 4427 5701 4427 4959 960 5518 960 5508 960 5508 960 5518 960 5513 960 5507 4428 4948 4428 5509 4428 5509 4429 4948 4429 4950 4429 5509 4430 4950 4430 5510 4430 5510 4431 4950 4431 4952 4431 5510 960 4952 960 5511 960 5511 960 4952 960 5512 960 5511 960 5512 960 4874 960 4874 4432 5512 4432 4955 4432 4874 4433 4955 4433 5513 4433 5513 4434 4955 4434 4953 4434 5513 960 4953 960 5508 960 5519 960 4883 960 5514 960 5514 3045 4883 3045 5515 3045 5514 960 5515 960 4958 960 4958 4435 5515 4435 5516 4435 4958 3042 5516 3042 4959 3042 4959 3043 5516 3043 5517 3043 4959 3041 5517 3041 5518 3041 5519 960 5514 960 4886 960 4886 4436 5514 4436 4962 4436 4886 4437 4962 4437 5520 4437 5699 960 4881 960 5521 960 5521 960 4881 960 4888 960 5521 4438 4888 4438 4887 4438 5522 4439 5523 4439 5524 4439 5523 4440 4879 4440 5524 4440 5524 4441 4879 4441 5525 4441 5524 4442 5525 4442 5699 4442 5699 960 5525 960 5526 960 5699 4443 5526 4443 4881 4443 5651 960 5527 960 5717 960 5718 960 5528 960 5725 960 5725 960 5528 960 5529 960 5725 3214 5529 3214 5726 3214 5541 4444 5530 4444 5531 4444 5531 960 5530 960 5532 960 5531 4445 5532 4445 5533 4445 5650 4446 5533 4446 5534 4446 5535 4447 5536 4447 5555 4447 5555 4448 5536 4448 5537 4448 5555 960 5537 960 5552 960 5552 3110 5537 3110 5538 3110 5538 960 5539 960 5552 960 5552 960 5539 960 5540 960 5552 960 5540 960 5541 960 5541 960 5540 960 5542 960 5541 4449 5542 4449 5543 4449 5691 4450 4906 4450 5702 4450 5702 4451 4906 4451 5531 4451 5698 4452 5544 4452 5700 4452 5700 960 5544 960 4895 960 5700 960 4895 960 5545 960 4895 4453 4896 4453 5545 4453 5545 4454 4896 4454 4898 4454 5545 3314 4898 3314 5668 3314 5668 4455 4898 4455 4900 4455 5668 960 4900 960 5695 960 5695 4456 4900 4456 5546 4456 5695 4457 5546 4457 5693 4457 5693 4458 5546 4458 4902 4458 5693 4459 4902 4459 5692 4459 5692 960 4902 960 4904 960 5692 960 4904 960 5691 960 4892 960 5698 960 5699 960 5547 960 5560 960 5475 960 5750 960 4917 960 5749 960 5749 4460 4917 4460 4918 4460 5749 960 4918 960 5548 960 5548 4461 4918 4461 4919 4461 5548 4462 4919 4462 5475 4462 5475 960 4919 960 4920 960 5475 4463 4920 4463 5547 4463 5549 960 5762 960 5453 960 5549 3119 5453 3119 4915 3119 4906 960 5550 960 5531 960 5531 960 5550 960 4911 960 5531 960 4911 960 5541 960 5541 3127 4911 3127 5551 3127 5541 960 5551 960 5552 960 5552 960 5551 960 5553 960 5552 960 5553 960 5555 960 5555 960 5553 960 5554 960 5555 960 5554 960 5556 960 5556 4464 5554 4464 4913 4464 5556 4465 4913 4465 4914 4465 5570 4466 5557 4466 5560 4466 5560 3139 5557 3139 5558 3139 5558 960 5559 960 5560 960 5560 960 5559 960 5561 960 5560 960 5561 960 5475 960 5475 960 5561 960 5562 960 5475 960 5562 960 5563 960 5564 960 5565 960 5574 960 5574 960 5565 960 5567 960 5574 4467 5567 4467 5566 4467 5566 960 5567 960 5568 960 5566 4468 5568 4468 5570 4468 5570 4469 5568 4469 5569 4469 5570 4470 5569 4470 5557 4470 5571 960 5572 960 5480 960 5480 4471 5572 4471 5573 4471 5480 960 5573 960 5574 960 5574 4472 5573 4472 5575 4472 5574 4473 5575 4473 5564 4473 4974 960 5768 960 5576 960 5576 4474 5768 4474 5577 4474 5576 4475 5577 4475 5469 4475 5581 4476 4935 4476 5578 4476 5578 960 4935 960 4933 960 5578 4477 4933 4477 5579 4477 5579 960 4933 960 4931 960 5579 4478 4931 4478 4938 4478 5683 4479 5585 4479 4930 4479 4930 960 5580 960 5683 960 5683 4480 5580 4480 5582 4480 5683 960 5582 960 5581 960 5581 960 5582 960 5583 960 5581 960 5583 960 4935 960 10699 4481 5584 4481 4928 4481 10700 4482 5585 4482 10701 4482 10701 960 5586 960 10700 960 10700 2561 5586 2561 5587 2561 10700 4483 5587 4483 4928 4483 4928 4484 5587 4484 5588 4484 4928 4485 5588 4485 10699 4485 5584 960 5589 960 5685 960 5589 960 10697 960 5685 960 5685 960 10697 960 5590 960 5685 960 5590 960 5683 960 5590 960 5591 960 5683 960 5683 3064 5591 3064 10696 3064 5683 4486 10696 4486 5585 4486 5585 960 10696 960 10695 960 5585 960 10695 960 10701 960 5685 4487 5732 4487 4921 4487 5584 960 5685 960 4928 960 4928 4488 5685 4488 4921 4488 4928 960 4921 960 10693 960 10346 4489 5592 4489 5594 4489 5482 960 5593 960 5592 960 5592 4490 5593 4490 5489 4490 5592 960 5489 960 5594 960 5594 960 5489 960 5595 960 5594 960 5595 960 5596 960 5596 4491 5595 4491 5600 4491 5596 960 5600 960 4984 960 5597 960 5598 960 5595 960 5595 960 5598 960 5599 960 5595 4492 5599 4492 5600 4492 5600 4493 5599 4493 4987 4493 5601 4494 4989 4494 5485 4494 5485 3150 4989 3150 5602 3150 5485 4495 5602 4495 5484 4495 5484 4496 5602 4496 4985 4496 5484 4497 4985 4497 5603 4497 5448 4498 5604 4498 5741 4498 5741 960 5604 960 5605 960 5741 960 5605 960 5606 960 5606 4499 5605 4499 5601 4499 5606 4500 5601 4500 5743 4500 5743 960 5601 960 5485 960 5607 4501 5441 4501 5608 4501 5608 960 5441 960 4978 960 5608 4502 4978 4502 4993 4502 5614 960 5609 960 5720 960 5720 4503 5609 4503 5610 4503 5720 4504 5610 4504 5611 4504 5001 960 5002 960 5612 960 5612 960 5002 960 5709 960 5612 960 5709 960 5613 960 5613 960 5709 960 5713 960 5619 960 5615 960 5614 960 5614 4505 5615 4505 5616 4505 5614 4506 5616 4506 5609 4506 5719 960 5016 960 5730 960 5730 3178 5016 3178 5617 3178 5730 3177 5617 3177 5618 3177 5619 4507 5614 4507 5011 4507 5011 960 5614 960 5624 960 5011 4508 5624 4508 5013 4508 5706 960 5620 960 5707 960 5707 3195 5620 3195 5621 3195 5707 4509 5621 4509 5630 4509 5630 960 5621 960 5622 960 5630 3193 5622 3193 5628 3193 5014 960 5013 960 5623 960 5623 4510 5013 4510 5624 4510 5623 4511 5624 4511 5625 4511 5625 4512 5624 4512 5633 4512 5710 960 5626 960 5627 960 5640 960 5636 960 5639 960 5628 960 5629 960 5630 960 5630 3184 5629 3184 5631 3184 5630 4513 5631 4513 5624 4513 5624 4514 5631 4514 5632 4514 5624 4515 5632 4515 5633 4515 5633 4516 5632 4516 5643 4516 5633 960 5643 960 5634 960 5635 960 5008 960 5636 960 5636 4517 5008 4517 5007 4517 5636 4518 5007 4518 5639 4518 5627 960 5637 960 5710 960 5710 960 5637 960 5638 960 5710 4519 5638 4519 5635 4519 5639 960 5641 960 5640 960 5640 3188 5641 3188 5642 3188 5640 4520 5642 4520 5643 4520 5643 4521 5642 4521 5644 4521 5643 4522 5644 4522 5634 4522 5645 4523 5646 4523 5033 4523 5033 4524 5646 4524 5653 4524 5647 960 5020 960 5649 960 5649 4525 5020 4525 5023 4525 5649 960 5656 960 5647 960 5647 960 5656 960 5646 960 5647 960 5646 960 5019 960 5019 4526 5646 4526 5645 4526 5023 960 5648 960 5649 960 5649 4527 5648 4527 5025 4527 5649 960 5025 960 5661 960 5661 4528 5025 4528 5026 4528 5661 4529 5026 4529 5027 4529 5027 4530 5028 4530 5661 4530 5661 960 5028 960 5650 960 5661 4531 5650 4531 5717 4531 5717 960 5650 960 5534 960 5717 4532 5534 4532 5651 4532 5028 960 5652 960 5650 960 5650 4533 5652 4533 5030 4533 5650 960 5030 960 5653 960 5653 4534 5030 4534 5032 4534 5653 4535 5032 4535 5033 4535 5658 4536 5654 4536 5655 4536 5655 4537 5654 4537 5426 4537 5655 4538 5426 4538 5689 4538 5419 960 5657 960 5656 960 5656 3284 5657 3284 5422 3284 5656 4539 5422 4539 5658 4539 5658 3282 5422 3282 5423 3282 5658 4540 5423 4540 5654 4540 5688 960 5690 960 5659 960 5716 960 5660 960 5661 960 5661 4541 5660 4541 5662 4541 5661 960 5662 960 5649 960 5649 4542 5662 4542 5431 4542 5649 960 5431 960 5656 960 5656 4543 5431 4543 5663 4543 5656 3271 5663 3271 5419 3271 5668 4544 5669 4544 5664 4544 5681 4545 5665 4545 5695 4545 5695 4546 5665 4546 5666 4546 5695 960 5666 960 5668 960 5668 4547 5666 4547 5667 4547 5668 4548 5667 4548 5669 4548 5670 960 5671 960 5434 960 5434 960 5671 960 5668 960 5434 960 5668 960 5672 960 5672 960 5668 960 5664 960 5433 4549 5673 4549 5434 4549 5434 4550 5673 4550 5674 4550 5434 960 5674 960 5676 960 5676 4551 5674 4551 5675 4551 5676 4552 5675 4552 5677 4552 5677 960 5678 960 5676 960 5676 4553 5678 4553 5679 4553 5676 960 5679 960 5695 960 5695 4554 5679 4554 5680 4554 5695 4555 5680 4555 5681 4555 5491 4556 5682 4556 5579 4556 5579 960 5682 960 5646 960 5579 4557 5646 4557 5578 4557 5578 4558 5646 4558 5656 4558 5578 4559 5656 4559 5581 4559 5581 4560 5656 4560 5658 4560 5581 960 5658 960 5683 960 5683 960 5658 960 5684 960 5683 960 5684 960 5685 960 5732 4561 5685 4561 5686 4561 5686 960 5685 960 5684 960 5686 4562 5684 4562 5687 4562 5687 960 5684 960 5655 960 5687 4563 5655 4563 5688 4563 5688 4564 5655 4564 5689 4564 5688 4565 5689 4565 5690 4565 5691 960 5702 960 5692 960 5692 960 5702 960 5703 960 5692 960 5703 960 5693 960 5693 960 5703 960 5694 960 5693 960 5694 960 5695 960 5695 960 5694 960 5696 960 5695 4566 5696 4566 5697 4566 5698 4567 5700 4567 5699 4567 5699 4568 5700 4568 5545 4568 5699 4569 5545 4569 5524 4569 5524 4570 5545 4570 5668 4570 5524 960 5668 960 5522 960 5522 960 5668 960 5701 960 5522 4571 5701 4571 5435 4571 5533 960 5650 960 5531 960 5531 4572 5650 4572 5653 4572 5531 960 5653 960 5702 960 5702 4573 5653 4573 5646 4573 5702 960 5646 960 5703 960 5703 960 5646 960 4858 960 5703 3307 4858 3307 5504 3307 5521 960 5566 960 5699 960 5699 4574 5566 4574 5570 4574 5699 960 5570 960 4892 960 4892 4575 5570 4575 5560 4575 4892 4576 5560 4576 5704 4576 5704 960 5560 960 5547 960 5636 960 5705 960 5635 960 5635 4577 5705 4577 5706 4577 5635 4578 5706 4578 5710 4578 5710 960 5706 960 5707 960 5710 4579 5707 4579 5708 4579 5002 960 5626 960 5709 960 5709 4580 5626 4580 5710 4580 5709 4581 5710 4581 5711 4581 5711 4582 5710 4582 5708 4582 5711 4583 5708 4583 5712 4583 5618 960 5713 960 5730 960 5730 960 5713 960 5709 960 5730 4584 5709 4584 5731 4584 5731 960 5709 960 5711 960 5731 4585 5711 4585 5714 4585 5714 4586 5711 4586 5712 4586 5714 4587 5712 4587 5715 4587 5659 960 5716 960 5688 960 5688 960 5716 960 5661 960 5688 4588 5661 4588 5729 4588 5729 4589 5661 4589 5717 4589 5729 4590 5717 4590 5725 4590 5725 960 5717 960 5527 960 5725 960 5527 960 5718 960 5611 3173 5719 3173 5720 3173 5720 4591 5719 4591 5730 4591 5720 960 5730 960 5728 960 4844 960 5480 960 5456 960 5456 960 5480 960 5574 960 5456 960 5574 960 4964 960 4964 4592 5574 4592 5566 4592 4964 4593 5566 4593 4963 4593 4963 4594 5566 4594 5521 4594 4963 4595 5521 4595 4962 4595 4962 4596 5521 4596 4887 4596 4962 4597 4887 4597 5520 4597 5059 960 5046 960 5737 960 5737 4598 5046 4598 5047 4598 5737 4599 5047 4599 5728 4599 5047 960 5049 960 5728 960 5728 4600 5049 4600 5721 4600 5728 960 5721 960 5720 960 5720 4601 5721 4601 5050 4601 5052 960 5722 960 5742 960 5742 4602 5722 4602 5053 4602 5053 960 5055 960 5742 960 5742 3218 5055 3218 5723 3218 5742 960 5723 960 5737 960 5737 3217 5723 3217 5058 3217 5737 4603 5058 4603 5059 4603 5050 960 5052 960 5720 960 5720 960 5052 960 5742 960 5720 960 5742 960 5614 960 5614 4604 5742 4604 5724 4604 5614 960 5724 960 5624 960 5624 4605 5724 4605 5744 4605 5624 4606 5744 4606 5630 4606 5630 4607 5744 4607 5745 4607 5035 960 5036 960 5725 960 5725 4608 5036 4608 5727 4608 5044 960 5035 960 5735 960 5735 4609 5035 4609 5725 4609 5735 4610 5725 4610 5555 4610 5555 4611 5725 4611 5726 4611 5555 4612 5726 4612 5535 4612 5727 4613 5037 4613 5725 4613 5725 960 5037 960 5728 960 5725 4614 5728 4614 5729 4614 5729 960 5728 960 5730 960 5729 4615 5730 4615 5688 4615 5688 960 5730 960 5731 960 5688 4616 5731 4616 5687 4616 5687 960 5731 960 5714 960 5687 4617 5714 4617 5686 4617 5686 960 5714 960 5715 960 5686 960 5715 960 5732 960 5738 960 5733 960 5737 960 5737 3203 5733 3203 5734 3203 5737 960 5734 960 5735 960 5735 3202 5734 3202 5043 3202 5735 4618 5043 4618 5044 4618 5037 960 5039 960 5728 960 5728 4619 5039 4619 5736 4619 5728 960 5736 960 5737 960 5737 4620 5736 4620 5041 4620 5737 4621 5041 4621 5738 4621 4807 960 5739 960 5555 960 5555 960 5739 960 5740 960 5555 960 5740 960 5735 960 5735 960 5740 960 5741 960 5735 4622 5741 4622 5737 4622 5737 4623 5741 4623 5606 4623 5737 4624 5606 4624 5742 4624 5742 4625 5606 4625 5743 4625 5742 960 5743 960 5724 960 5724 960 5743 960 5485 960 5724 960 5485 960 5744 960 5744 960 5485 960 5592 960 5744 960 5592 960 5745 960 5745 960 5592 960 4926 960 4914 960 4915 960 5556 960 5556 4626 4915 4626 5453 4626 5556 960 5453 960 5555 960 5555 960 5453 960 5451 960 5555 4627 5451 4627 5746 4627 5746 960 5451 960 4805 960 5747 4628 4846 4628 5548 4628 5548 960 4846 960 5748 960 5548 960 5748 960 5749 960 5749 960 5748 960 5762 960 5749 3117 5762 3117 5750 3117 5750 960 5762 960 5549 960 4832 4629 4833 4629 5762 4629 5762 4630 4833 4630 5751 4630 5762 960 5751 960 5453 960 5453 4631 5751 4631 5752 4631 5759 960 5754 960 5753 960 5753 4632 5754 4632 5755 4632 5753 960 5755 960 5473 960 5473 960 5755 960 5756 960 5473 4633 5756 4633 5760 4633 5752 960 4836 960 5453 960 5453 4634 4836 4634 5757 4634 5453 960 5757 960 5753 960 5753 4635 5757 4635 5758 4635 5753 960 5758 960 5759 960 5760 4636 5761 4636 5473 4636 5473 4637 5761 4637 5763 4637 5473 960 5763 960 5762 960 5762 960 5763 960 4831 960 5762 960 4831 960 4832 960 5764 960 5765 960 5473 960 5473 4638 5765 4638 5766 4638 5473 4639 5766 4639 5753 4639 5753 4640 5766 4640 5767 4640 5753 960 5767 960 4811 960 4811 4641 5767 4641 5439 4641 5765 960 5773 960 5766 960 5766 960 5773 960 5770 960 5766 4642 5770 4642 5767 4642 5767 4643 5770 4643 5771 4643 5767 960 5771 960 5440 960 5440 960 5771 960 4815 960 4974 960 4976 960 5768 960 5768 4644 4976 4644 5769 4644 5768 4645 5769 4645 5770 4645 5770 4646 5769 4646 4982 4646 5770 960 4982 960 5771 960 5771 960 4982 960 4980 960 5771 960 4980 960 5441 960 5441 960 4980 960 4979 960 5441 4647 4979 4647 4978 4647 5085 4648 5471 4648 5470 4648 5085 4649 5470 4649 5080 4649 5080 4650 5470 4650 5772 4650 5080 4651 5772 4651 5774 4651 5774 4652 5772 4652 5773 4652 5774 4653 5773 4653 4855 4653 6017 4654 6404 4654 6018 4654 6018 4655 6404 4655 6403 4655 6018 4656 6403 4656 5776 4656 5776 4656 6403 4656 5775 4656 5776 4657 5775 4657 6388 4657 5776 4658 6388 4658 5777 4658 5777 4659 6388 4659 6387 4659 5777 4660 6387 4660 6011 4660 6011 4661 6387 4661 6389 4661 6011 4662 6389 4662 5778 4662 5778 4663 6389 4663 5779 4663 5778 4664 5779 4664 5780 4664 6386 4665 5786 4665 5781 4665 5781 4666 5786 4666 5782 4666 5781 4667 5782 4667 5783 4667 5783 4668 5782 4668 6008 4668 5783 4669 6008 4669 6392 4669 6392 4669 6008 4669 6009 4669 6392 4670 6009 4670 5784 4670 5784 4671 6009 4671 6010 4671 5784 4672 6010 4672 5779 4672 5779 4673 6010 4673 5780 4673 5786 4674 6386 4674 5785 4674 5786 4675 5785 4675 5787 4675 5787 4676 5785 4676 6397 4676 5787 4676 6397 4676 6366 4676 6366 4677 6397 4677 6396 4677 6366 4677 6396 4677 6365 4677 6365 4678 6396 4678 6395 4678 6365 4679 6395 4679 5798 4679 5788 4680 5795 4680 5789 4680 5789 4681 5795 4681 5790 4681 5789 4682 5790 4682 5791 4682 5791 4683 5790 4683 5792 4683 5791 4684 5792 4684 6333 4684 6333 4685 5792 4685 6661 4685 5793 4686 6399 4686 5794 4686 5793 4687 5794 4687 6020 4687 6020 4688 5794 4688 5795 4688 6020 4689 5795 4689 5788 4689 6399 49 5793 49 5796 49 5796 49 5793 49 5797 49 5796 49 5797 49 6394 49 6394 49 5797 49 6360 49 6394 49 6360 49 6395 49 6395 49 6360 49 5798 49 6167 4690 5799 4690 5800 4690 5800 4691 5799 4691 6411 4691 5800 4692 6411 4692 6031 4692 6031 4692 6411 4692 6412 4692 6031 4693 6412 4693 5802 4693 5802 4693 6412 4693 5801 4693 5802 4694 5801 4694 5803 4694 5803 4695 5801 4695 5804 4695 5805 50 5806 50 5807 50 5807 50 5806 50 6430 50 5807 50 6430 50 6361 50 6361 50 6430 50 6429 50 6361 50 6429 50 6362 50 6362 50 6429 50 5808 50 6025 4696 6420 4696 5810 4696 5809 4697 5817 4697 6310 4697 6310 4698 5817 4698 6021 4698 5809 4699 6310 4699 6421 4699 6421 4700 6310 4700 6022 4700 6421 4701 6022 4701 5810 4701 5810 4702 6022 4702 6023 4702 5810 4703 6023 4703 6025 4703 6427 4704 6043 4704 6428 4704 6428 4704 6043 4704 6042 4704 6428 4705 6042 4705 5811 4705 5811 4706 6042 4706 5813 4706 5811 4707 5813 4707 5812 4707 5812 4708 5813 4708 6040 4708 5812 4709 6040 4709 6425 4709 6425 4710 6040 4710 5814 4710 6156 4711 5815 4711 6534 4711 6425 4712 5814 4712 6423 4712 6423 4713 5814 4713 6044 4713 6423 4714 6044 4714 6534 4714 6534 4715 6044 4715 6153 4715 6534 4716 6153 4716 6156 4716 5815 21 6156 21 5816 21 5816 21 6156 21 6157 21 5816 21 6157 21 5817 21 5817 21 6157 21 6021 21 6070 4717 5819 4717 5818 4717 5818 4718 5819 4718 6463 4718 5818 4719 6463 4719 5820 4719 5820 4720 6463 4720 6462 4720 5820 4721 6462 4721 6064 4721 6064 4722 6462 4722 6454 4722 6064 4723 6454 4723 5821 4723 6064 4724 5821 4724 6065 4724 6065 4725 5821 4725 6452 4725 6065 4726 6452 4726 6066 4726 6067 49 6066 49 5822 49 5822 49 6066 49 6452 49 6067 4727 5822 4727 5823 4727 6067 4728 5823 4728 6063 4728 6063 4729 5823 4729 6451 4729 6063 4729 6451 4729 6062 4729 6062 4730 6451 4730 6449 4730 6062 4730 6449 4730 6060 4730 6060 4731 6449 4731 6447 4731 6060 4732 6447 4732 5824 4732 5825 4733 6058 4733 5826 4733 5824 4734 6447 4734 6056 4734 6056 4735 6447 4735 5827 4735 6056 4736 5827 4736 5826 4736 5826 4737 5827 4737 6457 4737 5826 4738 6457 4738 5825 4738 6058 4739 5825 4739 5828 4739 6058 4740 5828 4740 5829 4740 5829 4741 5828 4741 6459 4741 5829 4742 6459 4742 6055 4742 6055 4743 6459 4743 5830 4743 6055 4744 5830 4744 5831 4744 5831 4745 5830 4745 6455 4745 5831 4746 6455 4746 5832 4746 5833 4747 6069 4747 5834 4747 5834 4748 6069 4748 6276 4748 5834 4749 6276 4749 6455 4749 6455 4749 6276 4749 5832 4749 5836 4750 6075 4750 6081 4750 6084 4751 5835 4751 6082 4751 6082 4752 5835 4752 6485 4752 6082 4753 6485 4753 6081 4753 6081 4754 6485 4754 6484 4754 6081 4755 6484 4755 5836 4755 5835 4756 6084 4756 5837 4756 5837 4757 6084 4757 6086 4757 5837 4758 6086 4758 6473 4758 6473 4759 6086 4759 6088 4759 6094 4760 6471 4760 5839 4760 6473 4761 6088 4761 5838 4761 5838 4761 6088 4761 6080 4761 5838 4762 6080 4762 5839 4762 5839 4763 6080 4763 6095 4763 5839 4764 6095 4764 6094 4764 5840 6 6312 6 6490 6 6490 6 6312 6 6099 6 6490 6 6099 6 6710 6 6710 6 6099 6 5841 6 6710 4765 5841 4765 5844 4765 5845 4766 6489 4766 6105 4766 6105 4767 6489 4767 5842 4767 6105 4768 5842 4768 5844 4768 5844 4769 5842 4769 5843 4769 5844 4770 5843 4770 6710 4770 6489 4771 5845 4771 5846 4771 5846 4772 5845 4772 6103 4772 5846 4773 6103 4773 6487 4773 6487 4774 6103 4774 6101 4774 6487 4775 6101 4775 6486 4775 6486 4776 6101 4776 6100 4776 6486 4777 6100 4777 6475 4777 6475 4777 6100 4777 6072 4777 6481 50 6480 50 6078 50 6078 50 6480 50 5847 50 5872 1446 5873 1446 5848 1446 5848 1446 5873 1446 6511 1446 5848 1447 6511 1447 6290 1447 6290 1447 6511 1447 5849 1447 6290 4778 5849 4778 6133 4778 6133 4779 5849 4779 5850 4779 6133 4780 5850 4780 6125 4780 6125 4781 5850 4781 6514 4781 6125 4782 6514 4782 5851 4782 5851 4783 6514 4783 6522 4783 5851 4784 6522 4784 6126 4784 6126 4785 6522 4785 6521 4785 6126 4786 6521 4786 6127 4786 6127 4787 6521 4787 6519 4787 6127 4788 6519 4788 5852 4788 5852 4788 6519 4788 5853 4788 5852 4789 5853 4789 6129 4789 6129 4790 5853 4790 6517 4790 6129 4791 6517 4791 6130 4791 6130 4792 6517 4792 5854 4792 6130 4793 5854 4793 6132 4793 6132 4794 5854 4794 5855 4794 6132 4795 5855 4795 5856 4795 5856 4796 5855 4796 6516 4796 5856 4797 6516 4797 5857 4797 5857 4798 6516 4798 6736 4798 5857 4799 6736 4799 6124 4799 6124 4800 6736 4800 6735 4800 6124 4801 6735 4801 5858 4801 5858 4802 6735 4802 5859 4802 5858 4803 5859 4803 6138 4803 6138 4804 5859 4804 5860 4804 6138 1417 5860 1417 5861 1417 5861 1417 5860 1417 5862 1417 5861 1418 5862 1418 5863 1418 5863 1418 5862 1418 5865 1418 5863 4805 5865 4805 5864 4805 5864 4806 5865 4806 6526 4806 5864 4807 6526 4807 6141 4807 6141 4808 6526 4808 6509 4808 6141 4809 6509 4809 5866 4809 5866 4810 6509 4810 5867 4810 5866 4811 5867 4811 6338 4811 6338 4812 5867 4812 6660 4812 6338 4813 6660 4813 5868 4813 5868 4814 6660 4814 5869 4814 5868 4815 5869 4815 6134 4815 6134 4816 5869 4816 5870 4816 6134 4817 5870 4817 6135 4817 6135 4817 5870 4817 6664 4817 6135 4818 6664 4818 6136 4818 6136 4819 6664 4819 6513 4819 6136 4820 6513 4820 6137 4820 6137 4821 6513 4821 5871 4821 6137 4822 5871 4822 5872 4822 5872 4823 5871 4823 5873 4823 5882 4824 6570 4824 5877 4824 6572 4825 5874 4825 5875 4825 5875 4826 5874 4826 5876 4826 5875 4827 5876 4827 5877 4827 5877 4828 5876 4828 5878 4828 5877 4829 5878 4829 5882 4829 6029 4830 5884 4830 5879 4830 5879 4831 5884 4831 6415 4831 5879 4832 6415 4832 5880 4832 5880 4833 6415 4833 6414 4833 5880 4834 6414 4834 6032 4834 6032 4835 6414 4835 5881 4835 6032 4836 5881 4836 6166 4836 6166 4837 5881 4837 5883 4837 6166 4838 5883 4838 5882 4838 5882 4839 5883 4839 6570 4839 5884 4840 6029 4840 5888 4840 5896 4841 5886 4841 5885 4841 5885 4842 5886 4842 5887 4842 5885 4843 5887 4843 5888 4843 5888 4844 5887 4844 6416 4844 5888 4845 6416 4845 5884 4845 6092 50 5898 50 5889 50 5889 50 5898 50 6470 50 5889 50 6470 50 5890 50 5890 50 6470 50 6466 50 5890 50 6466 50 5891 50 5891 50 6466 50 6713 50 5891 50 6713 50 6311 50 6311 50 6713 50 5892 50 6311 50 5892 50 5893 50 5893 50 5892 50 5894 50 5893 50 5894 50 6024 50 6024 50 5894 50 5895 50 6024 50 5895 50 5896 50 5896 50 5895 50 5886 50 6089 4846 6474 4846 5897 4846 5898 4847 6092 4847 6472 4847 6472 4848 6092 4848 5899 4848 6472 4849 5899 4849 5897 4849 5897 4850 5899 4850 5900 4850 5897 4851 5900 4851 6089 4851 6474 4852 6089 4852 5901 4852 5901 4853 6089 4853 6087 4853 5901 176 6087 176 5902 176 5902 4854 6087 4854 6085 4854 5902 4855 6085 4855 6083 4855 5905 4856 6478 4856 5903 4856 5903 4857 6478 4857 5904 4857 5903 4858 5904 4858 6083 4858 6083 4859 5904 4859 6468 4859 6083 4860 6468 4860 5902 4860 5906 6 6460 6 6061 6 6061 6 6460 6 6448 6 6061 6 6448 6 6260 6 6260 6 6448 6 6450 6 6260 6 6450 6 6263 6 6263 6 6450 6 6747 6 6263 6 6747 6 5905 6 5905 6 6747 6 6478 6 5906 4861 6059 4861 6460 4861 6460 4862 6059 4862 6461 4862 6057 4863 6456 4863 5907 4863 6057 4864 5907 4864 5908 4864 5908 4865 5907 4865 5909 4865 5908 4866 5909 4866 5910 4866 5910 4867 5909 4867 6461 4867 5910 4868 6461 4868 6059 4868 6171 4869 6458 4869 5911 4869 6171 4870 5911 4870 6172 4870 6172 4871 5911 4871 5912 4871 6172 4872 5912 4872 5913 4872 5913 4873 5912 4873 6456 4873 5913 4874 6456 4874 6057 4874 5914 4875 5920 4875 5915 4875 5915 4876 5920 4876 5916 4876 5915 4877 5916 4877 5917 4877 5917 4878 5916 4878 5918 4878 5917 4879 5918 4879 6170 4879 6170 4880 5918 4880 6568 4880 6170 4881 6568 4881 6171 4881 6171 4882 6568 4882 6458 4882 6566 4883 5920 4883 5919 4883 5919 4884 5920 4884 5914 4884 5921 4885 5923 4885 5922 4885 5922 4885 5923 4885 5924 4885 5922 4886 5924 4886 5919 4886 5919 4887 5924 4887 6566 4887 5923 6 5921 6 5925 6 5925 6 5921 6 6177 6 5925 6 6177 6 6551 6 6551 6 6177 6 5926 6 5926 4888 10334 4888 6551 4888 6551 4888 10334 4888 6384 4888 6384 49 10334 49 5927 49 5927 49 10334 49 5928 49 5927 49 5928 49 6722 49 6722 49 5928 49 6302 49 6722 49 6302 49 6720 49 6720 49 6302 49 5930 49 6720 49 5930 49 5929 49 5929 49 5930 49 5931 49 5929 49 5931 49 6613 49 6613 49 5931 49 5932 49 6613 49 5932 49 5934 49 5934 49 5932 49 5933 49 5934 49 5933 49 6665 49 6665 49 5933 49 6337 49 6665 49 6337 49 6671 49 6671 49 6337 49 5935 49 6671 49 5935 49 5939 49 5939 49 5935 49 10328 49 5936 4889 5940 4889 6188 4889 6188 4890 5940 4890 5937 4890 6188 4891 5937 4891 6187 4891 6187 4892 5937 4892 5938 4892 6187 4893 5938 4893 10328 4893 10328 4894 5938 4894 5939 4894 5940 21 5936 21 6549 21 6549 21 5936 21 6191 21 6549 21 6191 21 5941 21 5941 21 6191 21 5942 21 5941 4895 5942 4895 6442 4895 6442 4896 5942 4896 5943 4896 6442 4897 5943 4897 6548 4897 6548 4898 5943 4898 6054 4898 6548 4899 6054 4899 5944 4899 5944 4900 6054 4900 5946 4900 5944 4901 5946 4901 5945 4901 5945 4902 5946 4902 6194 4902 6680 4903 5945 4903 5947 4903 5947 4904 5945 4904 6194 4904 5948 4905 5956 4905 6195 4905 6195 4906 5956 4906 6689 4906 6195 4907 6689 4907 5949 4907 5949 4908 6689 4908 5950 4908 5949 4909 5950 4909 6192 4909 6192 4910 5950 4910 5951 4910 6192 4911 5951 4911 5947 4911 5947 4912 5951 4912 6680 4912 5952 4913 6390 4913 5953 4913 5952 4914 5953 4914 5954 4914 5954 4915 5953 4915 5955 4915 5954 4916 5955 4916 6015 4916 6015 4917 5955 4917 5956 4917 6015 4918 5956 4918 5948 4918 6390 4919 5952 4919 5957 4919 5957 4920 5952 4920 6013 4920 5957 4921 6013 4921 6391 4921 6391 4921 6013 4921 6012 4921 6391 4922 6012 4922 5958 4922 5958 4922 6012 4922 5959 4922 5958 4923 5959 4923 6393 4923 6393 4923 5959 4923 5961 4923 6393 4924 5961 4924 5960 4924 5960 4925 5961 4925 6196 4925 5960 4926 6196 4926 5964 4926 5964 4927 6196 4927 5962 4927 5962 4928 5963 4928 5964 4928 5964 4929 5963 4929 5965 4929 5965 21 5963 21 5966 21 5966 21 5963 21 5967 21 5966 21 5967 21 5968 21 5968 21 5967 21 6367 21 5968 21 6367 21 5969 21 5969 21 6367 21 5970 21 5969 21 5970 21 6572 21 6572 21 5970 21 5874 21 5971 6 5972 6 6583 6 6583 6 5972 6 6207 6 6583 6 6207 6 6587 6 6587 6 6207 6 6208 6 6587 6 6208 6 5973 6 5973 6 6208 6 5974 6 5975 21 5976 21 5977 21 5977 21 5976 21 6598 21 5977 21 6598 21 6294 21 6294 21 6598 21 6599 21 6294 21 6599 21 6213 21 6213 21 6599 21 6601 21 5989 1821 6695 1821 6326 1821 6326 4930 6695 4930 6698 4930 6326 4931 6698 4931 6327 4931 6327 1825 6698 1825 6694 1825 6327 1826 6694 1826 5979 1826 5979 4932 6694 4932 5978 4932 5979 4933 5978 4933 5980 4933 5980 4934 5978 4934 5981 4934 5980 4935 5981 4935 5982 4935 5982 4936 5981 4936 6688 4936 5982 4937 6688 4937 5983 4937 5983 4938 6688 4938 6687 4938 5983 4939 6687 4939 5984 4939 5984 4940 6687 4940 5985 4940 5984 4941 5985 4941 6332 4941 6332 4942 5985 4942 6686 4942 6332 4943 6686 4943 6324 4943 6324 4944 6686 4944 6697 4944 6324 4945 6697 4945 5987 4945 5987 4946 6697 4946 5986 4946 5987 4947 5986 4947 5988 4947 5988 1818 5986 1818 6696 1818 5988 1819 6696 1819 5989 1819 5989 1820 6696 1820 6695 1820 6000 4948 6001 4948 5990 4948 5990 4949 6001 4949 6672 4949 5990 4950 6672 4950 5991 4950 5991 4951 6672 4951 5992 4951 5991 4952 5992 4952 6315 4952 6315 4953 5992 4953 5993 4953 6315 4954 5993 4954 5994 4954 5994 4955 5993 4955 6683 4955 5994 4956 6683 4956 6313 4956 6313 4957 6683 4957 6682 4957 6313 4958 6682 4958 6314 4958 6314 4938 6682 4938 6677 4938 6314 4939 6677 4939 5995 4939 5995 4940 6677 4940 6676 4940 5995 4941 6676 4941 5996 4941 5996 4959 6676 4959 6674 4959 5996 4960 6674 4960 6320 4960 6320 4961 6674 4961 5997 4961 6320 4962 5997 4962 6323 4962 6323 4963 5997 4963 5998 4963 6323 4964 5998 4964 5999 4964 5999 4965 5998 4965 6673 4965 5999 4966 6673 4966 6000 4966 6000 4967 6673 4967 6001 4967 6002 960 6253 960 6278 960 10328 960 5935 960 6049 960 5880 960 6030 960 5879 960 5882 960 5878 960 5876 960 6123 960 6003 960 6121 960 5820 960 6004 960 5818 960 5814 4968 6040 4968 6041 4968 6033 960 6005 960 6037 960 6021 960 6157 960 6158 960 5798 960 6360 960 6006 960 5798 960 6006 960 6365 960 6007 960 5787 960 6364 960 6364 4969 5787 4969 6366 4969 6008 960 5782 960 6007 960 6007 960 5782 960 5786 960 6007 4970 5786 4970 5787 4970 6196 960 5961 960 6008 960 6008 4971 5961 4971 5959 4971 6008 4972 5959 4972 6009 4972 6009 960 5959 960 6010 960 5777 960 6011 960 6014 960 5777 960 6014 960 5776 960 5959 960 6012 960 6010 960 6010 4973 6012 4973 6013 4973 6010 4974 6013 4974 5780 4974 5780 960 6013 960 5952 960 5780 960 5952 960 5778 960 5778 960 5952 960 6011 960 5948 960 6014 960 6015 960 6015 4975 6014 4975 6011 4975 6015 960 6011 960 5954 960 5954 4976 6011 4976 5952 4976 5791 960 6333 960 6106 960 6016 960 6017 960 6014 960 6014 4977 6017 4977 6018 4977 6014 4978 6018 4978 5776 4978 6359 960 5797 960 6339 960 6339 960 5797 960 5793 960 5789 960 6019 960 5788 960 5788 960 6019 960 6339 960 5788 960 6339 960 6020 960 6020 4979 6339 4979 5793 4979 6021 960 6158 960 6310 960 6310 4980 5893 4980 6022 4980 6022 960 5893 960 6024 960 6022 4981 6024 4981 6023 4981 6023 960 6024 960 6025 960 5879 960 6030 960 6029 960 6025 960 6024 960 6026 960 6026 960 6024 960 5896 960 6026 960 5896 960 6027 960 6027 4982 5896 4982 5885 4982 6027 960 5885 960 6028 960 6028 1648 5885 1648 5888 1648 6028 960 5888 960 5803 960 5803 1653 5888 1653 6029 1653 5803 4983 6029 4983 5802 4983 5802 960 6029 960 6030 960 5802 960 6030 960 6031 960 6031 960 6030 960 5880 960 6031 4984 5880 4984 6032 4984 6166 960 6167 960 6032 960 6032 4985 6167 4985 5800 4985 6032 4986 5800 4986 6031 4986 6033 960 6037 960 6034 960 6362 4987 6035 4987 6363 4987 6363 4988 6035 4988 6036 4988 6363 960 6036 960 6037 960 6037 960 6036 960 6038 960 6037 4989 6038 4989 6034 4989 5807 960 6358 960 5805 960 5805 960 6358 960 6341 960 5805 960 6341 960 6039 960 6040 960 5813 960 6041 960 6041 960 5813 960 6042 960 6041 960 6042 960 6341 960 6341 960 6042 960 6043 960 6341 1647 6043 1647 6039 1647 6044 960 6340 960 6153 960 6153 960 6340 960 6045 960 6185 960 6046 960 6186 960 6186 4990 6046 4990 10370 4990 6052 4991 10640 4991 6047 4991 6047 4992 10640 4992 10641 4992 6047 960 10641 960 6193 960 10641 960 10642 960 6193 960 6193 1692 10642 1692 6048 1692 6193 4993 6048 4993 6049 4993 6049 4994 6048 4994 6050 4994 6049 1690 6050 1690 10644 1690 5943 4995 6190 4995 6053 4995 10370 960 10639 960 6186 960 6186 4996 10639 4996 6051 4996 6186 960 6051 960 6189 960 6052 960 6047 960 6053 960 6053 960 6047 960 6054 960 6053 4997 6054 4997 5943 4997 6055 960 5831 960 6169 960 6169 4998 5831 4998 5832 4998 6059 4999 6056 4999 5826 4999 6169 5000 6172 5000 6055 5000 6055 960 6172 960 5913 960 6055 960 5913 960 5829 960 5829 5001 5913 5001 6057 5001 5829 960 6057 960 6058 960 6058 960 6057 960 5908 960 6058 960 5908 960 5826 960 5826 5002 5908 5002 5910 5002 5826 960 5910 960 6059 960 6060 960 6061 960 6062 960 6062 5003 6061 5003 6260 5003 6062 5004 6260 5004 6063 5004 6059 960 5906 960 6056 960 6056 960 5906 960 6061 960 6056 960 6061 960 5824 960 5824 960 6061 960 6060 960 6064 960 6065 960 6274 960 6274 5005 6065 5005 6066 5005 6274 960 6066 960 6260 960 6260 960 6066 960 6067 960 6260 5006 6067 5006 6063 5006 6069 960 6068 960 6285 960 6069 960 6285 960 6276 960 5818 960 6004 960 6070 960 6070 960 6004 960 6281 960 6070 1798 6281 1798 6071 1798 6268 1622 6079 1622 6072 1622 6073 5007 6076 5007 6263 5007 6073 960 6263 960 6074 960 6074 960 6263 960 5905 960 6074 5008 5905 5008 6075 5008 6076 960 6077 960 6263 960 6263 5009 6077 5009 6078 5009 6263 960 6078 960 6268 960 6268 960 6078 960 5847 960 6268 5010 5847 5010 6079 5010 5899 960 6080 960 5900 960 5900 1613 6080 1613 6088 1613 6075 5011 5905 5011 6081 5011 6081 960 5905 960 5903 960 6081 960 5903 960 6082 960 6082 960 5903 960 6083 960 6082 960 6083 960 6084 960 6084 5012 6083 5012 6085 5012 6084 5013 6085 5013 6086 5013 6086 960 6085 960 6087 960 6086 960 6087 960 6088 960 6088 5014 6087 5014 6089 5014 6088 5015 6089 5015 5900 5015 6090 5016 6091 5016 5889 5016 5889 5017 6091 5017 6093 5017 5889 960 6093 960 6092 960 6092 960 6093 960 6094 960 6092 960 6094 960 5899 960 5899 5018 6094 5018 6095 5018 5899 1614 6095 1614 6080 1614 6090 5019 5889 5019 6096 5019 6096 960 5889 960 5890 960 6096 5020 5890 5020 6097 5020 6098 960 6104 960 6105 960 6105 960 5844 960 6098 960 6098 5021 5844 5021 5841 5021 6098 960 5841 960 6286 960 6286 960 5841 960 6099 960 6286 960 6099 960 6312 960 6100 960 6101 960 6102 960 6102 960 6101 960 6103 960 6102 960 6103 960 6104 960 6104 5022 6103 5022 5845 5022 6104 5023 5845 5023 6105 5023 6325 960 6307 960 6106 960 6106 5024 6307 5024 6113 5024 6106 960 6113 960 6107 960 6108 5025 6109 5025 6306 5025 6306 5026 6109 5026 6110 5026 6308 960 6111 960 6307 960 6307 5027 6111 5027 6112 5027 6307 5028 6112 5028 6113 5028 6121 960 6003 960 6114 960 6114 5029 6003 5029 6115 5029 6114 5030 6115 5030 6283 5030 6248 5031 6283 5031 6249 5031 6107 960 6116 960 6106 960 6106 5032 6116 5032 6117 5032 6106 960 6117 960 6139 960 6139 1678 6117 1678 6118 1678 6118 960 6119 960 6139 960 6139 1667 6119 1667 6120 1667 6139 960 6120 960 6121 960 6121 1666 6120 1666 6122 1666 6121 960 6122 960 6123 960 5857 960 6124 960 6284 960 6284 960 6124 960 6114 960 6125 960 5851 960 6282 960 6282 960 5851 960 6126 960 6282 960 6126 960 6128 960 6126 960 6127 960 6128 960 6128 960 6127 960 5852 960 6128 960 5852 960 6268 960 6268 5033 5852 5033 6129 5033 6268 960 6129 960 6274 960 6274 5034 6129 5034 6130 5034 6274 960 6130 960 6131 960 6131 1802 6130 1802 6132 1802 6131 960 6132 960 6280 960 6280 960 6132 960 5856 960 6280 960 5856 960 5857 960 6133 960 6125 960 6098 960 6289 960 6045 960 5848 960 6134 5035 6135 5035 6342 5035 6342 960 6135 960 6136 960 6342 960 6136 960 6340 960 6340 5036 6136 5036 6137 5036 6340 960 6137 960 6045 960 6045 5037 6137 5037 5872 5037 6045 5038 5872 5038 5848 5038 5868 960 6341 960 6339 960 5868 960 6339 960 6338 960 6124 5039 5858 5039 6114 5039 6114 5040 5858 5040 6138 5040 6114 960 6138 960 6121 960 6121 1676 6138 1676 5861 1676 6121 960 5861 960 6139 960 6139 1675 5861 1675 5863 1675 6139 960 5863 960 6106 960 6106 5041 5863 5041 5864 5041 6106 960 5864 960 6140 960 6140 960 5864 960 6141 960 6140 960 6141 960 5866 960 6288 960 6150 960 6289 960 6289 1665 6150 1665 6142 1665 6142 5042 6143 5042 6289 5042 6289 960 6143 960 6144 960 6289 960 6144 960 6045 960 6045 960 6144 960 6145 960 6165 960 6146 960 6163 960 6163 5043 6146 5043 6147 5043 6163 960 6147 960 6287 960 6287 5044 6147 5044 6148 5044 6287 960 6148 960 6288 960 6288 5030 6148 5030 6149 5030 6288 5045 6149 5045 6150 5045 6145 5046 6151 5046 6045 5046 6045 1678 6151 1678 6152 1678 6045 5047 6152 5047 6153 5047 6153 960 6152 960 6154 960 6153 960 6154 960 6156 960 6156 960 6154 960 6155 960 6156 960 6155 960 6157 960 6157 5048 6155 5048 6159 5048 6157 960 6159 960 6158 960 6158 5049 6159 5049 6160 5049 6160 960 6161 960 6158 960 6158 5050 6161 5050 6162 5050 6158 960 6162 960 6163 960 6163 960 6162 960 6164 960 6163 5051 6164 5051 6165 5051 5882 960 6037 960 6166 960 6166 960 6037 960 6005 960 6166 5052 6005 5052 6167 5052 6173 960 5917 960 6168 960 6168 960 5917 960 6170 960 6168 960 6170 960 6169 960 6169 960 6170 960 6171 960 6169 5053 6171 5053 6172 5053 6176 960 5914 960 6173 960 6173 960 5914 960 5915 960 6173 960 5915 960 5917 960 6174 960 10629 960 6177 960 6175 960 5922 960 6176 960 6176 960 5922 960 5919 960 6176 1702 5919 1702 5914 1702 5921 960 6182 960 6177 960 6177 5054 6182 5054 6178 5054 6177 5055 6178 5055 6174 5055 10629 960 6179 960 6183 960 6175 960 10630 960 5922 960 5922 5056 10630 5056 6180 5056 5922 5057 6180 5057 5921 5057 5921 960 6180 960 6181 960 5921 5058 6181 5058 6182 5058 6179 960 10632 960 6183 960 6183 1630 10632 1630 10631 1630 6183 960 10631 960 6176 960 6176 5059 10631 5059 6184 5059 6176 1627 6184 1627 6175 1627 6183 960 5928 960 10334 960 10629 960 6183 960 6177 960 6177 960 6183 960 10334 960 6177 960 10334 960 5926 960 10328 960 6049 960 6187 960 10644 5060 6185 5060 6049 5060 6049 960 6185 960 6186 960 6049 960 6186 960 6187 960 6187 960 6186 960 6189 960 6187 5061 6189 5061 6188 5061 6188 960 6189 960 6191 960 6188 960 6191 960 5936 960 6051 5062 6190 5062 6189 5062 6189 5063 6190 5063 5943 5063 6189 960 5943 960 6191 960 6191 5064 5943 5064 5942 5064 6192 960 5947 960 6193 960 6193 1687 5947 1687 6194 1687 6193 960 6194 960 6047 960 6047 5065 6194 5065 5946 5065 6047 960 5946 960 6054 960 5948 960 6195 960 6014 960 6014 960 6195 960 5949 960 6014 960 5949 960 6335 960 6335 960 5949 960 6192 960 6335 960 6192 960 6336 960 6336 960 6192 960 6193 960 6008 960 6007 960 6196 960 6196 5066 6007 5066 5963 5066 6196 5067 5963 5067 5962 5067 5975 5068 5977 5068 6197 5068 6197 960 5977 960 6299 960 6197 960 6299 960 6198 960 6198 1779 6299 1779 6298 1779 6309 960 6199 960 6330 960 6330 1710 6199 1710 6200 1710 6330 960 6200 960 6297 960 5972 5069 6201 5069 6202 5069 6201 960 6203 960 6202 960 6202 5070 6203 5070 6204 5070 6202 960 6204 960 6316 960 6316 5071 6204 5071 6205 5071 6316 960 6205 960 6206 960 5972 960 6202 960 6207 960 6207 960 6202 960 6318 960 6207 960 6318 960 6208 960 6209 5072 6291 5072 6210 5072 6210 5073 6211 5073 6209 5073 6209 5074 6211 5074 6212 5074 6209 960 6212 960 6214 960 6295 960 6294 960 6213 960 6212 960 6215 960 6214 960 6214 960 6215 960 6216 960 6214 5075 6216 5075 6217 5075 6217 5076 6216 5076 6219 5076 6217 960 6219 960 6218 960 6218 5077 6219 5077 6220 5077 5974 960 6208 960 6221 960 6221 960 6208 960 6318 960 6221 960 6318 960 6222 960 6222 5078 6318 5078 6227 5078 6293 1724 6223 1724 5932 1724 5932 5079 6223 5079 6224 5079 5932 960 6224 960 5933 960 5933 5080 6224 5080 6225 5080 5933 5081 6225 5081 6226 5081 6220 5082 6227 5082 6218 5082 6218 5083 6227 5084 6318 5085 6218 960 6318 960 6228 960 6228 1772 6318 1772 5933 1772 6228 1712 5933 1712 6229 1712 6229 960 5933 960 6226 960 6213 960 6230 960 6295 960 6295 5086 6230 5086 6231 5086 6295 960 6231 960 6291 960 6236 5087 6285 5087 6242 5087 6242 960 6285 960 6241 960 6234 960 6232 960 6233 960 6233 5088 6232 5088 6243 5088 6233 960 6257 960 6234 960 6234 5089 6257 1789 6285 5090 6234 960 6285 960 6235 960 6235 960 6285 960 6236 960 6237 960 6238 960 6248 960 6248 5091 6238 5091 6239 5091 6248 960 6239 960 6241 960 6241 5092 6239 5092 6240 5092 6241 5093 6240 5093 6242 5093 6243 960 6244 960 6233 960 6233 5094 6244 5094 6245 5094 6233 960 6245 960 6254 960 6254 5095 6245 5095 6246 5095 6254 5096 6246 5096 6247 5096 6247 960 6237 960 6254 960 6254 5097 6237 5097 6248 5097 6254 960 6248 960 6306 960 6306 960 6248 960 6249 960 6306 5098 6249 5098 6108 5098 6253 960 6374 960 6278 960 6278 5099 6374 5099 6250 5099 6278 5100 6250 5100 6251 5100 6370 960 6252 960 6257 960 6257 5101 6252 5101 6371 5101 6257 5102 6371 5102 6253 5102 6253 5103 6371 5103 6372 5103 6253 5104 6372 5104 6374 5104 6304 5105 6279 5105 6303 5105 6305 5106 6377 5106 6254 5106 6254 5107 6377 5107 6255 5107 6254 960 6255 960 6233 960 6233 5108 6255 5108 6256 5108 6233 960 6256 960 6257 960 6257 5109 6256 5109 6379 5109 6257 1782 6379 1782 6370 1782 6258 960 6260 960 6259 960 6259 960 6260 960 6263 960 6259 5110 6263 5110 6265 5110 6271 5111 6261 5111 6268 5111 6268 960 6261 960 6262 960 6268 960 6262 960 6263 960 6263 5112 6262 5112 6264 5112 6263 5113 6264 5113 6265 5113 6266 960 6267 960 6274 960 6274 1809 6267 1809 6269 1809 6274 960 6269 960 6268 960 6268 1808 6269 1808 6270 1808 6268 5114 6270 5114 6271 5114 6258 960 6272 960 6260 960 6260 960 6272 960 6273 960 6260 960 6273 960 6274 960 6274 960 6273 960 6275 960 6274 960 6275 960 6266 960 5832 5115 6276 5115 6169 5115 6169 960 6276 960 6285 960 6169 960 6285 960 6168 960 6168 960 6285 960 6257 960 6168 960 6257 960 6173 960 6173 960 6257 960 6253 960 6173 960 6253 960 6176 960 6176 960 6253 960 6002 960 6176 960 6002 960 6183 960 5928 960 6183 960 6331 960 6331 960 6183 960 6002 960 6331 960 6002 960 6277 960 6277 960 6002 960 6278 960 6277 960 6278 960 6304 960 6304 960 6278 960 6251 960 6304 5116 6251 5116 6279 5116 5857 960 6284 960 6280 960 6280 960 6284 960 6281 960 6280 960 6281 960 6131 960 6131 960 6281 960 6004 960 6131 960 6004 960 6274 960 6274 960 6004 960 5820 960 6274 960 5820 960 6064 960 6125 5117 6282 5117 6098 5117 6098 960 6282 960 6128 960 6098 960 6128 960 6104 960 6104 960 6128 960 6268 960 6104 960 6268 960 6102 960 6102 960 6268 960 6072 960 6102 960 6072 960 6100 960 6283 960 6248 960 6114 960 6114 960 6248 960 6241 960 6114 960 6241 960 6284 960 6284 960 6241 960 6285 960 6284 960 6285 960 6281 960 6281 5118 6285 5119 6068 5120 6281 960 6068 960 6071 960 6286 960 6287 960 6098 960 6098 960 6287 960 6288 960 6098 960 6288 960 6133 960 6133 960 6288 960 6289 960 6133 960 6289 960 6290 960 6290 960 6289 960 5848 960 6209 960 6292 960 6291 960 6291 5121 6292 5121 6293 5121 6291 960 6293 960 6295 960 6295 1723 6293 1723 5932 1723 6295 960 5932 960 5931 960 5977 960 6294 960 6299 960 6299 960 6294 960 6295 960 6299 960 6295 960 6296 960 6296 960 6295 960 5931 960 6296 960 5931 960 5930 960 6297 960 6298 960 6330 960 6330 5122 6298 5122 6299 5122 6330 960 6299 960 6300 960 6300 960 6299 960 6296 960 6300 960 6296 960 6301 960 6301 960 6296 960 5930 960 6301 960 5930 960 6302 960 6303 960 6305 960 6304 960 6304 960 6305 960 6254 960 6304 960 6254 960 6329 960 6329 960 6254 960 6306 960 6329 960 6306 960 6307 960 6307 960 6306 960 6110 960 6307 960 6110 960 6308 960 6206 960 6309 960 6316 960 6316 960 6309 960 6330 960 6316 960 6330 960 6328 960 6310 5123 6158 5123 5893 5123 5893 960 6158 960 6163 960 5893 960 6163 960 6311 960 6311 960 6163 960 6287 960 6311 960 6287 960 5891 960 5891 960 6287 960 6286 960 5891 960 6286 960 5890 960 5890 960 6286 960 6312 960 5890 5124 6312 5124 6097 5124 6321 5125 5995 5125 5996 5125 5991 960 6328 960 5990 960 5990 960 6328 960 6322 960 5990 960 6322 960 6000 960 5994 960 6313 960 6321 960 6321 5126 6313 5126 6314 5126 6321 5127 6314 5127 5995 5127 5991 960 6315 960 6328 960 6328 5128 6315 5128 5994 5128 6328 5129 5994 5129 6316 5129 6316 960 5994 960 6321 960 6316 960 6321 960 6202 960 6202 960 6321 960 6317 960 6202 960 6317 960 6318 960 6318 960 6317 960 6319 960 6318 960 6319 960 5933 960 5933 960 6319 960 6337 960 5996 960 6320 960 6321 960 6321 5130 6320 5130 6323 5130 6321 960 6323 960 6322 960 6322 1744 6323 1744 5999 1744 6322 5131 5999 5131 6000 5131 5988 960 6325 960 5987 960 5987 5132 6325 1733 6322 5133 5987 960 6322 960 6324 960 6324 960 6322 960 6332 960 5988 960 5989 960 6325 960 6325 5134 5989 5134 6326 5134 6325 960 6326 960 6307 960 6307 5135 6326 5135 6327 5135 6307 5136 6327 5136 5979 5136 5979 960 5980 960 6307 960 6307 5137 5980 5137 6328 5137 6307 960 6328 960 6329 960 6329 960 6328 960 6330 960 6329 960 6330 960 6304 960 6304 960 6330 960 6300 960 6304 960 6300 960 6277 960 6277 960 6300 960 6301 960 6277 960 6301 960 6331 960 6331 960 6301 960 6302 960 6331 960 6302 960 5928 960 5980 960 5982 960 6328 960 6328 5138 5982 5138 5983 5138 6328 960 5983 960 6322 960 6322 5139 5983 5139 5984 5139 6322 5140 5984 5140 6332 5140 6333 1642 6334 1642 6106 1642 6106 960 6334 960 6016 960 6106 5141 6016 5142 6325 5143 6325 960 6016 960 6014 960 6325 960 6014 960 6322 960 6322 960 6014 960 6335 960 6322 960 6335 960 6321 960 6321 960 6335 960 6336 960 6321 960 6336 960 6317 960 6317 960 6336 960 6193 960 6317 960 6193 960 6319 960 6319 960 6193 960 6049 960 6319 960 6049 960 6337 960 6337 960 6049 960 5935 960 5866 1668 6338 1668 6140 1668 6140 960 6338 960 6339 960 6140 960 6339 960 6106 960 6106 960 6339 960 6019 960 6106 960 6019 960 5791 960 5791 960 6019 960 5789 960 6044 5144 5814 5144 6340 5144 6340 960 5814 960 6041 960 6340 960 6041 960 6342 960 6342 960 6041 960 6341 960 6342 960 6341 960 6134 960 6134 960 6341 960 5868 960 6341 1759 6343 1759 6344 1759 6343 960 6341 960 6345 960 6345 960 6341 960 6358 960 6345 5145 6358 5145 6351 5145 6352 960 6339 960 6346 960 6346 960 6339 960 6341 960 6346 1757 6341 1757 6347 1757 6347 1758 6341 1758 6344 1758 6356 960 6348 960 6359 960 6359 5146 6348 5146 6349 5146 6359 960 6349 960 6358 960 6358 5147 6349 5147 6350 5147 6358 5148 6350 5148 6351 5148 6352 960 6353 960 6339 960 6339 960 6353 960 6354 960 6339 960 6354 960 6359 960 6359 960 6354 960 6355 960 6359 960 6355 960 6356 960 5807 960 6361 960 6358 960 6358 960 6361 960 6357 960 6358 960 6357 960 6359 960 6359 960 6357 960 6006 960 6359 960 6006 960 5797 960 5797 960 6006 960 6360 960 6361 960 6362 960 6357 960 6357 960 6362 960 6363 960 6357 960 6363 960 6006 960 6006 960 6363 960 6364 960 6006 960 6364 960 6365 960 6365 960 6364 960 6366 960 5882 960 5876 960 6037 960 6037 960 5876 960 5874 960 6037 960 5874 960 6363 960 6363 960 5874 960 5970 960 6363 960 5970 960 6364 960 6364 960 5970 960 6367 960 6364 960 6367 960 6007 960 6007 960 6367 960 5967 960 6007 960 5967 960 5963 960 6379 5149 6368 5149 6369 5149 6379 5150 6369 5150 6370 5150 6370 5151 6369 5151 6635 5151 6370 5152 6635 5152 6252 5152 6252 5153 6635 5153 6634 5153 6252 4954 6634 4954 6371 4954 6371 4955 6634 4955 6373 4955 6371 5154 6373 5154 6372 5154 6372 1594 6373 1594 6633 1594 6372 1595 6633 1595 6374 1595 6374 1596 6633 1596 6375 1596 6374 1573 6375 1573 6250 1573 6250 5155 6375 5155 6251 5155 6251 5156 6375 5156 6376 5156 6251 5157 6376 5157 6279 5157 6376 5157 6708 5157 6279 5157 6279 1576 6708 1576 6707 1576 6279 1577 6707 1577 6303 1577 6303 5158 6707 5158 6640 5158 6303 4962 6640 4962 6305 4962 6305 4963 6640 4963 6638 4963 6305 5159 6638 5159 6377 5159 6377 5160 6638 5160 6378 5160 6368 5161 6379 5161 6636 5161 6636 5162 6379 5162 6256 5162 6636 5163 6256 5163 6378 5163 6378 5163 6256 5163 6255 5163 6378 5164 6255 5164 6377 5164 6380 5165 6381 5165 6453 5165 6382 590 6691 590 6693 590 6708 590 6376 590 6383 590 6384 590 5927 590 6557 590 6539 590 6528 590 6385 590 6516 590 6734 590 6736 590 6386 590 5781 590 6573 590 6690 1877 6387 1877 6388 1877 6689 590 5956 590 6690 590 6690 5166 5956 5166 5955 5166 6690 590 5955 590 6387 590 6387 590 5955 590 5953 590 6387 5167 5953 5167 6389 5167 6389 590 5953 590 6390 590 6389 590 6390 590 5779 590 5779 590 6390 590 5784 590 6390 590 5957 590 5784 590 5784 5168 5957 5168 6391 5168 5784 590 6391 590 6392 590 6392 5169 6391 5169 5958 5169 6392 5170 5958 5170 5783 5170 5783 5171 5958 5171 6393 5171 5783 5172 6393 5172 5960 5172 6400 590 6394 590 6647 590 6647 590 6394 590 6395 590 6647 590 6395 590 6641 590 6395 590 6396 590 6641 590 6641 5173 6396 5173 6397 5173 6641 590 6397 590 6573 590 6573 5174 6397 5174 5785 5174 6573 590 5785 590 6386 590 6661 590 5792 590 6398 590 6398 590 5792 590 5790 590 6398 590 5790 590 6644 590 6644 590 5790 590 5795 590 5795 5175 5794 5175 6644 5175 6644 1872 5794 1872 6399 1872 6644 590 6399 590 6400 590 6400 590 6399 590 5796 590 6400 590 5796 590 6394 590 6401 590 6508 590 6402 590 6402 590 6508 590 6692 590 6388 590 5775 590 6690 590 6690 590 5775 590 6403 590 6690 590 6403 590 6692 590 6692 5176 6403 5176 6404 5176 6692 5177 6404 5177 6402 5177 5799 590 6405 590 6569 590 6569 590 6405 590 6406 590 6406 590 6407 590 6569 590 6569 5178 6407 5178 6408 5178 6569 590 6408 590 6571 590 6408 590 6409 590 6571 590 6571 5179 6409 5179 6410 5179 6571 590 6410 590 6648 590 6648 5180 6410 5180 5808 5180 5883 590 5881 590 6411 590 6411 5181 5881 5181 6412 5181 6412 5182 5881 5182 6413 5182 6412 590 6413 590 5801 590 5881 590 6414 590 6413 590 6413 590 6414 590 6415 590 6413 590 6415 590 5801 590 5801 590 6415 590 5884 590 5801 5183 5884 5183 5804 5183 5804 590 5884 590 6416 590 5804 590 6416 590 6417 590 6417 1887 6416 1887 5887 1887 6417 590 5887 590 6418 590 6418 590 5887 590 6419 590 6419 5184 5887 5184 5886 5184 6419 590 5886 590 6420 590 6420 590 5886 590 5895 590 6420 590 5895 590 5810 590 6716 590 5816 590 5817 590 5894 590 5809 590 5895 590 5895 5185 5809 5185 6421 5185 5895 5186 6421 5186 5810 5186 6534 590 6422 590 6423 590 6423 590 6422 590 6424 590 6423 590 6424 590 6425 590 6425 590 6424 590 5812 590 6430 590 5806 590 6663 590 5806 590 6426 590 6663 590 6663 5187 6426 5187 6427 5187 6663 590 6427 590 6662 590 6662 590 6427 590 6428 590 6662 590 6428 590 5811 590 5808 590 6429 590 6648 590 6648 590 6429 590 6430 590 6648 590 6430 590 6656 590 6656 590 6430 590 6663 590 6433 5188 6678 5188 6669 5188 6431 5189 6432 5189 6550 5189 6433 5190 6669 5190 6432 5190 6434 5191 6435 5191 6681 5191 6681 1922 6435 1922 6436 1922 6681 590 6436 590 6437 590 6437 5192 6436 5192 6438 5192 6437 5193 6438 5193 6439 5193 6439 5194 6440 5194 6437 5194 6437 590 6440 590 6441 590 6437 590 6441 590 6442 590 6442 5195 6441 5195 6444 5195 6442 590 6444 590 6443 590 6443 5196 6444 5196 6445 5196 6443 590 6445 590 6550 590 6550 590 6445 590 6446 590 6550 5197 6446 5197 6431 5197 5827 590 6447 590 6448 590 6448 590 6447 590 6449 590 6448 5198 6449 5198 6450 5198 6450 5199 6449 5199 6451 5199 6450 5200 6451 5200 5823 5200 5822 590 6452 590 6453 590 6453 1849 6452 1849 5821 1849 6453 5201 5821 5201 6454 5201 5830 590 6459 590 6567 590 5830 590 6567 590 6455 590 6459 5202 5828 5202 6456 5202 6456 1838 5828 1838 5825 1838 6456 5203 5825 5203 5907 5203 5907 590 5825 590 6457 590 6458 590 6567 590 5911 590 5911 590 6567 590 6459 590 5911 590 6459 590 5912 590 5912 590 6459 590 6456 590 6448 590 6460 590 5827 590 5827 5204 6460 5204 6461 5204 5827 590 6461 590 6457 590 6457 590 6461 590 5909 590 6457 590 5909 590 5907 590 6726 5205 5833 5205 6567 5205 6567 5206 5833 5206 5834 5206 6567 590 5834 590 6455 590 6454 590 6462 590 6731 590 6731 590 6462 590 6463 590 6731 590 6463 590 6733 590 6733 590 6463 590 5819 590 6469 5207 6464 5207 6470 5207 6470 5208 6464 5208 6465 5208 6470 590 6465 590 6466 590 6466 590 6465 590 6467 590 6466 5209 6467 5209 6712 5209 5904 590 6485 590 6468 590 6468 5210 6485 5210 5835 5210 6469 590 6470 590 6471 590 6471 590 6470 590 5898 590 6471 5211 5898 5211 5839 5211 5839 5212 5898 5212 6472 5212 5839 590 6472 590 5838 590 5838 5213 6472 5213 5897 5213 5838 590 5897 590 6473 590 6473 590 5897 590 6474 590 6473 5214 6474 5214 5837 5214 5837 590 6474 590 5901 590 5837 590 5901 590 5835 590 5835 590 5901 590 5902 590 5835 5215 5902 5215 6468 5215 6486 590 6475 590 6742 590 6476 590 6477 590 6747 590 6747 5216 6477 5216 6482 5216 6747 5217 6482 5217 6478 5217 6475 590 6479 590 6742 590 6742 5218 6479 5218 6480 5218 6742 590 6480 590 6747 590 6747 590 6480 590 6481 590 6747 5219 6481 5219 6476 5219 6482 590 6483 590 6478 590 6478 5220 6483 5220 5836 5220 6478 590 5836 590 5904 590 5904 590 5836 590 6484 590 5904 590 6484 590 6485 590 6486 590 6488 590 6487 590 6487 590 6488 590 5846 590 5846 590 6488 590 6489 590 6489 590 6488 590 6737 590 6489 590 6737 590 5842 590 5842 590 6737 590 5843 590 5843 590 6737 590 6738 590 5843 5221 6738 5221 6710 5221 6712 590 5840 590 6711 590 6711 590 5840 590 6490 590 6711 590 6490 590 6710 590 6491 590 6492 590 6627 590 6492 590 6493 590 6523 590 6523 5222 6493 5222 6524 5222 6700 590 6495 590 6494 590 6494 5223 6495 5223 6496 5223 6701 590 6498 590 6497 590 6497 5224 6498 5224 6499 5224 6497 5225 6499 5225 6500 5225 6501 590 6508 590 6502 590 6502 590 6508 590 6510 590 6502 590 6510 590 6503 590 6525 590 6504 590 6527 590 6527 1902 6504 1902 6505 1902 6527 590 6505 590 6510 590 6510 1901 6505 1901 6506 1901 6510 590 6506 590 6503 590 6660 5226 5867 5226 6507 5226 6507 590 5867 590 6509 590 6507 590 6509 590 6508 590 6508 5227 6509 5227 6526 5227 6508 590 6526 590 6510 590 5870 590 5869 590 6663 590 6663 590 5869 590 6644 590 6515 590 5849 590 6385 590 6385 1906 5849 1906 6511 1906 6385 590 6511 590 6422 590 6422 1905 6511 1905 5873 1905 6422 590 5873 590 6424 590 6424 5228 5873 5228 5871 5228 6424 590 5871 590 6512 590 6512 590 5871 590 6513 590 6512 590 6513 590 6664 590 6738 590 6514 590 6515 590 6515 5229 6514 5229 5850 5229 6515 5230 5850 5230 5849 5230 6734 590 6516 590 6732 590 6516 590 5855 590 6732 590 6732 590 5855 590 5854 590 6732 590 5854 590 6453 590 6453 5231 5854 5231 6517 5231 6453 590 6517 590 6742 590 6742 5232 6517 5232 5853 5232 6742 590 5853 590 6518 590 6518 590 5853 590 6519 590 6518 590 6519 590 6520 590 6520 590 6519 590 6521 590 6520 590 6521 590 6522 590 6735 590 6724 590 5859 590 5859 590 6724 590 6523 590 5859 590 6523 590 6527 590 6527 590 6523 590 6524 590 6527 1916 6524 1916 6525 1916 6526 590 5865 590 6510 590 6510 1914 5865 1914 5862 1914 6510 590 5862 590 6527 590 6527 1913 5862 1913 5860 1913 6527 5233 5860 5233 5859 5233 6385 590 6528 590 6515 590 6515 590 6528 590 6529 590 6515 590 6529 590 6530 590 6542 590 6531 590 5815 590 5815 5234 6531 5234 6532 5234 5815 590 6532 590 6534 590 6534 590 6532 590 6533 590 6534 590 6533 590 6422 590 6422 1912 6533 1912 6535 1912 6535 590 6536 590 6422 590 6422 1901 6536 1901 6537 1901 6422 590 6537 590 6385 590 6385 1902 6537 1902 6538 1902 6385 590 6538 590 6539 590 6714 590 6540 590 6715 590 6715 5235 6540 5235 6541 5235 5815 5236 5816 5236 6542 5236 6542 590 5816 590 6716 590 6542 590 6716 590 6543 590 6543 590 6716 590 6544 590 6541 590 6545 590 6715 590 6715 5237 6545 5237 6546 5237 6715 590 6546 590 6716 590 6716 590 6546 590 6547 590 6716 5238 6547 5238 6544 5238 6680 590 5951 590 6382 590 6382 590 5951 590 5950 590 6382 590 5950 590 6691 590 6691 590 5950 590 6689 590 6442 590 6548 590 6437 590 6437 590 6548 590 5944 590 6437 590 5944 590 6681 590 6681 590 5944 590 5945 590 5937 590 5940 590 6549 590 5941 590 6442 590 6549 590 6549 590 6442 590 6443 590 6549 590 6443 590 5937 590 5937 590 6443 590 6550 590 5937 590 6550 590 5938 590 6432 590 6669 590 6550 590 6550 590 6669 590 5939 590 6550 5239 5939 5239 5938 5239 6384 5240 6557 5240 6551 5240 6560 590 6552 590 6557 590 6551 590 6557 590 5925 590 5925 590 6557 590 6552 590 5925 5241 6552 5241 6553 5241 6553 5242 6554 5242 5925 5242 5925 5243 6554 5243 6563 5243 5925 590 6563 590 5923 590 6555 590 6556 590 6565 590 6565 1865 6556 1865 6558 1865 6565 5244 6558 5244 6557 5244 6557 5245 6558 5245 6559 5245 6557 5246 6559 5246 6560 5246 6564 5247 5924 5247 6561 5247 6561 5248 5924 5248 5923 5248 6561 590 5923 590 6562 590 6562 5249 5923 5249 6563 5249 5916 5250 5920 5250 6565 5250 6564 590 6555 590 5924 590 5924 590 6555 590 6565 590 5924 590 6565 590 6566 590 6566 1993 6565 1993 5920 1993 6458 590 6568 590 6567 590 6567 590 6568 590 5918 590 6567 590 5918 590 6729 590 6729 590 5918 590 5916 590 6729 590 5916 590 6730 590 6730 590 5916 590 6565 590 6411 590 5799 590 5883 590 5883 5251 5799 5251 6569 5251 5883 590 6569 590 6570 590 6570 590 6569 590 5877 590 5968 590 5969 590 6571 590 6571 590 5969 590 6572 590 6571 5252 6572 5252 6569 5252 6569 590 6572 590 5875 590 6569 590 5875 590 5877 590 5964 5253 6573 5253 5960 5253 5960 590 6573 590 5781 590 5960 590 5781 590 5783 590 5976 590 6576 590 6578 590 6575 590 6574 590 6684 590 6575 5254 6684 5254 6703 5254 6576 590 6577 590 6578 590 6578 5255 6577 5255 6579 5255 6578 5256 6579 5256 6705 5256 6579 5257 6580 5257 6705 5257 6705 5258 6580 5258 6581 5258 6705 5259 6581 5259 6582 5259 5971 590 6583 590 6584 590 6584 590 6583 590 6586 590 6584 590 6586 590 6585 590 6585 590 6586 590 6668 590 6587 590 5973 590 6594 590 6594 5260 5973 5260 6588 5260 6589 590 6613 590 6590 590 6590 590 6613 590 5934 590 6590 590 5934 590 6591 590 6591 590 5934 590 6667 590 6594 5261 6603 5261 6666 5261 6588 590 6592 590 6594 590 6594 5262 6592 5262 6593 5262 6594 590 6593 590 6603 590 6602 590 6597 590 6610 590 6596 5263 6600 5263 6595 5263 6596 590 6595 590 6597 590 5976 590 6578 590 6598 590 6598 590 6578 590 6595 590 6598 590 6595 590 6599 590 6599 590 6595 590 6600 590 6599 5264 6600 5264 6601 5264 6602 590 6610 590 6612 590 6593 590 6604 590 6603 590 6603 5265 6604 5265 6605 5265 6603 5266 6605 5266 6606 5266 6606 5267 6605 5267 6608 5267 6606 590 6608 590 6607 590 6607 590 6608 590 6609 590 6607 590 6609 590 6610 590 6610 5268 6609 5268 6611 5268 6610 5269 6611 5269 6612 5269 6589 590 6614 590 6613 590 6613 1987 6614 1987 6615 1987 6613 1986 6615 1986 6595 1986 6595 590 6615 590 6597 590 6597 5270 6615 5270 6616 5270 6597 5271 6616 5271 6610 5271 6723 590 6622 590 6617 590 6727 5272 6618 5272 6619 5272 6619 590 6620 590 6727 590 6727 2004 6620 2004 6621 2004 6727 2003 6621 2003 6622 2003 6622 2002 6621 2002 6623 2002 6622 2001 6623 2001 6617 2001 6617 5273 6624 5273 6723 5273 6723 5274 6624 5274 6625 5274 6723 590 6625 590 6627 590 6627 5275 6625 5275 6626 5275 6626 5276 6628 5276 6627 5276 6627 5277 6628 5277 6629 5277 6627 5278 6629 5278 6704 5278 6632 590 6637 590 6630 590 6630 590 6637 590 6704 590 6630 590 6704 590 6631 590 6631 590 6704 590 6629 590 6375 5279 6633 5279 6728 5279 6369 590 6637 590 6727 590 6727 590 6637 590 6632 590 6727 5280 6632 5280 6618 5280 6633 590 6373 590 6728 590 6728 5281 6373 5281 6634 5281 6728 590 6634 590 6727 590 6727 5282 6634 5282 6635 5282 6727 5283 6635 5283 6369 5283 6369 590 6368 590 6637 590 6637 5284 6368 5284 6636 5284 6637 590 6636 590 6704 590 6704 5285 6636 5285 6378 5285 6378 590 6638 590 6704 590 6704 5286 6638 5286 6640 5286 6704 590 6640 590 6639 590 6639 5287 6640 5287 6707 5287 5968 590 6641 590 5966 590 5966 590 6641 590 6573 590 5966 590 6573 590 5965 590 5965 590 6573 590 5964 590 6650 590 6642 590 6400 590 6400 5288 6642 5288 6643 5288 6400 590 6643 590 6644 590 6644 590 6643 590 6645 590 6644 2013 6645 2013 6651 2013 6659 590 6646 590 6656 590 6656 5289 6646 5289 6649 5289 5968 590 6571 590 6641 590 6641 590 6571 590 6648 590 6641 590 6648 590 6647 590 6647 590 6648 590 6656 590 6647 590 6656 590 6400 590 6400 590 6656 590 6649 590 6400 5290 6649 5290 6650 5290 6651 590 6652 590 6644 590 6644 2017 6652 2017 6653 2017 6644 590 6653 590 6663 590 6663 2016 6653 2016 6654 2016 6654 590 6655 590 6663 590 6663 2015 6655 2015 6657 2015 6663 590 6657 590 6656 590 6656 590 6657 590 6658 590 6656 5291 6658 5291 6659 5291 5869 5292 6660 5292 6644 5292 6644 590 6660 590 6507 590 6644 590 6507 590 6398 590 6398 590 6507 590 6508 590 6398 590 6508 590 6661 590 6661 590 6508 590 6401 590 5811 590 5812 590 6662 590 6662 590 5812 590 6424 590 6662 590 6424 590 6663 590 6663 590 6424 590 6512 590 6663 590 6512 590 5870 590 5870 5293 6512 5293 6664 5293 6665 590 6594 590 5934 590 5934 1951 6594 1951 6666 1951 5934 1950 6666 1950 6667 1950 6583 590 6587 590 6586 590 6586 590 6587 590 6594 590 6586 590 6594 590 6670 590 6670 590 6594 590 6665 590 6670 590 6665 590 6671 590 6574 5294 6668 5294 6684 5294 6684 5295 6668 5295 6586 5295 6684 590 6586 590 6679 590 6679 590 6586 590 6670 590 6679 590 6670 590 6669 590 6669 590 6670 590 6671 590 6669 590 6671 590 5939 590 6693 590 6685 590 6672 590 6672 590 6001 590 6693 590 6693 5296 6001 5296 6673 5296 6693 5297 6673 5297 5998 5297 5997 590 6674 590 6675 590 6675 5298 6674 5298 6676 5298 6675 5299 6676 5299 6677 5299 6678 5191 6434 5191 6669 5191 6669 590 6434 590 6681 590 6669 590 6681 590 6679 590 6679 590 6681 590 6675 590 6679 590 6675 590 6684 590 6684 590 6675 590 6677 590 6684 5300 6677 5300 6682 5300 5945 5301 6680 5301 6681 5301 6681 5302 6680 5302 6382 5302 6681 590 6382 590 6675 590 6675 590 6382 590 6693 590 6675 590 6693 590 5997 590 5997 590 6693 590 5998 590 6682 590 6683 590 6684 590 6684 5303 6683 5303 5993 5303 6684 590 5993 590 6685 590 6685 5304 5993 5304 5992 5304 6685 5305 5992 5305 6672 5305 6686 590 5985 590 6693 590 6693 5306 5985 5306 6687 5306 6693 590 6687 590 6685 590 6685 5307 6687 5307 6688 5307 6698 5308 6695 5308 6692 5308 6689 590 6690 590 6691 590 6691 590 6690 590 6692 590 6691 590 6692 590 6693 590 6693 1959 6692 1959 6697 1959 6693 1958 6697 1958 6686 1958 6688 590 5981 590 6685 590 6685 5309 5981 5309 5978 5309 6685 5310 5978 5310 6495 5310 6495 5311 5978 5311 6694 5311 6695 5312 6696 5312 6692 5312 6692 1961 6696 1961 5986 1961 6692 1960 5986 1960 6697 1960 6694 5313 6698 5313 6495 5313 6495 590 6698 590 6692 590 6495 590 6692 590 6496 590 6496 590 6692 590 6508 590 6496 590 6508 590 6699 590 6699 590 6508 590 6501 590 6700 590 6701 590 6495 590 6495 590 6701 590 6497 590 6495 590 6497 590 6685 590 6685 590 6497 590 6702 590 6685 590 6702 590 6684 590 6684 590 6702 590 6705 590 6684 590 6705 590 6703 590 6703 590 6705 590 6582 590 6500 5314 6491 5314 6497 5314 6497 590 6491 590 6627 590 6497 590 6627 590 6702 590 6702 590 6627 590 6704 590 6702 590 6704 590 6705 590 6705 590 6704 590 6639 590 6705 590 6639 590 6578 590 6578 590 6639 590 6706 590 6578 590 6706 590 6595 590 6595 590 6706 590 6709 590 6595 590 6709 590 6613 590 6613 590 6709 590 5929 590 6707 590 6708 590 6639 590 6639 590 6708 590 6383 590 6639 590 6383 590 6706 590 6706 590 6383 590 6717 590 6706 590 6717 590 6709 590 6709 590 6717 590 6719 590 6709 590 6719 590 5929 590 5929 590 6719 590 6720 590 6710 590 6738 590 6711 590 6711 590 6738 590 6515 590 6711 590 6515 590 6714 590 6714 5315 6515 5315 6530 5315 6714 5316 6530 5316 6540 5316 6712 590 6711 590 6466 590 6466 590 6711 590 6714 590 6466 590 6714 590 6713 590 6713 590 6714 590 6715 590 6713 590 6715 590 5892 590 5892 590 6715 590 6716 590 5892 590 6716 590 5894 590 5894 5317 6716 5317 5817 5317 5894 5318 5817 5318 5809 5318 6376 590 6375 590 6383 590 6383 590 6375 590 6728 590 6383 590 6728 590 6717 590 6717 590 6728 590 6718 590 6717 590 6718 590 6719 590 6719 590 6718 590 6721 590 6719 590 6721 590 6720 590 6720 590 6721 590 6722 590 6492 590 6523 590 6627 590 6627 590 6523 590 6724 590 6627 590 6724 590 6723 590 6723 590 6724 590 6733 590 6723 590 6733 590 6622 590 5819 590 6725 590 6733 590 6733 590 6725 590 6726 590 6733 5319 6726 5319 6622 5319 6622 590 6726 590 6567 590 6622 590 6567 590 6727 590 6727 590 6567 590 6729 590 6727 590 6729 590 6728 590 6728 590 6729 590 6730 590 6728 590 6730 590 6718 590 6718 590 6730 590 6565 590 6718 590 6565 590 6721 590 6721 590 6565 590 6557 590 6721 590 6557 590 6722 590 6722 590 6557 590 5927 590 6454 590 6731 590 6453 590 6453 590 6731 590 6733 590 6453 590 6733 590 6732 590 6732 590 6733 590 6724 590 6732 590 6724 590 6734 590 6734 590 6724 590 6735 590 6734 590 6735 590 6736 590 6486 590 6742 590 6488 590 6488 590 6742 590 6518 590 6488 590 6518 590 6737 590 6737 590 6518 590 6520 590 6737 590 6520 590 6738 590 6738 590 6520 590 6522 590 6738 590 6522 590 6514 590 5823 590 5822 590 6450 590 6450 590 5822 590 6453 590 6450 590 6453 590 6739 590 6739 590 6453 590 6381 590 6740 590 6741 590 6742 590 6742 1980 6741 1980 6743 1980 6742 590 6743 590 6453 590 6453 1979 6743 1979 6744 1979 6453 5320 6744 5320 6380 5320 6739 5321 6745 5321 6450 5321 6450 5322 6745 5322 6746 5322 6450 5323 6746 5323 6747 5323 6747 5324 6746 5324 6748 5324 6747 5325 6748 5325 6749 5325 6749 590 6750 590 6747 590 6747 5326 6750 5326 6751 5326 6747 590 6751 590 6742 590 6742 590 6751 590 6752 590 6742 5327 6752 5327 6740 5327 6753 5328 6754 5328 7405 5328 6753 5329 7405 5329 6755 5329 6755 5330 7405 5330 7404 5330 6755 5331 7404 5331 6756 5331 6756 5332 7404 5332 6757 5332 6756 5332 6757 5332 7374 5332 7374 5333 6757 5333 7406 5333 7374 5334 7406 5334 7056 5334 6754 5335 6753 5335 6758 5335 6758 5336 6753 5336 7057 5336 6758 5337 7057 5337 6759 5337 6759 5338 7057 5338 6760 5338 6759 5339 6760 5339 6762 5339 6762 5340 6760 5340 6761 5340 6762 5341 6761 5341 6763 5341 6763 5342 6761 5342 7060 5342 6763 5343 7060 5343 7399 5343 7399 5344 7060 5344 6770 5344 6764 5345 7417 5345 6765 5345 6764 5346 6765 5346 6766 5346 6766 5347 6765 5347 6767 5347 6766 5348 6767 5348 7063 5348 7063 5349 6767 5349 6769 5349 7063 5350 6769 5350 6768 5350 6768 5351 6769 5351 7399 5351 6768 5352 7399 5352 6770 5352 7417 5353 6764 5353 7418 5353 7418 5353 6764 5353 6771 5353 7418 5354 6771 5354 6774 5354 6774 5355 6771 5355 7066 5355 7342 5356 7655 5356 6773 5356 7342 5357 6773 5357 6772 5357 6772 5358 6773 5358 7419 5358 6772 5358 7419 5358 7343 5358 7343 5359 7419 5359 6774 5359 7343 5360 6774 5360 7066 5360 7655 5361 7342 5361 7409 5361 7409 5362 7342 5362 6775 5362 7409 5363 6775 5363 7411 5363 7411 5364 6775 5364 7351 5364 7411 5365 7351 5365 6776 5365 6776 5366 7351 5366 6777 5366 6778 5367 7413 5367 6779 5367 6778 5368 6779 5368 7069 5368 7069 5369 6779 5369 6776 5369 7069 5370 6776 5370 6777 5370 7413 5371 6778 5371 7414 5371 7414 5372 6778 5372 6780 5372 7414 5373 6780 5373 7415 5373 7415 5374 6780 5374 7055 5374 7415 5375 7055 5375 7406 5375 7406 5375 7055 5375 7056 5375 6781 5376 7566 5376 6782 5376 6782 5377 7566 5377 7428 5377 6782 5378 7428 5378 7084 5378 7084 5379 7428 5379 6784 5379 7084 5380 6784 5380 6783 5380 6783 5381 6784 5381 7431 5381 6783 5382 7431 5382 7080 5382 7080 5383 7431 5383 7432 5383 7071 5384 7435 5384 6789 5384 6803 5385 7054 5385 7317 5385 6803 5386 7317 5386 6785 5386 6785 5387 7317 5387 6786 5387 6785 5388 6786 5388 6787 5388 6787 5389 6786 5389 6788 5389 6788 5390 6786 5390 7075 5390 6788 5391 7075 5391 6789 5391 6789 5392 7075 5392 7072 5392 6789 5384 7072 5384 7071 5384 7093 5393 6794 5393 6790 5393 6790 5394 6794 5394 7446 5394 6790 5395 7446 5395 7371 5395 7371 5396 7446 5396 6791 5396 7371 5397 6791 5397 7087 5397 7087 5397 6791 5397 7427 5397 6795 2680 6792 2680 6793 2680 6795 2680 6793 2680 7094 2680 7094 5398 6793 5398 6794 5398 7094 5399 6794 5399 7093 5399 6792 5400 6795 5400 6796 5400 6796 5401 6795 5401 6797 5401 6796 5402 6797 5402 7444 5402 7444 5403 6797 5403 7092 5403 7444 5404 7092 5404 7443 5404 7443 5405 7092 5405 6798 5405 6799 5406 6800 5406 6802 5406 7443 5407 6798 5407 7441 5407 7441 5408 6798 5409 6801 5410 7441 5411 6801 5411 6802 5411 6802 5412 6801 5412 7186 5412 6802 5406 7186 5406 6799 5406 6800 5413 6799 5413 7532 5413 7532 5414 6799 5414 7187 5414 7532 5415 7187 5415 6803 5415 6803 5416 7187 5416 7054 5416 7288 5417 7722 5417 7721 5417 7288 5418 7721 5418 6804 5418 6804 5419 7721 5419 7720 5419 6804 5420 7720 5420 7289 5420 7289 5421 7720 5421 7719 5421 7289 5422 7719 5422 7283 5422 7283 5423 7719 5423 7718 5423 7283 5424 7718 5424 6805 5424 6805 5425 7718 5425 7717 5425 6805 5426 7717 5426 7284 5426 7284 5427 7717 5427 6806 5427 7284 5428 6806 5428 7285 5428 7285 5429 6806 5429 6807 5429 7285 5430 6807 5430 7287 5430 6808 3703 6809 3703 6810 3703 6808 5431 6810 5431 6811 5431 6811 5432 6810 5432 7715 5432 6811 3706 7715 3706 6812 3706 6812 3707 7715 3707 7714 3707 6812 5433 7714 5433 7281 5433 7281 384 7714 384 6813 384 7281 3710 6813 3710 6814 3710 6814 5434 6813 5434 6815 5434 6814 5435 6815 5435 6816 5435 6816 5436 6815 5436 7723 5436 6816 5437 7723 5437 6817 5437 6808 5438 7287 5438 6809 5438 6809 5439 7287 5439 6807 5439 7121 5440 6818 5440 6819 5440 7121 5440 6819 5440 6820 5440 6820 5441 6819 5441 6821 5441 6820 5442 6821 5442 6822 5442 6822 5443 6821 5443 6823 5443 6822 5444 6823 5444 6828 5444 7704 5445 6829 5445 6825 5445 6825 5446 6829 5446 6824 5446 6825 5447 6824 5447 6826 5447 6826 5448 6824 5448 6827 5448 6826 5449 6827 5449 6823 5449 6823 5450 6827 5450 6828 5450 6829 5451 7704 5451 7467 5451 6829 5451 7467 5451 7119 5451 7119 5452 7467 5452 6830 5452 7119 5452 6830 5452 6831 5452 6832 5453 6831 5453 7465 5453 7465 5454 6831 5454 6830 5454 6832 5455 7465 5455 6833 5455 6832 5455 6833 5455 7120 5455 7120 5456 6833 5456 6834 5456 7120 5457 6834 5457 7115 5457 7115 5458 6834 5458 6835 5458 7115 5459 6835 5459 7114 5459 7114 5460 6835 5460 7464 5460 7114 5461 7464 5461 7118 5461 6836 5462 7111 5462 7113 5462 7118 5463 7464 5463 6837 5463 6837 5463 7464 5463 7471 5463 6837 5464 7471 5464 7113 5464 7113 5465 7471 5465 7472 5465 7113 5466 7472 5466 6836 5466 7111 5467 6836 5467 6838 5467 7111 5468 6838 5468 7110 5468 7110 5469 6838 5469 6839 5469 7110 5469 6839 5469 6840 5469 6840 5470 6839 5470 6842 5470 6840 5471 6842 5471 6841 5471 6841 5472 6842 5472 6843 5472 6841 5473 6843 5473 6844 5473 6818 5474 7121 5474 6845 5474 6845 5475 7121 5475 7290 5475 6845 5476 7290 5476 6843 5476 6843 5477 7290 5477 6844 5477 6846 5478 7133 5478 7485 5478 7485 5479 7133 5479 7134 5479 7485 5480 7134 5480 7484 5480 7484 5481 7134 5481 7129 5481 6847 2730 7476 2730 7135 2730 7135 2729 7476 2729 6848 2729 6847 5482 7135 5482 7474 5482 7474 5483 7135 5484 7138 5485 7474 5486 7138 5487 6849 5488 7138 5489 6850 5490 6849 5491 6849 5492 6850 5492 7320 5492 6849 5493 7320 5493 7504 5493 7504 5494 7320 5494 6851 5494 7504 5495 6851 5495 6852 5495 6852 5496 6851 5496 7505 5496 7505 5497 6851 5497 6853 5497 7505 5498 6853 5498 7503 5498 7503 5498 6853 5498 7145 5498 7499 5499 7142 5499 7398 5499 7398 5499 7142 5499 6854 5499 7398 5500 6854 5500 7709 5500 7709 5501 6854 5501 7053 5501 7709 5502 7053 5502 7487 5502 7487 5503 7053 5503 7299 5503 7490 5504 6859 5504 6855 5504 7490 5505 6855 5505 6856 5505 6856 3726 6855 3726 6857 3726 6856 3719 6857 3719 7491 3719 7491 5506 6857 5506 7123 5506 7491 5507 7123 5507 7493 5507 7490 5508 6858 5508 6859 5508 6859 5508 6858 5508 6860 5508 7151 5509 6861 5509 7507 5509 7507 5510 6861 5510 6862 5510 7152 5511 7676 5511 7153 5511 7153 5512 7676 5512 7510 5512 7153 5513 7510 5513 6863 5513 7510 5513 7511 5513 6863 5513 6863 5514 7511 5514 6864 5514 6863 5515 6864 5515 7154 5515 7154 5516 6864 5516 6865 5516 7154 5517 6865 5517 6866 5517 6866 5518 6865 5518 6867 5518 6866 5519 6867 5519 7157 5519 7157 5520 6867 5520 7513 5520 6862 5521 6861 5521 7512 5521 7512 5522 6861 5522 7150 5522 7512 5523 7150 5523 7513 5523 7513 5524 7150 5524 7051 5524 7513 5525 7051 5525 7157 5525 7152 5526 6868 5526 7676 5526 7676 5527 6868 5527 7675 5527 7520 5528 6869 5528 6870 5528 6870 5529 6869 5529 6871 5529 6870 5530 6871 5530 7521 5530 7521 5531 6871 5531 7170 5531 7521 5532 7170 5532 7522 5532 7522 5533 7170 5533 7173 5533 7522 5534 7173 5534 6872 5534 6872 5535 7173 5535 6873 5535 6872 5536 6873 5536 7653 5536 7653 5537 6873 5537 6874 5537 7653 5538 6874 5538 6875 5538 6875 5539 6874 5539 7349 5539 6875 5540 7349 5540 6876 5540 6876 5541 7349 5541 6877 5541 6876 5542 6877 5542 6878 5542 6878 5543 6877 5543 7178 5543 6878 5544 7178 5544 6879 5544 6879 5545 7178 5545 6880 5545 6879 5546 6880 5546 7517 5546 7517 5547 6880 5547 6881 5547 7517 5548 6881 5548 7514 5548 7514 5549 6881 5549 7176 5549 7514 5550 7176 5550 6882 5550 6882 5551 7176 5551 6883 5551 6882 5552 6883 5552 6884 5552 6884 5553 6883 5553 6885 5553 6884 5554 6885 5554 7708 5554 7708 5555 6885 5556 7175 5557 7708 5558 7175 5558 6886 5558 6886 5559 7175 5559 7158 5559 6886 5560 7158 5560 6887 5560 6887 5561 7158 5561 7169 5561 6887 5562 7169 5562 6888 5562 6888 5563 7169 5563 7168 5563 6888 5564 7168 5564 7524 5564 7524 5565 7168 5565 7166 5565 7524 5566 7166 5566 7713 5566 7713 5567 7166 5567 7165 5567 7713 5568 7165 5568 6889 5568 6889 5569 7165 5569 6890 5569 6889 5570 6890 5570 7525 5570 7525 5571 6890 5571 7163 5571 7525 5572 7163 5572 6891 5572 6891 5573 7163 5573 6892 5573 6891 5574 6892 5574 7397 5574 7397 5575 6892 5575 6893 5575 7397 5576 6893 5576 6894 5576 6894 5577 6893 5577 7160 5577 6894 5578 7160 5578 6895 5578 6895 5579 7160 5579 7303 5579 6895 5580 7303 5580 7518 5580 7518 5581 7303 5581 7304 5581 7518 5582 7304 5582 6896 5582 6896 5583 7304 5583 7306 5583 6896 5584 7306 5584 7520 5584 7520 5585 7306 5585 6869 5585 7192 5586 6902 5586 7182 5586 7182 5587 6902 5587 7528 5587 7182 5588 7528 5588 7183 5588 7528 5589 7396 5589 7183 5589 7183 3699 7396 3699 7531 3699 7183 5590 7531 5590 6897 5590 6897 5591 7531 5591 6898 5591 6897 5592 6898 5592 7180 5592 7180 5593 6898 5593 7530 5593 7180 5593 7530 5593 7181 5593 7181 5432 7530 5432 6901 5432 7529 5594 7185 5594 6899 5594 6899 5595 7185 5595 7184 5595 6899 5596 7184 5596 6901 5596 6901 5597 7184 5597 6900 5597 6901 3706 6900 3706 7181 3706 7192 5509 7190 5509 6902 5509 6902 5510 7190 5510 7693 5510 6903 5598 6915 5598 6904 5598 6904 5598 6915 5598 6905 5598 6904 5599 6905 5599 7188 5599 6905 5600 7533 5600 7188 5600 7188 5601 7533 5601 6907 5601 7188 5601 6907 5601 6906 5601 6906 5602 6907 5602 7537 5602 6906 5603 7537 5603 6908 5603 6908 5604 7537 5604 7536 5604 6908 5605 7536 5605 6909 5605 6909 5606 7536 5606 6911 5606 6909 5607 6911 5607 6910 5607 6910 5608 6911 5608 6912 5608 7693 5609 7190 5609 7534 5609 7534 5610 7190 5610 6913 5610 7534 5611 6913 5611 6912 5611 6912 5611 6913 5611 6914 5611 6912 5612 6914 5612 6910 5612 6903 5613 7185 5613 6915 5613 6915 5614 7185 5614 7529 5614 7204 5615 7558 5615 6916 5615 6916 5616 7558 5616 6917 5616 6916 5617 6917 5617 6918 5617 6918 5618 6917 5618 7561 5618 7558 2821 7204 2821 6919 2821 6919 2822 7204 2822 7206 2822 6919 5619 7206 5619 7547 5619 7547 5620 7206 5620 7213 5620 6920 5621 7562 5621 7199 5621 7199 5622 7562 5622 7565 5622 7199 5623 7565 5623 7196 5623 7196 5624 7565 5624 6921 5624 7196 5625 6921 5625 6922 5625 6922 5626 6921 5626 6923 5626 6922 5627 6923 5627 7197 5627 7197 5628 6923 5628 6924 5628 7197 5629 6924 5629 6925 5629 7197 5630 6925 5630 6926 5630 6926 5631 6925 5631 6927 5631 6926 5632 6927 5632 7109 5632 7109 5633 6927 5633 7469 5633 7109 5634 7469 5634 7112 5634 7112 5635 7469 5635 7468 5635 7112 5636 7468 5636 6928 5636 6928 5637 7468 5637 7473 5637 6928 5638 7473 5638 6929 5638 6929 5639 7473 5639 6930 5639 6929 5640 6930 5640 7116 5640 7117 5641 7116 5641 6932 5641 6932 5642 7116 5642 6930 5642 7117 5643 6932 5643 6931 5643 6931 5644 6932 5644 7470 5644 6931 5645 7470 5645 7282 5645 7282 5646 7470 5646 7716 5646 7282 5647 7716 5647 7125 5647 7125 5648 7716 5648 6934 5648 7125 5649 6934 5649 6933 5649 6933 5649 6934 5649 7492 5649 6935 5650 7132 5650 6936 5650 6933 5651 7492 5652 6937 5653 6937 5654 7492 5655 7495 5656 6937 5657 7495 5657 6936 5657 6936 5658 7495 5658 6938 5658 6936 5650 6938 5650 6935 5650 7483 5659 6941 5659 7486 5659 7486 5660 6941 5660 6939 5660 7486 5661 6939 5661 6935 5661 6935 5661 6939 5661 7132 5661 6941 5662 7483 5662 7482 5662 6942 5663 6940 5663 7481 5663 7481 5664 6940 5664 7126 5664 7481 5665 7126 5665 7482 5665 7482 5666 7126 5666 7128 5666 7482 5667 7128 5667 6941 5667 6940 5668 6942 5668 7139 5668 7139 5669 6942 5669 7477 5669 7139 5670 7477 5670 7140 5670 7140 5671 7477 5671 7475 5671 7140 5672 7475 5672 7318 5672 7318 5673 7475 5673 6943 5673 7318 5674 6943 5674 6944 5674 6944 5675 6943 5675 6945 5675 6944 5676 6945 5676 7074 5676 7074 5677 6945 5677 7694 5677 7074 5678 7694 5678 7073 5678 7073 5679 7694 5679 6946 5679 7073 5680 6946 5680 6947 5680 6947 5681 6946 5681 7436 5681 6951 5682 7081 5682 6950 5682 6947 5683 7436 5683 6948 5683 6948 5684 7436 5684 6949 5684 6948 5685 6949 5685 6950 5685 6950 5686 6949 5686 7433 5686 6950 5687 7433 5687 6951 5687 7081 5688 6951 5688 7076 5688 7076 5689 6951 5689 6952 5689 7076 5690 6952 5690 6953 5690 6953 5691 6952 5692 7429 5693 6953 5694 7429 5694 7083 5694 7083 5695 7429 5695 6954 5695 7083 5696 6954 5696 7194 5696 7194 5697 6954 5697 7568 5697 7194 5698 7568 5698 6955 5698 6955 5698 7568 5698 7569 5698 6955 5699 7569 5699 7570 5699 6989 5700 7378 5700 6956 5700 6956 5700 7378 5700 7376 5700 6956 5701 7376 5701 7570 5701 7570 5702 7376 5702 7050 5702 7570 5703 7050 5703 6955 5703 6957 5704 7212 5704 7395 5704 7395 5705 7212 5705 7341 5705 7395 5706 7341 5706 7703 5706 7703 5707 7341 5707 6958 5707 7703 5708 6958 5708 7688 5708 7688 5709 6958 5709 7313 5709 7688 5710 7313 5710 6959 5710 6959 5711 7313 5711 7309 5711 6959 5712 7309 5712 7599 5712 7599 5713 7309 5713 7246 5713 7599 5714 7246 5714 6960 5714 6960 5715 7246 5715 6961 5715 6960 5716 6961 5716 7668 5716 7668 5717 6961 5717 7348 5717 7668 5718 7348 5718 7544 5718 7544 5719 7348 5719 6962 5719 7544 5720 6962 5720 11460 5720 11460 5721 6962 5721 10439 5721 6963 5722 6964 5722 6965 5722 6965 5723 6964 5723 6966 5723 6965 5724 6966 5724 6967 5724 6967 5725 6966 5725 6968 5725 6967 5726 6968 5726 10439 5726 10439 5727 6968 5727 11460 5727 6964 5728 6963 5728 6969 5728 6969 5729 6963 5729 6970 5729 6969 2856 6970 2856 6971 2856 6971 2857 6970 2857 10323 2857 7217 5730 7541 5730 7218 5730 7218 5731 7541 5731 6972 5731 7218 5732 6972 5732 6973 5732 6973 5733 6972 5733 7540 5733 6973 5734 7540 5734 7107 5734 7107 5735 7540 5735 7542 5735 7107 5736 7542 5736 10323 5736 10323 5736 7542 5736 6971 5736 7662 5737 7541 5737 6974 5737 6974 5738 7541 5738 7217 5738 7662 5739 6974 5739 7538 5739 7538 5740 6974 5740 7220 5740 7538 5741 7220 5741 7539 5741 7539 5741 7220 5741 7219 5741 7539 5742 7219 5742 6975 5742 6975 5743 7219 5743 6976 5743 6975 5744 6976 5744 6979 5744 6979 5745 6976 5745 6977 5745 7062 5746 6978 5746 7400 5746 7062 5747 7400 5747 7065 5747 7065 5748 7400 5748 7401 5748 7065 5748 7401 5748 7064 5748 7064 5749 7401 5749 6979 5749 7064 5750 6979 5750 6977 5750 6978 5751 7062 5751 7402 5751 7402 5751 7062 5751 7061 5751 7402 5752 7061 5752 6980 5752 6980 5753 7061 5753 6981 5753 6980 5754 6981 5754 7403 5754 7403 5754 6981 5754 7059 5754 7403 5755 7059 5755 6982 5755 6982 5756 7059 5756 6983 5756 6982 5757 6983 5757 7573 5757 7573 5758 6983 5758 7223 5758 7573 5759 7223 5759 7631 5759 7631 5760 7223 5760 7224 5760 7224 5761 6985 5761 7631 5761 7631 5762 6985 5762 6984 5762 6984 5763 6985 5763 6986 5763 6986 5764 6985 5764 7380 5764 6986 5765 7380 5765 7639 5765 7639 5766 7380 5766 7379 5766 7639 5767 7379 5767 6988 5767 6988 5768 7379 5768 6987 5768 6988 5769 6987 5769 6989 5769 6989 5770 6987 5770 7378 5770 6990 5771 7238 5771 7616 5771 7616 5772 7238 5772 6991 5772 7616 5773 6991 5773 6992 5773 6992 5774 6991 5774 7239 5774 6992 5775 7239 5775 6993 5775 6993 5776 7239 5776 7240 5776 6993 5777 7240 5777 6995 5777 6993 5778 6995 5778 6994 5778 6994 5779 6995 5779 6996 5779 6994 5780 6996 5780 7588 5780 7588 5781 6996 5781 7242 5781 7588 5782 7242 5782 7592 5782 7592 5783 7242 5783 7243 5783 7592 5784 7243 5784 7593 5784 7593 5785 7243 5785 6997 5785 7593 5786 6997 5786 7611 5786 7611 5787 6997 5787 7251 5787 7611 5788 7251 5788 6998 5788 6999 5789 7602 5789 7310 5789 7310 5790 7602 5790 7001 5790 7310 5791 7001 5791 7000 5791 7000 5792 7001 5792 7604 5792 7000 5793 7604 5793 7260 5793 7260 5794 7604 5794 7606 5794 7018 4059 7690 4059 7002 4059 7018 4081 7002 4081 7003 4081 7003 5795 7002 5795 7004 5795 7003 5796 7004 5796 7264 5796 7264 3343 7004 3343 7005 3343 7264 3344 7005 3344 7006 3344 7006 3346 7005 3346 7007 3346 7006 3345 7007 3345 7008 3345 7008 3347 7007 3347 7619 3347 7008 3348 7619 3348 7266 3348 7266 5797 7619 5797 7009 5797 7266 4069 7009 4069 7010 4069 7010 5798 7009 5798 7011 5798 7011 5799 7009 5799 7618 5799 7011 5800 7618 5800 7268 5800 7618 5801 7012 5801 7268 5801 7268 5802 7012 5802 7013 5802 7268 5803 7013 5803 7269 5803 7269 5804 7013 5804 7014 5804 7269 5805 7014 5805 7015 5805 7015 4077 7014 4077 7621 4077 7015 5806 7621 5806 7016 5806 7016 4078 7621 4078 7017 4078 7690 5807 7018 5807 7620 5807 7620 5808 7018 5808 7019 5808 7620 5809 7019 5809 7017 5809 7017 5810 7019 5810 7265 5810 7017 5811 7265 5811 7016 5811 7335 4058 7669 4058 7020 4058 7020 4059 7669 4059 7022 4059 7020 4081 7022 4081 7021 4081 7021 3341 7022 3341 7673 3341 7021 3342 7673 3342 7023 3342 7023 5812 7673 5812 7024 5812 7023 3344 7024 3344 7333 3344 7333 3346 7024 3346 7026 3346 7333 4066 7026 4066 7025 4066 7025 3347 7026 3347 7672 3347 7025 4050 7672 4050 7027 4050 7027 4051 7672 4051 7671 4051 7027 2998 7671 2998 7334 2998 7334 2997 7671 2997 7670 2997 7334 2999 7670 2999 7028 2999 7028 3000 7670 3000 7030 3000 7028 5813 7030 5813 7029 5813 7029 2973 7030 2973 7031 2973 7029 2974 7031 2974 7032 2974 7032 2976 7031 2976 7033 2976 7032 4052 7033 4052 7034 4052 7034 2977 7033 2977 7035 2977 7034 5814 7035 5814 7335 5814 7335 4057 7035 4057 7669 4057 7047 4058 7660 4058 7036 4058 7036 4081 7660 4081 7658 4081 7036 4060 7658 4060 7324 4060 7324 3341 7658 3341 7661 3341 7324 3342 7661 3342 7037 3342 7037 5812 7661 5812 7038 5812 7037 5815 7038 5815 7039 5815 7039 5816 7038 5816 7040 5816 7039 5817 7040 5817 7327 5817 7327 5818 7040 5818 7041 5818 7327 5819 7041 5819 7042 5819 7042 5820 7041 5820 7043 5820 7042 5821 7043 5821 7328 5821 7328 5822 7043 5822 7044 5822 7328 5823 7044 5823 7329 5823 7329 5824 7044 5824 7045 5824 7329 5825 7045 5825 7330 5825 7330 5826 7045 5826 7666 5826 7330 5827 7666 5827 7046 5827 7046 5828 7666 5828 7657 5828 7046 5829 7657 5829 7332 5829 7332 5830 7657 5830 7048 5830 7332 5831 7048 5831 7047 5831 7047 4080 7048 4080 7660 4080 7293 5832 7292 5832 7294 5832 10439 960 6962 960 7049 960 6953 5833 7082 5833 7076 5833 6955 5834 7050 5834 7376 5834 7051 960 7150 960 7156 960 6854 960 7052 960 7053 960 6824 5835 7297 5835 6827 5835 7085 960 7193 960 7377 960 7054 960 7187 960 7070 960 7056 5836 7055 5836 7370 5836 6756 960 7375 960 6755 960 6755 960 7375 960 7058 960 7056 960 7370 960 7374 960 6760 960 7057 960 7058 960 7058 5837 7057 5837 6753 5837 7058 5838 6753 5838 6755 5838 7223 960 6983 960 6760 960 6760 960 6983 960 7059 960 6760 5839 7059 5839 6761 5839 6761 960 7059 960 7060 960 6764 960 6766 960 7067 960 7067 5840 6766 5840 7063 5840 7059 960 6981 960 7060 960 7060 5841 6981 5841 7061 5841 7060 960 7061 960 6770 960 6770 5842 7061 5842 7062 5842 6770 960 7062 960 6768 960 6768 960 7062 960 7063 960 6977 960 7067 960 7064 960 7064 960 7067 960 7063 960 7064 5843 7063 5843 7065 5843 7065 5844 7063 5844 7062 5844 6775 5845 7342 5845 7177 5845 7343 960 7066 960 7067 960 7067 5846 7066 5846 6771 5846 7067 5847 6771 5847 6764 5847 7369 960 6780 960 7350 960 7350 960 6780 960 6778 960 7351 960 7068 960 6777 960 6777 960 7068 960 7350 960 6777 960 7350 960 7069 960 7069 960 7350 960 6778 960 7054 960 7070 960 7317 960 7071 960 7072 960 7073 960 7073 5848 7072 5848 7075 5848 7073 960 7075 960 7074 960 7074 5849 7075 5849 6786 5849 7074 5850 6786 5850 7317 5850 7076 960 7082 960 7081 960 7071 960 7073 960 7077 960 7077 5851 7073 5851 6947 5851 7077 960 6947 960 7078 960 7078 5852 6947 5852 6948 5852 7078 960 6948 960 7079 960 7079 960 6948 960 6950 960 7079 960 6950 960 7080 960 7080 960 6950 960 7081 960 7080 5853 7081 5853 6783 5853 6783 960 7081 960 7082 960 6783 960 7082 960 7084 960 7084 5854 7082 5854 6953 5854 7084 960 6953 960 7083 960 7194 960 6781 960 7083 960 7083 5855 6781 5855 6782 5855 7083 960 6782 960 7084 960 7085 5856 7377 5856 7086 5856 7087 960 7088 960 7373 960 7088 960 7089 960 7373 960 7373 5857 7089 5857 7090 5857 7373 5858 7090 5858 7377 5858 7377 5859 7090 5859 7091 5859 7377 5860 7091 5860 7086 5860 6798 5861 7092 5861 7352 5861 7352 960 7092 960 6797 960 7352 5862 6797 5862 7174 5862 7174 960 6797 960 6795 960 6790 5863 7368 5863 7093 5863 7093 960 7368 960 7174 960 7093 960 7174 960 7094 960 7094 960 7174 960 6795 960 6801 960 7171 960 7186 960 7186 960 7171 960 7095 960 10659 5864 7101 5864 7096 5864 10659 960 7096 960 7215 960 7105 5865 7097 5865 7098 5865 7098 5866 7097 5866 10665 5866 7098 960 10665 960 7216 960 10665 960 10664 960 7216 960 7216 5867 10664 5867 10662 5867 7216 5868 10662 5868 7049 5868 7049 960 10662 960 7099 960 7049 960 7099 960 7214 960 7107 5869 7100 5869 7106 5869 7101 960 7102 960 7096 960 7096 5870 7102 5870 7103 5870 7096 960 7103 960 7104 960 7105 960 7098 960 7106 960 7106 5871 7098 5871 6973 5871 7106 5872 6973 5872 7107 5872 6840 960 6841 960 7108 960 7108 5873 6841 5873 6844 5873 7116 960 6837 960 7113 960 7108 5874 6926 5874 6840 5874 6840 960 6926 960 7109 960 6840 5875 7109 5875 7110 5875 7110 5876 7109 5876 7112 5876 7110 5877 7112 5877 7111 5877 7111 960 7112 960 6928 960 7111 960 6928 960 7113 960 7113 960 6928 960 6929 960 7113 960 6929 960 7116 960 7114 5878 6931 5878 7115 5878 7115 5879 6931 5879 7282 5879 7115 960 7282 960 7120 960 7116 960 7117 960 6837 960 6837 5880 7117 5880 6931 5880 6837 960 6931 960 7118 960 7118 960 6931 960 7114 960 6829 960 7119 960 7286 960 7286 960 7119 960 6831 960 7286 960 6831 960 7282 960 7282 960 6831 960 6832 960 7282 5881 6832 5881 7120 5881 7121 5882 6820 5882 7263 5882 6827 5883 7297 5883 6828 5883 6828 960 7297 960 7296 960 6828 960 7296 960 6822 960 7121 960 7263 960 7290 960 7164 5884 7122 5884 7299 5884 6857 5885 7125 5885 7123 5885 7123 960 7125 960 6933 960 7123 960 6933 960 7124 960 6857 5886 6855 5886 7125 5886 7125 5887 6855 5887 6859 5887 7125 5888 6859 5888 7164 5888 7164 5889 6859 5889 6860 5889 7164 960 6860 960 7122 960 7126 960 7127 960 7128 960 7128 5890 7127 5890 7129 5890 7124 960 6933 960 7130 960 7130 5891 6933 5891 6937 5891 7130 5892 6937 5892 7131 5892 7131 5893 6937 5893 6936 5893 7131 5894 6936 5894 7133 5894 7133 5895 6936 5895 7132 5895 7133 960 7132 960 7134 960 7134 5896 7132 5896 6939 5896 7134 960 6939 960 7129 960 7129 5897 6939 5897 6941 5897 7129 5898 6941 5898 7128 5898 7138 960 7135 960 7139 960 7139 960 7135 960 6848 960 7139 960 6848 960 6940 960 6940 5899 6848 5899 7136 5899 6940 960 7136 960 7126 960 7126 5900 7136 5900 7137 5900 7126 5901 7137 5901 7127 5901 7138 960 7139 960 6850 960 6850 960 7139 960 7140 960 6850 960 7140 960 7320 960 7298 5902 7145 5902 7319 5902 7319 960 7145 960 6853 960 7319 5903 6853 5903 6851 5903 7052 960 6854 960 7141 960 6854 960 7142 960 7141 960 7141 5904 7142 5904 7143 5904 7141 5905 7143 5905 7298 5905 7298 5906 7143 5906 7144 5906 7298 5907 7144 5907 7145 5907 7177 5908 7344 5908 7147 5908 7727 960 7146 960 7147 960 7147 5909 7146 5909 7729 5909 7147 5910 7729 5910 7731 5910 6868 960 7177 960 7148 960 7148 960 7177 960 7147 960 7148 960 7147 960 7734 960 7734 5911 7147 5911 7731 5911 7156 5912 7150 5912 7149 5912 7149 5913 7150 5913 6861 5913 7149 5914 6861 5914 7151 5914 7300 5915 7151 5915 7270 5915 6868 5916 7152 5916 7177 5916 7177 5917 7152 5917 7153 5917 7177 960 7153 960 7155 960 7155 5918 7153 5918 6863 5918 6863 5919 7154 5919 7155 5919 7155 960 7154 960 6866 960 7155 960 6866 960 7156 960 7156 960 6866 960 7157 960 7156 3108 7157 3108 7051 3108 7158 5920 7175 5920 7159 5920 7159 960 7175 960 7149 960 7160 5921 6893 5921 7161 5921 7161 5922 6893 5922 6892 5922 7161 960 6892 960 7162 960 6892 960 7163 960 7162 960 7162 960 7163 960 6890 960 7162 5923 6890 5923 7164 5923 7164 960 6890 960 7165 960 7164 5924 7165 5924 7286 5924 7286 5925 7165 5925 7166 5925 7286 5926 7166 5926 7167 5926 7167 960 7166 960 7168 960 7167 960 7168 960 7295 960 7295 960 7168 960 7169 960 7295 960 7169 960 7158 960 7303 960 7160 960 7298 960 6869 5927 7095 5927 6871 5927 6871 960 7095 960 7171 960 6871 5928 7171 5928 7170 5928 7170 960 7171 960 7172 960 7170 5929 7172 5929 7173 5929 7173 5930 7172 5930 6873 5930 7349 5931 6874 5931 7350 5931 7350 5932 6874 5932 7174 5932 7175 960 6885 960 7149 960 7149 960 6885 960 6883 960 7149 5933 6883 5933 7156 5933 7156 960 6883 960 7176 960 7156 960 7176 960 7155 960 7155 4463 7176 4463 6881 4463 7155 960 6881 960 7177 960 7177 5934 6881 5934 6880 5934 7177 5935 6880 5935 7179 5935 7179 960 6880 960 7178 960 7179 5936 7178 5936 6877 5936 7180 960 7181 960 7095 960 7191 5937 7182 5937 7305 5937 7305 5938 7182 5938 7183 5938 7305 960 7183 960 6897 960 6869 960 7306 960 7095 960 7095 960 7306 960 7305 960 7095 960 7305 960 7180 960 7180 960 7305 960 6897 960 7181 5939 6900 5939 7095 5939 7095 5940 6900 5940 7184 5940 7095 960 7184 960 7186 960 7186 5941 7184 5941 7185 5941 7186 5942 7185 5942 6799 5942 6799 5943 7185 5943 6903 5943 6799 960 6903 960 7187 960 7187 5944 6903 5944 6904 5944 7187 960 6904 960 7070 960 7070 5945 6904 5945 7188 5945 7188 5946 6906 5946 7070 5946 7070 960 6906 960 6908 960 7070 5947 6908 5947 7189 5947 7189 5948 6908 5948 6909 5948 7189 5949 6909 5949 6910 5949 6910 5950 6914 5950 7189 5950 7189 5951 6914 5951 6913 5951 7189 5952 6913 5952 7302 5952 7302 5953 6913 5953 7190 5953 7302 960 7190 960 7191 960 7191 5954 7190 5954 7192 5954 7191 5955 7192 5955 7182 5955 6955 960 7377 960 7194 960 7194 960 7377 960 7193 960 7194 960 7193 960 6781 960 7195 960 7196 960 7291 960 7291 960 7196 960 6922 960 7291 5956 6922 5956 7108 5956 7108 5957 6922 5957 7197 5957 7108 5958 7197 5958 6926 5958 6916 960 6918 960 7198 960 7198 5959 6918 5959 6920 5959 7198 5960 6920 5960 7195 5960 7195 960 6920 960 7199 960 7195 960 7199 960 7196 960 7206 960 7209 960 7210 960 7210 960 7200 960 7211 960 7204 960 6916 960 10652 960 7200 960 7201 960 7211 960 7211 5961 7201 5961 10655 5961 7211 5962 10655 5962 7198 5962 10655 960 7202 960 7198 960 7198 5963 7202 5963 10654 5963 7198 5964 10654 5964 6916 5964 6916 5965 10654 5965 7203 5965 6916 5966 7203 5966 10652 5966 10652 960 7205 960 7204 960 7204 5967 7205 5967 7207 5967 7204 5968 7207 5968 7206 5968 7206 5969 7207 5969 7208 5969 7206 5970 7208 5970 7209 5970 7211 5971 7341 5971 7212 5971 7210 5972 7211 5972 7206 5972 7206 5973 7211 5973 7212 5973 7206 5974 7212 5974 7213 5974 10439 960 7049 960 6967 960 7214 960 7215 960 7049 960 7049 960 7215 960 7096 960 7049 960 7096 960 6967 960 6967 960 7096 960 7104 960 6967 960 7104 960 6965 960 6965 5975 7104 5975 6970 5975 6965 960 6970 960 6963 960 7103 5976 7100 5976 7104 5976 7104 5977 7100 5977 7107 5977 7104 960 7107 960 6970 960 6970 5978 7107 5978 10323 5978 7220 5979 6974 5979 7216 5979 7216 960 6974 960 7217 960 7216 960 7217 960 7098 960 7098 960 7217 960 7218 960 7098 960 7218 960 6973 960 6977 960 6976 960 7067 960 7067 960 6976 960 7219 960 7067 960 7219 960 7221 960 7221 960 7219 960 7220 960 7221 5980 7220 5980 7222 5980 7222 960 7220 960 7216 960 6760 5981 7058 5981 7223 5981 7223 5982 7058 5982 6985 5982 7223 5983 6985 5983 7224 5983 7238 960 7225 960 7321 960 6999 5984 7310 5984 7226 5984 7226 5985 7310 5985 7312 5985 7226 960 7312 960 7227 960 7227 5986 7312 5986 7228 5986 7225 960 7229 960 7321 960 7321 5987 7229 5987 7230 5987 7321 960 7230 960 7232 960 7230 960 7231 960 7232 960 7232 5988 7231 5988 7233 5988 7232 5989 7233 5989 7326 5989 7234 5990 7235 5990 7325 5990 7325 5991 7235 5991 7236 5991 7237 960 7252 960 7243 960 7322 5992 6996 5992 6995 5992 7238 5993 7321 5993 6991 5993 6991 960 7321 960 7322 960 6991 5994 7322 5994 7239 5994 7239 5995 7322 5995 6995 5995 7239 5996 6995 5996 7240 5996 7244 960 6961 960 7241 960 7241 960 6961 960 7250 960 6996 960 7322 960 7242 960 7242 960 7322 960 6961 960 7242 960 6961 960 7243 960 7243 5997 6961 5997 7244 5997 7243 5998 7244 5998 7237 5998 7245 960 7247 960 7246 960 7246 5999 7247 5999 7248 5999 7246 960 7248 960 6961 960 6961 6000 7248 6000 7249 6000 6961 6001 7249 6001 7250 6001 7257 6002 7251 6002 7252 6002 7252 6003 7251 6003 6997 6003 7252 6004 6997 6004 7243 6004 7255 6005 7259 6005 7253 6005 7253 6006 7254 6006 7255 6006 7255 6007 7254 6007 7256 6007 7255 6008 7256 6008 7257 6008 7257 6009 7256 6009 7258 6009 7257 6010 7258 6010 7251 6010 7308 6011 7262 6011 7259 6011 7000 960 7260 960 7308 960 7308 6012 7260 6012 7261 6012 7308 6013 7261 6013 7262 6013 7278 6014 7008 6014 7266 6014 7008 960 7278 960 7006 960 7301 960 7018 960 7263 960 7263 6015 7018 6015 7003 6015 7278 6016 7279 6016 7006 6016 7006 960 7279 960 7263 960 7006 960 7263 960 7264 960 7264 960 7263 960 7003 960 7015 960 7016 960 7300 960 7300 6017 7016 6017 7265 6017 7300 960 7265 960 7301 960 7301 6018 7265 6018 7019 6018 7301 6019 7019 6019 7018 6019 7266 960 7010 960 7278 960 7278 6020 7010 6020 7011 6020 7278 960 7011 960 7267 960 7267 6021 7011 6021 7268 6021 7267 6022 7268 6022 7269 6022 7269 960 7015 960 7267 960 7267 6023 7015 6023 7300 6023 7267 6024 7300 6024 7316 6024 7316 960 7300 960 7270 960 7316 6025 7270 6025 7724 6025 7271 960 7272 960 7279 960 7279 6026 7272 6026 7383 6026 7279 960 7383 960 7292 960 7383 960 7384 960 7292 960 7292 6027 7384 6027 7273 6027 7292 960 7273 960 7294 960 7294 6028 7273 6028 7274 6028 7294 6029 7274 6029 7275 6029 7315 6030 7386 6030 7276 6030 7314 960 7391 960 7267 960 7267 6031 7391 6031 7277 6031 7267 960 7277 960 7278 960 7278 6032 7277 6032 7392 6032 7278 960 7392 960 7279 960 7279 6033 7392 6033 7280 6033 7279 6034 7280 6034 7271 6034 6811 960 6812 960 7286 960 7286 6035 6812 6035 7281 6035 7286 5932 7281 5932 7164 5932 7164 6036 7281 6036 6814 6036 7164 6037 6814 6037 6816 6037 7282 6038 6805 6038 7284 6038 6805 960 7282 960 7283 960 7283 960 7282 960 7125 960 7283 960 7125 960 7289 960 7284 960 7285 960 7282 960 7282 6039 7285 6039 7287 6039 7282 6040 7287 6040 7286 6040 7286 6041 7287 6041 6808 6041 7286 6042 6808 6042 6811 6042 6816 960 6817 960 7164 960 7164 960 6817 960 7288 960 7164 6043 7288 6043 7125 6043 7125 6044 7288 6044 6804 6044 7125 6045 6804 6045 7289 6045 6844 960 7290 960 7108 960 7108 960 7290 960 7263 960 7108 960 7263 960 7291 960 7291 960 7263 960 7279 960 7291 960 7279 960 7195 960 7195 960 7279 960 7292 960 7195 960 7292 960 7198 960 7198 960 7292 960 7293 960 7198 960 7293 960 7211 960 7341 6046 7211 6046 7340 6046 7340 960 7211 960 7293 960 7340 6047 7293 6047 7337 6047 7337 960 7293 960 7294 960 7337 960 7294 960 7315 960 7315 960 7294 960 7275 960 7315 6048 7275 6048 7386 6048 7158 6049 7159 6049 7295 6049 7295 6050 7159 6050 7296 6050 7295 960 7296 960 7167 960 7167 6051 7296 6051 7297 6051 7167 960 7297 960 7286 960 7286 960 7297 960 6824 960 7286 960 6824 960 6829 960 7160 960 7161 960 7298 960 7298 6052 7161 6052 7162 6052 7298 960 7162 960 7141 960 7141 6053 7162 6053 7164 6053 7141 960 7164 960 7052 960 7052 6054 7164 6054 7299 6054 7052 960 7299 960 7053 960 7151 960 7300 960 7149 960 7149 6055 7300 6055 7301 6055 7149 960 7301 960 7159 960 7159 6056 7301 6056 7263 6056 7159 960 7263 960 7296 960 7296 960 7263 960 6820 960 7296 960 6820 960 6822 960 7319 960 7302 960 7298 960 7298 960 7302 960 7191 960 7298 960 7191 960 7303 960 7303 6057 7191 6057 7305 6057 7303 6058 7305 6058 7304 6058 7304 960 7305 960 7306 960 7255 960 7307 960 7259 960 7259 6059 7307 6059 7245 6059 7259 960 7245 960 7308 960 7308 6060 7245 6060 7246 6060 7308 6061 7246 6061 7309 6061 7310 960 7000 960 7312 960 7312 6062 7000 6062 7308 6062 7312 6063 7308 6063 7311 6063 7311 6064 7308 6064 7309 6064 7311 6065 7309 6065 7313 6065 7236 960 7228 960 7325 960 7325 960 7228 960 7312 960 7325 6066 7312 6066 7338 6066 7338 6067 7312 6067 7311 6067 7338 6068 7311 6068 7339 6068 7339 960 7311 960 7313 960 7339 6069 7313 6069 6958 6069 7276 6070 7314 6070 7315 6070 7315 6071 7314 6071 7267 6071 7315 6072 7267 6072 7336 6072 7336 960 7267 960 7316 960 7336 6073 7316 6073 7147 6073 7147 960 7316 960 7724 960 7147 6074 7724 6074 7727 6074 7317 6075 7070 6075 7074 6075 7074 960 7070 960 7189 960 7074 960 7189 960 6944 960 6944 6076 7189 6076 7302 6076 6944 960 7302 960 7318 960 7318 6077 7302 6077 7319 6077 7318 960 7319 960 7140 960 7140 6078 7319 6078 6851 6078 7140 6079 6851 6079 7320 6079 7232 960 7345 960 7321 960 7321 960 7345 960 7346 960 7321 6080 7346 6080 7322 6080 7322 960 7346 960 7347 960 7322 960 7347 960 6961 960 6961 960 7347 960 7348 960 7047 960 7036 960 7331 960 7331 960 7036 960 7323 960 7323 6081 7036 6081 7324 6081 7323 6082 7324 6082 7037 6082 7037 6083 7039 6083 7323 6083 7323 6084 7039 6084 7232 6084 7323 6085 7232 6085 7325 6085 7325 960 7232 960 7326 960 7325 6086 7326 6086 7234 6086 7039 960 7327 960 7232 960 7232 960 7327 960 7042 960 7232 6087 7042 6087 7345 6087 7345 6088 7042 6088 7328 6088 7345 6089 7328 6089 7329 6089 7329 6090 7330 6090 7345 6090 7345 6091 7330 6091 7046 6091 7345 6092 7046 6092 7331 6092 7331 6093 7046 6093 7332 6093 7331 6094 7332 6094 7047 6094 7333 6095 7025 6095 7323 6095 7323 6096 7025 6096 7027 6096 7323 6097 7027 6097 7331 6097 7331 6098 7027 6098 7334 6098 7331 6099 7334 6099 7028 6099 7028 960 7029 960 7331 960 7331 6100 7029 6100 7032 6100 7331 960 7032 960 7344 960 7344 6101 7032 6101 7034 6101 7034 6102 7335 6102 7344 6102 7344 6103 7335 6103 7020 6103 7344 6104 7020 6104 7147 6104 7147 6105 7020 6105 7021 6105 7147 6106 7021 6106 7023 6106 7023 6107 7333 6107 7147 6107 7147 6108 7333 6108 7323 6108 7147 6109 7323 6109 7336 6109 7336 6110 7323 6110 7325 6110 7336 6111 7325 6111 7315 6111 7315 6112 7325 6112 7338 6112 7315 960 7338 960 7337 960 7337 960 7338 960 7339 960 7337 6113 7339 6113 7340 6113 7340 6114 7339 6114 6958 6114 7340 6115 6958 6115 7341 6115 7342 960 6772 960 7177 960 7177 6116 6772 6116 7343 6116 7177 960 7343 960 7344 960 7344 6117 7343 6117 7067 6117 7344 960 7067 960 7331 960 7331 960 7067 960 7221 960 7331 960 7221 960 7345 960 7345 960 7221 960 7222 960 7345 960 7222 960 7346 960 7346 960 7222 960 7216 960 7346 960 7216 960 7347 960 7347 960 7216 960 7049 960 7347 960 7049 960 7348 960 7348 960 7049 960 6962 960 6877 6118 7349 6118 7179 6118 7179 960 7349 960 7350 960 7179 6119 7350 6119 7177 6119 7177 960 7350 960 7068 960 7177 6120 7068 6120 6775 6120 6775 960 7068 960 7351 960 6801 6121 6798 6121 7171 6121 7171 6122 6798 6122 7352 6122 7171 6119 7352 6119 7172 6119 7172 960 7352 960 7174 960 7172 6123 7174 6123 6873 6123 6873 6124 7174 6124 6874 6124 7353 960 7356 960 7174 960 7363 6125 7350 6125 7354 6125 7354 960 7350 960 7174 960 7354 960 7174 960 7355 960 7355 960 7174 960 7356 960 7367 6126 7357 6126 7369 6126 7353 960 7174 960 7358 960 7358 960 7174 960 7368 960 7358 6127 7368 6127 7359 6127 7357 960 7360 960 7369 960 7369 6128 7360 6128 7361 6128 7369 6129 7361 6129 7368 6129 7368 960 7361 960 7362 960 7368 6130 7362 6130 7359 6130 7363 6131 7364 6131 7350 6131 7350 6132 7364 6132 7365 6132 7350 960 7365 960 7369 960 7369 6133 7365 6133 7366 6133 7369 6134 7366 6134 7367 6134 6790 6135 7371 6135 7368 6135 7368 6136 7371 6136 7372 6136 7368 960 7372 960 7369 960 7369 960 7372 960 7370 960 7369 6137 7370 6137 6780 6137 6780 6138 7370 6138 7055 6138 7371 960 7087 960 7372 960 7372 960 7087 960 7373 960 7372 6139 7373 6139 7370 6139 7370 960 7373 960 7375 960 7370 960 7375 960 7374 960 7374 960 7375 960 6756 960 6955 6140 7376 6140 7377 6140 7377 6141 7376 6141 7378 6141 7377 6142 7378 6142 7373 6142 7373 960 7378 960 6987 960 7373 6143 6987 6143 7375 6143 7375 960 6987 960 7379 960 7375 960 7379 960 7058 960 7058 960 7379 960 7380 960 7058 6144 7380 6144 6985 6144 7280 4060 7627 4060 7381 4060 7280 4081 7381 4081 7271 4081 7271 3341 7381 3341 7624 3341 7271 3342 7624 3342 7272 3342 7272 3343 7624 3343 7382 3343 7272 3344 7382 3344 7383 3344 7383 5816 7382 5816 7385 5816 7383 5816 7385 5816 7384 5816 7384 6145 7385 6145 7623 6145 7384 5819 7623 5819 7273 5819 7273 6146 7623 6146 7622 6146 7273 6147 7622 6147 7274 6147 7274 6148 7622 6148 7275 6148 7275 6149 7622 6149 7387 6149 7275 6150 7387 6150 7386 6150 7387 6151 7388 6151 7386 6151 7386 3000 7388 3000 7389 3000 7386 3001 7389 3001 7276 3001 7276 2973 7389 2973 7630 2973 7276 2974 7630 2974 7314 2974 7314 2976 7630 2976 7390 2976 7314 2975 7390 2975 7391 2975 7391 2977 7390 2977 7629 2977 7627 6152 7280 6152 7628 6152 7628 6153 7280 6153 7392 6153 7628 6154 7392 6154 7629 6154 7629 6155 7392 6155 7277 6155 7629 2978 7277 2978 7391 2978 7663 6156 7393 6156 7659 6156 7388 590 7387 590 7394 590 7587 590 6990 590 7616 590 6957 6157 7395 6157 7545 6157 7396 590 7528 590 7519 590 6887 6158 7707 6158 6886 6158 7397 6159 7712 6159 6891 6159 7709 6160 7498 6160 7398 6160 6767 590 6765 590 7416 590 6763 590 7399 590 6978 590 6978 6161 7399 6161 6769 6161 6978 590 6769 590 7400 590 7400 6162 6769 6162 6767 6162 7400 590 6767 590 7401 590 7401 6163 6767 6163 7416 6163 7401 590 7416 590 6979 590 6979 6164 7416 6164 6975 6164 6978 590 7402 590 6763 590 6763 590 7402 590 6980 590 6763 6165 6980 6165 6762 6165 6762 6166 6980 6166 7403 6166 6762 590 7403 590 6759 590 6759 6167 7403 6167 6982 6167 6759 6168 6982 6168 7573 6168 7572 6169 7408 6169 7404 6169 7404 590 7405 590 7572 590 7572 6170 7405 6170 6754 6170 7572 6171 6754 6171 6758 6171 7412 6172 7415 6172 7407 6172 7407 590 7415 590 7406 590 7407 6173 7406 6173 7408 6173 7408 590 7406 590 6757 590 7408 590 6757 590 7404 590 7655 590 7409 590 7410 590 7410 590 7409 590 7411 590 7410 590 7411 590 7650 590 7650 6174 7411 6174 6776 6174 6776 590 6779 590 7650 590 7650 6175 6779 6175 7413 6175 7650 590 7413 590 7412 590 7412 590 7413 590 7414 590 7412 590 7414 590 7415 590 6773 590 7654 590 7419 590 7419 590 7654 590 7674 590 6765 590 7417 590 7416 590 7416 6176 7417 6176 7418 6176 7416 6177 7418 6177 7674 6177 7674 6178 7418 6178 6774 6178 7674 6179 6774 6179 7419 6179 7566 6180 7420 6180 7567 6180 7567 6181 7420 6181 7421 6181 7424 590 7571 590 7422 590 7422 6182 7571 6182 7567 6182 7422 590 7567 590 7423 590 7423 590 7567 590 7421 590 7424 590 7425 590 7571 590 7571 6183 7425 6183 7426 6183 7571 6184 7426 6184 7640 6184 7640 590 7426 590 7427 590 7568 6185 6954 6185 7428 6185 7428 6186 6954 6186 6784 6186 6784 590 6954 590 7430 590 6784 590 7430 590 7431 590 6954 6187 7429 6187 7430 6187 7430 6188 7429 6188 6952 6188 7430 590 6952 590 7431 590 7431 590 6952 590 6951 590 7431 6189 6951 6189 7432 6189 7432 6190 6951 6190 7433 6190 7432 6191 7433 6191 7434 6191 7434 6192 7433 6192 6949 6192 6788 590 6789 590 6946 590 6946 6193 6789 6193 7435 6193 6946 6194 7435 6194 7436 6194 7436 6195 7435 6195 7437 6195 7436 6196 7437 6196 6949 6196 6949 6197 7437 6197 7438 6197 6949 6198 7438 6198 7434 6198 6788 590 6946 590 6787 590 6787 590 6946 590 7694 590 6787 590 7694 590 6785 590 7439 6199 7532 6199 6803 6199 6802 6200 7440 6200 7441 6200 7441 590 7440 590 7442 590 7441 590 7442 590 7443 590 7443 6201 7442 6201 7444 6201 7446 6202 6794 6202 7636 6202 6796 590 7445 590 6792 590 6792 590 7445 590 7636 590 6792 590 7636 590 6793 590 6793 590 7636 590 6794 590 7427 590 6791 590 7640 590 7640 6203 6791 6203 7446 6203 7640 6204 7446 6204 7634 6204 7634 590 7446 590 7636 590 7461 6205 7463 6205 7453 6205 7455 6206 7447 6206 7452 6206 7452 6207 7447 6207 7664 6207 7447 590 7448 590 7664 590 7664 6208 7448 6208 7449 6208 7664 6209 7449 6209 7457 6209 7457 6210 7449 6210 7450 6210 7457 6211 7450 6211 7451 6211 7461 6212 7453 6212 7452 6212 7452 6213 7453 6213 7454 6213 7452 6214 7454 6214 7455 6214 7451 590 7456 590 7457 590 7457 6215 7456 6215 7458 6215 7457 6216 7458 6216 7542 6216 7542 6217 7458 6217 7459 6217 7542 590 7459 590 7543 590 7543 6218 7459 6218 7460 6218 7543 590 7460 590 7461 590 7461 6219 7460 6219 7462 6219 7461 6220 7462 6220 7463 6220 7471 590 7464 590 7470 590 7470 6221 7464 6221 6835 6221 7470 6222 6835 6222 7716 6222 7716 6223 6835 6223 6834 6223 7716 6224 6834 6224 6833 6224 7465 6225 6830 6225 7466 6225 7466 6226 6830 6226 7467 6226 7466 6227 7467 6227 7704 6227 6843 6228 6842 6228 7563 6228 7563 6229 6842 6229 6839 6229 7472 590 7468 590 6836 590 6836 6230 7468 6230 7469 6230 6836 6231 7469 6231 6838 6231 6838 590 7469 590 6839 590 6924 6232 7563 6232 6925 6232 6925 590 7563 590 6839 590 6925 6233 6839 6233 6927 6233 6927 6234 6839 6234 7469 6234 7470 590 6932 590 7471 590 7471 590 6932 590 6930 590 7471 590 6930 590 7472 590 7472 590 6930 590 7473 590 7472 590 7473 590 7468 590 6819 590 6818 590 7563 590 7563 6235 6818 6235 6845 6235 7563 6236 6845 6236 6843 6236 7704 6237 6825 6237 7705 6237 7705 590 6825 590 6826 590 7705 590 6826 590 7706 590 7706 6238 6826 6238 6823 6238 7476 590 6847 590 7477 590 7477 6239 6847 6239 7474 6239 7477 6240 7474 6240 7475 6240 7475 6241 7474 6241 6849 6241 7475 6242 6849 6242 7504 6242 7495 6243 7497 6243 6938 6243 6938 6244 7497 6244 6846 6244 7476 590 7477 590 7478 590 7478 590 7477 590 6942 590 7478 6245 6942 6245 7479 6245 7479 590 6942 590 7481 590 7479 590 7481 590 7480 590 7480 6246 7481 6246 7482 6246 7480 6247 7482 6247 7484 6247 7484 6248 7482 6248 7483 6248 7484 6249 7483 6249 7485 6249 7485 6250 7483 6250 7486 6250 7485 590 7486 590 6846 590 6846 6251 7486 6251 6935 6251 6846 6252 6935 6252 6938 6252 6934 6253 6856 6253 7491 6253 7709 590 7487 590 7489 590 6934 590 7491 590 7492 590 7487 590 7488 590 7489 590 7489 6254 7488 6254 6858 6254 7489 590 6858 590 6934 590 6934 590 6858 590 7490 590 6934 6255 7490 6255 6856 6255 7491 590 7493 590 7492 590 7492 6256 7493 6256 7494 6256 7492 6257 7494 6257 7495 6257 7495 6258 7494 6258 7496 6258 7495 6259 7496 6259 7497 6259 7398 590 7498 590 7499 590 7499 6260 7498 6260 7711 6260 7499 6261 7711 6261 7500 6261 7500 590 7711 590 7501 590 7501 590 7711 590 7502 590 7501 6262 7502 6262 7503 6262 7504 6263 6852 6263 7691 6263 7691 6264 6852 6264 7505 6264 7691 590 7505 590 7503 590 7689 6265 7506 6265 7512 6265 7512 6266 7506 6266 6862 6266 6862 590 7506 590 7507 590 7507 6267 7506 6267 7681 6267 7507 590 7681 590 7680 590 7730 590 7508 590 7733 590 7733 590 7508 590 7732 590 7509 6268 7728 6268 7682 6268 7682 6269 7728 6269 7726 6269 7682 6270 7726 6270 7725 6270 7676 590 7654 590 7510 590 7510 590 7654 590 7516 590 7510 590 7516 590 7511 590 7511 6271 7516 6271 6864 6271 7512 590 7513 590 7689 590 7689 590 7513 590 6867 590 7689 6272 6867 6272 6865 6272 7514 590 7689 590 7516 590 7516 6273 7689 6273 6865 6273 7516 590 6865 590 6864 590 6875 590 6876 590 7515 590 7515 6274 6876 6274 6878 6274 7515 590 6878 590 7654 590 7654 6275 6878 6275 6879 6275 7654 590 6879 590 7516 590 7516 590 6879 590 7517 590 7516 4168 7517 4168 7514 4168 7523 590 7518 590 7519 590 7519 3484 7518 3484 6896 3484 7519 590 6896 590 7440 590 7440 590 6896 590 7520 590 7440 6276 7520 6276 7442 6276 7442 6277 7520 6277 6870 6277 7442 6278 6870 6278 7656 6278 7656 6279 6870 6279 7521 6279 7656 590 7521 590 7522 590 7502 6280 6894 6280 7523 6280 7523 6281 6894 6281 6895 6281 7523 590 6895 590 7518 590 7466 590 7526 590 7524 590 6891 6282 7712 6282 7525 6282 7525 590 7712 590 7710 590 7525 590 7710 590 6889 590 6889 590 7710 590 7489 590 6889 590 7489 590 7713 590 7707 6283 6887 6283 7526 6283 7526 6284 6887 6284 6888 6284 7526 590 6888 590 7524 590 6884 590 7708 590 7527 590 7519 6285 7528 6285 7523 6285 7523 6286 7528 6286 6902 6286 7523 590 6902 590 7693 590 6905 590 6915 590 6800 590 6800 6287 6915 6287 7529 6287 6800 590 7529 590 6802 590 6802 6288 7529 6288 6899 6288 6802 6289 6899 6289 7440 6289 7440 6290 6899 6290 6901 6290 6901 590 7530 590 7440 590 7440 6291 7530 6291 6898 6291 7440 590 6898 590 7519 590 7519 590 6898 590 7531 590 7519 590 7531 590 7396 590 6800 590 7532 590 6905 590 6905 590 7532 590 7439 590 6905 6292 7439 6292 7533 6292 7533 6293 7439 6293 6907 6293 7692 6294 7534 6294 7535 6294 7535 6295 7534 6295 6912 6295 6912 590 6911 590 7535 590 7535 6296 6911 6296 7536 6296 7535 590 7536 590 7439 590 7439 6297 7536 6297 7537 6297 7439 6298 7537 6298 6907 6298 7662 6299 7538 6299 7663 6299 7663 590 7538 590 7539 590 7663 6300 7539 6300 7393 6300 7393 590 7539 590 6975 590 7542 590 7540 590 7457 590 7457 6301 7540 6301 6972 6301 7457 590 6972 590 7664 590 7664 6302 6972 6302 7541 6302 6966 590 6964 590 6969 590 6971 590 7542 590 6969 590 6969 6303 7542 6303 7543 6303 6969 6304 7543 6304 6966 6304 6966 6305 7543 6305 7461 6305 6966 6306 7461 6306 6968 6306 6968 590 7461 590 11460 590 11460 590 7461 590 7452 590 11460 590 7452 590 7544 590 6957 6307 7545 6307 7547 6307 7545 6308 7546 6308 7548 6308 7547 590 7545 590 6919 590 6919 590 7545 590 7548 590 6919 6309 7548 6309 7555 6309 7558 6310 7549 6310 6917 6310 6917 6311 7549 6311 7550 6311 7551 590 7552 590 7560 590 7560 6312 7552 6312 7553 6312 7560 590 7553 590 7545 590 7545 6313 7553 6313 7554 6313 7545 6314 7554 6314 7546 6314 7555 6315 7556 6315 6919 6315 6919 590 7556 590 7557 590 6919 590 7557 590 7558 590 7558 6316 7557 6316 7559 6316 7558 6317 7559 6317 7549 6317 7565 590 7562 590 7560 590 7550 590 7551 590 6917 590 6917 6318 7551 6318 7560 6318 6917 590 7560 590 7561 590 7561 6319 7560 6319 7562 6319 6924 6320 6923 6320 7563 6320 7563 590 6923 590 6921 590 7563 6321 6921 6321 7564 6321 7564 590 6921 590 7565 590 7564 6322 7565 6322 7701 6322 7701 590 7565 590 7560 590 7428 6323 7566 6323 7568 6323 7568 590 7566 590 7567 590 7568 6324 7567 6324 7569 6324 7569 6325 7567 6325 7570 6325 7639 6326 6988 6326 7571 6326 7571 590 6988 590 6989 590 7571 6327 6989 6327 7567 6327 7567 6328 6989 6328 6956 6328 7567 590 6956 590 7570 590 7631 6329 7572 6329 7573 6329 7573 6330 7572 6330 6758 6330 7573 6331 6758 6331 6759 6331 7574 6332 7575 6332 7576 6332 7602 590 7579 590 7684 590 7679 6333 7577 6333 7578 6333 7579 590 7580 590 7684 590 7684 6334 7580 6334 7581 6334 7684 590 7581 590 7679 590 7679 6335 7581 6335 7582 6335 7679 6336 7582 6336 7577 6336 7575 6337 7583 6337 7576 6337 7576 6338 7583 6338 7584 6338 7576 590 7584 590 7585 590 7585 6339 7584 6339 7586 6339 7585 6340 7586 6340 7587 6340 6994 6341 7588 6341 7617 6341 7617 6342 7588 6342 7592 6342 7597 590 6960 590 7589 590 7589 590 6960 590 7617 590 7589 590 7617 590 7590 590 7590 590 7617 590 7592 590 7590 590 7592 590 7591 590 7591 6343 7592 6343 7593 6343 7591 590 7593 590 7594 590 7594 590 7593 590 7595 590 7596 590 7615 590 7599 590 7597 590 7598 590 6960 590 6960 6344 7598 6344 7600 6344 6960 590 7600 590 7599 590 7599 6345 7600 6345 7601 6345 7599 6346 7601 6346 7596 6346 7602 590 7684 590 7001 590 7001 590 7684 590 7603 590 7001 6347 7603 6347 7604 6347 7604 590 7603 590 7605 590 7604 590 7605 590 7606 590 7615 590 7607 590 7599 590 7599 6348 7607 6348 7608 6348 7599 6349 7608 6349 7603 6349 7603 6350 7608 6350 7609 6350 7603 6351 7609 6351 7605 6351 7595 590 7593 590 7610 590 7610 6352 7593 6352 7611 6352 7610 590 7611 590 6998 590 6998 590 7612 590 7610 590 7610 6353 7612 6353 7613 6353 7610 590 7613 590 7615 590 7615 6354 7613 6354 7614 6354 7615 6355 7614 6355 7607 6355 7587 6356 7616 6356 7585 6356 7585 590 7616 590 6992 590 7585 6357 6992 6357 7617 6357 7617 6358 6992 6358 6993 6358 7617 590 6993 590 6994 590 7618 6359 7009 6359 7625 6359 7625 6360 7009 6360 7619 6360 7005 6361 7004 6361 7699 6361 7699 6362 7004 6362 7002 6362 7699 6363 7002 6363 7690 6363 7620 590 7017 590 7681 590 7626 6364 7683 6364 7012 6364 7017 6365 7621 6365 7681 6365 7681 6366 7621 6366 7014 6366 7681 6367 7014 6367 7683 6367 7683 6368 7014 6368 7013 6368 7683 6369 7013 6369 7012 6369 7622 590 7623 590 7696 590 7382 590 7624 590 7626 590 7626 6370 7624 6370 7381 6370 7012 590 7618 590 7626 590 7626 590 7618 590 7625 590 7626 6371 7625 6371 7382 6371 7382 590 7625 590 7696 590 7382 590 7696 590 7385 590 7385 590 7696 590 7623 590 7381 590 7627 590 7626 590 7626 6372 7627 6372 7628 6372 7626 590 7628 590 7683 590 7683 6373 7628 6373 7629 6373 7629 590 7390 590 7683 590 7683 6374 7390 6374 7630 6374 7683 590 7630 590 7685 590 7685 6375 7630 6375 7389 6375 7639 590 7408 590 6986 590 6986 590 7408 590 7572 590 6986 590 7572 590 6984 590 6984 6376 7572 6376 7631 6376 7651 590 7638 590 7650 590 7637 590 7642 590 7636 590 7632 590 7634 590 7633 590 7633 6377 7634 6377 7646 6377 7641 590 7635 590 7412 590 6872 590 7653 590 7636 590 7636 6378 7653 6378 7650 6378 7636 4176 7650 4176 7637 4176 7637 590 7650 590 7638 590 7639 590 7571 590 7408 590 7408 590 7571 590 7640 590 7408 590 7640 590 7407 590 7407 6379 7640 6379 7634 6379 7407 590 7634 590 7412 590 7412 6380 7634 6380 7632 6380 7412 6381 7632 6381 7641 6381 7642 590 7643 590 7636 590 7636 6382 7643 6382 7644 6382 7636 6383 7644 6383 7634 6383 7634 590 7644 590 7645 590 7634 590 7645 590 7646 590 7635 590 7647 590 7412 590 7412 6384 7647 6384 7648 6384 7412 590 7648 590 7650 590 7650 590 7648 590 7649 590 7650 6385 7649 6385 7651 6385 7668 590 7544 590 7667 590 7667 590 7544 590 7452 590 7667 590 7452 590 7652 590 7652 590 7452 590 7664 590 7652 590 7664 590 7665 590 7653 6386 6875 6386 7650 6386 7650 590 6875 590 7515 590 7650 590 7515 590 7410 590 7410 590 7515 590 7654 590 7410 590 7654 590 7655 590 7655 590 7654 590 6773 590 6796 6387 7444 6387 7445 6387 7445 6388 7444 6388 7442 6388 7445 590 7442 590 7636 590 7636 590 7442 590 7656 590 7636 6389 7656 6389 6872 6389 6872 6390 7656 6390 7522 6390 7043 590 7041 590 7576 590 7659 6391 7048 6391 7657 6391 7677 590 7658 590 7659 590 7659 6392 7658 6392 7660 6392 7659 6393 7660 6393 7048 6393 7666 590 7045 590 7665 590 7665 590 7045 590 7044 590 7041 6394 7040 6394 7576 6394 7576 6395 7040 6395 7038 6395 7576 590 7038 590 7677 590 7677 6396 7038 6396 7661 6396 7677 6397 7661 6397 7658 6397 7541 6398 7662 6398 7664 6398 7664 590 7662 590 7663 590 7664 6399 7663 6399 7665 6399 7665 590 7663 590 7659 590 7665 590 7659 590 7666 590 7666 590 7659 590 7657 590 7044 590 7043 590 7665 590 7665 590 7043 590 7576 590 7665 590 7576 590 7652 590 7652 590 7576 590 7585 590 7652 590 7585 590 7667 590 7667 6400 7585 6400 7617 6400 7667 590 7617 590 7668 590 7668 590 7617 590 6960 590 7022 590 7669 590 7674 590 7669 590 7035 590 7674 590 7674 6401 7035 6401 7033 6401 7674 6402 7033 6402 7031 6402 6975 590 7416 590 7393 590 7393 6403 7416 6403 7674 6403 7393 590 7674 590 7659 590 7659 6404 7674 6404 7031 6404 7659 6405 7031 6405 7030 6405 7030 590 7670 590 7659 590 7659 6406 7670 6406 7671 6406 7659 6407 7671 6407 7677 6407 7677 6408 7671 6408 7672 6408 7672 590 7026 590 7677 590 7677 6409 7026 6409 7024 6409 7677 6410 7024 6410 7508 6410 7508 6411 7024 6411 7673 6411 7673 6412 7022 6412 7508 6412 7508 6413 7022 6413 7674 6413 7508 590 7674 590 7732 590 7732 590 7674 590 7654 590 7732 6414 7654 6414 7675 6414 7675 590 7654 590 7676 590 7730 590 7509 590 7508 590 7508 590 7509 590 7682 590 7508 590 7682 590 7677 590 7677 6415 7682 6415 7678 6415 7677 6416 7678 6416 7576 6416 7576 590 7678 590 7679 590 7576 590 7679 590 7574 590 7574 590 7679 590 7578 590 7725 590 7680 590 7682 590 7682 590 7680 590 7681 590 7682 590 7681 590 7678 590 7678 590 7681 590 7683 590 7678 6417 7683 6417 7679 6417 7679 590 7683 590 7685 590 7679 590 7685 590 7684 590 7684 590 7685 590 7686 590 7684 590 7686 590 7603 590 7603 590 7686 590 7687 590 7603 590 7687 590 7599 590 7599 590 7687 590 6959 590 7389 6418 7388 6418 7685 6418 7685 590 7388 590 7394 590 7685 590 7394 590 7686 590 7686 590 7394 590 7695 590 7686 590 7695 590 7687 590 7687 6419 7695 6419 7698 6419 7687 590 7698 590 6959 590 6959 590 7698 590 7688 590 7514 590 6882 590 7689 590 7689 590 6882 590 6884 590 7689 6420 6884 6420 7506 6420 7506 6421 6884 6421 7527 6421 7506 590 7527 590 7681 590 7681 590 7527 590 7699 590 7681 590 7699 590 7620 590 7620 590 7699 590 7690 590 7503 590 7502 590 7691 590 7691 590 7502 590 7523 590 7691 590 7523 590 7692 590 7692 6422 7523 6422 7693 6422 7692 6423 7693 6423 7534 6423 7504 590 7691 590 7475 590 7475 590 7691 590 7692 590 7475 590 7692 590 6943 590 6943 590 7692 590 7535 590 6943 590 7535 590 6945 590 6945 6424 7535 6424 7439 6424 6945 6425 7439 6425 7694 6425 7694 590 7439 590 6803 590 7694 6426 6803 6426 6785 6426 7387 6427 7622 6427 7394 6427 7394 590 7622 590 7696 590 7394 590 7696 590 7695 590 7695 590 7696 590 7702 590 7695 590 7702 590 7698 590 7698 6428 7702 6428 7697 6428 7698 6429 7697 6429 7688 6429 7688 590 7697 590 7703 590 7527 590 7706 590 7699 590 7699 6430 7706 6430 7700 6430 7699 6431 7700 6431 7005 6431 7005 590 7700 590 7625 590 7005 590 7625 590 7007 590 7007 590 7625 590 7619 590 6823 590 6821 590 7706 590 7706 6432 6821 6432 6819 6432 7706 590 6819 590 7700 590 7700 590 6819 590 7563 590 7700 3639 7563 3639 7625 3639 7625 3638 7563 3638 7564 3638 7625 590 7564 590 7696 590 7696 590 7564 590 7701 590 7696 590 7701 590 7702 590 7702 590 7701 590 7560 590 7702 590 7560 590 7697 590 7697 590 7560 590 7545 590 7697 590 7545 590 7703 590 7703 590 7545 590 7395 590 7704 590 7705 590 7466 590 7466 6433 7705 6433 7706 6433 7466 590 7706 590 7526 590 7526 6434 7706 6434 7527 6434 7526 590 7527 590 7707 590 7707 6435 7527 6435 7708 6435 7707 590 7708 590 6886 590 7709 590 7489 590 7498 590 7498 6436 7489 6436 7710 6436 7498 590 7710 590 7711 590 7711 6437 7710 6437 7712 6437 7711 590 7712 590 7502 590 7502 6438 7712 6438 7397 6438 7502 6439 7397 6439 6894 6439 7489 590 6815 590 6813 590 7524 590 7713 590 7466 590 7466 6440 7713 6440 7489 6440 7466 4332 7489 4332 7714 4332 7714 590 7489 590 6813 590 6807 6441 6806 6441 7716 6441 7714 590 7715 590 7466 590 7466 6442 7715 6442 6810 6442 7466 6443 6810 6443 6809 6443 6833 6444 7465 6444 7716 6444 7716 590 7465 590 7466 590 7716 590 7466 590 6807 590 6807 590 7466 590 6809 590 6806 590 7717 590 7716 590 7716 6445 7717 6445 7718 6445 7716 590 7718 590 6934 590 6934 6446 7718 6446 7719 6446 6934 6447 7719 6447 7720 6447 7720 6448 7721 6448 6934 6448 6934 6449 7721 6449 7722 6449 6934 6450 7722 6450 7489 6450 7489 590 7722 590 7723 590 7489 6451 7723 6451 6815 6451 7151 6452 7507 6452 7270 6452 7270 6452 7507 6452 7680 6452 7270 6453 7680 6453 7724 6453 7680 6454 7725 6454 7724 6454 7724 6455 7725 6455 7726 6455 7724 6455 7726 6455 7727 6455 7727 6456 7726 6456 7728 6456 7727 6456 7728 6456 7146 6456 7146 6457 7728 6457 7509 6457 7146 6458 7509 6458 7729 6458 7729 6459 7509 6459 7730 6459 7729 6460 7730 6460 7731 6460 7731 6461 7730 6461 7733 6461 7675 6462 6868 6462 7732 6462 7732 6463 6868 6463 7148 6463 7732 6464 7148 6464 7733 6464 7733 6464 7148 6464 7734 6464 7733 6465 7734 6465 7731 6465 7996 6466 8373 6466 7735 6466 7735 6467 8373 6467 8369 6467 7735 6468 8369 6468 7997 6468 7997 6469 8369 6469 8693 6469 7997 6470 8693 6470 7988 6470 7988 6471 8693 6471 7736 6471 8373 6472 7996 6472 7737 6472 8373 6472 7737 6472 8372 6472 8372 3785 7737 3785 7738 3785 8372 3785 7738 3785 7739 3785 7743 6473 8366 6473 7740 6473 7740 6474 8366 6474 7741 6474 7740 6475 7741 6475 7995 6475 7995 6476 7741 6476 7742 6476 7995 6477 7742 6477 7738 6477 7738 6478 7742 6478 7739 6478 8366 6479 7743 6479 7744 6479 8366 6480 7744 6480 8666 6480 8666 6481 7744 6481 7745 6481 8666 6482 7745 6482 8667 6482 8667 6483 7745 6483 7746 6483 8667 6483 7746 6483 7761 6483 7993 6484 7747 6484 7748 6484 7748 6484 7747 6484 7749 6484 7748 6485 7749 6485 7750 6485 7750 6486 7749 6486 8529 6486 7750 6487 8529 6487 7986 6487 7986 6488 8529 6488 7751 6488 7986 6489 7751 6489 7752 6489 7752 6489 7751 6489 8361 6489 7752 6490 8361 6490 7753 6490 7753 6491 8361 6491 8365 6491 7760 6492 7754 6492 7755 6492 7760 6493 7755 6493 8362 6493 8362 6494 7755 6494 7756 6494 8362 6495 7756 6495 8363 6495 8363 6496 7756 6496 7757 6496 8363 6496 7757 6496 7758 6496 7758 6497 7757 6497 7753 6497 7758 6498 7753 6498 8365 6498 7754 6499 7760 6499 7759 6499 7759 6500 7760 6500 8368 6500 7759 6501 8368 6501 7746 6501 7746 6502 8368 6502 7761 6502 8002 6503 7762 6503 8387 6503 8387 6503 7762 6503 7763 6503 8496 6504 7999 6504 7764 6504 7764 6505 7999 6505 8009 6505 7764 6506 8009 6506 7765 6506 7765 6507 8009 6507 8010 6507 7765 6508 8010 6508 7766 6508 7766 6509 8010 6509 8013 6509 7766 6510 8013 6510 7767 6510 7767 6511 8013 6511 8015 6511 7768 6512 7769 6512 8019 6512 7770 6513 7774 6513 8375 6513 8375 6514 7774 6514 8354 6514 7770 6515 8375 6515 7771 6515 7771 6516 8375 6516 8374 6516 7771 6517 8374 6517 8019 6517 8019 6518 8374 6518 8380 6518 8019 6519 8380 6519 7768 6519 7775 6520 7772 6520 7773 6520 7773 6520 7772 6520 8486 6520 7773 6521 8486 6521 7774 6521 7774 6522 8486 6522 8354 6522 7772 6523 7775 6523 7776 6523 7780 6524 8388 6524 8021 6524 8021 6525 8388 6525 7777 6525 8021 6526 7777 6526 7776 6526 7776 6526 7777 6526 8484 6526 7776 6527 8484 6527 7772 6527 7778 6528 7779 6528 8253 6528 8253 6529 7779 6529 8390 6529 8253 6530 8390 6530 8023 6530 8023 6531 8390 6531 7781 6531 8023 6532 7781 6532 7780 6532 7780 6532 7781 6532 8388 6532 8391 6533 8024 6533 8690 6533 8690 6534 8024 6534 8028 6534 8690 6535 8028 6535 7782 6535 7782 6536 8028 6536 8027 6536 7782 6537 8027 6537 8694 6537 8694 6537 8027 6537 7783 6537 8607 6538 8606 6538 8331 6538 8331 6539 8606 6539 7784 6539 8610 6540 8327 6540 8326 6540 8610 6541 8326 6541 8611 6541 8611 5436 8326 5436 7785 5436 8611 5437 7785 5437 7786 5437 7786 6542 7785 6542 7787 6542 7786 6543 7787 6543 8599 6543 8599 6544 7787 6544 8333 6544 8599 6545 8333 6545 7788 6545 7788 6546 8333 6546 8332 6546 7788 6547 8332 6547 8604 6547 8604 6548 8332 6548 7784 6548 8604 6549 7784 6549 8606 6549 8610 6550 8609 6550 8327 6550 8327 3945 8609 3945 7793 3945 8607 6551 8331 6551 7789 6551 8607 6552 7789 6552 8608 6552 8608 6553 7789 6553 8329 6553 8608 6554 8329 6554 8600 6554 8600 3703 8329 3703 8328 3703 8600 5431 8328 5431 8601 5431 8601 6555 8328 6555 7790 6555 8601 6556 7790 6556 7791 6556 7791 6557 7790 6557 7792 6557 7791 6558 7792 6558 8602 6558 8602 3709 7792 3709 7793 3709 8602 3710 7793 3710 8609 3710 8318 6559 8618 6559 7794 6559 7794 6560 8618 6560 7795 6560 7794 6561 7795 6561 7796 6561 7796 6562 7795 6562 7797 6562 7796 6563 7797 6563 8054 6563 8054 6564 7797 6564 7798 6564 8052 6565 8416 6565 7799 6565 7799 6566 8416 6566 7801 6566 7799 6567 7801 6567 7800 6567 7800 6567 7801 6567 8612 6567 8406 6568 7809 6568 7802 6568 8406 6569 7802 6569 7804 6569 7804 6570 7802 6570 7803 6570 7804 6571 7803 6571 8409 6571 8409 6572 7803 6572 7805 6572 8409 6573 7805 6573 8401 6573 8401 6574 7805 6574 7800 6574 8401 6575 7800 6575 8612 6575 7809 6576 8406 6576 8405 6576 8411 6577 8044 6577 7806 6577 7806 6578 8044 6578 7807 6578 7806 6579 7807 6579 8405 6579 8405 6580 7807 6580 7808 6580 8405 6581 7808 6581 7809 6581 7810 6582 7815 6582 7811 6582 7810 6583 7811 6583 7812 6583 7812 6584 7811 6584 7813 6584 7812 6584 7813 6584 8413 6584 8413 6585 7813 6585 7814 6585 8413 6586 7814 6586 8412 6586 8412 6587 7814 6587 8044 6587 8412 6588 8044 6588 8411 6588 7810 6589 8415 6589 7815 6589 7815 6590 8415 6590 8047 6590 7816 6591 7817 6591 7818 6591 7818 6592 7817 6592 8432 6592 7818 6593 8432 6593 8067 6593 8067 6594 8432 6594 8425 6594 8073 6595 8072 6595 7819 6595 7819 6596 8072 6596 7820 6596 8083 6597 8441 6597 7821 6597 7821 6598 8441 6598 7822 6598 7821 6599 7822 6599 8323 6599 8323 6600 7822 6600 8622 6600 8323 6601 8622 6601 7823 6601 7823 6602 8622 6602 8621 6602 8087 6603 8648 6603 8088 6603 8088 6604 8648 6604 7824 6604 8088 6605 7824 6605 7825 6605 7825 6606 7824 6606 7826 6606 7853 6607 8470 6607 8108 6607 8108 6608 8470 6608 8471 6608 8108 6609 8471 6609 7827 6609 7827 6610 8471 6610 7828 6610 7827 6611 7828 6611 8257 6611 8257 6612 7828 6612 8473 6612 8257 6613 8473 6613 8256 6613 8256 6614 8473 6614 7829 6614 8256 6615 7829 6615 8235 6615 8235 6616 7829 6616 7830 6616 8235 6617 7830 6617 8251 6617 8251 6618 7830 6618 8673 6618 8251 6619 8673 6619 8104 6619 8104 6620 8673 6620 7831 6620 8104 6621 7831 6621 8105 6621 8105 6622 7831 6622 8476 6622 8105 6623 8476 6623 8106 6623 8106 6624 8476 6624 7832 6624 8106 6625 7832 6625 8121 6625 8121 6626 7832 6626 7833 6626 8121 6627 7833 6627 7835 6627 7835 6628 7833 6628 7834 6628 7835 6629 7834 6629 7836 6629 7836 6630 7834 6630 7837 6630 7836 6631 7837 6631 8118 6631 8118 6631 7837 6631 8474 6631 8118 6632 8474 6632 8322 6632 8322 6633 8474 6633 8461 6633 8322 6634 8461 6634 7838 6634 7838 6635 8461 6635 7839 6635 7838 6636 7839 6636 8113 6636 8113 6637 7839 6637 8469 6637 8113 6638 8469 6638 7840 6638 7840 6639 8469 6639 8468 6639 7840 6640 8468 6640 8114 6640 8114 6641 8468 6641 7841 6641 8114 6642 7841 6642 8115 6642 8115 6643 7841 6643 7842 6643 8115 6644 7842 6644 8116 6644 8116 6645 7842 6645 8465 6645 8116 6646 8465 6646 7843 6646 7843 173 8465 173 7845 173 7843 6647 7845 6647 7844 6647 7844 6648 7845 6648 7847 6648 7844 6649 7847 6649 7846 6649 7846 6649 7847 6649 8462 6649 7846 6650 8462 6650 7849 6650 7849 6651 8462 6651 7848 6651 7849 6652 7848 6652 8110 6652 8110 6653 7848 6653 7850 6653 8110 6654 7850 6654 7851 6654 7851 6655 7850 6655 8631 6655 7851 6656 8631 6656 7852 6656 7852 6657 8631 6657 8632 6657 7852 6658 8632 6658 7853 6658 7853 6659 8632 6659 8470 6659 7854 6660 7855 6660 7856 6660 7856 6661 7855 6661 8020 6661 7856 6662 8020 6662 7857 6662 8020 6663 7858 6663 7857 6663 7857 6664 7858 6664 7859 6664 7857 3708 7859 3708 8488 3708 8488 6665 7859 6665 7860 6665 8488 6666 7860 6666 8490 6666 8490 5434 7860 5434 7861 5434 8490 6667 7861 6667 7865 6667 7865 6668 7861 6668 7862 6668 8302 6669 8492 6669 7864 6669 7864 6670 8492 6670 7863 6670 7864 6671 7863 6671 7862 6671 7862 6671 7863 6671 8491 6671 7862 5437 8491 5437 7865 5437 8523 6672 7866 6672 8524 6672 8524 6673 7866 6673 8137 6673 8524 6674 8137 6674 7867 6674 7867 6675 8137 6675 7869 6675 7867 6676 7869 6676 7868 6676 7868 6677 7869 6677 8039 6677 7868 6678 8039 6678 7870 6678 7870 6679 8039 6679 7871 6679 8139 6680 8519 6680 8140 6680 8140 6681 8519 6681 8518 6681 8140 3885 8518 3885 7871 3885 7871 3886 8518 3886 7870 3886 8143 6682 7873 6682 7872 6682 7872 6683 7873 6683 8511 6683 7872 6684 8511 6684 7874 6684 7874 6685 8511 6685 8641 6685 7874 6686 8641 6686 8300 6686 8300 6687 8641 6687 8635 6687 8300 6688 8635 6688 7875 6688 7875 3944 8635 3944 7876 3944 7875 6689 7876 6689 7877 6689 7877 6690 7876 6690 8552 6690 7877 6691 8552 6691 7878 6691 7878 6692 8552 6692 7880 6692 7878 6693 7880 6693 7879 6693 7879 6694 7880 6694 8670 6694 7879 6695 8670 6695 7881 6695 7881 6696 8670 6696 8671 6696 7881 6697 8671 6697 8263 6697 8263 6698 8671 6698 2962 6698 8513 6699 7873 6699 7882 6699 7882 6700 7873 6700 8143 6700 8150 3986 8505 3986 8147 3986 8147 3987 8505 3987 8512 3987 8147 6701 8512 6701 7882 6701 7882 6702 8512 6702 8513 6702 8505 6703 8150 6703 8503 6703 8503 6704 8150 6704 8154 6704 8503 6705 8154 6705 7883 6705 7883 6706 8154 6706 8160 6706 8160 6707 7885 6707 7883 6707 7883 6708 7885 6708 8498 6708 8498 6709 7885 6709 7884 6709 7884 6710 7885 6710 8161 6710 7884 6711 8161 6711 7886 6711 7886 6711 8161 6711 7888 6711 7886 6712 7888 6712 7887 6712 7887 6713 7888 6713 7890 6713 7887 6714 7890 6714 7889 6714 7889 6715 7890 6715 7891 6715 7889 6716 7891 6716 7893 6716 7889 6717 7893 6717 7892 6717 7892 6718 7893 6718 8050 6718 7892 6718 8050 6718 8408 6718 8408 6719 8050 6719 8049 6719 8408 6720 8049 6720 8407 6720 8407 6721 8049 6721 8051 6721 8407 6722 8051 6722 8404 6722 8404 6723 8051 6723 7894 6723 8404 6724 7894 6724 7895 6724 7895 6725 7894 6725 7896 6725 7895 6726 7896 6726 8403 6726 7904 6727 7902 6727 7897 6727 7897 6728 7902 6728 7898 6728 7897 6729 7898 6729 8526 6729 8526 6730 7898 6730 8270 6730 8526 6731 8270 6731 8527 6731 8527 6732 8270 6732 8135 6732 8527 6733 8135 6733 8521 6733 8521 6734 8135 6734 8134 6734 7940 6735 7984 6735 7900 6735 7940 6736 7900 6736 7899 6736 7899 6737 7900 6737 7901 6737 7899 6738 7901 6738 7903 6738 7903 6739 7901 6739 7902 6739 7903 6740 7902 6740 7904 6740 7905 6741 7906 6741 8410 6741 8410 6742 7906 6742 8045 6742 8410 6743 8045 6743 8603 6743 8603 6744 8045 6744 8330 6744 8603 6745 8330 6745 8421 6745 8421 6746 8330 6746 8325 6746 8421 6747 8325 6747 8423 6747 8423 6748 8325 6748 8078 6748 7909 6749 8431 6749 7908 6749 8423 6750 8078 6750 7907 6750 7907 6750 8078 6750 8059 6750 7907 6751 8059 6751 7908 6751 7908 6752 8059 6752 8060 6752 7908 6753 8060 6753 7909 6753 8068 6754 7910 6754 8069 6754 8069 6755 7910 6755 7911 6755 8069 6756 7911 6756 7909 6756 7909 6757 7911 6757 8431 6757 7910 6758 8068 6758 8066 6758 7914 6759 7913 6759 8064 6759 8064 6760 7913 6760 7912 6760 8064 6761 7912 6761 8066 6761 8066 6762 7912 6762 8426 6762 8066 6763 8426 6763 7910 6763 7913 6764 7914 6764 7915 6764 7915 6765 7914 6765 8057 6765 7915 6766 8057 6766 7916 6766 7916 6767 8057 6767 7918 6767 7916 3872 7918 3872 7917 3872 7917 6768 7918 6768 8304 6768 7917 6769 8304 6769 8647 6769 8647 6770 8304 6770 7919 6770 8647 6771 7919 6771 8646 6771 8646 6772 7919 6772 8306 6772 8646 6773 8306 6773 8379 6773 8379 6774 8306 6774 7920 6774 8379 6775 7920 6775 8378 6775 8378 6776 7920 6776 8018 6776 7922 6777 7921 6777 8376 6777 8378 6778 8018 6778 8377 6778 8377 6779 8018 6779 8017 6779 8377 6780 8017 6780 8376 6780 8376 6781 8017 6781 8011 6781 8376 6782 8011 6782 7922 6782 7921 6783 7922 6783 8381 6783 8381 6784 7922 6784 7923 6784 8381 6785 7923 6785 7924 6785 7924 6786 7923 6786 7925 6786 7924 6787 7925 6787 7926 6787 7926 6788 7925 6788 7927 6788 7926 6789 7927 6789 7928 6789 7928 6790 7927 6790 8008 6790 7928 6791 8008 6791 7929 6791 7929 6792 8008 6792 8164 6792 7929 6793 8164 6793 8165 6793 7937 6794 7931 6794 7930 6794 7930 6795 7931 6796 8697 6797 7930 6798 8697 6798 8165 6798 8165 6799 8697 6799 7932 6799 8165 6793 7932 6793 7929 6793 7939 6800 7933 6800 7934 6800 7934 6801 7933 6801 8701 6801 7934 6802 8701 6802 8237 6802 8237 6803 8701 6803 7935 6803 8237 6804 7935 6804 7936 6804 7936 6805 7935 6805 7938 6805 7936 6806 7938 6806 7937 6806 7937 6806 7938 6806 7931 6806 8530 6807 7933 6807 8166 6807 8166 6808 7933 6808 7939 6808 7984 6809 7940 6809 7985 6809 7985 6810 7940 6810 7942 6810 7985 6811 7942 6811 7941 6811 7941 6812 7942 6812 7944 6812 7941 6813 7944 6813 7943 6813 7943 6814 7944 6814 8360 6814 7943 6815 8360 6815 7945 6815 7945 6816 8360 6816 8359 6816 7945 6817 8359 6817 7987 6817 7987 6818 8359 6818 8358 6818 7987 6819 8358 6819 8166 6819 8166 6820 8358 6820 8530 6820 7946 6821 7947 6821 7948 6821 7948 6822 7947 6822 7949 6822 7948 6823 7949 6823 8570 6823 8570 6824 7949 6824 8202 6824 8570 6825 8202 6825 7950 6825 7950 6826 8202 6826 7951 6826 7952 6827 8195 6827 8563 6827 8563 6538 8195 6538 8561 6538 7953 6828 8543 6828 8170 6828 8170 6829 8543 6829 8544 6829 8170 6830 8544 6830 8259 6830 8259 6831 8544 6831 7954 6831 8259 6832 7954 6832 8188 6832 8188 6833 7954 6833 8546 6833 8290 6834 7955 6834 8541 6834 8541 6834 7955 6834 8651 6834 8657 4052 7956 4052 8659 4052 8659 2977 7956 2977 8278 2977 8659 6835 8278 6835 8660 6835 8660 6836 8278 6836 8280 6836 8660 2980 8280 2980 7957 2980 7957 6837 8280 6837 7959 6837 7957 6838 7959 6838 7958 6838 7958 6839 7959 6839 7961 6839 7958 6840 7961 6840 7960 6840 7960 6841 7961 6841 7962 6841 7960 6842 7962 6842 8654 6842 8654 6843 7962 6843 8284 6843 8654 2989 8284 2989 7963 2989 7963 2991 8284 2991 8282 2991 7963 6844 8282 6844 8350 6844 8350 3020 8282 3020 8287 3020 8350 2998 8287 2998 8655 2998 8655 2970 8287 2970 7964 2970 8655 2999 7964 2999 8656 2999 8656 3000 7964 3000 7965 3000 8656 3001 7965 3001 7966 3001 7966 6845 7965 6845 8279 6845 7966 6846 8279 6846 8657 6846 8657 2976 8279 2976 7956 2976 8649 2975 8267 2975 8650 2975 8650 2977 8267 2977 8266 2977 8650 2978 8266 2978 7967 2978 7967 4080 8266 4080 7968 4080 7967 4058 7968 4058 7969 4058 7969 4060 7968 4060 8269 4060 7969 4081 8269 4081 7970 4081 7970 3341 8269 3341 8268 3341 7970 3342 8268 3342 7971 3342 7971 3343 8268 3343 7973 3343 7971 3344 7973 3344 7972 3344 7972 5816 7973 5816 7974 5816 7972 5816 7974 5816 7975 5816 7975 6145 7974 6145 8264 6145 7975 5819 8264 5819 7976 5819 7976 6146 8264 6146 8265 6146 7976 6147 8265 6147 7977 6147 7977 6847 8265 6847 7979 6847 7977 6847 7979 6847 7978 6847 7978 3000 7979 3000 7980 3000 7978 3001 7980 3001 7982 3001 7982 2973 7980 2973 7981 2973 7982 2974 7981 2974 8649 2974 8649 2976 7981 2976 8267 2976 8280 590 8278 590 8281 590 8032 590 8271 590 8276 590 8342 590 8341 590 8298 590 7923 590 8014 590 7925 590 8143 590 7872 590 8317 590 7858 590 8020 590 8305 590 8113 590 8112 590 7838 590 8323 6387 8082 6387 7821 6387 7993 590 7748 590 7991 590 7983 6229 7756 6229 7755 6229 7898 6848 7902 6848 7983 6848 7983 6849 7902 6849 7901 6849 7983 590 7901 590 7756 590 7756 6850 7901 6850 7900 6850 7756 6851 7900 6851 7757 6851 7757 590 7900 590 7984 590 7757 590 7984 590 7753 590 7753 6852 7984 6852 7752 6852 7984 6853 7985 6853 7752 6853 7752 590 7985 590 7941 590 7752 590 7941 590 7986 590 7986 6854 7941 6854 7943 6854 7986 590 7943 590 7750 590 7750 590 7943 590 7945 590 7750 590 7945 590 7987 590 8244 590 7997 590 8238 590 8238 590 7997 590 7988 590 8238 590 7988 590 8230 590 7988 590 7989 590 8230 590 8230 6855 7989 6855 7990 6855 8230 590 7990 590 7991 590 7991 6856 7990 6856 7992 6856 7991 590 7992 590 7993 590 7743 590 7740 590 7994 590 7994 590 7740 590 7995 590 7994 6857 7995 6857 8245 6857 8245 590 7995 590 7738 590 7738 590 7737 590 8245 590 8245 6226 7737 6226 7996 6226 8245 6858 7996 6858 8244 6858 8244 6859 7996 6859 7735 6859 8244 590 7735 590 7997 590 7745 590 7744 590 7998 590 7755 6228 7754 6228 7983 6228 7983 6236 7754 6236 7759 6236 7983 590 7759 590 8277 590 8277 6860 7759 6860 7746 6860 7999 6861 8000 6861 8163 6861 8163 6862 8000 6862 8001 6862 8003 590 8005 590 8002 590 8002 590 8005 590 8163 590 8002 6863 8163 6863 7762 6863 7762 590 8163 590 8001 590 8003 590 8004 590 8005 590 8005 6864 8004 6864 8006 6864 8005 6865 8006 6865 8007 6865 8007 6866 8006 6866 7783 6866 8008 6867 7927 6867 8009 6867 8009 590 7927 590 8010 590 8015 6868 8011 6868 8012 6868 8012 6246 8011 6246 8017 6246 8012 590 8017 590 8705 590 7927 6869 7925 6869 8010 6869 8010 6870 7925 6870 8014 6870 8010 590 8014 590 8013 590 8013 6871 8014 6871 7923 6871 8013 3551 7923 3551 8015 3551 8015 6872 7923 6872 7922 6872 8015 6248 7922 6248 8011 6248 8705 6873 8017 6873 8016 6873 8016 590 8017 590 8018 590 8016 590 8018 590 7769 590 7769 590 8018 590 7920 590 7769 590 7920 590 8019 590 8306 6874 7770 6874 7920 6874 7920 6875 7770 6875 7771 6875 7920 6876 7771 6876 8019 6876 7774 6877 8305 6877 7773 6877 7773 6878 8305 6878 8020 6878 7773 6879 8020 6879 7775 6879 7775 6880 8020 6880 7855 6880 7775 590 7855 590 7776 590 7776 590 8124 590 8021 590 8021 590 8124 590 8022 590 8021 6261 8022 6261 7780 6261 7780 590 8022 590 8023 590 8028 6881 8024 6881 8025 6881 8253 590 8254 590 7778 590 7778 590 8254 590 8025 590 7778 590 8025 590 8026 590 8026 590 8025 590 8024 590 7783 590 8027 590 8007 590 8007 590 8027 590 8028 590 8007 590 8028 590 8239 590 8239 590 8028 590 8025 590 8043 6882 8029 6882 8141 6882 8273 6883 8030 6883 8032 6883 8032 6312 8030 6312 8031 6312 8032 590 8031 590 8136 590 8136 6884 8031 6884 8033 6884 8136 6885 8033 6885 8034 6885 8029 590 8035 590 8274 590 8274 6308 8035 6308 8272 6308 8034 590 8036 590 8136 590 8136 6886 8036 6886 8037 6886 8136 590 8037 590 8039 590 8039 6887 8037 6887 8038 6887 8039 6888 8038 6888 8040 6888 8040 6889 8038 6889 8041 6889 8040 590 8041 590 8141 590 8141 590 8041 590 8042 590 8141 590 8042 590 8043 590 8046 6890 8048 6890 8318 6890 7807 590 8044 590 8045 590 8045 6891 8044 6891 7814 6891 8045 590 7814 590 8330 590 8330 6892 7814 6892 7813 6892 7813 590 7811 590 8330 590 8330 6893 7811 6893 7815 6893 8330 590 7815 590 8046 590 8046 6894 7815 6894 8047 6894 8046 6175 8047 6175 8048 6175 7805 590 7803 590 8313 590 7805 590 8313 590 7800 590 7803 6895 7802 6895 8049 6895 8049 6161 7802 6161 7809 6161 8049 590 7809 590 8051 590 8051 6896 7809 6896 7808 6896 7891 590 8313 590 7893 590 7893 6163 8313 6163 7803 6163 7893 590 7803 590 8050 590 8050 590 7803 590 8049 590 8045 590 7906 590 7807 590 7807 6897 7906 6897 7896 6897 7807 6898 7896 6898 7808 6898 7808 6899 7896 6899 7894 6899 7808 6900 7894 6900 8051 6900 8312 590 8052 590 8313 590 8313 6901 8052 6901 7799 6901 8313 6176 7799 6176 7800 6176 8318 590 7794 590 8053 590 8053 590 7794 590 7796 590 8053 590 7796 590 8319 590 8319 6902 7796 6902 8054 6902 8055 590 7918 590 8056 590 8056 590 7918 590 8057 590 8056 6903 8057 6903 8058 6903 8058 590 8057 590 8061 590 8059 590 8081 590 8060 590 8060 6904 8081 6904 7816 6904 8061 590 8057 590 8062 590 8062 6905 8057 6905 7914 6905 8062 590 7914 590 8063 590 8063 6906 7914 6906 8064 6906 8063 590 8064 590 8065 590 8065 6192 8064 6192 8066 6192 8065 590 8066 590 8067 590 8067 6190 8066 6190 8068 6190 8067 6907 8068 6907 7818 6907 7818 590 8068 590 8069 590 7818 590 8069 590 7816 590 7816 590 8069 590 7909 590 7816 590 7909 590 8060 590 8323 590 7823 590 8070 590 7823 590 8071 590 8070 590 8070 6908 8071 6908 8072 6908 8070 590 8072 590 8325 590 8325 6909 8072 6909 8073 6909 8325 6910 8073 6910 8074 6910 8074 590 8075 590 8325 590 8325 6911 8075 6911 8076 6911 8325 6912 8076 6912 8078 6912 8076 590 8077 590 8078 590 8078 6913 8077 6913 8079 6913 8078 590 8079 590 8059 590 8059 6914 8079 6914 8080 6914 8059 6915 8080 6915 8081 6915 7821 590 8082 590 8083 590 8083 6916 8082 6916 8085 6916 8083 6917 8085 6917 8084 6917 8084 590 8085 590 8086 590 8086 590 8085 590 8109 590 8086 590 8109 590 7825 590 8055 6918 8087 6918 8301 6918 8301 6919 8087 6919 8088 6919 8301 590 8088 590 7825 590 8089 590 8090 590 8216 590 8090 6920 8091 6920 8309 6920 8309 6921 8091 6921 8120 6921 8095 590 8092 590 8291 590 8093 590 8094 590 8281 590 8281 6922 8094 6922 8288 6922 8095 6923 8291 6923 8289 6923 8096 590 8093 590 7998 590 7998 6924 8093 6924 8277 6924 7998 590 8277 590 7745 590 7745 590 8277 590 7746 590 8097 6925 8107 6925 8098 6925 8098 6926 8107 6926 8119 6926 8098 6927 8119 6927 8099 6927 8099 590 8119 590 8100 590 8097 590 8101 590 8107 590 8107 6928 8101 6928 8102 6928 8107 6929 8102 6929 7998 6929 7998 6930 8102 6930 8103 6930 7998 590 8103 590 8096 590 8251 6931 8104 6931 8252 6931 8252 590 8104 590 8105 590 8252 6932 8105 6932 7998 6932 7998 590 8105 590 8106 590 7998 6933 8106 6933 8107 6933 8111 6934 7851 6934 8126 6934 8126 590 7851 590 7852 590 8126 590 7852 590 8124 590 8124 3484 7852 3484 7853 3484 8124 590 7853 590 8022 590 8022 590 7853 590 8108 590 8022 590 8108 590 8255 590 8255 6935 8108 6935 7827 6935 8255 6936 7827 6936 8257 6936 8109 6937 7849 6937 8111 6937 8111 6938 7849 6938 8110 6938 8111 6939 8110 6939 7851 6939 8112 590 8113 590 8321 590 8113 590 7840 590 8321 590 8321 6940 7840 6940 8114 6940 8321 590 8114 590 8046 590 8046 6941 8114 6941 8115 6941 8046 4332 8115 4332 8070 4332 8070 590 8115 590 8116 590 8070 6389 8116 6389 8324 6389 8324 590 8116 590 7843 590 8324 590 7843 590 8117 590 8117 6942 7843 6942 7844 6942 8117 590 7844 590 7846 590 8322 6943 8320 6943 8118 6943 8118 590 8320 590 8309 590 8118 590 8309 590 8119 590 8119 6944 8309 6944 8120 6944 8119 590 8120 590 8100 590 8106 590 8121 590 8107 590 8107 590 8121 590 7835 590 8107 590 7835 590 8119 590 8119 4168 7835 4168 7836 4168 8119 6945 7836 6945 8118 6945 7855 590 8122 590 7776 590 7776 6946 8122 6946 8123 6946 7776 6947 8123 6947 8124 6947 8124 590 8123 590 8128 590 8129 590 8126 590 8125 590 8125 590 8126 590 8124 590 8125 6948 8124 6948 8127 6948 8127 590 8124 590 8128 590 8129 590 8130 590 8126 590 8126 6290 8130 6290 8131 6290 8126 590 8131 590 8111 590 8111 6949 8131 6949 8132 6949 8111 6950 8132 6950 8302 6950 8133 590 7864 590 8303 590 8303 6951 7864 6951 7862 6951 7862 6952 7861 6952 8303 6952 8303 590 7861 590 7860 590 8303 590 7860 590 8305 590 8305 6953 7860 6953 7859 6953 8305 6954 7859 6954 7858 6954 8286 590 8270 590 7898 590 8032 6955 8134 6955 8271 6955 8271 590 8134 590 8135 590 8271 6956 8135 6956 8270 6956 8039 590 7869 590 8136 590 8136 6957 7869 6957 8137 6957 8136 590 8137 590 8032 590 8032 6958 8137 6958 7866 6958 8032 6959 7866 6959 8134 6959 8138 590 8139 590 8140 590 7871 590 8039 590 8140 590 8140 590 8039 590 8040 590 8140 6960 8040 6960 8138 6960 8138 6961 8040 6961 8141 6961 8138 590 8141 590 8142 590 8029 590 8274 590 8141 590 8141 6962 8274 6962 8263 6962 8141 6963 8263 6963 8142 6963 8143 590 8317 590 7882 590 8159 590 8144 590 8317 590 7882 6964 8317 6964 8147 6964 8147 6965 8317 6965 8144 6965 8147 6966 8144 6966 8145 6966 8145 590 8146 590 8147 590 8147 6967 8146 6967 8148 6967 8147 6968 8148 6968 8150 6968 8148 590 8149 590 8150 590 8150 6969 8149 6969 8151 6969 8150 6970 8151 6970 8154 6970 8151 6971 8152 6971 8154 6971 8154 590 8152 590 8153 590 8154 590 8153 590 8156 590 8153 590 8155 590 8156 590 8156 6208 8155 6208 8157 6208 8156 6972 8157 6972 8317 6972 8317 6973 8157 6973 8158 6973 8317 6974 8158 6974 8159 6974 8161 6975 7885 6975 8156 6975 8156 6976 7885 6976 8160 6976 8156 590 8160 590 8154 590 7891 6164 7890 6164 8313 6164 8313 590 7890 590 7888 590 8313 6977 7888 6977 8162 6977 8162 590 7888 590 8161 590 8162 6978 8161 6978 8315 6978 8315 590 8161 590 8156 590 8009 590 7999 590 8008 590 8008 6979 7999 6979 8163 6979 8008 590 8163 590 8164 590 8164 6980 8163 6980 8165 6980 8237 6981 7936 6981 8005 6981 8005 6982 7936 6982 7937 6982 8005 6983 7937 6983 8163 6983 8163 6984 7937 6984 7930 6984 8163 6985 7930 6985 8165 6985 8166 590 7991 590 7987 590 7987 590 7991 590 7748 590 7987 590 7748 590 7750 590 7947 6986 8174 6986 8294 6986 8290 590 8167 590 8262 590 8262 6336 8167 6336 8168 6336 7953 590 8170 590 8169 590 8169 590 8170 590 8258 590 8169 590 8258 590 8171 590 8171 590 8258 590 8172 590 8176 6987 8173 6987 7955 6987 8174 590 8175 590 8294 590 8294 6339 8175 6339 8177 6339 8294 590 8177 590 8176 590 8176 6338 8177 6338 8178 6338 8176 6988 8178 6988 8173 6988 8260 6989 8259 6989 8188 6989 8179 6990 8183 6990 7878 6990 8186 590 8204 590 8196 590 8194 590 8181 590 8180 590 8180 6991 8181 6991 8182 6991 8180 6992 8182 6992 8192 6992 7878 590 8183 590 7877 590 7877 6993 8183 6993 8184 6993 7877 6344 8184 6344 8185 6344 8186 590 8196 590 8187 590 8188 590 8189 590 8260 590 8260 6994 8189 6994 8190 6994 8260 6995 8190 6995 8191 6995 8179 590 7878 590 8192 590 8192 590 7878 590 8193 590 8192 6996 8193 6996 8180 6996 8180 590 8195 590 8194 590 8194 590 8195 590 7952 590 8194 6997 7952 6997 8196 6997 8196 590 7952 590 8197 590 8196 6998 8197 6998 8187 6998 8204 6999 8198 6999 8201 6999 8201 7000 8198 7000 8203 7000 8185 7001 8199 7001 7877 7001 7877 7002 8199 7002 8200 7002 7877 7003 8200 7003 8201 7003 7947 7004 8294 7004 7949 7004 7949 590 8294 590 8201 590 7949 7005 8201 7005 8202 7005 8202 590 8201 590 8203 590 8202 7006 8203 7006 7951 7006 8201 7007 8200 7007 8204 7007 8204 7008 8200 7008 8205 7008 8204 7009 8205 7009 8196 7009 8224 590 8206 590 8207 590 8207 6406 8206 6406 8208 6406 8310 7010 8210 7010 8213 7010 8208 590 8209 590 8207 590 8207 6405 8209 6405 8211 6405 8207 6404 8211 6404 8210 6404 8210 6402 8211 6402 8212 6402 8210 6401 8212 6401 8213 6401 8213 7011 8214 7011 8310 7011 8310 7012 8214 7012 8215 7012 8310 590 8215 590 8216 590 8216 7013 8215 7013 8217 7013 8225 590 8229 590 8223 590 8217 590 8218 590 8216 590 8216 7014 8218 7014 8219 7014 8216 7015 8219 7015 8229 7015 8229 7016 8219 7016 8220 7016 8229 7017 8220 7017 8223 7017 8307 590 8227 590 8226 590 8221 590 8222 590 8225 590 8225 7018 8222 7018 8335 7018 8223 590 8224 590 8225 590 8225 590 8224 590 8207 590 8225 7019 8207 7019 8221 7019 8221 590 8207 590 8226 590 8221 590 8226 590 8338 590 8338 590 8226 590 8227 590 8335 7020 8228 7020 8225 7020 8225 7021 8228 7021 8347 7021 8225 590 8347 590 8229 590 8229 7022 8347 7022 8349 7022 8349 590 8345 590 8229 590 8229 7023 8345 7023 8344 7023 8229 7024 8344 7024 8293 7024 8293 7025 8344 7025 8297 7025 8237 7026 8230 7026 7934 7026 7934 590 8230 590 7991 590 7934 590 7991 590 7939 590 7939 7027 7991 7027 8166 7027 8245 6442 8231 6442 8232 6442 8025 590 8236 590 8247 590 8233 590 8234 590 8239 590 8239 590 8234 590 8240 590 8256 590 8235 590 8025 590 8025 7028 8235 7028 8245 7028 8025 6378 8245 6378 8236 6378 8236 590 8245 590 8232 590 8237 590 8005 590 8230 590 8230 590 8005 590 8007 590 8230 590 8007 590 8238 590 8238 7029 8007 7029 8239 7029 8238 7030 8239 7030 8244 7030 8244 7031 8239 7031 8240 7031 8244 7032 8240 7032 8241 7032 8241 7033 8242 7033 8244 7033 8244 590 8242 590 8243 590 8244 590 8243 590 8245 590 8245 590 8243 590 8246 590 8245 6443 8246 6443 8231 6443 8247 590 8248 590 8025 590 8025 6451 8248 6451 8249 6451 8025 590 8249 590 8239 590 8239 590 8249 590 8250 590 8239 7034 8250 7034 8233 7034 8235 590 8251 590 8245 590 8245 590 8251 590 8252 590 8245 590 8252 590 7994 590 7994 590 8252 590 7998 590 7994 7035 7998 7035 7743 7035 7743 590 7998 590 7744 590 8253 6160 8023 6160 8254 6160 8254 590 8023 590 8022 590 8254 7036 8022 7036 8025 7036 8025 590 8022 590 8255 590 8025 590 8255 590 8256 590 8256 590 8255 590 8257 590 7879 590 8260 590 7878 590 7878 7037 8260 7037 8191 7037 7878 7038 8191 7038 8193 7038 8170 590 8259 590 8258 590 8258 7039 8259 7039 8260 7039 8258 590 8260 590 8261 590 8261 590 8260 590 7879 590 8261 590 7879 590 7881 590 8168 590 8172 590 8262 590 8262 590 8172 590 8258 590 8262 590 8258 590 8275 590 8275 7040 8258 7040 8261 7040 8275 590 8261 590 8274 590 8274 590 8261 590 7881 590 8274 7041 7881 7041 8263 7041 8264 7042 7974 7042 8276 7042 8264 590 8276 590 8265 590 8285 7043 8266 7043 8283 7043 8283 7044 8266 7044 8267 7044 7973 7045 8268 7045 8262 7045 8262 7046 8268 7046 8269 7046 8262 590 8269 590 8285 590 8285 7047 8269 7047 7968 7047 8285 7048 7968 7048 8266 7048 8267 590 7981 590 8283 590 8283 7049 7981 7049 7980 7049 8283 7050 7980 7050 7979 7050 8270 590 8286 590 8271 590 8271 7051 8286 7051 8283 7051 8271 590 8283 590 8276 590 8276 7052 8283 7052 7979 7052 8276 7053 7979 7053 8265 7053 8272 590 8273 590 8274 590 8274 7054 8273 7054 8032 7054 8274 590 8032 590 8275 590 8275 590 8032 590 8276 590 8275 590 8276 590 8262 590 8262 7055 8276 7055 7974 7055 8262 7056 7974 7056 7973 7056 8093 7057 8281 7057 8277 7057 8277 590 8281 590 8278 590 8277 7058 8278 7058 7956 7058 7956 590 8279 590 8277 590 8277 7059 8279 7059 7965 7059 8277 7060 7965 7060 7964 7060 8280 590 8281 590 7959 590 7959 590 8281 590 8285 590 7959 590 8285 590 7961 590 8287 590 8282 590 8283 590 8283 6360 8282 6360 8284 6360 8283 7061 8284 7061 8285 7061 8285 7062 8284 7062 7962 7062 8285 7063 7962 7063 7961 7063 7898 590 7983 590 8286 590 8286 7064 7983 7064 8277 7064 8286 590 8277 590 8283 590 8283 7065 8277 7065 7964 7065 8283 7066 7964 7066 8287 7066 8288 7067 8289 7067 8281 7067 8281 590 8289 590 8291 590 8281 590 8291 590 8285 590 8285 590 8291 590 8292 590 8285 590 8292 590 8262 590 8262 590 8292 590 8176 590 8262 7068 8176 7068 8290 7068 8290 7069 8176 7069 7955 7069 8092 7070 8089 7070 8291 7070 8291 590 8089 590 8216 590 8291 7071 8216 7071 8292 7071 8292 590 8216 590 8229 590 8292 7072 8229 7072 8176 7072 8176 590 8229 590 8293 590 8176 590 8293 590 8294 590 8294 590 8293 590 8295 590 8294 590 8295 590 8201 590 8201 7073 8295 7073 8296 7073 8201 590 8296 590 7877 590 7877 590 8296 590 7875 590 8297 7074 8342 7074 8293 7074 8293 590 8342 590 8298 590 8293 590 8298 590 8295 590 8295 590 8298 590 8308 590 8295 7075 8308 7075 8296 7075 8296 7076 8308 7076 8299 7076 8296 590 8299 590 7875 590 7875 590 8299 590 8300 590 7825 590 8109 590 8301 590 8301 7077 8109 7077 8111 7077 8301 7078 8111 7078 8133 7078 8133 7079 8111 7079 8302 7079 8133 590 8302 590 7864 590 8055 590 8301 590 7918 590 7918 590 8301 590 8133 590 7918 590 8133 590 8304 590 8304 590 8133 590 8303 590 8304 590 8303 590 7919 590 7919 590 8303 590 8305 590 7919 590 8305 590 8306 590 8306 590 8305 590 7774 590 8306 7080 7774 7080 7770 7080 8341 590 8307 590 8298 590 8298 590 8307 590 8226 590 8298 7081 8226 7081 8308 7081 8308 590 8226 590 8314 590 8308 6428 8314 6428 8299 6428 8299 590 8314 590 8316 590 8299 590 8316 590 8300 590 8300 590 8316 590 7874 590 8090 590 8309 590 8216 590 8216 590 8309 590 8320 590 8216 590 8320 590 8310 590 8310 7082 8320 7082 8319 7082 8310 7083 8319 7083 8210 7083 8054 590 8311 590 8319 590 8319 7084 8311 7084 8312 7084 8319 590 8312 590 8210 590 8210 590 8312 590 8313 590 8210 7085 8313 7085 8207 7085 8207 590 8313 590 8162 590 8207 590 8162 590 8226 590 8226 590 8162 590 8315 590 8226 590 8315 590 8314 590 8314 590 8315 590 8156 590 8314 7086 8156 7086 8316 7086 8316 590 8156 590 8317 590 8316 590 8317 590 7874 590 7874 590 8317 590 7872 590 8318 590 8053 590 8046 590 8046 7087 8053 7087 8319 7087 8046 590 8319 590 8321 590 8321 7088 8319 7088 8320 7088 8321 590 8320 590 8112 590 8112 7089 8320 7089 8322 7089 8112 590 8322 590 7838 590 8323 590 8070 590 8082 590 8082 7090 8070 7090 8324 7090 8082 590 8324 590 8085 590 8085 590 8324 590 8117 590 8085 590 8117 590 8109 590 8109 7091 8117 7091 7846 7091 8109 590 7846 590 7849 590 7785 590 8326 590 8325 590 8325 7092 8326 7092 8327 7092 8325 590 8327 590 8070 590 8070 590 8327 590 7793 590 8070 6382 7793 6382 7792 6382 7792 590 7790 590 8070 590 8070 7093 7790 7093 8328 7093 8070 4176 8328 4176 8046 4176 8046 590 8328 590 8329 590 8046 590 8329 590 7789 590 7785 590 8325 590 7787 590 7787 7094 8325 7094 8330 7094 7787 590 8330 590 8333 590 7789 590 8331 590 8046 590 8046 590 8331 590 7784 590 8046 590 7784 590 8330 590 8330 7095 7784 7095 8332 7095 8330 7096 8332 7096 8333 7096 8346 2977 8228 2977 8335 2977 8346 2978 8335 2978 8334 2978 8334 7097 8335 7097 8222 7097 8334 7098 8222 7098 8336 7098 8336 7099 8222 7099 8221 7099 8336 7100 8221 7100 8337 7100 8337 7101 8221 7101 8338 7101 8337 7102 8338 7102 8339 7102 8339 7103 8338 7103 8227 7103 8339 7104 8227 7104 8594 7104 8594 7105 8227 7105 8307 7105 8594 7106 8307 7106 8595 7106 8595 7107 8307 7107 8340 7107 8340 7108 8307 7108 8341 7108 8340 7109 8341 7109 8343 7109 8341 7110 8342 7110 8343 7110 8343 6146 8342 6146 8297 6146 8343 7111 8297 7111 8642 7111 8642 7112 8297 7112 8344 7112 8642 6847 8344 6847 8643 6847 8643 7113 8344 7113 8345 7113 8643 5813 8345 5813 8596 5813 8596 2973 8345 2973 8349 2973 8228 7114 8346 7114 8347 7114 8347 7115 8346 7115 8348 7115 8347 7116 8348 7116 8349 7116 8349 7117 8348 7117 8597 7117 8349 2974 8597 2974 8596 2974 8675 7118 8681 7118 8684 7118 7963 960 8350 960 8665 960 7975 7119 7976 7119 8351 7119 8614 7120 8593 7120 8616 7120 2962 7121 8671 7121 8352 7121 8353 960 3262 960 8507 960 7924 7122 8382 7122 8381 7122 7929 960 7932 960 8697 960 7822 960 8440 960 8622 960 7795 7123 8417 7123 7797 7123 8384 960 8495 960 8698 960 8354 960 8486 960 8487 960 7736 960 8693 960 8695 960 8700 7124 8355 7124 8696 7124 8696 7125 8355 7125 8356 7125 7736 960 8695 960 8357 960 8529 7126 7749 7126 8700 7126 8700 7127 7749 7127 7747 7127 8700 7128 7747 7128 8355 7128 8358 7129 8359 7129 8529 7129 8529 7130 8359 7130 8360 7130 8529 960 8360 960 7751 960 7751 7131 8360 7131 8361 7131 8362 960 8363 960 8364 960 8362 960 8364 960 7760 960 8360 960 7944 960 8361 960 8361 7132 7944 7132 7942 7132 8361 7133 7942 7133 8365 7133 8365 960 7942 960 7940 960 8365 960 7940 960 7758 960 7758 7134 7940 7134 8363 7134 7904 7135 8364 7135 7903 7135 7903 7136 8364 7136 8363 7136 7903 960 8363 960 7899 960 7899 7137 8363 7137 7940 7137 7741 960 8366 960 8367 960 8667 960 7761 960 8364 960 8364 7138 7761 7138 8368 7138 8364 7139 8368 7139 7760 7139 8684 960 8369 960 8370 960 8370 7140 8369 7140 8373 7140 7742 960 8371 960 7739 960 7739 7141 8371 7141 8370 7141 7739 960 8370 960 8372 960 8372 960 8370 960 8373 960 8375 960 8646 960 8374 960 8374 960 8646 960 8379 960 8374 960 8379 960 8380 960 8354 960 8487 960 8375 960 7766 960 7767 960 7921 960 7921 7142 7767 7142 8376 7142 8376 5890 7767 5890 8703 5890 8376 960 8703 960 8377 960 8377 5901 8703 5901 8704 5901 8377 960 8704 960 8378 960 8378 7143 8704 7143 8702 7143 8378 960 8702 960 8379 960 8379 7144 8702 7144 7768 7144 8379 7145 7768 7145 8380 7145 7921 960 8381 960 7766 960 7766 7146 8381 7146 8382 7146 7766 7147 8382 7147 7765 7147 7765 7148 8382 7148 7924 7148 7765 960 7924 960 7764 960 7764 7149 7924 7149 7926 7149 7764 960 7926 960 8496 960 8496 960 7926 960 7928 960 8694 960 8383 960 8699 960 8384 960 8698 960 7763 960 8383 7150 8385 7150 8699 7150 8699 7151 8385 7151 8386 7151 8699 960 8386 960 8698 960 8698 7152 8386 7152 8387 7152 8698 7153 8387 7153 7763 7153 8388 960 7781 960 8389 960 8389 960 7781 960 8390 960 8389 960 8390 960 8674 960 8674 7154 8390 7154 7779 7154 8690 960 8691 960 8391 960 8391 960 8691 960 8674 960 8391 960 8674 960 8392 960 8392 960 8674 960 7779 960 7777 7155 8393 7155 8484 7155 8484 960 8393 960 8394 960 3269 960 3268 960 8515 960 8515 960 3268 960 3275 960 3274 960 8395 960 8525 960 8525 7156 8395 7156 8396 7156 8525 960 8396 960 8522 960 8396 7157 3271 7157 8522 7157 8522 5963 3271 5963 8397 5963 8522 960 8397 960 8352 960 8352 7158 8397 7158 8398 7158 8352 5961 8398 5961 8514 5961 7868 7159 3265 7159 8399 7159 3275 960 3266 960 8515 960 8515 7160 3266 7160 8400 7160 8515 960 8400 960 8520 960 3274 960 8525 960 8399 960 8399 7161 8525 7161 7867 7161 8399 7162 7867 7162 7868 7162 8409 7163 8401 7163 8402 7163 8402 7164 8401 7164 8612 7164 7895 960 8403 960 8405 960 8405 960 8403 960 7806 960 7895 960 8405 960 8404 960 8404 7165 8405 7165 8406 7165 8404 7166 8406 7166 8407 7166 8407 7167 8406 7167 7804 7167 8407 7168 7804 7168 8408 7168 8408 7169 7804 7169 8409 7169 8408 5843 8409 5843 7892 5843 7892 960 8409 960 8402 960 7892 960 8402 960 7889 960 8403 7170 7905 7170 7806 7170 7806 7171 7905 7171 8410 7171 7806 960 8410 960 8411 960 8411 960 8410 960 8412 960 8412 960 8410 960 8413 960 8413 960 8410 960 8603 960 8413 7172 8603 7172 7812 7172 8618 960 8414 960 8605 960 8605 7173 8414 7173 8415 7173 8605 7174 8415 7174 8603 7174 8603 7175 8415 7175 7810 7175 8603 7176 7810 7176 7812 7176 8416 960 8627 960 8575 960 8416 960 8575 960 7801 960 7797 960 8417 960 7798 960 7798 960 8417 960 8626 960 7798 960 8626 960 8628 960 8466 7177 8422 7177 8621 7177 8418 960 8419 960 8421 960 8419 960 8420 960 8421 960 8421 7178 8420 7178 7819 7178 8421 960 7819 960 8466 960 8466 7179 7819 7179 7820 7179 8466 7180 7820 7180 8422 7180 8418 960 8421 960 8424 960 8424 7181 8421 7181 8423 7181 8424 960 8423 960 8428 960 8425 960 8426 960 8427 960 8427 960 8426 960 7912 960 8427 960 7912 960 8433 960 8428 7182 8423 7182 8429 7182 8429 7183 8423 7183 7907 7183 8429 7184 7907 7184 8430 7184 8430 7185 7907 7185 7908 7185 8430 960 7908 960 7817 960 7817 960 7908 960 8431 960 7817 960 8431 960 8432 960 8432 7186 8431 7186 7911 7186 8432 7187 7911 7187 8425 7187 8425 7188 7911 7188 7910 7188 8425 960 7910 960 8426 960 8433 960 7912 960 8434 960 8434 5852 7912 5852 7913 5852 8434 7189 7913 7189 8435 7189 8435 7190 7913 7190 7915 7190 8435 960 7915 960 8436 960 7916 960 8437 960 7915 960 7915 7191 8437 7191 8438 7191 7915 7192 8438 7192 8436 7192 8619 960 7826 960 8439 960 8439 960 7826 960 7824 960 8439 7193 7824 7193 8648 7193 8440 7194 7822 7194 8620 7194 7822 7195 8441 7195 8620 7195 8620 7196 8441 7196 8442 7196 8620 7197 8442 7197 8619 7197 8619 960 8442 960 8443 960 8619 7198 8443 7198 7826 7198 8658 7199 8661 7199 8367 7199 8367 7200 8661 7200 8444 7200 8367 7201 8444 7201 8445 7201 8587 960 8446 960 8645 960 8447 960 8448 960 8661 960 8661 960 8448 960 8449 960 8661 7202 8449 7202 8444 7202 8588 7203 8623 7203 8586 7203 8445 7204 8450 7204 8367 7204 8367 7205 8450 7205 8451 7205 8367 960 8451 960 8452 960 8452 7206 8451 7206 8453 7206 8453 960 8454 960 8452 960 8452 960 8454 960 8455 960 8452 960 8455 960 8475 960 8475 960 8455 960 8456 960 8456 3109 8457 3109 8475 3109 8475 5918 8457 5918 8459 5918 8475 7207 8459 7207 8458 7207 8458 960 8459 960 8460 960 8458 7208 8460 7208 8623 7208 7839 7209 8461 7209 8625 7209 8625 7210 8461 7210 8458 7210 7848 7211 8462 7211 8463 7211 8463 960 8462 960 7847 960 8463 960 7847 960 8464 960 7847 7212 7845 7212 8464 7212 8464 5930 7845 5930 8465 5930 8464 6123 8465 6123 8466 6123 8466 7213 8465 7213 7842 7213 8466 960 7842 960 8605 960 8605 7214 7842 7214 7841 7214 8605 7215 7841 7215 8467 7215 8467 7216 7841 7216 8468 7216 8467 7217 8468 7217 8617 7217 8617 960 8468 960 8469 960 8617 960 8469 960 7839 960 7850 960 7848 960 8619 960 8470 960 8394 960 8471 960 8471 960 8394 960 8393 960 8471 7218 8393 7218 7828 7218 7828 7219 8393 7219 8472 7219 7828 7220 8472 7220 8473 7220 8473 960 8472 960 7829 960 7830 960 8674 960 8370 960 7830 5925 8370 5925 8673 5925 8461 960 8474 960 8458 960 8458 960 8474 960 7837 960 8458 960 7837 960 8475 960 8475 4463 7837 4463 7834 4463 8475 960 7834 960 8452 960 8452 960 7834 960 7833 960 8452 960 7833 960 8367 960 8367 960 7833 960 7832 960 8367 960 7832 960 8672 960 8672 7221 7832 7221 8476 7221 8672 7222 8476 7222 7831 7222 8394 960 8477 960 8478 960 8493 7223 8479 7223 8630 7223 8630 5940 8479 5940 8480 5940 8630 7224 8480 7224 8481 7224 8470 960 8632 960 8394 960 8394 960 8632 960 8630 960 8394 960 8630 960 8477 960 8477 960 8630 960 8481 960 8478 960 8482 960 8394 960 8394 5938 8482 5938 8483 5938 8394 960 8483 960 8484 960 8484 7225 8483 7225 8485 7225 8484 960 8485 960 7772 960 7772 7226 8485 7226 7854 7226 7772 960 7854 960 8486 960 8486 7227 7854 7227 7856 7227 8486 7228 7856 7228 8487 7228 7856 960 7857 960 8487 960 8487 7229 7857 7229 8488 7229 8487 960 8488 960 8489 960 8489 7230 8488 7230 8490 7230 8489 7231 8490 7231 7865 7231 7865 960 8491 960 8489 960 8489 960 8491 960 7863 960 8489 7232 7863 7232 8629 7232 8629 960 7863 960 8492 960 8629 7233 8492 7233 8493 7233 8493 7234 8492 7234 8494 7234 8493 7235 8494 7235 8479 7235 7929 960 8698 960 7928 960 7928 7236 8698 7236 8495 7236 7928 7237 8495 7237 8496 7237 7889 960 8402 960 7887 960 7887 960 8402 960 8497 960 7887 960 8497 960 7886 960 7886 7238 8497 7238 8613 7238 7886 7239 8613 7239 7884 7239 7884 960 8613 960 8498 960 8498 960 8613 960 8499 960 8498 960 8499 960 7883 960 8500 7240 8502 7240 8503 7240 8512 7241 8501 7241 8353 7241 8503 960 8502 960 8505 960 7883 960 8499 960 8503 960 8503 7242 8499 7242 8510 7242 8503 960 8510 960 8500 960 8502 960 8504 960 8505 960 8505 7243 8504 7243 8506 7243 8505 7244 8506 7244 8512 7244 8512 7245 8506 7245 3263 7245 8512 7246 3263 7246 8501 7246 3262 960 3260 960 8507 960 8507 960 3260 960 8508 960 8507 960 8508 960 8499 960 8499 7247 8508 7247 8509 7247 8499 5867 8509 5867 8510 5867 8507 7248 8511 7248 7873 7248 8353 960 8507 960 8512 960 8512 7249 8507 7249 7873 7249 8512 960 7873 960 8513 960 2962 7250 8352 7250 8516 7250 8514 960 3269 960 8352 960 8352 7251 3269 7251 8515 7251 8352 960 8515 960 8516 960 8516 960 8515 960 8520 960 8516 960 8520 960 8517 960 8517 7252 8520 7252 8518 7252 8517 960 8518 960 8519 960 8400 960 3265 960 8520 960 8520 960 3265 960 7868 960 8520 7253 7868 7253 8518 7253 8518 7254 7868 7254 7870 7254 8527 7255 8521 7255 8522 7255 8522 5959 8521 5959 8523 5959 8522 7256 8523 7256 8525 7256 8525 7257 8523 7257 8524 7257 8525 7258 8524 7258 7867 7258 7904 7259 7897 7259 8364 7259 8364 960 7897 960 8526 960 8364 960 8526 960 8668 960 8668 7260 8526 7260 8527 7260 8668 7261 8527 7261 8528 7261 8528 960 8527 960 8522 960 8529 7262 8700 7262 8358 7262 8358 960 8700 960 7933 960 8358 7263 7933 7263 8530 7263 8543 960 8535 960 8531 960 7946 960 7948 960 8533 960 8533 960 7948 960 8532 960 8533 960 8532 960 8534 960 8534 960 8532 960 8637 960 8535 960 8536 960 8531 960 8531 7264 8536 7264 8537 7264 8531 960 8537 960 8538 960 8537 960 8539 960 8538 960 8538 5991 8539 5991 8540 5991 8538 7265 8540 7265 8541 7265 8651 960 8542 960 8638 960 8638 5988 8542 5988 8636 5988 8554 7266 8545 7266 8653 7266 8543 7267 8531 7267 8544 7267 8544 960 8531 960 8653 960 8544 7268 8653 7268 7954 7268 7954 960 8653 960 8545 960 7954 960 8545 960 8546 960 7880 960 8552 960 8547 960 8547 960 8548 960 7880 960 7880 5999 8548 5999 8549 5999 7880 7269 8549 7269 8558 7269 8550 960 8551 960 8552 960 8552 7270 8551 7270 8553 7270 8552 6001 8553 6001 8547 6001 8554 7271 8653 7271 8555 7271 8555 960 8653 960 7880 960 8555 960 7880 960 8556 960 8556 960 7880 960 8558 960 8556 960 8558 960 8560 960 8566 7272 8557 7272 8565 7272 8558 7273 8559 7273 8560 7273 8560 7274 8559 7274 8562 7274 8560 960 8562 960 8561 960 8561 7275 8562 7275 8564 7275 8561 960 8564 960 8563 960 8563 7276 8564 7276 8566 7276 8565 960 8567 960 8566 960 8566 7277 8567 7277 8568 7277 8566 7278 8568 7278 8563 7278 8571 7279 8569 7279 8557 7279 8570 7280 7950 7280 8571 7280 8571 960 7950 960 8572 960 8571 960 8572 960 8569 960 8624 960 8592 960 8575 960 8575 6103 8592 6103 8573 6103 8579 960 8598 960 8578 960 8573 960 8574 960 8575 960 8575 6101 8574 6101 8576 6101 8575 960 8576 960 8598 960 8598 6100 8576 6100 8577 6100 8598 4603 8577 4603 8578 4603 8578 960 8580 960 8579 960 8579 7281 8580 7281 8581 7281 8579 960 8581 960 8585 960 8585 7282 8581 7282 8582 7282 8585 7283 8582 7283 8583 7283 8583 7284 8584 7284 8585 7284 8585 960 8584 960 8588 960 8585 7285 8588 7285 8645 7285 8645 960 8588 960 8586 960 8645 7286 8586 7286 8587 7286 8584 960 8589 960 8588 960 8588 7287 8589 7287 8590 7287 8588 960 8590 960 8624 960 8624 7288 8590 7288 8591 7288 8624 7289 8591 7289 8592 7289 8593 7290 8594 7290 8616 7290 8616 7291 8594 7291 8595 7291 8616 7292 8595 7292 8340 7292 8334 960 8336 960 8598 960 8598 6093 8336 6093 8337 6093 8598 7293 8337 7293 8593 7293 8593 6091 8337 6091 8339 6091 8593 7294 8339 7294 8594 7294 8643 960 8596 960 8585 960 8585 7295 8596 7295 8597 7295 8585 960 8597 960 8579 960 8579 7296 8597 7296 8348 7296 8579 960 8348 960 8598 960 8598 7297 8348 7297 8346 7297 8598 7298 8346 7298 8334 7298 8662 960 8343 960 8642 960 8421 7299 7786 7299 8603 7299 8603 7300 7786 7300 8599 7300 8603 7301 8599 7301 7788 7301 8608 6131 8600 6131 8605 6131 8605 7302 8600 7302 8601 7302 8605 960 8601 960 8466 960 8466 7303 8601 7303 7791 7303 8466 7304 7791 7304 8602 7304 7788 7305 8604 7305 8603 7305 8603 7306 8604 7306 8606 7306 8603 960 8606 960 8605 960 8605 7307 8606 7307 8607 7307 8605 6132 8607 6132 8608 6132 8602 960 8609 960 8466 960 8466 7308 8609 7308 8610 7308 8466 960 8610 960 8421 960 8421 7309 8610 7309 8611 7309 8421 960 8611 960 7786 960 8612 7310 7801 7310 8402 7310 8402 960 7801 960 8575 960 8402 4558 8575 4558 8497 4558 8497 4557 8575 4557 8598 4557 8497 7311 8598 7311 8613 7311 8613 7312 8598 7312 8593 7312 8613 960 8593 960 8499 960 8499 960 8593 960 8614 960 8499 960 8614 960 8507 960 8511 7313 8507 7313 8663 7313 8663 960 8507 960 8614 960 8663 7314 8614 7314 8615 7314 8615 960 8614 960 8616 960 8615 7315 8616 7315 8662 7315 8662 7316 8616 7316 8340 7316 8662 7317 8340 7317 8343 7317 7839 960 8625 960 8617 960 8617 960 8625 960 8626 960 8617 960 8626 960 8467 960 8467 960 8626 960 8417 960 8467 960 8417 960 8605 960 8605 960 8417 960 7795 960 8605 7318 7795 7318 8618 7318 7848 7319 8463 7319 8619 7319 8619 7320 8463 7320 8464 7320 8619 7321 8464 7321 8620 7321 8620 7322 8464 7322 8466 7322 8620 960 8466 960 8440 960 8440 960 8466 960 8621 960 8440 7323 8621 7323 8622 7323 8623 960 8588 960 8458 960 8458 7324 8588 7324 8624 7324 8458 960 8624 960 8625 960 8625 7325 8624 7325 8575 7325 8625 960 8575 960 8626 960 8626 960 8575 960 8627 960 8626 6116 8627 6116 8628 6116 8439 960 8629 960 8619 960 8619 7326 8629 7326 8493 7326 8619 960 8493 960 7850 960 7850 7327 8493 7327 8630 7327 7850 7328 8630 7328 8631 7328 8631 960 8630 960 8632 960 8566 960 8633 960 8557 960 8557 7329 8633 7329 8550 7329 8557 7330 8550 7330 8571 7330 8571 960 8550 960 8552 960 8571 7331 8552 7331 7876 7331 7948 960 8570 960 8532 960 8532 7332 8570 7332 8571 7332 8532 7333 8571 7333 8634 7333 8634 7334 8571 7334 7876 7334 8634 7335 7876 7335 8635 7335 8636 960 8637 960 8638 960 8638 960 8637 960 8532 960 8638 7336 8532 7336 8639 7336 8639 960 8532 960 8634 960 8639 7337 8634 7337 8640 7337 8640 7338 8634 7338 8635 7338 8640 7339 8635 7339 8641 7339 8642 960 8643 960 8662 960 8662 960 8643 960 8585 960 8662 7340 8585 7340 8644 7340 8644 7341 8585 7341 8645 7341 8644 7342 8645 7342 8661 7342 8661 960 8645 960 8446 960 8661 960 8446 960 8447 960 8375 960 8487 960 8646 960 8646 960 8487 960 8489 960 8646 960 8489 960 8647 960 8647 7343 8489 7343 8629 7343 8647 7344 8629 7344 7917 7344 7917 7345 8629 7345 8439 7345 7917 7346 8439 7346 7916 7346 7916 7347 8439 7347 8648 7347 7916 7348 8648 7348 8437 7348 7975 7349 8351 7349 7972 7349 8649 960 8664 960 7982 960 7982 960 8664 960 7978 960 8538 7350 7970 7350 7971 7350 8649 960 8650 960 8664 960 8664 7351 8650 7351 7967 7351 8664 7352 7967 7352 7969 7352 7969 7353 7970 7353 8664 7353 8664 960 7970 960 8538 960 8664 7354 8538 7354 8638 7354 8638 7355 8538 7355 8541 7355 8638 960 8541 960 8651 960 7971 960 7972 960 8538 960 8538 960 7972 960 8351 960 8538 960 8351 960 8531 960 8531 7356 8351 7356 8669 7356 8531 960 8669 960 8653 960 8653 7357 8669 7357 8652 7357 8653 7358 8652 7358 7880 7358 7880 7359 8652 7359 8670 7359 7963 960 8665 960 8654 960 7958 960 7960 960 8664 960 8350 960 8655 960 8665 960 8665 7360 8655 7360 8656 7360 8665 960 8656 960 8658 960 8658 7361 8656 7361 7966 7361 7966 960 8657 960 8658 960 8658 6015 8657 6015 8659 6015 8658 7362 8659 7362 8661 7362 8661 960 8659 960 8660 960 8661 7363 8660 7363 7957 7363 7957 7364 7958 7364 8661 7364 8661 960 7958 960 8664 960 8661 7365 8664 7365 8644 7365 8644 960 8664 960 8638 960 8644 7366 8638 7366 8662 7366 8662 960 8638 960 8639 960 8662 7367 8639 7367 8615 7367 8615 960 8639 960 8640 960 8615 7368 8640 7368 8663 7368 8663 960 8640 960 8641 960 8663 960 8641 960 8511 960 7960 960 8654 960 8664 960 8664 960 8654 960 8665 960 8664 960 8665 960 7978 960 7978 960 8665 960 8351 960 7978 960 8351 960 7977 960 7977 7369 8351 7369 7976 7369 8366 960 8666 960 8367 960 8367 960 8666 960 8667 960 8367 960 8667 960 8658 960 8658 960 8667 960 8364 960 8658 4623 8364 4623 8665 4623 8665 4622 8364 4622 8668 4622 8665 7370 8668 7370 8351 7370 8351 7371 8668 7371 8528 7371 8351 960 8528 960 8669 960 8669 960 8528 960 8522 960 8669 960 8522 960 8652 960 8652 960 8522 960 8352 960 8652 960 8352 960 8670 960 8670 960 8352 960 8671 960 7831 960 8673 960 8672 960 8672 7372 8673 7372 8370 7372 8672 960 8370 960 8367 960 8367 960 8370 960 8371 960 8367 7373 8371 7373 7741 7373 7741 960 8371 960 7742 960 7777 7374 8388 7374 8393 7374 8393 960 8388 960 8389 960 8393 960 8389 960 8472 960 8472 960 8389 960 8674 960 8472 5923 8674 5923 7829 5923 7829 960 8674 960 7830 960 8675 960 8684 960 8676 960 8676 960 8684 960 8370 960 8676 960 8370 960 8680 960 8689 7375 8677 7375 8674 7375 8674 6036 8677 6036 8678 6036 8674 960 8678 960 8370 960 8370 6035 8678 6035 8679 6035 8370 7376 8679 7376 8680 7376 8681 960 8682 960 8684 960 8684 960 8682 960 8683 960 8684 960 8683 960 8691 960 8691 7377 8683 7377 8685 7377 8685 960 8686 960 8691 960 8691 7378 8686 7378 8687 7378 8691 960 8687 960 8674 960 8674 960 8687 960 8688 960 8674 960 8688 960 8689 960 8690 960 7782 960 8691 960 8691 7379 7782 7379 8692 7379 8691 7380 8692 7380 8684 7380 8684 7381 8692 7381 8695 7381 8684 960 8695 960 8369 960 8369 7382 8695 7382 8693 7382 7782 960 8694 960 8692 960 8692 960 8694 960 8699 960 8692 7383 8699 7383 8695 7383 8695 7384 8699 7384 8696 7384 8695 960 8696 960 8357 960 8357 960 8696 960 8356 960 7929 960 8697 960 8698 960 8698 7385 8697 7385 7931 7385 8698 7386 7931 7386 8699 7386 8699 7387 7931 7387 7938 7387 8699 960 7938 960 8696 960 8696 960 7938 960 7935 960 8696 960 7935 960 8700 960 8700 960 7935 960 8701 960 8700 7388 8701 7388 7933 7388 8016 7389 8702 7389 8704 7389 7767 7390 8015 7390 8703 7390 8703 7391 8015 7391 8012 7391 8703 7392 8012 7392 8704 7392 8704 7392 8012 7392 8705 7392 8704 7389 8705 7389 8016 7389 8706 21 8708 21 8707 21 8707 21 8708 21 8709 21 8707 21 8709 21 9248 21 9263 7393 8713 7393 9265 7393 9265 7394 8713 7394 8710 7394 9265 7395 8710 7395 9255 7395 9270 7396 8711 7396 8712 7396 8712 7397 8711 7397 8715 7397 9270 7398 8712 7398 8714 7398 8714 7399 8712 7399 8713 7399 8714 7400 8713 7400 9263 7400 8711 6 9272 6 8715 6 8715 6 9272 6 8717 6 9272 7401 8716 7401 8717 7401 8717 7402 8716 7402 8719 7402 8718 49 8719 49 8720 49 8720 49 8719 49 8716 49 9785 6 8722 6 8721 6 8721 6 8722 6 8723 6 8721 6 8723 6 9273 6 8722 7403 9785 7403 9784 7403 8722 7404 9784 7404 8724 7404 9784 7405 9276 7405 8724 7405 8724 7406 9276 7406 8725 7406 8724 7407 8725 7407 8726 7407 8726 7408 8725 7408 8727 7408 8726 7409 8727 7409 8728 7409 8728 7410 8727 7410 9275 7410 8728 7411 9275 7411 8730 7411 8730 7412 9275 7412 8729 7412 8730 7413 8729 7413 8740 7413 9709 7414 8731 7414 8733 7414 8733 7415 8731 7415 8732 7415 8733 7416 8732 7416 8734 7416 8734 7417 8732 7417 8735 7417 8734 7418 8735 7418 8737 7418 8737 7419 8735 7419 8736 7419 8737 7420 8736 7420 9619 7420 9619 7421 8736 7421 8739 7421 9619 7422 8739 7422 8738 7422 8738 7423 8739 7423 8740 7423 8738 7424 8740 7424 8741 7424 8741 7425 8740 7425 8729 7425 8742 7426 8743 7426 8744 7426 8744 7427 8743 7427 8745 7427 8746 7428 9307 7428 9278 7428 8746 7429 9278 7429 8747 7429 8747 7430 9278 7430 9279 7430 8747 7431 9279 7431 8748 7431 8748 7432 9279 7432 8750 7432 8748 7433 8750 7433 8749 7433 8749 7434 8750 7434 9281 7434 8749 7435 9281 7435 8751 7435 8751 7436 9281 7436 9570 7436 8751 7437 9570 7437 8752 7437 8752 7438 9570 7438 8753 7438 8752 7439 8753 7439 8755 7439 8753 7440 8754 7440 8755 7440 8755 7441 8754 7441 8756 7441 8755 7442 8756 7442 8757 7442 8757 7443 8756 7443 8759 7443 8757 7444 8759 7444 8758 7444 8758 7445 8759 7445 8761 7445 8758 7446 8761 7446 8760 7446 8760 7447 8761 7447 9319 7447 8760 7448 9319 7448 8762 7448 9285 50 9284 50 8763 50 8763 50 9284 50 8764 50 9284 7449 9287 7449 8764 7449 8764 7450 9287 7450 8765 7450 8766 6 8765 6 8767 6 8767 6 8765 6 9287 6 9340 7451 8768 7451 9288 7451 9288 7452 8768 7452 8769 7452 9288 7453 8769 7453 9289 7453 9289 7454 8769 7454 8766 7454 9289 7455 8766 7455 8767 7455 9298 7456 9299 7456 8771 7456 9298 7457 8771 7457 8770 7457 8770 7458 8771 7458 8768 7458 8770 7459 8768 7459 9340 7459 8772 21 9304 21 9305 21 8772 21 9305 21 8773 21 8773 21 9305 21 8774 21 8773 21 8774 21 9309 21 8775 50 8776 50 8777 50 8777 50 8776 50 8778 50 8777 7460 9313 7460 8775 7460 8775 7461 9313 7461 8779 7461 9283 21 9314 21 8780 21 8780 21 9314 21 8781 21 9314 7462 8782 7462 8781 7462 8781 7463 8782 7463 8785 7463 9316 50 8783 50 8784 50 8784 50 8783 50 8785 50 8784 50 8785 50 8782 50 9316 7464 9317 7464 8783 7464 8783 7464 9317 7464 8787 7464 8786 6 8787 6 9777 6 9777 6 8787 6 9317 6 9321 49 8788 49 9322 49 9322 49 8788 49 8789 49 9322 49 8789 49 9324 49 8790 49 8792 49 8791 49 8791 49 8792 49 9775 49 8793 50 8794 50 9772 50 9772 50 8794 50 9774 50 8795 21 8796 21 8797 21 8797 21 8796 21 8798 21 8797 21 8798 21 9266 21 8799 6 8800 6 9352 6 9352 6 8800 6 8802 6 9352 6 8802 6 8801 6 8801 6 8802 6 9350 6 9297 7465 8812 7465 8803 7465 8803 7466 8812 7466 8804 7466 8803 7467 8804 7467 8805 7467 9293 7468 8814 7468 8806 7468 9293 7469 8806 7469 8807 7469 8807 7470 8806 7470 8808 7470 8807 7471 8808 7471 9290 7471 9290 7472 8808 7472 8809 7472 9290 7473 8809 7473 8810 7473 8810 7474 8809 7474 8811 7474 8810 7474 8811 7474 9296 7474 9296 7475 8811 7475 8812 7475 9296 7476 8812 7476 9297 7476 8813 6 8820 6 9292 6 9292 6 8820 6 8814 6 9292 6 8814 6 9293 6 9264 7477 8815 7477 8816 7477 9264 7478 8816 7478 9267 7478 9267 7479 8816 7479 8817 7479 9267 7479 8817 7479 9268 7479 9268 7480 8817 7480 8818 7480 9268 7481 8818 7481 9269 7481 9269 7482 8818 7482 8819 7482 9269 7483 8819 7483 9291 7483 9291 7484 8819 7484 8820 7484 9291 7485 8820 7485 8813 7485 8821 49 8822 49 9770 49 9770 49 8822 49 9769 49 8823 50 8824 50 9768 50 9768 50 8824 50 8825 50 8826 7486 8847 7486 8827 7486 8827 7487 8847 7487 8828 7487 8827 7488 8828 7488 8829 7488 8829 7489 8828 7489 9371 7489 8829 7490 9371 7490 8830 7490 9371 7491 8831 7491 8830 7491 8830 7492 8831 7492 8832 7492 8830 7493 8832 7493 8833 7493 8833 7494 8832 7494 9362 7494 8833 7495 9362 7495 8834 7495 8834 7496 9362 7496 8836 7496 8834 7497 8836 7497 8835 7497 8835 7498 8836 7498 8837 7498 8835 7499 8837 7499 8838 7499 8838 7500 8837 7500 9360 7500 8838 7501 9360 7501 8839 7501 8839 7502 9360 7502 8840 7502 8839 7503 8840 7503 8841 7503 8841 7504 8840 7504 8842 7504 8841 7505 8842 7505 8843 7505 8843 7506 8842 7506 9366 7506 8843 7507 9366 7507 8844 7507 8844 7508 9366 7508 8845 7508 8844 7509 8845 7509 8826 7509 8826 7510 8845 7510 8846 7510 8826 7511 8846 7511 8847 7511 8848 7512 8849 7512 8850 7512 8850 7513 8849 7513 9384 7513 8850 7514 9384 7514 8851 7514 8851 7515 9384 7515 9381 7515 8851 7516 9381 7516 8853 7516 9381 7517 8852 7517 8853 7517 8853 7492 8852 7492 8855 7492 8853 7493 8855 7493 8854 7493 8854 7494 8855 7494 9377 7494 8854 7495 9377 7495 8856 7495 8856 7518 9377 7518 9379 7518 8856 7519 9379 7519 8858 7519 8858 7520 9379 7520 8857 7520 8858 7521 8857 7521 8859 7521 8859 7522 8857 7522 9376 7522 8859 7523 9376 7523 8860 7523 8860 7524 9376 7524 8861 7524 8860 7525 8861 7525 8862 7525 8862 7504 8861 7504 9373 7504 8862 7505 9373 7505 8863 7505 8863 7506 9373 7506 8864 7506 8863 7507 8864 7507 8865 7507 8865 7526 8864 7526 8866 7526 8865 7527 8866 7527 8848 7527 8848 7528 8866 7528 8867 7528 8848 7529 8867 7529 8849 7529 8883 7486 8884 7486 8868 7486 8868 7530 8884 7530 8870 7530 8868 7531 8870 7531 8869 7531 8869 7532 8870 7532 9789 7532 8869 7533 9789 7533 8871 7533 9789 7491 9388 7491 8871 7491 8871 7492 9388 7492 9387 7492 8871 7493 9387 7493 8872 7493 8872 7494 9387 7494 8874 7494 8872 7495 8874 7495 8873 7495 8873 7518 8874 7518 8875 7518 8873 7519 8875 7519 8876 7519 8876 7534 8875 7534 9392 7534 8876 7535 9392 7535 8877 7535 8877 7500 9392 7500 9391 7500 8877 7501 9391 7501 8878 7501 8878 7502 9391 7502 9390 7502 8878 7503 9390 7503 8879 7503 8879 7504 9390 7504 9389 7504 8879 7505 9389 7505 8881 7505 8881 7506 9389 7506 8880 7506 8881 7507 8880 7507 8882 7507 8882 7536 8880 7536 9385 7536 8882 7537 9385 7537 8883 7537 8883 7538 9385 7538 9393 7538 8883 7511 9393 7511 8884 7511 8900 7539 9765 7539 8885 7539 8885 7513 9765 7513 9402 7513 8885 7514 9402 7514 8886 7514 8886 7540 9402 7540 9401 7540 8886 7541 9401 7541 8888 7541 9401 7542 8887 7542 8888 7542 8888 7492 8887 7492 9399 7492 8888 7493 9399 7493 8889 7493 8889 7494 9399 7494 9779 7494 8889 7495 9779 7495 8890 7495 8890 7518 9779 7518 9398 7518 8890 7519 9398 7519 8892 7519 8892 7520 9398 7520 8891 7520 8892 7521 8891 7521 8893 7521 8893 7543 8891 7543 9397 7543 8893 7544 9397 7544 8894 7544 8894 7502 9397 7502 8896 7502 8894 7503 8896 7503 8895 7503 8895 7504 8896 7504 8897 7504 8895 7505 8897 7505 8898 7505 8898 7506 8897 7506 9396 7506 8898 7507 9396 7507 8899 7507 8899 7526 9396 7526 9395 7526 8899 7545 9395 7545 8900 7545 8900 7546 9395 7546 9394 7546 8900 7547 9394 7547 9765 7547 8901 49 8902 49 9623 49 9623 49 8902 49 8903 49 9623 49 8903 49 9406 49 8904 21 8905 21 9274 21 9274 21 8905 21 9403 21 8906 50 8907 50 9405 50 9405 50 8907 50 8908 50 9405 50 8908 50 8909 50 8910 6 9407 6 8911 6 8911 6 9407 6 8912 6 8913 21 9761 21 8922 21 8913 21 8922 21 8914 21 8914 21 8922 21 8915 21 8914 21 8915 21 8917 21 8920 49 8918 49 8915 49 8915 7548 8918 7548 8916 7548 8915 49 8916 49 8917 49 8918 6 8920 6 8919 6 8919 6 8920 6 8921 6 8919 6 8921 6 9411 6 9411 6 8921 6 9409 6 9409 50 8921 50 9414 50 9414 50 8921 50 8922 50 9414 50 8922 50 9761 50 9753 50 8923 50 9415 50 9415 50 8923 50 8924 50 9415 50 8924 50 9416 50 8925 21 8926 21 9246 21 9246 21 8926 21 8927 21 8927 7549 8926 7549 8928 7549 8928 7550 8926 7550 8930 7550 8928 7551 8930 7551 9419 7551 9419 49 8930 49 8929 49 8929 49 8930 49 8931 49 8929 49 8931 49 8932 49 9424 7552 8932 7552 8933 7552 8933 7553 8932 7553 8931 7553 8934 6 9424 6 8935 6 8935 6 9424 6 8933 6 8936 7554 9454 7554 8937 7554 8937 7501 9454 7501 8938 7501 8937 7500 8938 7500 8939 7500 8939 7555 8938 7555 9452 7555 8939 7556 9452 7556 8940 7556 9452 7557 8941 7557 8940 7557 8940 7558 8941 7558 8942 7558 8940 7559 8942 7559 8943 7559 8943 7560 8942 7560 9444 7560 8943 7561 9444 7561 8944 7561 8944 7562 9444 7562 8946 7562 8944 7563 8946 7563 8945 7563 8945 7486 8946 7486 9443 7486 8945 7511 9443 7511 8947 7511 8947 7564 9443 7564 8949 7564 8947 7565 8949 7565 8948 7565 8948 7566 8949 7566 9442 7566 8948 7567 9442 7567 8950 7567 8950 7568 9442 7568 8951 7568 8950 7569 8951 7569 8952 7569 8952 7570 8951 7570 9441 7570 8952 7571 9441 7571 8953 7571 8953 7572 9441 7572 9245 7572 8953 7573 9245 7573 8936 7573 8936 7574 9245 7574 8954 7574 8936 7575 8954 7575 9454 7575 9473 6 8956 6 8955 6 8955 6 8956 6 8957 6 8955 6 8957 6 9471 6 9503 21 9501 21 8958 21 9503 21 8958 21 9484 21 9484 21 8958 21 8959 21 9484 21 8959 21 9486 21 9509 6 9504 6 8960 6 8960 6 9504 6 8961 6 8962 49 8964 49 8963 49 8963 49 8964 49 8965 49 8963 49 8965 49 9664 49 8970 21 8967 21 8966 21 8966 21 8967 21 9747 21 8973 7576 8969 7576 8968 7576 8968 7577 8969 7577 8970 7577 8968 7578 8970 7578 8966 7578 9511 50 8971 50 8972 50 8972 50 8971 50 8969 50 8972 50 8969 50 8973 50 9524 7579 8974 7579 9523 7579 9523 7580 8974 7580 8975 7580 9523 7581 8975 7581 9475 7581 9529 6 8977 6 8976 6 8976 6 8977 6 8978 6 8976 6 8978 6 8979 6 8980 7582 8981 7582 8982 7582 8982 7583 8981 7583 8983 7583 8984 7584 8985 7584 8986 7584 8984 7585 8986 7585 8987 7585 8986 7586 8988 7586 8987 7586 8987 7587 8988 7587 8989 7587 8987 7588 8989 7588 8990 7588 8990 7589 8989 7589 9536 7589 8990 7590 9536 7590 8991 7590 8991 7591 9536 7591 9534 7591 8991 7592 9534 7592 8992 7592 8992 7593 9534 7593 9712 7593 8992 7594 9712 7594 8993 7594 8993 7595 9712 7595 9418 7595 8993 7596 9418 7596 9000 7596 9003 7597 8994 7597 9538 7597 9538 7598 8994 7598 8995 7598 9538 7599 8995 7599 8996 7599 8996 7600 8995 7600 8997 7600 8996 7601 8997 7601 9422 7601 9422 7602 8997 7602 8998 7602 9422 7603 8998 7603 9423 7603 9423 7604 8998 7604 9000 7604 9423 7605 9000 7605 8999 7605 8999 7606 9000 7606 9418 7606 9244 21 9001 21 9002 21 9002 21 9001 21 8994 21 9002 21 8994 21 9003 21 9517 7607 9516 7607 9005 7607 9005 7608 9516 7608 9790 7608 9243 49 9517 49 9004 49 9004 49 9517 49 9005 49 9361 21 9386 21 9006 21 9006 21 9386 21 9551 21 9006 21 9551 21 9008 21 9008 21 9551 21 9007 21 9008 21 9007 21 9010 21 9011 7609 9008 7609 9009 7609 9009 7610 9008 7610 9010 7610 9011 7611 9009 7611 9556 7611 9011 7611 9556 7611 9012 7611 9012 7612 9556 7612 9013 7612 9012 7613 9013 7613 9014 7613 9014 7614 9013 7614 9015 7614 9014 7615 9015 7615 9016 7615 9017 7616 9018 7616 9019 7616 9019 7617 9018 7617 9020 7617 9019 7618 9020 7618 9021 7618 9021 7619 9020 7619 9022 7619 9021 7620 9022 7620 9565 7620 9565 7621 9022 7621 9016 7621 9565 7622 9016 7622 9023 7622 9023 7623 9016 7623 9015 7623 9025 7624 9024 7624 9027 7624 9017 7625 9787 7625 9018 7625 9018 7626 9787 7626 9567 7626 9018 7627 9567 7627 9027 7627 9027 7628 9567 7628 9568 7628 9027 7629 9568 7629 9025 7629 9024 49 9569 49 9027 49 9027 7630 9569 7630 9315 7630 9027 49 9315 49 9571 49 9571 49 9026 49 9027 49 9027 7631 9026 7631 9028 7631 9027 49 9028 49 9030 49 9030 49 9028 49 9510 49 9030 49 9510 49 9029 49 9029 7632 9512 7632 9030 7632 9030 7633 9512 7633 9734 7633 9030 49 9734 49 9733 49 9733 7634 9732 7634 9030 7634 9030 7635 9732 7635 9240 7635 9030 7636 9240 7636 9031 7636 9031 7637 9240 7637 9572 7637 9031 7638 9572 7638 9034 7638 9575 7639 9032 7639 9574 7639 9574 7640 9032 7640 9033 7640 9574 7641 9033 7641 9573 7641 9573 7642 9033 7642 9031 7642 9573 7643 9031 7643 9034 7643 9575 7644 9576 7644 9032 7644 9032 7645 9576 7645 9035 7645 9032 7646 9035 7646 9036 7646 9036 7647 9035 7647 9037 7647 9036 7648 9037 7648 9039 7648 9037 7649 9038 7649 9039 7649 9039 7650 9038 7650 9040 7650 9039 7651 9040 7651 9041 7651 9041 7652 9040 7652 9042 7652 9041 7652 9042 7652 9043 7652 9044 7653 9043 7653 9727 7653 9727 7654 9043 7654 9042 7654 9727 6 9728 6 9044 6 9044 6 9728 6 9045 6 9044 6 9045 6 9047 6 9047 6 9045 6 9046 6 9047 6 9046 6 9048 6 9049 50 9050 50 9051 50 9051 50 9050 50 9052 50 9051 50 9052 50 9453 50 9054 6 9053 6 9445 6 9445 6 9694 6 9054 6 9054 6 9694 6 9055 6 9054 6 9055 6 9056 6 9056 6 9055 6 9586 6 9056 6 9586 6 9057 6 9056 7655 9057 7655 9587 7655 9056 7656 9587 7656 9058 7656 9058 7657 9587 7657 9588 7657 9058 7657 9588 7657 9059 7657 9059 7658 9588 7658 9589 7658 9059 7658 9589 7658 9060 7658 9060 7659 9589 7659 9583 7659 9060 7660 9583 7660 9061 7660 9061 7661 9583 7661 9581 7661 9061 7662 9581 7662 9062 7662 9062 7663 9581 7663 9580 7663 9062 7664 9580 7664 9064 7664 9594 49 9063 49 9591 49 9591 49 9063 49 9064 49 9591 49 9064 49 9580 49 9065 6 9066 6 9737 6 9737 6 9067 6 9065 6 9065 6 9067 6 9068 6 9065 6 9068 6 9069 6 9069 6 9068 6 9613 6 9071 7665 9069 7665 9070 7665 9070 7666 9069 7666 9613 7666 9071 7667 9070 7667 9610 7667 9071 7667 9610 7667 9072 7667 9072 7668 9610 7668 9073 7668 9072 7669 9073 7669 9074 7669 9074 7670 9073 7670 9607 7670 9074 7671 9607 7671 9075 7671 9075 7672 9607 7672 9076 7672 9075 7673 9076 7673 9077 7673 9077 7674 9076 7674 9081 7674 9077 7675 9081 7675 9080 7675 9616 7676 9084 7676 9078 7676 9078 7677 9084 7677 9080 7677 9078 7678 9080 7678 9079 7678 9079 7679 9080 7679 9081 7679 9617 7680 9083 7680 9082 7680 9082 7681 9083 7681 9084 7681 9082 7682 9084 7682 9616 7682 9617 50 9618 50 9083 50 9083 7683 9618 7683 9085 7683 9083 50 9085 50 9420 50 9420 50 9421 50 9083 50 9083 50 9421 50 9715 50 9083 50 9715 50 9088 50 9088 7684 9715 7684 9086 7684 9088 7685 9086 7685 9622 7685 9622 7686 9087 7686 9088 7686 9088 7687 9087 7687 9404 7687 9088 50 9404 50 9624 50 9088 7688 9624 7688 9626 7688 9088 7689 9626 7689 9090 7689 9090 7690 9626 7690 9089 7690 9090 7691 9089 7691 9630 7691 9090 7692 9630 7692 9091 7692 9090 7693 9091 7693 9092 7693 9091 7694 9093 7694 9092 7694 9092 7695 9093 7695 9635 7695 9092 7696 9635 7696 9094 7696 9094 7697 9635 7697 9641 7697 9094 7698 9641 7698 9095 7698 9095 7699 9641 7699 9096 7699 9095 7700 9096 7700 9097 7700 9097 7701 9096 7701 9098 7701 9097 7702 9098 7702 9099 7702 9099 7703 9098 7703 9100 7703 9099 7703 9100 7703 9101 7703 9103 7704 9101 7704 9102 7704 9102 7705 9101 7705 9100 7705 9374 21 9375 21 9104 21 9103 21 9102 21 9643 21 9103 21 9643 21 9104 21 9104 21 9643 21 9778 21 9104 21 9778 21 9374 21 9105 49 9378 49 9106 49 9106 49 9378 49 9380 49 9106 49 9380 49 9382 49 9106 7706 9382 7706 9383 7706 9106 7707 9383 7707 9108 7707 9108 7708 9383 7708 9107 7708 9108 7709 9107 7709 9109 7709 9109 7710 9107 7710 9110 7710 9109 7711 9110 7711 9112 7711 9112 7712 9110 7712 9111 7712 9112 7713 9111 7713 9113 7713 9113 7714 9111 7714 9114 7714 9113 7715 9114 7715 9115 7715 9115 7716 9114 7716 9116 7716 9115 7717 9116 7717 9117 7717 9117 7718 9116 7718 9648 7718 9117 7719 9648 7719 9118 7719 9645 21 9247 21 9119 21 9648 21 9120 21 9118 21 9118 21 9120 21 9121 21 9118 21 9121 21 9119 21 9119 21 9121 21 9646 21 9119 21 9646 21 9645 21 9363 50 9122 50 9123 50 9123 50 9122 50 9124 50 9123 50 9124 50 9125 50 9126 6 9128 6 9127 6 9127 6 9128 6 9130 6 9127 6 9130 6 9129 6 9129 6 9130 6 9650 6 9657 7720 9131 7720 9132 7720 9132 7721 9131 7721 9469 7721 9132 7722 9469 7722 9136 7722 9136 7723 9469 7723 9137 7723 9133 7724 9134 7724 9135 7724 9135 7725 9134 7725 9138 7725 9133 7726 9135 7726 9464 7726 9464 7727 9135 7727 9136 7727 9464 7728 9136 7728 9137 7728 9134 21 9754 21 9138 21 9138 21 9754 21 9139 21 9754 7729 9669 7729 9139 7729 9139 7730 9669 7730 9140 7730 9141 50 9140 50 9667 50 9667 50 9140 50 9669 50 9142 7731 9665 7731 9663 7731 9142 7732 9663 7732 9143 7732 9143 7733 9663 7733 9505 7733 9143 7734 9505 7734 9144 7734 9144 7735 9505 7735 9145 7735 9144 406 9145 406 9146 406 9146 7736 9145 7736 9147 7736 9146 7737 9147 7737 9148 7737 9148 7738 9147 7738 9149 7738 9148 7739 9149 7739 9150 7739 9149 7740 9671 7740 9150 7740 9150 7741 9671 7741 9151 7741 9150 7742 9151 7742 9153 7742 9153 7743 9151 7743 9152 7743 9153 7744 9152 7744 9154 7744 9154 7745 9152 7745 9155 7745 9154 7746 9155 7746 9156 7746 9156 7747 9155 7747 9157 7747 9156 7748 9157 7748 9158 7748 9158 7749 9157 7749 9159 7749 9158 7750 9159 7750 9160 7750 9161 7751 9163 7751 9162 7751 9162 7752 9163 7752 9164 7752 9163 50 9649 50 9164 50 9164 50 9649 50 9165 50 9166 49 9167 49 9168 49 9168 49 9167 49 9169 49 9170 50 9171 50 9172 50 9172 50 9171 50 9746 50 9652 7753 9526 7753 9173 7753 9173 7754 9526 7754 9174 7754 9652 6 9173 6 9175 6 9175 6 9173 6 9176 6 9175 6 9176 6 9177 6 9177 7755 9176 7755 9178 7755 9177 7756 9178 7756 9658 7756 9480 7757 9179 7757 9180 7757 9480 7758 9180 7758 9481 7758 9481 7759 9180 7759 9182 7759 9481 7760 9182 7760 9181 7760 9181 7761 9182 7761 9183 7761 9181 7762 9183 7762 9184 7762 9184 7763 9183 7763 9185 7763 9184 7763 9185 7763 9521 7763 9521 7764 9185 7764 9186 7764 9521 7765 9186 7765 9522 7765 9478 21 9187 21 9479 21 9479 21 9187 21 9179 21 9479 21 9179 21 9480 21 9188 49 9189 49 9741 49 9741 49 9189 49 9745 49 9191 21 9188 21 9742 21 9742 21 9188 21 9741 21 9190 50 9191 50 9744 50 9744 50 9191 50 9742 50 9209 7520 9192 7520 9194 7520 9194 7766 9192 7766 9193 7766 9194 7767 9193 7767 9195 7767 9195 7768 9193 7768 9585 7768 9195 7769 9585 7769 9196 7769 9585 7770 9197 7770 9196 7770 9196 7558 9197 7558 9599 7558 9196 7559 9599 7559 9199 7559 9199 7560 9599 7560 9198 7560 9199 7561 9198 7561 9200 7561 9200 7771 9198 7771 9597 7771 9200 7772 9597 7772 9201 7772 9201 7773 9597 7773 9595 7773 9201 7774 9595 7774 9202 7774 9202 7514 9595 7514 9203 7514 9202 7513 9203 7513 9205 7513 9205 7775 9203 7775 9204 7775 9205 7776 9204 7776 9206 7776 9206 7568 9204 7568 9593 7568 9206 7569 9593 7569 9207 7569 9207 7570 9593 7570 9592 7570 9207 7571 9592 7571 9208 7571 9208 7777 9592 7777 9590 7777 9208 7778 9590 7778 9209 7778 9209 132 9590 132 9582 132 9209 7521 9582 7521 9192 7521 9693 50 9217 50 9695 50 9695 50 9217 50 9212 50 9695 50 9212 50 9210 50 9211 21 9210 21 9212 21 9211 21 9212 21 9213 21 9213 21 9212 21 9214 21 9213 21 9214 21 9579 21 9216 49 9215 49 9214 49 9214 7779 9215 7779 9697 7779 9214 49 9697 49 9579 49 9215 6 9216 6 9218 6 9218 6 9216 6 9217 6 9218 6 9217 6 9692 6 9692 6 9217 6 9693 6 9219 21 9221 21 9220 21 9220 21 9221 21 9670 21 9703 50 9223 50 9222 50 9222 50 9223 50 9224 50 9222 50 9224 50 9702 50 9705 6 9706 6 9225 6 9225 6 9706 6 9226 6 9706 7582 9707 7582 9226 7582 9226 7780 9707 7780 9229 7780 9701 49 9228 49 9227 49 9227 49 9228 49 9229 49 9227 49 9229 49 9707 49 9230 21 9231 21 9537 21 9537 21 9231 21 9535 21 9239 50 9232 50 9532 50 9532 50 9232 50 9233 50 9532 50 9233 50 9242 50 9718 6 9717 6 9234 6 9234 6 9717 6 9235 6 9714 49 9236 49 9237 49 9237 49 9236 49 9238 49 9237 49 9238 49 9716 49 9239 590 9532 590 9531 590 9649 590 9163 590 9161 590 9616 590 9078 590 9688 590 9197 590 9585 590 9598 590 9694 590 9211 590 9213 590 9572 590 9240 590 9731 590 9731 590 9240 590 9732 590 9567 590 9786 590 9241 590 8988 590 8986 590 9537 590 8985 590 9530 590 9242 590 9243 7781 9244 7781 9002 7781 9471 590 9465 590 9469 590 8954 590 9245 590 9437 590 9246 590 8927 590 9736 590 9409 590 9414 590 9773 590 9370 590 9247 590 9645 590 9248 590 9249 590 9710 590 9710 7782 9249 7782 9250 7782 9710 590 9250 590 8743 590 9251 590 9252 590 9256 590 9254 7783 9253 7783 9265 7783 9265 7784 9255 7784 9254 7784 9254 7785 9255 7785 9257 7785 9254 590 9257 590 9256 590 9256 7786 9257 7786 9258 7786 9256 7787 9258 7787 9251 7787 9251 7788 9258 7788 9259 7788 9251 590 9259 590 9651 590 9651 7789 9259 7789 9260 7789 9651 7790 9260 7790 9261 7790 9263 7791 9265 7791 9266 7791 9266 590 9262 590 9263 590 9263 590 9262 590 9355 590 9263 590 9355 590 9357 590 9253 7792 9264 7792 9265 7792 9265 7793 9264 7793 9267 7793 9265 590 9267 590 9266 590 9266 7794 9267 7794 9268 7794 9266 7795 9268 7795 9269 7795 8711 7796 9270 7796 9357 7796 9357 590 9270 590 8714 590 9357 590 8714 590 9263 590 9785 590 8721 590 9271 590 9271 590 8721 590 9273 590 8711 590 9357 590 9272 590 9272 7797 9357 7797 9271 7797 9272 590 9271 590 8716 590 8716 7798 9271 7798 9273 7798 8716 590 9273 590 8720 590 9783 590 8909 590 9784 590 9784 7799 8909 7799 9274 7799 9784 7800 9274 7800 9276 7800 8729 590 9275 590 9403 590 9403 7801 9275 7801 8727 7801 9403 590 8727 590 9274 590 9274 7802 8727 7802 8725 7802 9274 590 8725 590 9276 590 8738 7803 8741 7803 9621 7803 9620 590 8737 590 9619 590 8737 590 9620 590 8734 590 8734 590 9620 590 9708 590 8734 590 9708 590 8733 590 9709 590 9710 590 9277 590 9277 590 9710 590 8743 590 9277 7804 8743 7804 8742 7804 9570 590 9281 590 9280 590 9278 590 9312 590 9279 590 9279 590 9312 590 9280 590 9279 590 9280 590 8750 590 8750 7805 9280 7805 9281 7805 8754 590 8753 590 9282 590 8756 590 9314 590 8759 590 8759 590 9314 590 9283 590 8759 7806 9283 7806 8761 7806 8761 7807 9283 7807 9319 7807 9287 590 9284 590 9323 590 9323 590 9284 590 9320 590 9320 590 9284 590 9285 590 9320 7808 9285 7808 9286 7808 9338 7809 8767 7809 9287 7809 9340 590 9288 590 9338 590 9338 590 9288 590 9289 590 9338 7796 9289 7796 8767 7796 8807 7810 9290 7810 8795 7810 8795 7795 9290 7795 8810 7795 8795 590 8810 590 8770 590 9269 7810 9291 7810 9266 7810 9266 590 9291 590 8813 590 9266 590 8813 590 8797 590 8797 590 8813 590 9292 590 8797 590 9292 590 8795 590 8795 590 9292 590 9293 590 8795 590 9293 590 8807 590 9252 590 9251 590 9294 590 9294 7787 9251 7787 9295 7787 9294 590 9295 590 8805 590 8810 590 9296 590 8770 590 8770 7811 9296 7811 9297 7811 8770 7812 9297 7812 9298 7812 9298 7813 9297 7813 8803 7813 9298 7814 8803 7814 9299 7814 9299 7815 8803 7815 8805 7815 9299 590 8805 590 9300 590 9300 590 8805 590 9295 590 9301 7816 9302 7816 9651 7816 9651 590 9302 590 9251 590 9251 7817 9302 7817 9303 7817 9251 7788 9303 7788 9295 7788 9301 7818 9651 7818 9304 7818 9304 590 9651 590 9655 590 9304 590 9655 590 9305 590 9305 590 9655 590 9308 590 9305 590 9308 590 8774 590 9313 590 9312 590 9306 590 9306 590 9312 590 9278 590 9306 590 9278 590 9307 590 8774 590 9308 590 9309 590 9309 7819 9308 7819 9311 7819 9309 590 9311 590 9310 590 9310 590 9311 590 9312 590 9310 7782 9312 7782 8778 7782 8778 7820 9312 7820 9313 7820 8778 590 9313 590 8777 590 8756 7801 8754 7801 9314 7801 9314 590 8754 590 9282 590 9314 590 9282 590 8782 590 8782 590 9282 590 9571 590 8782 590 9571 590 8784 590 8784 590 9571 590 9315 590 8784 590 9315 590 9316 590 9316 590 9315 590 9569 590 9316 590 9569 590 9317 590 9317 590 9569 590 9318 590 9319 590 9283 590 9320 590 9320 7821 9283 7821 9321 7821 9320 590 9321 590 9323 590 9323 590 9321 590 9322 590 9323 590 9322 590 9764 590 9764 590 9322 590 9324 590 9764 7822 9324 7822 9777 7822 9351 590 9330 590 9325 590 9338 590 9337 590 9326 590 9339 7823 9327 7823 9329 7823 9329 590 9327 590 9328 590 9329 590 9328 590 9350 590 9330 590 9331 590 9325 590 9325 7824 9331 7824 9332 7824 9325 590 9332 590 9334 590 9332 590 9333 590 9334 590 9334 590 9333 590 9335 590 9334 590 9335 590 9338 590 9338 7825 9335 7825 9336 7825 9338 7826 9336 7826 9337 7826 9326 590 9339 590 9338 590 9338 590 9339 590 9329 590 9338 590 9329 590 9340 590 9340 590 9329 590 9341 590 9340 7827 9341 7827 8770 7827 8770 590 9341 590 9342 590 8770 590 9342 590 8795 590 9759 7828 9343 7828 9760 7828 9344 7829 9355 7829 9345 7829 9345 590 9355 590 8799 590 9345 590 8799 590 9352 590 9343 590 9346 590 9760 590 9760 590 9346 590 9347 590 9760 590 9347 590 9348 590 9348 7830 9347 7830 9349 7830 9348 7831 9349 7831 9353 7831 9328 7832 9351 7832 9350 7832 9350 590 9351 590 9325 590 9350 590 9325 590 8801 590 8801 590 9325 590 9348 590 8801 7833 9348 7833 9352 7833 9352 590 9348 590 9353 590 9352 7834 9353 7834 9345 7834 9344 590 9354 590 9355 590 9355 7835 9354 7835 9356 7835 9355 590 9356 590 9357 590 9357 590 9356 590 9358 590 9357 590 9358 590 9359 590 9363 590 9360 590 9361 590 9361 590 9360 590 8837 590 9361 590 8837 590 9386 590 9386 590 8837 590 8836 590 9362 590 8832 590 9364 590 9123 590 8842 590 9363 590 9363 7836 8842 7836 8840 7836 9363 7837 8840 7837 9360 7837 8832 590 8831 590 9364 590 9364 7838 8831 7838 9371 7838 9364 590 9371 590 9368 590 9368 7839 9372 7839 9365 7839 8846 590 8845 590 9123 590 9123 7840 8845 7840 9366 7840 9123 7841 9366 7841 8842 7841 9365 590 9367 590 9368 590 9368 7842 9367 7842 9369 7842 9368 7843 9369 7843 9644 7843 9644 7844 9369 7844 9370 7844 9371 590 8828 590 9368 590 9368 590 8828 590 8847 590 9368 590 8847 590 9372 590 9372 7845 8847 7845 8846 7845 9372 590 8846 590 9125 590 9125 590 8846 590 9123 590 8861 590 9376 590 9374 590 8866 590 8864 590 9780 590 9780 7846 8864 7846 9373 7846 9374 7847 9376 7847 9375 7847 9375 590 9376 590 8857 590 9375 590 8857 590 9378 590 8855 590 9380 590 9377 590 9377 590 9380 590 9378 590 9377 590 9378 590 9379 590 9379 590 9378 590 8857 590 9771 7848 9111 7848 9110 7848 8855 590 8852 590 9380 590 9380 7840 8852 7840 9381 7840 9380 590 9381 590 9382 590 9382 7849 9381 7849 9384 7849 9382 590 9384 590 9383 590 9111 7850 9771 7850 9114 7850 9114 7851 9771 7851 9647 7851 9114 590 9647 590 9116 590 8866 590 9780 590 8867 590 8867 590 9780 590 9771 590 8867 590 9771 590 8849 590 8849 590 9771 590 9110 590 8849 7852 9110 7852 9384 7852 9384 7853 9110 7853 9107 7853 9384 7854 9107 7854 9383 7854 9364 7855 9385 7855 8880 7855 8880 590 9389 590 9364 590 9364 590 9389 590 9386 590 9364 590 9386 590 9362 590 9362 590 9386 590 8836 590 8875 7856 8874 7856 9551 7856 8874 590 9387 590 9550 590 9550 7857 9387 7857 9388 7857 9389 590 9390 590 9386 590 9386 7858 9390 7858 9391 7858 9386 7859 9391 7859 9551 7859 9551 7860 9391 7860 9392 7860 9551 7861 9392 7861 8875 7861 8870 590 8884 590 9788 590 8870 590 9788 590 9789 590 9385 590 9364 590 9393 590 9393 590 9364 590 9368 590 9393 590 9368 590 8884 590 9394 590 9395 590 9628 590 9628 7862 9395 7862 9396 7862 9628 7857 9396 7857 8897 7857 9779 590 9399 590 9400 590 8896 7856 9397 7856 9643 7856 9643 7861 9397 7861 8891 7861 9643 590 8891 590 9778 590 9778 7863 8891 7863 9398 7863 9765 590 9394 590 9625 590 9399 590 8887 590 9400 590 9400 7864 8887 7864 9401 7864 9400 590 9401 590 9781 590 9781 590 9401 590 9402 590 9781 7865 9402 7865 9765 7865 8741 590 8729 590 9621 590 9621 590 8729 590 9403 590 9621 590 9403 590 9622 590 9622 7866 9403 7866 8901 7866 9622 590 8901 590 9087 590 9087 590 8901 590 9623 590 9087 590 9623 590 9404 590 9767 590 8906 590 9783 590 9783 590 8906 590 9405 590 9783 590 9405 590 8909 590 9406 590 9407 590 9408 590 9408 590 9407 590 8910 590 9409 590 9644 590 9410 590 9409 590 9410 590 9411 590 9411 590 9410 590 9412 590 9411 7867 9412 7867 8919 7867 8919 590 9412 590 8918 590 8918 590 9412 590 9647 590 8918 590 9647 590 8916 590 8916 590 9647 590 9413 590 8916 590 9413 590 8917 590 9773 590 9414 590 9334 590 9334 590 9414 590 9761 590 9334 7868 9761 7868 9325 7868 9752 7869 9246 7869 9735 7869 9415 590 9416 590 9417 590 8999 590 9418 590 9713 590 9618 590 8928 590 9085 590 9085 7870 8928 7870 9419 7870 9085 590 9419 590 9420 590 9420 590 9419 590 8929 590 9420 590 8929 590 9421 590 9421 590 8929 590 8932 590 9421 7871 8932 7871 9713 7871 9713 590 8932 590 9424 590 9713 590 9424 590 8999 590 9538 7872 8996 7872 8934 7872 8934 590 8996 590 9422 590 8934 590 9422 590 9424 590 9424 590 9422 590 9423 590 9424 7873 9423 7873 8999 7873 9425 590 9426 590 9730 590 9730 7874 9426 7874 9428 7874 9730 590 9428 590 9427 590 9427 7875 9428 7875 9429 7875 9429 7876 9430 7876 9427 7876 9427 7877 9430 7877 9431 7877 9427 7878 9431 7878 9577 7878 9434 590 9437 590 9432 590 9432 590 9437 590 9577 590 9432 590 9577 590 9433 590 9433 590 9577 590 9431 590 9434 590 9435 590 9437 590 9437 7879 9435 7879 9436 7879 9437 590 9436 590 9748 590 9748 7880 9436 7880 9438 7880 9425 590 9730 590 9440 590 9440 590 9730 590 9439 590 9440 590 9439 590 9749 590 9245 590 9441 590 9437 590 9437 7881 9441 7881 8951 7881 9437 590 8951 590 9577 590 9577 7882 8951 7882 9442 7882 9442 590 8949 590 9577 590 9577 590 8949 590 9443 590 9577 7883 9443 7883 9578 7883 9578 7884 9443 7884 8946 7884 9578 7885 8946 7885 9050 7885 9050 7886 8946 7886 9444 7886 9050 590 9444 590 9052 590 9052 7887 9444 7887 8942 7887 9448 590 9445 590 9053 590 9053 590 9446 590 9448 590 9448 7888 9446 7888 9447 7888 9448 7889 9447 7889 9748 7889 9447 590 9449 590 9748 590 9748 7890 9449 7890 9450 7890 9748 590 9450 590 9437 590 9437 7891 9450 7891 9451 7891 9437 590 9451 590 8954 590 8942 590 8941 590 9052 590 9052 7892 8941 7892 9452 7892 9052 590 9452 590 9453 590 9453 7893 9452 7893 8938 7893 9453 590 8938 590 9451 590 9451 7894 8938 7894 9454 7894 9451 590 9454 590 8954 590 9458 7895 9456 7895 9455 7895 9456 7896 9458 7896 9457 7896 9457 590 9458 590 9755 590 9457 590 9755 590 9468 590 9455 590 9459 590 9458 590 9458 590 9459 590 9460 590 9458 590 9460 590 9461 590 9461 7897 9460 7897 9462 7897 9461 7898 9462 7898 9502 7898 9498 590 9463 590 9499 590 9499 7899 9463 7899 9467 7899 9469 590 9465 590 9137 590 9755 590 9464 590 9137 590 9465 7900 9466 7900 9137 7900 9137 590 9466 590 9499 590 9137 590 9499 590 9755 590 9755 590 9499 590 9467 590 9755 590 9467 590 9468 590 9653 590 9470 590 9469 590 9469 7901 9470 7901 9471 7901 9471 7902 9470 7902 9472 7902 9471 7903 9472 7903 9476 7903 9481 7904 9181 7904 9473 7904 9473 7903 9181 7903 9184 7903 9184 590 9521 590 9473 590 9473 7905 9521 7905 9523 7905 9473 590 9523 590 9474 590 9474 7906 9523 7906 9475 7906 9474 590 9475 590 9489 590 9476 7904 9477 7904 9471 7904 9471 590 9477 590 9478 590 9471 590 9478 590 8955 590 8955 590 9478 590 9479 590 8955 590 9479 590 9473 590 9473 590 9479 590 9480 590 9473 590 9480 590 9481 590 9482 7907 9491 7907 9513 7907 9483 590 9484 590 9485 590 9485 590 9484 590 9486 590 9485 590 9486 590 9487 590 9487 590 9486 590 9488 590 9486 590 9489 590 9488 590 9488 590 9489 590 9513 590 9488 590 9513 590 9490 590 9490 590 9513 590 9491 590 9492 590 9494 590 9493 590 9493 7908 9494 7908 9495 7908 9493 7909 9495 7909 9750 7909 9750 590 9495 590 9496 590 9750 590 9496 590 9497 590 9498 7910 9499 7910 9500 7910 9500 590 9499 590 9501 590 9500 7911 9501 7911 9502 7911 9502 7912 9501 7912 9503 7912 9502 590 9503 590 9461 590 9461 590 9503 590 9484 590 9461 7913 9484 7913 9493 7913 9493 590 9484 590 9483 590 9493 7914 9483 7914 9492 7914 9668 590 8963 590 9664 590 9509 590 9145 590 9504 590 9504 7915 9145 7915 9505 7915 8963 590 9668 590 8962 590 8962 590 9668 590 9756 590 8962 590 9756 590 9506 590 9507 590 8966 590 9747 590 8966 590 9507 590 8968 590 8968 590 9507 590 9734 590 8968 590 9734 590 9512 590 9508 590 9509 590 9510 590 9510 7916 9509 7916 9511 7916 9510 590 9511 590 9029 590 9029 590 9511 590 8972 590 9029 590 8972 590 9512 590 9512 590 8972 590 8973 590 9512 7870 8973 7870 8968 7870 9489 7917 9475 7917 9513 7917 9513 590 9475 590 9791 590 9513 590 9791 590 9793 590 9793 590 9514 590 9513 590 9513 7918 9514 7918 9516 7918 9513 7919 9516 7919 9515 7919 9515 7920 9516 7920 9517 7920 9518 7921 9519 7921 9651 7921 9518 7922 9651 7922 8979 7922 9261 7818 8706 7818 9651 7818 9651 7923 8706 7923 9711 7923 9651 7924 9711 7924 8979 7924 8979 590 9711 590 8976 590 9519 590 9520 590 9652 590 9652 590 9520 590 9526 590 9521 7925 9522 7925 9523 7925 9523 7926 9522 7926 9525 7926 9523 7927 9525 7927 9524 7927 9524 7928 9525 7928 9526 7928 9524 590 9526 590 9527 590 9527 590 9526 590 9520 590 9530 7808 8981 7808 8980 7808 9531 7929 9528 7929 9711 7929 9711 590 9528 590 9529 590 9711 590 9529 590 8976 590 8980 590 9528 590 9530 590 9530 590 9528 590 9531 590 9530 590 9531 590 9242 590 9242 590 9531 590 9532 590 8985 590 9242 590 8986 590 8986 590 9242 590 9533 590 8986 590 9533 590 9537 590 9712 590 9534 590 9535 590 9535 7930 9534 7930 9536 7930 9535 590 9536 590 9537 590 9537 590 9536 590 8989 590 9537 590 8989 590 8988 590 8934 7931 9753 7931 9538 7931 9538 590 9753 590 9539 590 9538 590 9539 590 9003 590 9003 590 9539 590 9515 590 9003 590 9515 590 9002 590 9002 590 9515 590 9517 590 9002 590 9517 590 9243 590 9542 590 9544 590 50101 590 50101 590 9544 590 9729 590 50101 7932 9729 7932 9540 7932 9540 590 9729 590 9541 590 9542 590 9543 590 9544 590 9544 7933 9543 7933 9545 7933 9544 7934 9545 7934 9547 7934 9545 590 9546 590 9547 590 9547 590 9546 590 9720 590 9547 590 9720 590 9722 590 9564 7935 9548 7935 9559 7935 9562 7936 9549 7936 9552 7936 8874 590 9550 590 9551 590 9551 590 9550 590 9562 590 9551 590 9562 590 9007 590 9007 590 9562 590 9552 590 9007 7937 9552 7937 9558 7937 9548 590 9564 590 9553 590 9553 590 9564 590 9015 590 9553 590 9015 590 9554 590 9554 590 9015 590 9013 590 9554 590 9013 590 9555 590 9555 590 9013 590 9556 590 9555 7938 9556 7938 9557 7938 9557 590 9556 590 9009 590 9557 590 9009 590 9558 590 9558 590 9009 590 9010 590 9558 590 9010 590 9007 590 9559 590 9560 590 9564 590 9564 590 9560 590 9561 590 9564 590 9561 590 9562 590 9562 7939 9561 7939 9563 7939 9562 590 9563 590 9549 590 9021 590 9565 590 9564 590 9564 7940 9565 7940 9023 7940 9564 590 9023 590 9015 590 9787 590 9017 590 9564 590 9564 7941 9017 7941 9019 7941 9564 7942 9019 7942 9021 7942 9566 7943 9025 7943 9568 7943 9567 590 9241 590 9568 590 9568 590 9241 590 9788 590 9568 590 9788 590 9566 590 9318 590 9569 590 9566 590 9566 590 9569 590 9024 590 9566 7944 9024 7944 9025 7944 8753 590 9570 590 9282 590 9282 590 9570 590 9280 590 9282 590 9280 590 9571 590 9571 590 9280 590 9026 590 9731 590 9544 590 9572 590 9572 590 9544 590 9547 590 9572 590 9547 590 9034 590 9034 590 9547 590 9573 590 9722 590 9037 590 9035 590 9573 590 9547 590 9574 590 9574 590 9547 590 9722 590 9574 590 9722 590 9575 590 9575 7945 9722 7945 9035 7945 9575 590 9035 590 9576 590 9728 590 9427 590 9045 590 9045 590 9427 590 9577 590 9045 590 9577 590 9046 590 9046 590 9577 590 9578 590 9046 7946 9578 7946 9048 7946 9694 590 9213 590 9055 590 9055 590 9213 590 9579 590 9055 7947 9579 7947 9586 7947 9598 590 9585 590 9584 590 9583 590 9589 590 9743 590 9590 7948 9591 7948 9582 7948 9582 590 9591 590 9580 590 9582 7949 9580 7949 9581 7949 9581 590 9583 590 9582 590 9582 7950 9583 7950 9743 7950 9582 7951 9743 7951 9192 7951 9192 7952 9743 7952 9584 7952 9192 590 9584 590 9193 590 9193 590 9584 590 9585 590 9057 590 9586 590 9587 590 9587 590 9586 590 9743 590 9587 590 9743 590 9588 590 9588 590 9743 590 9589 590 9590 590 9592 590 9591 590 9591 7953 9592 7953 9593 7953 9591 590 9593 590 9594 590 9594 7954 9593 7954 9204 7954 9594 590 9204 590 9738 590 9204 590 9203 590 9738 590 9738 7884 9203 7884 9595 7884 9738 7883 9595 7883 9596 7883 9595 590 9597 590 9596 590 9596 7955 9597 7955 9198 7955 9596 590 9198 590 9598 590 9598 7956 9198 7956 9599 7956 9598 7881 9599 7881 9197 7881 9737 590 9675 590 9067 590 9067 590 9675 590 9673 590 9067 590 9673 590 9068 590 9068 590 9673 590 9613 590 9602 590 9078 590 9600 590 9600 7957 9078 7957 9079 7957 9600 590 9079 590 9601 590 9601 7958 9079 7958 9081 7958 9601 590 9081 590 9606 590 9602 590 9603 590 9078 590 9078 590 9603 590 9604 590 9078 7959 9604 7959 9688 7959 9688 7960 9604 7960 9605 7960 9688 7961 9605 7961 9672 7961 9081 7962 9076 7962 9606 7962 9606 7963 9076 7963 9607 7963 9606 590 9607 590 9608 590 9608 590 9607 590 9073 590 9608 590 9073 590 9609 590 9609 590 9073 590 9610 590 9609 7964 9610 7964 9611 7964 9611 590 9610 590 9070 590 9611 590 9070 590 9612 590 9612 590 9070 590 9613 590 9612 590 9613 590 9614 590 9614 7965 9613 7965 9673 7965 9614 590 9673 590 9615 590 9615 7966 9673 7966 9672 7966 9616 590 9688 590 9082 590 9082 590 9688 590 9689 590 9082 590 9689 590 9617 590 9617 590 9689 590 9736 590 9617 590 9736 590 9618 590 9618 590 9736 590 8927 590 9618 7967 8927 7967 8928 7967 9619 7805 8738 7805 9620 7805 9620 590 8738 590 9621 590 9620 590 9621 590 9086 590 9086 590 9621 590 9622 590 9623 590 9406 590 9404 590 9404 7968 9406 7968 9408 7968 9404 590 9408 590 9624 590 9624 590 9408 590 9766 590 9624 590 9766 590 9626 590 9626 590 9766 590 9625 590 9626 590 9625 590 9089 590 9394 590 9628 590 9625 590 9625 590 9628 590 9630 590 9625 7969 9630 7969 9089 7969 9642 7970 9627 7970 9628 7970 9628 7971 9627 7971 9629 7971 9629 590 9631 590 9628 590 9628 7972 9631 7972 9091 7972 9628 7973 9091 7973 9630 7973 9631 590 9632 590 9091 590 9091 590 9632 590 9633 590 9091 7974 9633 7974 9093 7974 9093 7975 9633 7975 9634 7975 9093 590 9634 590 9635 590 9635 7976 9634 7976 9636 7976 9635 590 9636 590 9641 590 9641 590 9636 590 9640 590 9637 590 9102 590 9638 590 9638 590 9102 590 9100 590 9638 590 9100 590 9639 590 9639 590 9100 590 9098 590 9639 7977 9098 7977 9640 7977 9640 590 9098 590 9096 590 9640 590 9096 590 9641 590 9637 590 9642 590 9102 590 9102 590 9642 590 9628 590 9102 590 9628 590 9643 590 9643 590 9628 590 8897 590 9643 7978 8897 7978 8896 7978 9778 590 9780 590 9374 590 9374 590 9780 590 9373 590 9374 7979 9373 7979 8861 7979 9370 590 9645 590 9644 590 9644 590 9645 590 9646 590 9644 590 9646 590 9410 590 9410 590 9646 590 9121 590 9410 7980 9121 7980 9412 7980 9412 590 9121 590 9120 590 9412 590 9120 590 9647 590 9647 590 9120 590 9648 590 9647 7981 9648 7981 9116 7981 9161 7982 9700 7982 9649 7982 9649 590 9700 590 9311 590 9649 590 9311 590 9650 590 9650 7983 9311 7983 9308 7983 9650 590 9308 590 9129 590 9129 590 9308 590 9655 590 9129 590 9655 590 9127 590 9519 7984 9652 7984 9651 7984 9651 590 9652 590 9175 590 9651 590 9175 590 9177 590 9653 590 9469 590 9654 590 9654 7985 9469 7985 9131 7985 9654 7986 9131 7986 9658 7986 9127 590 9655 590 9126 590 9126 590 9655 590 9651 590 9126 7922 9651 7922 9656 7922 9131 7987 9657 7987 9658 7987 9658 7988 9657 7988 9659 7988 9658 590 9659 590 9177 590 9177 7989 9659 7989 9660 7989 9177 590 9660 590 9651 590 9651 7990 9660 7990 9661 7990 9651 7991 9661 7991 9656 7991 9669 590 9754 590 9668 590 9666 7804 9662 7804 9667 7804 9754 7918 9134 7918 9755 7918 9755 7992 9134 7992 9133 7992 9755 590 9133 590 9464 590 9505 7993 9663 7993 9504 7993 9504 7994 9663 7994 9665 7994 9504 7995 9665 7995 9664 7995 9664 590 9665 590 9666 590 9664 590 9666 590 9668 590 9668 590 9666 590 9667 590 9668 590 9667 590 9669 590 9152 590 9220 590 9155 590 9155 590 9220 590 9670 590 9155 590 9670 590 9157 590 9157 7996 9670 7996 9159 7996 9151 7997 9671 7997 9508 7997 9508 7998 9671 7998 9149 7998 9508 590 9149 590 9509 590 9509 590 9149 590 9147 590 9509 7873 9147 7873 9145 7873 9672 590 9673 590 9688 590 9688 590 9673 590 9681 590 9688 7999 9681 7999 9685 7999 9674 590 9675 590 9677 590 9677 590 9675 590 9676 590 9677 590 9676 590 9684 590 9674 590 9678 590 9675 590 9675 8000 9678 8000 9679 8000 9675 590 9679 590 9673 590 9673 7877 9679 7877 9680 7877 9673 8001 9680 8001 9681 8001 9739 590 9682 590 9676 590 9676 590 9682 590 9683 590 9676 8002 9683 8002 9684 8002 9685 590 9686 590 9688 590 9688 8003 9686 8003 9687 8003 9688 590 9687 590 9689 590 9689 8004 9687 8004 9690 8004 9689 8005 9690 8005 9691 8005 9699 590 9692 590 9696 590 9696 590 9692 590 9693 590 9211 590 9694 590 9210 590 9210 590 9694 590 9445 590 9210 590 9445 590 9695 590 9695 590 9445 590 9448 590 9695 590 9448 590 9693 590 9693 590 9448 590 9757 590 9693 590 9757 590 9696 590 9586 590 9579 590 9743 590 9743 590 9579 590 9697 590 9743 590 9697 590 9698 590 9698 590 9697 590 9215 590 9698 590 9215 590 9699 590 9699 590 9215 590 9218 590 9699 590 9218 590 9692 590 9159 590 9670 590 9700 590 9700 8006 9670 8006 9701 8006 9700 590 9701 590 9311 590 9311 590 9701 590 9227 590 9311 590 9227 590 9312 590 9152 8007 9151 8007 9220 8007 9220 590 9151 590 9508 590 9220 590 9508 590 9702 590 9702 590 9508 590 9510 590 9702 590 9510 590 9222 590 9222 590 9510 590 9704 590 9222 590 9704 590 9703 590 9703 590 9704 590 9026 590 9703 590 9026 590 9705 590 9705 590 9026 590 9280 590 9705 590 9280 590 9706 590 9706 590 9280 590 9312 590 9706 8008 9312 8008 9707 8008 9707 590 9312 590 9227 590 9719 590 9710 590 9708 590 9708 590 9710 590 9709 590 9708 590 9709 590 8733 590 9719 590 9239 590 9710 590 9710 590 9239 590 9531 590 9710 590 9531 590 9248 590 9248 7819 9531 7819 9711 7819 9248 590 9711 590 8707 590 8707 590 9711 590 8706 590 9418 590 9712 590 9713 590 9713 590 9712 590 9535 590 9713 590 9535 590 9421 590 9421 8009 9535 8009 9714 8009 9421 590 9714 590 9715 590 9715 590 9714 590 9237 590 9715 590 9237 590 9086 590 9086 590 9237 590 9716 590 9086 8010 9716 8010 9620 8010 9620 590 9716 590 9717 590 9620 590 9717 590 9708 590 9708 590 9717 590 9718 590 9708 590 9718 590 9719 590 9720 590 50084 590 9722 590 9722 590 50084 590 9721 590 9722 590 9721 590 9037 590 9037 8011 9721 8011 9723 8011 9037 590 9723 590 9038 590 9038 590 9723 590 9724 590 9038 8012 9724 8012 9040 8012 9040 8013 9724 8013 9725 8013 9040 590 9725 590 9042 590 9042 8014 9725 8014 9726 8014 9042 590 9726 590 9727 590 9727 590 9726 590 9541 590 9727 590 9541 590 9728 590 9728 590 9541 590 9729 590 9728 590 9729 590 9427 590 9427 590 9729 590 9544 590 9427 590 9544 590 9730 590 9730 590 9544 590 9731 590 9730 590 9731 590 9439 590 9439 590 9731 590 9732 590 9439 590 9732 590 9507 590 9507 8015 9732 8015 9733 8015 9507 590 9733 590 9734 590 9246 590 9736 590 9735 590 9735 590 9736 590 9689 590 9735 590 9689 590 9739 590 9739 590 9689 590 9691 590 9739 8016 9691 8016 9682 8016 9066 7946 9738 7946 9737 7946 9737 590 9738 590 9596 590 9737 590 9596 590 9675 590 9675 590 9596 590 9598 590 9675 590 9598 590 9676 590 9676 590 9598 590 9584 590 9676 590 9584 590 9739 590 9739 590 9584 590 9740 590 9739 590 9740 590 9735 590 9745 590 9740 590 9741 590 9741 590 9740 590 9584 590 9741 590 9584 590 9742 590 9742 590 9584 590 9743 590 9742 590 9743 590 9744 590 9744 590 9743 590 9698 590 9744 8017 9698 8017 9745 8017 9745 8018 9698 8018 9740 8018 9758 590 9172 590 9748 590 9748 590 9172 590 9746 590 9748 8019 9746 8019 9448 8019 9448 8020 9746 8020 9168 8020 9448 590 9168 590 9757 590 9757 590 9168 590 9169 590 9506 590 9756 590 9747 590 9747 590 9756 590 9758 590 9747 590 9758 590 9507 590 9507 590 9758 590 9748 590 9507 590 9748 590 9439 590 9439 8021 9748 8021 9438 8021 9439 8022 9438 8022 9749 8022 9757 590 9458 590 9696 590 9696 590 9458 590 9461 590 9696 590 9461 590 9699 590 9699 590 9461 590 9493 590 9699 590 9493 590 9698 590 9698 590 9493 590 9750 590 9698 590 9750 590 9740 590 9740 590 9750 590 9751 590 9740 590 9751 590 9735 590 9735 590 9751 590 9417 590 9735 590 9417 590 9752 590 9752 8023 9417 8023 9416 8023 9497 8024 9482 8024 9750 8024 9750 590 9482 590 9513 590 9750 590 9513 590 9751 590 9751 590 9513 590 9515 590 9751 590 9515 590 9417 590 9417 590 9515 590 9539 590 9417 590 9539 590 9415 590 9415 590 9539 590 9753 590 9754 8025 9755 8025 9668 8025 9668 590 9755 590 9458 590 9668 590 9458 590 9756 590 9756 590 9458 590 9757 590 9756 590 9757 590 9758 590 9758 8026 9757 8026 9169 8026 9758 8017 9169 8017 9172 8017 9359 8027 9759 8027 9357 8027 9357 590 9759 590 9760 590 9357 590 9760 590 9271 590 9271 590 9760 590 9762 590 9761 590 8913 590 9325 590 9325 590 8913 590 8914 590 9325 8028 8914 8028 9348 8028 9348 590 8914 590 8917 590 9348 8029 8917 8029 9760 8029 9760 590 8917 590 9413 590 9760 590 9413 590 9762 590 9762 590 9413 590 9763 590 9287 7797 9323 7797 9338 7797 9338 590 9323 590 9764 590 9338 590 9764 590 9334 590 9334 590 9764 590 9776 590 9334 590 9776 590 9773 590 9765 590 9625 590 9781 590 9781 590 9625 590 9766 590 9781 590 9766 590 9782 590 9782 590 9766 590 9408 590 9782 590 9408 590 9767 590 9767 590 9408 590 8910 590 9767 8030 8910 8030 8906 8030 9770 590 9763 590 8825 590 8825 590 9763 590 9413 590 8825 590 9413 590 9768 590 9768 590 9413 590 9647 590 9768 8031 9647 8031 9769 8031 9769 8032 9647 8032 9771 8032 9769 590 9771 590 9770 590 9770 590 9771 590 9763 590 9409 590 9773 590 9644 590 9644 590 9773 590 9775 590 9644 590 9775 590 9368 590 9368 8033 9775 8033 9772 8033 9368 590 9772 590 9776 590 9776 590 9772 590 9774 590 9776 8034 9774 8034 9773 8034 9773 8035 9774 8035 8791 8035 9773 590 8791 590 9775 590 8884 590 9368 590 9788 590 9788 590 9368 590 9776 590 9788 590 9776 590 9566 590 9566 590 9776 590 9764 590 9566 590 9764 590 9318 590 9318 8036 9764 8036 9777 8036 9318 590 9777 590 9317 590 9398 590 9779 590 9778 590 9778 590 9779 590 9400 590 9778 590 9400 590 9780 590 9780 590 9400 590 9781 590 9780 590 9781 590 9771 590 9771 590 9781 590 9782 590 9771 590 9782 590 9763 590 9763 590 9782 590 9767 590 9763 590 9767 590 9762 590 9762 590 9767 590 9783 590 9762 590 9783 590 9271 590 9271 590 9783 590 9784 590 9271 8037 9784 8037 9785 8037 9567 590 9787 590 9786 590 9786 590 9787 590 9564 590 9786 590 9564 590 9241 590 9241 590 9564 590 9562 590 9241 590 9562 590 9788 590 9788 590 9562 590 9550 590 9788 590 9550 590 9789 590 9789 590 9550 590 9388 590 9794 21 9790 21 9514 21 9514 21 9790 21 9516 21 9475 8038 8975 8038 9791 8038 9791 8039 8975 8039 9792 8039 9791 8040 9792 8040 9793 8040 9793 8041 9792 8041 9794 8041 9793 8042 9794 8042 9514 8042 9871 8043 9826 8043 9795 8043 9795 8044 9826 8044 9844 8044 9795 8045 9844 8045 9868 8045 9868 8046 9844 8046 9796 8046 9868 8047 9796 8047 9797 8047 9797 8048 9796 8048 9842 8048 9797 8049 9842 8049 9874 8049 9874 8050 9842 8050 9798 8050 9874 8051 9798 8051 9875 8051 9875 8052 9798 8052 9829 8052 9875 8053 9829 8053 9799 8053 9799 8054 9829 8054 9827 8054 9799 8055 9827 8055 9800 8055 9800 8056 9827 8056 9801 8056 9800 8057 9801 8057 9802 8057 9802 8058 9801 8058 9803 8058 9802 8059 9803 8059 9865 8059 9865 8060 9803 8060 9840 8060 9865 8061 9840 8061 9869 8061 9869 8062 9840 8062 9839 8062 9869 8063 9839 8063 9804 8063 9804 8064 9839 8064 9838 8064 9804 8065 9838 8065 9871 8065 9871 8066 9838 8066 9826 8066 9843 8067 9834 8067 9863 8067 9863 8068 9834 8068 9805 8068 9807 8069 9870 8069 9806 8069 9806 8070 9870 8070 9837 8070 9807 8071 9806 8071 9815 8071 9807 8072 9815 8072 9808 8072 9808 8073 9815 8073 9810 8073 9808 8074 9810 8074 9809 8074 9809 8075 9810 8075 9811 8075 9809 8076 9811 8076 9866 8076 9866 8077 9811 8077 9812 8077 9866 8078 9812 8078 9864 8078 9813 8079 9814 8079 9837 8079 9837 8080 9814 8080 9823 8080 9803 8081 9812 8081 9840 8081 9840 8082 9812 8082 9811 8082 9811 8083 9810 8083 9840 8083 9840 8084 9810 8084 9815 8084 9840 8085 9815 8085 9806 8085 9816 8086 9817 8086 9823 8086 9823 8087 9817 8087 9899 8087 9891 8088 9818 8088 9820 8088 9820 8089 9818 8089 9819 8089 9820 8090 9819 8090 9823 8090 9823 8091 9819 8091 9821 8091 9823 8092 9821 8092 9816 8092 9822 8093 9823 8093 9859 8093 9859 8094 9823 8094 9899 8094 9859 8095 9899 8095 9824 8095 9825 8096 9854 8096 9826 8096 9803 8097 9801 8097 9812 8097 9812 8098 9801 8098 9827 8098 9812 8099 9827 8099 9828 8099 9828 8100 9827 8100 9829 8100 9828 8101 9829 8101 9830 8101 9830 8102 9829 8102 9798 8102 9830 8103 9798 8103 9831 8103 9831 8104 9798 8104 9842 8104 9825 8105 9826 8105 9857 8105 9853 8106 9851 8106 9796 8106 9899 8107 9832 8107 9824 8107 9824 8108 9832 8108 9897 8108 9824 8109 9897 8109 9833 8109 9833 8110 9897 8110 9895 8110 9833 8111 9895 8111 9834 8111 9834 8112 9895 8112 9894 8112 9894 8113 9892 8113 9834 8113 9834 8114 9892 8114 9835 8114 9834 8115 9835 8115 9836 8115 9822 8116 9857 8116 9823 8116 9823 8117 9857 8117 9826 8117 9823 8118 9826 8118 9837 8118 9837 8119 9826 8119 9838 8119 9837 8120 9838 8120 9806 8120 9806 8121 9838 8121 9839 8121 9806 8122 9839 8122 9840 8122 9850 8123 9848 8123 9834 8123 9834 8124 9848 8124 9847 8124 9834 8125 9847 8125 9833 8125 9891 8126 9820 8126 9892 8126 9892 8127 9820 8127 9841 8127 9892 8128 9841 8128 9835 8128 9851 8129 9850 8129 9796 8129 9796 8130 9850 8130 9834 8130 9796 8131 9834 8131 9842 8131 9842 8132 9834 8132 9843 8132 9842 8133 9843 8133 9831 8133 9853 8134 9796 8134 9854 8134 9854 8135 9796 8135 9844 8135 9854 8136 9844 8136 9826 8136 9884 8137 9824 8137 9845 8137 9845 8138 9824 8138 9833 8138 9845 8139 9833 8139 9846 8139 9846 8140 9833 8140 9847 8140 9846 8141 9847 8141 9860 8141 9860 8142 9847 8142 9848 8142 9860 8143 9848 8143 9849 8143 9849 8144 9848 8144 9850 8144 9849 8145 9850 8145 9862 8145 9862 8146 9850 8146 9851 8146 9862 8147 9851 8147 9852 8147 9852 8148 9851 8148 9853 8148 9852 8149 9853 8149 9867 8149 9867 8150 9853 8150 9854 8150 9867 8151 9854 8151 9855 8151 9855 8152 9854 8152 9825 8152 9855 8153 9825 8153 9856 8153 9856 8154 9825 8154 9857 8154 9856 8155 9857 8155 9879 8155 9879 8156 9857 8156 9822 8156 9879 8157 9822 8157 9858 8157 9858 8158 9822 8158 9859 8158 9858 8159 9859 8159 9884 8159 9884 8160 9859 8160 9824 8160 9862 8161 9863 8161 9805 8161 9846 8162 9860 8162 9805 8162 9805 8163 9860 8163 9849 8163 9805 8164 9849 8164 9862 8164 9875 8165 9799 8165 9861 8165 9861 8166 9799 8166 9800 8166 9861 8167 9800 8167 9864 8167 9862 8168 9852 8168 9863 8168 9863 8169 9852 8169 9867 8169 9863 8170 9867 8170 9797 8170 9800 8171 9802 8171 9864 8171 9864 8172 9802 8172 9865 8172 9864 8173 9865 8173 9866 8173 9866 8174 9865 8174 9869 8174 9856 8175 9871 8175 9855 8175 9855 8176 9871 8176 9795 8176 9855 8177 9795 8177 9867 8177 9867 8178 9795 8178 9868 8178 9867 8179 9868 8179 9797 8179 9809 8180 9866 8180 9808 8180 9808 8181 9866 8181 9869 8181 9808 8182 9869 8182 9807 8182 9807 8183 9869 8183 9804 8183 9807 8184 9804 8184 9870 8184 9870 8185 9804 8185 9871 8185 9870 8186 9871 8186 9879 8186 9879 8187 9871 8187 9856 8187 9872 8188 9863 8188 9873 8188 9873 8189 9863 8189 9797 8189 9873 8190 9797 8190 9861 8190 9861 8191 9797 8191 9874 8191 9861 8192 9874 8192 9875 8192 9876 8193 9877 8193 9881 8193 9881 8194 9877 8194 9878 8194 9881 8195 9878 8195 9901 8195 9901 8196 9878 8196 9870 8196 9901 8197 9870 8197 9900 8197 9900 8198 9870 8198 9879 8198 9900 8199 9879 8199 9898 8199 9898 8200 9879 8200 9858 8200 9898 8201 9858 8201 9880 8201 9881 8202 9902 8202 9876 8202 9876 8203 9902 8203 9882 8203 9876 8204 9882 8204 9883 8204 9883 8205 9882 8205 9890 8205 9883 8206 9890 8206 9889 8206 9858 8207 9884 8207 9880 8207 9880 8208 9884 8208 9845 8208 9880 8209 9845 8209 9885 8209 9885 8210 9845 8210 9846 8210 9885 8211 9846 8211 9896 8211 9896 8212 9846 8212 9805 8212 9896 8213 9805 8213 9893 8213 9893 8214 9805 8214 9889 8214 9886 8215 9883 8215 9887 8215 9887 8216 9883 8216 9889 8216 9887 8217 9889 8217 9888 8217 9888 8218 9889 8218 9805 8218 9902 8219 9819 8219 9882 8219 9882 8220 9819 8220 9818 8220 9882 8221 9818 8221 9890 8221 9890 8222 9818 8222 9891 8222 9890 8223 9891 8223 9889 8223 9889 8224 9891 8224 9892 8224 9889 8225 9892 8225 9893 8225 9893 8226 9892 8226 9894 8226 9893 8227 9894 8227 9896 8227 9896 8228 9894 8228 9895 8228 9896 8229 9895 8229 9885 8229 9885 8230 9895 8230 9897 8230 9885 8231 9897 8231 9880 8231 9880 8232 9897 8232 9832 8232 9880 8233 9832 8233 9898 8233 9898 8234 9832 8234 9899 8234 9898 8235 9899 8235 9900 8235 9900 8236 9899 8236 9817 8236 9900 8237 9817 8237 9901 8237 9901 8238 9817 8238 9816 8238 9901 8239 9816 8239 9881 8239 9881 8240 9816 8240 9821 8240 9881 8241 9821 8241 9902 8241 9902 8242 9821 8242 9819 8242 10052 8243 9904 8243 9903 8243 9903 8244 9904 8244 9985 8244 9903 8245 9985 8245 10045 8245 10045 8246 9985 8246 9905 8246 10045 8247 9905 8247 9906 8247 9906 8248 9905 8248 9983 8248 9906 8249 9983 8249 9907 8249 9907 8250 9983 8250 9908 8250 9907 8251 9908 8251 10047 8251 10047 8252 9908 8252 9982 8252 10047 8253 9982 8253 9909 8253 9909 8254 9982 8254 9988 8254 9909 8255 9988 8255 10057 8255 10057 8256 9988 8256 9910 8256 10057 8257 9910 8257 10059 8257 10059 8258 9910 8258 9980 8258 10059 8259 9980 8259 10060 8259 10060 8260 9980 8260 9981 8260 10060 8261 9981 8261 10044 8261 10044 8262 9981 8262 9911 8262 10044 8263 9911 8263 9913 8263 9913 8264 9911 8264 9912 8264 9913 8265 9912 8265 10052 8265 10052 8266 9912 8266 9904 8266 9923 8267 9914 8267 10050 8267 10050 8268 9914 8268 9915 8268 10050 8269 9915 8269 10051 8269 10051 8246 9915 8246 9987 8246 10051 8247 9987 8247 9916 8247 9916 8270 9987 8270 9977 8270 9916 8271 9977 8271 10043 8271 10043 8272 9977 8272 9917 8272 10043 8273 9917 8273 9918 8273 9918 8252 9917 8252 9992 8252 9918 8253 9992 8253 10058 8253 10058 8274 9992 8274 9919 8274 10058 8275 9919 8275 10055 8275 10055 8276 9919 8276 9921 8276 10055 8277 9921 8277 9920 8277 9920 8258 9921 8258 9995 8258 9920 8278 9995 8278 10053 8278 10053 8279 9995 8279 10001 8279 10053 8280 10001 8280 10082 8280 10082 8281 10001 8281 9979 8281 10082 8282 9979 8282 10083 8282 10083 8264 9979 8264 9922 8264 10083 8283 9922 8283 9923 8283 9923 8284 9922 8284 9914 8284 9924 8285 10089 8285 10010 8285 10010 8286 10089 8286 9925 8286 10010 8287 9925 8287 9996 8287 9996 8288 9925 8288 9926 8288 9996 8289 9926 8289 9997 8289 9997 8290 9926 8290 10098 8290 9997 8291 10098 8291 9927 8291 9927 8292 10098 8292 9928 8292 9927 8293 9928 8293 10006 8293 10006 8294 9928 8294 10094 8294 10006 8295 10094 8295 10003 8295 10003 8296 10094 8296 9929 8296 10003 8297 9929 8297 9930 8297 9930 8298 9929 8298 9931 8298 9930 8057 9931 8057 9932 8057 9932 8299 9931 8299 9933 8299 9932 8300 9933 8300 9934 8300 9934 8301 9933 8301 9935 8301 9934 8302 9935 8302 9998 8302 9998 8303 9935 8303 10091 8303 9998 8304 10091 8304 9999 8304 9999 8305 10091 8305 9936 8305 9999 8306 9936 8306 9924 8306 9924 8307 9936 8307 10089 8307 10022 8308 9938 8308 9937 8308 9937 8309 9938 8309 9939 8309 9937 8310 9939 8310 9940 8310 9940 8311 9939 8311 9941 8311 9940 8312 9941 8312 9942 8312 9942 8313 9941 8313 9944 8313 9942 8314 9944 8314 9943 8314 9943 8315 9944 8315 9946 8315 9943 8316 9946 8316 9945 8316 9945 8317 9946 8317 10067 8317 9945 8318 10067 8318 10018 8318 10018 8230 10067 8230 10069 8230 10018 8319 10069 8319 9947 8319 9947 8320 10069 8320 10073 8320 9947 8321 10073 8321 10020 8321 10020 8322 10073 8322 10070 8322 10020 8235 10070 8235 9948 8235 9948 8323 10070 8323 9949 8323 9948 8324 9949 8324 9950 8324 9950 8325 9949 8325 10078 8325 9950 8326 10078 8326 9951 8326 9951 8240 10078 8240 9952 8240 9951 8241 9952 8241 10022 8241 10022 8327 9952 8327 9938 8327 10092 8328 10093 8328 10004 8328 10004 8329 10093 8329 9953 8329 9955 8330 10090 8330 9954 8330 9955 8331 9954 8331 9956 8331 9956 8332 9954 8332 9957 8332 9956 8333 9957 8333 10005 8333 10005 8334 9957 8334 10088 8334 10005 8335 10088 8335 9958 8335 9958 8336 10088 8336 10092 8336 9958 8337 10092 8337 10004 8337 10015 8338 9959 8338 10000 8338 10000 8339 9959 8339 10085 8339 10000 8340 10085 8340 9955 8340 9955 8341 10085 8341 10090 8341 10065 8342 10024 8342 9960 8342 9960 8343 10024 8343 9961 8343 9960 8344 9961 8344 9962 8344 9962 8345 9961 8345 10027 8345 9990 8346 9964 8346 9963 8346 9963 8346 9964 8346 10099 8346 9970 8347 10009 8347 9965 8347 9965 8348 10009 8348 10097 8348 9966 8349 9978 8349 10084 8349 10084 8350 9978 8350 9967 8350 10084 8351 9967 8351 10086 8351 9967 8352 9968 8352 10086 8352 10086 8353 9968 8353 9969 8353 10086 8354 9969 8354 10087 8354 10087 8355 9969 8355 9970 8355 10087 8356 9970 8356 9965 8356 9986 8357 9978 8357 9971 8357 9971 8358 9978 8358 9966 8358 10049 8359 9975 8359 9984 8359 10049 8360 9984 8360 9972 8360 9972 8361 9984 8361 9973 8361 9972 8362 9973 8362 9974 8362 9974 8363 9973 8363 9986 8363 9974 8364 9986 8364 9971 8364 10102 21 9975 21 10048 21 10048 8365 9975 8365 10049 8365 9976 8366 10034 8366 10002 8366 9911 8367 9981 8367 9977 8367 9986 8368 9915 8368 9978 8368 9978 8369 9915 8369 9914 8369 9978 8370 9914 8370 9967 8370 9967 8371 9914 8371 9922 8371 9967 8372 9922 8372 9979 8372 9980 8373 9992 8373 9981 8373 9981 8374 9992 8374 9917 8374 9981 8375 9917 8375 9977 8375 9982 8376 9908 8376 10102 8376 10102 8377 9908 8377 9983 8377 10102 8378 9983 8378 9975 8378 9975 8379 9983 8379 9905 8379 9975 8380 9905 8380 9984 8380 9984 8381 9905 8381 9985 8381 9984 8382 9985 8382 9973 8382 9973 8383 9985 8383 9986 8383 9985 8384 9904 8384 9986 8384 9986 8385 9904 8385 9912 8385 9986 8386 9912 8386 9915 8386 9915 8387 9912 8387 9911 8387 9915 8388 9911 8388 9987 8388 9987 8389 9911 8389 9977 8389 10102 8390 10100 8390 9982 8390 9982 8391 10100 8391 9989 8391 9982 8392 9989 8392 9988 8392 9988 8393 9989 8393 9964 8393 9988 8394 9964 8394 9910 8394 9910 8395 9964 8395 9990 8395 9910 8396 9990 8396 9980 8396 9980 8397 9990 8397 9991 8397 9980 8398 9991 8398 9992 8398 9993 8399 9921 8399 9991 8399 9991 8400 9921 8400 9919 8400 9991 8401 9919 8401 9992 8401 9993 8402 9994 8402 9921 8402 9921 8403 9994 8403 10002 8403 9921 8404 10002 8404 9995 8404 9995 8405 10002 8405 10001 8405 10010 8406 9996 8406 10002 8406 10002 8407 9996 8407 9997 8407 9956 8408 9998 8408 9955 8408 9955 8409 9998 8409 9999 8409 9955 8410 9999 8410 10000 8410 10000 8411 9999 8411 9924 8411 10000 8412 9924 8412 10010 8412 9979 8413 10001 8413 9967 8413 9967 8414 10001 8414 10002 8414 9967 8415 10002 8415 9968 8415 10006 8416 10003 8416 9953 8416 9953 8417 10003 8417 9930 8417 9953 8418 9930 8418 10004 8418 9930 8419 9932 8419 10004 8419 10004 8420 9932 8420 9934 8420 10004 8173 9934 8173 9958 8173 9958 8421 9934 8421 9998 8421 9958 8422 9998 8422 10005 8422 10005 8423 9998 8423 9956 8423 9953 8424 10007 8424 10006 8424 10006 8425 10007 8425 10008 8425 10006 8426 10008 8426 9927 8426 9927 8427 10008 8427 10009 8427 9927 8428 10009 8428 9997 8428 9997 8429 10009 8429 9970 8429 9997 8430 9970 8430 10002 8430 10002 8431 9970 8431 9969 8431 10002 8432 9969 8432 9968 8432 10010 8433 10002 8433 10000 8433 10000 8434 10002 8434 10034 8434 10000 8435 10034 8435 10036 8435 10036 8436 10011 8436 10000 8436 10000 8437 10011 8437 10038 8437 10000 8438 10038 8438 10015 8438 10015 8439 10038 8439 10040 8439 10015 8440 10040 8440 10019 8440 10023 8441 10012 8441 10014 8441 10014 8442 10012 8442 10013 8442 10014 8443 10013 8443 10002 8443 10002 8444 10013 8444 10031 8444 10002 8445 10031 8445 9976 8445 10019 8446 9948 8446 10015 8446 10015 8447 9948 8447 9950 8447 10015 8448 9950 8448 10016 8448 10016 8449 9950 8449 9951 8449 10016 8450 9951 8450 10017 8450 10023 8451 10018 8451 10030 8451 10030 8452 10018 8452 9947 8452 10030 8453 9947 8453 10019 8453 10019 8454 9947 8454 10020 8454 10019 8455 10020 8455 9948 8455 10017 8193 9951 8193 10021 8193 10021 8456 9951 8456 10022 8456 10021 8457 10022 8457 10014 8457 10014 8458 10022 8458 9937 8458 10014 8459 9937 8459 9940 8459 9940 8460 9942 8460 10014 8460 10014 8461 9942 8461 9943 8461 10014 8462 9943 8462 10023 8462 10023 8463 9943 8463 9945 8463 10023 8464 9945 8464 10018 8464 10024 8465 10025 8465 10026 8465 9994 8466 10027 8466 10002 8466 10002 8467 10027 8467 9961 8467 10002 8468 9961 8468 10014 8468 10014 8469 9961 8469 10024 8469 10014 8470 10024 8470 10028 8470 10028 8471 10024 8471 10026 8471 10028 8472 10026 8472 10029 8472 10019 8473 10072 8473 10030 8473 10030 8474 10072 8474 10068 8474 10030 8475 10068 8475 10023 8475 10023 8476 10068 8476 10081 8476 10023 8477 10081 8477 10012 8477 10012 8478 10081 8478 10080 8478 10012 8479 10080 8479 10013 8479 10013 8480 10080 8480 10032 8480 10013 8481 10032 8481 10031 8481 10031 8482 10032 8482 10033 8482 10031 8483 10033 8483 9976 8483 9976 8484 10033 8484 10071 8484 9976 8485 10071 8485 10034 8485 10034 8486 10071 8486 10035 8486 10034 8487 10035 8487 10036 8487 10036 8152 10035 8152 10074 8152 10036 8153 10074 8153 10011 8153 10011 8488 10074 8488 10037 8488 10011 8489 10037 8489 10038 8489 10038 8490 10037 8490 10039 8490 10038 8491 10039 8491 10040 8491 10040 8492 10039 8492 10041 8492 10040 8493 10041 8493 10019 8493 10019 8494 10041 8494 10072 8494 10083 8495 9923 8495 10084 8495 10057 8496 10056 8497 10042 8498 10052 8499 10043 8499 9913 8499 9913 8500 10043 8500 10044 8500 9903 8501 10045 8501 10049 8501 10057 8502 10042 8502 9909 8502 9909 8503 10042 8503 9963 8503 9909 8504 9963 8504 10099 8504 10099 8505 10046 8505 9909 8505 9909 8506 10046 8506 10101 8506 9909 8507 10101 8507 10047 8507 10047 8508 10101 8508 10048 8508 10047 8509 10048 8509 9907 8509 9907 8510 10048 8510 10049 8510 9907 8511 10049 8511 9906 8511 9906 8512 10049 8512 10045 8512 10084 8513 9923 8513 9966 8513 9966 8514 9923 8514 10050 8514 9966 8515 10050 8515 9971 8515 9971 8516 10050 8516 10051 8516 9971 8517 10051 8517 9974 8517 9974 8518 10051 8518 9916 8518 9974 8519 9916 8519 9972 8519 9972 8520 9916 8520 10043 8520 9972 8521 10043 8521 10049 8521 10049 8522 10043 8522 10052 8522 10049 8523 10052 8523 9903 8523 9920 8524 10053 8524 10061 8524 10061 8525 10053 8525 10082 8525 10044 8526 10043 8526 10060 8526 10060 8527 10043 8527 9918 8527 10060 8528 9918 8528 10058 8528 9960 8529 9962 8529 10061 8529 10061 8530 9962 8530 10054 8530 10061 8531 10054 8531 9920 8531 9920 8532 10054 8532 10056 8532 9920 8533 10056 8533 10055 8533 10055 8534 10056 8534 10057 8534 10055 8535 10057 8535 10058 8535 10058 8536 10057 8536 10059 8536 10058 8537 10059 8537 10060 8537 9960 8538 10061 8538 10065 8538 10065 8539 10061 8539 10075 8539 10065 8540 10075 8540 10062 8540 10062 8541 10063 8541 10065 8541 10065 8542 10063 8542 10064 8542 10065 8543 10064 8543 10066 8543 10078 8544 9949 8544 9959 8544 10067 8545 10068 8545 10069 8545 10069 8546 10068 8546 10072 8546 10069 8547 10072 8547 10073 8547 9959 8548 9949 8548 10085 8548 10085 8549 9949 8549 10070 8549 10085 8550 10070 8550 10073 8550 10035 8551 10071 8551 10061 8551 10072 8552 10041 8552 10073 8552 10073 8553 10041 8553 10039 8553 10073 8554 10039 8554 10085 8554 10085 8555 10039 8555 10037 8555 10085 8556 10037 8556 10074 8556 10071 8557 10033 8557 10061 8557 10061 8558 10033 8558 10032 8558 10061 8559 10032 8559 10080 8559 9941 8560 9939 8560 10075 8560 10075 8561 9939 8561 9938 8561 10075 8562 9938 8562 10076 8562 10076 8563 9938 8563 9952 8563 10076 8564 9952 8564 10077 8564 10077 8565 9952 8565 10078 8565 10077 8566 10078 8566 10079 8566 10079 8567 10078 8567 9959 8567 9941 8568 10075 8568 9944 8568 9944 8569 10075 8569 10061 8569 9944 8570 10061 8570 9946 8570 9946 8571 10061 8571 10080 8571 9946 8572 10080 8572 10067 8572 10067 8573 10080 8573 10081 8573 10067 8574 10081 8574 10068 8574 10074 8575 10035 8575 10085 8575 10085 8576 10035 8576 10061 8576 10085 8577 10061 8577 10084 8577 10084 8578 10061 8578 10082 8578 10084 8579 10082 8579 10083 8579 10098 8580 9926 8580 9965 8580 9935 8581 9933 8581 10092 8581 10084 8582 10086 8582 10085 8582 10085 8583 10086 8583 10087 8583 10085 8584 10087 8584 9965 8584 9954 8585 10090 8585 9957 8585 9957 8586 10090 8586 9935 8586 9957 8083 9935 8083 10088 8083 10088 8587 9935 8587 10092 8587 9926 8588 9925 8588 9965 8588 9965 8589 9925 8589 10089 8589 9965 8590 10089 8590 10085 8590 10085 8591 10089 8591 9936 8591 10085 8592 9936 8592 10090 8592 10090 8593 9936 8593 10091 8593 10090 8594 10091 8594 9935 8594 9933 8595 9931 8595 10092 8595 10092 8596 9931 8596 9929 8596 10092 8597 9929 8597 10093 8597 10093 8598 9929 8598 10094 8598 10093 8599 10094 8599 10095 8599 10095 8600 10094 8600 9928 8600 10095 8601 9928 8601 10096 8601 10096 8602 9928 8602 10098 8602 10096 8603 10098 8603 10097 8603 10097 8604 10098 8604 9965 8604 10099 8605 9964 8605 9989 8605 10099 8606 9989 8606 10046 8606 10046 8607 9989 8607 10100 8607 10046 8608 10100 8608 10101 8608 10101 8609 10100 8609 10102 8609 10101 8610 10102 8610 10048 8610 10165 8611 10104 8611 10103 8611 10103 8612 10104 8612 10105 8612 10103 8612 10105 8612 10106 8612 10106 8613 10105 8613 10107 8613 10106 8614 10107 8614 10176 8614 10176 8615 10107 8615 10108 8615 10176 8616 10108 8616 10175 8616 10175 8617 10108 8617 10110 8617 10175 8617 10110 8617 10109 8617 10109 8618 10110 8618 10111 8618 10109 8618 10111 8618 10172 8618 10172 8619 10111 8619 10112 8619 10172 8620 10112 8620 10171 8620 10171 8621 10112 8621 10113 8621 10171 8622 10113 8622 10114 8622 10114 8623 10113 8623 10115 8623 10114 8624 10115 8624 10116 8624 10116 8625 10115 8625 10267 8625 10116 8626 10267 8626 10117 8626 10117 8627 10267 8627 10119 8627 10117 8627 10119 8627 10118 8627 10118 8628 10119 8628 10120 8628 10118 8628 10120 8628 10165 8628 10165 8629 10120 8629 10104 8629 10143 8630 10184 8630 10121 8630 10121 8631 10184 8631 10183 8631 10121 8632 10183 8632 10122 8632 10122 8633 10183 8633 10182 8633 10122 8634 10182 8634 10123 8634 10123 8635 10182 8635 10179 8635 10123 8636 10179 8636 10134 8636 10134 8637 10179 8637 10124 8637 10134 8638 10124 8638 10135 8638 10135 8639 10124 8639 10188 8639 10135 8640 10188 8640 10137 8640 10137 8641 10188 8641 10187 8641 10137 8642 10187 8642 10125 8642 10125 8643 10187 8643 10127 8643 10125 8644 10127 8644 10126 8644 10126 8645 10127 8645 10128 8645 10126 8646 10128 8646 10138 8646 10138 8647 10128 8647 10185 8647 10138 8648 10185 8648 10129 8648 10129 8649 10185 8649 10130 8649 10129 8650 10130 8650 10141 8650 10141 8651 10130 8651 10131 8651 10141 8652 10131 8652 10143 8652 10143 8653 10131 8653 10184 8653 10144 8654 10121 8654 10132 8654 10132 8655 10121 8655 10122 8655 10132 8656 10122 8656 10146 8656 10146 8657 10122 8657 10123 8657 10146 8658 10123 8658 10133 8658 10133 8659 10123 8659 10134 8659 10133 8660 10134 8660 10148 8660 10148 8661 10134 8661 10135 8661 10148 8662 10135 8662 10136 8662 10136 8663 10135 8663 10137 8663 10136 8664 10137 8664 10152 8664 10152 8665 10137 8665 10125 8665 10152 8666 10125 8666 10153 8666 10153 8667 10125 8667 10126 8667 10153 8668 10126 8668 10156 8668 10156 8669 10126 8669 10138 8669 10156 8670 10138 8670 10139 8670 10139 8671 10138 8671 10129 8671 10139 8672 10129 8672 10140 8672 10140 8673 10129 8673 10141 8673 10140 8674 10141 8674 10142 8674 10142 8675 10141 8675 10143 8675 10142 8676 10143 8676 10144 8676 10144 8677 10143 8677 10121 8677 10159 8678 10132 8678 10145 8678 10145 8679 10132 8679 10146 8679 10145 8680 10146 8680 10161 8680 10161 8681 10146 8681 10133 8681 10161 8682 10133 8682 10147 8682 10147 8683 10133 8683 10148 8683 10147 8684 10148 8684 10149 8684 10149 8685 10148 8685 10136 8685 10149 8686 10136 8686 10150 8686 10150 8687 10136 8687 10152 8687 10150 8688 10152 8688 10151 8688 10151 8689 10152 8689 10153 8689 10151 8690 10153 8690 10154 8690 10154 8691 10153 8691 10156 8691 10154 8692 10156 8692 10155 8692 10155 8693 10156 8693 10139 8693 10155 8694 10139 8694 10157 8694 10157 8695 10139 8695 10140 8695 10157 8696 10140 8696 10158 8696 10158 8697 10140 8697 10142 8697 10158 8698 10142 8698 10164 8698 10164 8699 10142 8699 10144 8699 10164 8700 10144 8700 10159 8700 10159 8701 10144 8701 10132 8701 10178 8702 10145 8702 10160 8702 10160 8703 10145 8703 10161 8703 10160 8704 10161 8704 10166 8704 10166 8705 10161 8705 10147 8705 10166 8706 10147 8706 10167 8706 10167 8707 10147 8707 10149 8707 10167 8708 10149 8708 10168 8708 10168 8709 10149 8709 10150 8709 10168 8710 10150 8710 10169 8710 10169 8711 10150 8711 10151 8711 10169 8712 10151 8712 10170 8712 10170 8713 10151 8713 10154 8713 10170 8714 10154 8714 10162 8714 10162 8715 10154 8715 10155 8715 10162 8716 10155 8716 10173 8716 10173 8717 10155 8717 10157 8717 10173 8718 10157 8718 10174 8718 10174 8719 10157 8719 10158 8719 10174 8720 10158 8720 10163 8720 10163 8721 10158 8721 10164 8721 10163 8722 10164 8722 10177 8722 10177 8723 10164 8723 10159 8723 10177 8724 10159 8724 10178 8724 10178 8725 10159 8725 10145 8725 10103 8726 10160 8726 10165 8726 10165 8727 10160 8727 10166 8727 10165 8728 10166 8728 10118 8728 10118 8729 10166 8729 10167 8729 10118 8730 10167 8730 10117 8730 10117 8731 10167 8731 10168 8731 10117 8732 10168 8732 10116 8732 10116 8733 10168 8733 10169 8733 10116 8734 10169 8734 10114 8734 10114 8735 10169 8735 10170 8735 10114 8736 10170 8736 10171 8736 10171 8737 10170 8737 10162 8737 10171 8738 10162 8738 10172 8738 10172 8739 10162 8739 10173 8739 10172 8740 10173 8740 10109 8740 10109 8741 10173 8741 10174 8741 10109 8742 10174 8742 10175 8742 10175 8743 10174 8743 10163 8743 10175 8744 10163 8744 10176 8744 10176 8745 10163 8745 10177 8745 10176 8746 10177 8746 10106 8746 10106 8747 10177 8747 10178 8747 10106 8748 10178 8748 10103 8748 10103 8749 10178 8749 10160 8749 10195 8750 10189 8750 10124 8750 10195 8751 10124 8751 10180 8751 10180 8752 10124 8752 10179 8752 10180 8753 10179 8753 10181 8753 10181 8754 10179 8754 10182 8754 10181 8755 10182 8755 10198 8755 10198 8756 10182 8756 10183 8756 10198 8757 10183 8757 10199 8757 10199 8758 10183 8758 10184 8758 10199 8759 10184 8759 10201 8759 10201 8760 10184 8760 10131 8760 10201 8761 10131 8761 10202 8761 10202 8762 10131 8762 10130 8762 10202 8763 10130 8763 10190 8763 10190 8764 10130 8764 10185 8764 10190 8765 10185 8765 10191 8765 10191 8766 10185 8766 10128 8766 10191 8767 10128 8767 10193 8767 10193 8768 10128 8768 10127 8768 10193 8769 10127 8769 10186 8769 10186 8770 10127 8770 10187 8770 10186 8771 10187 8771 10189 8771 10189 8772 10187 8772 10188 8772 10189 8773 10188 8773 10124 8773 10217 8774 10202 8774 10203 8774 10203 8775 10202 8775 10190 8775 10203 8776 10190 8776 10205 8776 10205 8777 10190 8777 10191 8777 10205 8778 10191 8778 10192 8778 10192 8779 10191 8779 10193 8779 10192 8780 10193 8780 10209 8780 10209 8781 10193 8781 10186 8781 10209 8782 10186 8782 10194 8782 10194 8783 10186 8783 10189 8783 10194 8784 10189 8784 10212 8784 10212 8785 10189 8785 10195 8785 10212 8786 10195 8786 10213 8786 10213 8787 10195 8787 10180 8787 10213 8788 10180 8788 10196 8788 10196 8789 10180 8789 10181 8789 10196 8790 10181 8790 10197 8790 10197 8791 10181 8791 10198 8791 10197 8792 10198 8792 10216 8792 10216 8793 10198 8793 10199 8793 10216 8794 10199 8794 10200 8794 10200 8795 10199 8795 10201 8795 10200 8796 10201 8796 10217 8796 10217 8797 10201 8797 10202 8797 10218 8798 10203 8798 10204 8798 10204 8799 10203 8799 10205 8799 10204 8800 10205 8800 10206 8800 10206 8801 10205 8801 10192 8801 10206 8802 10192 8802 10207 8802 10207 8803 10192 8803 10209 8803 10207 8804 10209 8804 10208 8804 10208 8805 10209 8805 10194 8805 10208 8806 10194 8806 10210 8806 10210 8807 10194 8807 10212 8807 10210 8808 10212 8808 10211 8808 10211 8809 10212 8809 10213 8809 10211 8810 10213 8810 10214 8810 10214 8811 10213 8811 10196 8811 10214 8812 10196 8812 10222 8812 10222 8813 10196 8813 10197 8813 10222 8814 10197 8814 10215 8814 10215 8815 10197 8815 10216 8815 10215 8816 10216 8816 10223 8816 10223 8817 10216 8817 10200 8817 10223 8818 10200 8818 10226 8818 10226 8819 10200 8819 10217 8819 10226 8820 10217 8820 10218 8820 10218 8821 10217 8821 10203 8821 10227 8822 10204 8822 10219 8822 10219 8823 10204 8823 10206 8823 10219 8824 10206 8824 10220 8824 10220 8825 10206 8825 10207 8825 10220 8826 10207 8826 10230 8826 10230 8827 10207 8827 10208 8827 10230 8828 10208 8828 10232 8828 10232 8829 10208 8829 10210 8829 10232 8830 10210 8830 10221 8830 10221 8831 10210 8831 10211 8831 10221 8832 10211 8832 10233 8832 10233 8833 10211 8833 10214 8833 10233 8834 10214 8834 10235 8834 10235 8835 10214 8835 10222 8835 10235 8836 10222 8836 10237 8836 10237 8837 10222 8837 10215 8837 10237 8838 10215 8838 10239 8838 10239 8839 10215 8839 10223 8839 10239 8840 10223 8840 10224 8840 10224 8841 10223 8841 10226 8841 10224 8842 10226 8842 10225 8842 10225 8843 10226 8843 10218 8843 10225 8844 10218 8844 10227 8844 10227 8845 10218 8845 10204 8845 10252 8846 10219 8846 10228 8846 10228 8847 10219 8847 10220 8847 10228 8848 10220 8848 10229 8848 10229 8849 10220 8849 10230 8849 10229 8850 10230 8850 10231 8850 10231 8851 10230 8851 10232 8851 10231 8852 10232 8852 10244 8852 10244 8853 10232 8853 10221 8853 10244 8854 10221 8854 10245 8854 10245 8855 10221 8855 10233 8855 10245 8856 10233 8856 10234 8856 10234 8857 10233 8857 10235 8857 10234 8858 10235 8858 10236 8858 10236 8859 10235 8859 10237 8859 10236 8860 10237 8860 10238 8860 10238 8861 10237 8861 10239 8861 10238 8862 10239 8862 10249 8862 10249 8863 10239 8863 10224 8863 10249 8864 10224 8864 10240 8864 10240 8865 10224 8865 10225 8865 10240 8866 10225 8866 10241 8866 10241 8867 10225 8867 10227 8867 10241 8868 10227 8868 10252 8868 10252 8869 10227 8869 10219 8869 10242 8870 10228 8870 10243 8870 10243 8871 10228 8871 10229 8871 10243 8872 10229 8872 10263 8872 10263 8873 10229 8873 10231 8873 10263 8874 10231 8874 10262 8874 10262 8875 10231 8875 10244 8875 10262 8876 10244 8876 10260 8876 10260 8877 10244 8877 10245 8877 10260 8878 10245 8878 10246 8878 10246 8879 10245 8879 10234 8879 10246 8880 10234 8880 10247 8880 10247 8881 10234 8881 10236 8881 10247 8882 10236 8882 10257 8882 10257 8883 10236 8883 10238 8883 10257 8884 10238 8884 10248 8884 10248 8885 10238 8885 10249 8885 10248 8886 10249 8886 10250 8886 10250 8887 10249 8887 10240 8887 10250 8888 10240 8888 10251 8888 10251 8889 10240 8889 10241 8889 10251 8890 10241 8890 10253 8890 10253 8891 10241 8891 10252 8891 10253 8892 10252 8892 10242 8892 10242 8893 10252 8893 10228 8893 10243 8894 10265 8894 10242 8894 10242 8895 10265 8895 10270 8895 10242 8895 10270 8895 10253 8895 10253 8896 10270 8896 10269 8896 10253 8896 10269 8896 10251 8896 10251 8897 10269 8897 10268 8897 10251 8898 10268 8898 10250 8898 10250 8899 10268 8899 10254 8899 10250 8900 10254 8900 10248 8900 10248 8901 10254 8901 10255 8901 10248 8902 10255 8902 10257 8902 10257 8903 10255 8903 10256 8903 10257 8904 10256 8904 10247 8904 10247 8905 10256 8905 10258 8905 10247 8906 10258 8906 10246 8906 10246 8907 10258 8907 10259 8907 10246 8908 10259 8908 10260 8908 10260 8909 10259 8909 10261 8909 10260 8910 10261 8910 10262 8910 10262 8911 10261 8911 10264 8911 10262 8911 10264 8911 10263 8911 10263 8912 10264 8912 10266 8912 10263 8912 10266 8912 10243 8912 10243 8913 10266 8913 10265 8913 10265 8914 10104 8914 10120 8914 10104 21 10265 21 10105 21 10105 8915 10265 8915 10266 8915 10105 8916 10266 8916 10107 8916 10107 21 10266 21 10264 21 10107 21 10264 21 10108 21 10108 21 10264 21 10261 21 10108 21 10261 21 10110 21 10110 21 10261 21 10259 21 10110 21 10259 21 10111 21 10111 21 10259 21 10258 21 10111 21 10258 21 10112 21 10112 8917 10258 8917 10256 8917 10112 21 10256 21 10113 21 10113 8918 10256 8918 10255 8918 10113 8919 10255 8919 10115 8919 10115 21 10255 21 10254 21 10115 21 10254 21 10267 21 10267 8920 10254 8920 10268 8920 10267 8921 10268 8921 10119 8921 10119 8922 10268 8922 10269 8922 10119 21 10269 21 10120 21 10120 21 10269 21 10270 21 10120 21 10270 21 10265 21 10271 8923 10272 8923 10967 8923 10967 8924 10272 8924 10475 8924 10967 6701 10475 6701 10273 6701 10273 8925 10475 8925 10274 8925 10273 8926 10274 8926 10840 8926 10840 8927 10274 8927 10275 8927 10276 6 10278 6 10277 6 10277 6 10278 6 10279 6 10277 6 10279 6 10280 6 10280 6 10279 6 10750 6 10281 21 10282 21 10283 21 10283 21 10282 21 10871 21 10283 21 10871 21 10284 21 10284 21 10871 21 10285 21 10917 8928 10286 8928 10914 8928 10914 8929 10286 8929 10287 8929 10914 8930 10287 8930 10913 8930 10913 8931 10287 8931 10289 8931 10913 8932 10289 8932 10288 8932 10288 8933 10289 8933 10373 8933 10290 8934 10567 8934 10291 8934 10291 8935 10567 8935 10566 8935 10291 8936 10566 8936 10998 8936 10998 8937 10566 8937 10677 8937 10292 8938 10293 8938 10294 8938 10294 8939 10293 8939 10676 8939 10295 8940 11110 8940 10583 8940 10583 8941 11110 8941 10594 8941 11113 8942 10296 8942 10297 8942 10297 8943 10296 8943 10627 8943 10297 8944 10627 8944 10298 8944 10298 215 10627 215 10595 215 10303 8945 11092 8945 10299 8945 10299 8946 11092 8946 10300 8946 10299 8947 10300 8947 10301 8947 10301 8948 10300 8948 10745 8948 10301 8949 10745 8949 10302 8949 10302 8950 10745 8950 11107 8950 11092 50 10303 50 10894 50 10894 50 10303 50 10304 50 10894 50 10304 50 10887 50 10887 50 10304 50 10727 50 10887 50 10727 50 11157 50 11157 50 10727 50 10634 50 11157 50 10634 50 10305 50 10305 50 10634 50 10635 50 10649 8951 10306 8951 10637 8951 10637 8952 10306 8952 11089 8952 10637 8953 11089 8953 10636 8953 10636 8954 11089 8954 11075 8954 10636 8955 11075 8955 10635 8955 10635 8956 11075 8956 10305 8956 10306 8957 10649 8957 11073 8957 11073 8958 10649 8958 10648 8958 11073 8959 10648 8959 10307 8959 10307 8960 10648 8960 10371 8960 10308 8961 10313 8961 10368 8961 10368 8962 10313 8962 11059 8962 10368 8963 11059 8963 10723 8963 10723 8964 11059 8964 11160 8964 10723 8965 11160 8965 10724 8965 10724 8965 11160 8965 10309 8965 10724 8966 10309 8966 10548 8966 10548 8967 10309 8967 10995 8967 10548 8968 10995 8968 10310 8968 10310 8968 10995 8968 10311 8968 10316 8969 11050 8969 10312 8969 10312 8970 11050 8970 11049 8970 10312 8971 11049 8971 10722 8971 10722 8972 11049 8972 11053 8972 10722 8973 11053 8973 10721 8973 10721 8974 11053 8974 11057 8974 10721 8975 11057 8975 10308 8975 10308 8976 11057 8976 10313 8976 10314 8977 10905 8977 10656 8977 10656 8978 10905 8978 11165 8978 10656 8979 11165 8979 10315 8979 10315 8980 11165 8980 10317 8980 10315 8981 10317 8981 10316 8981 10316 8982 10317 8982 11050 8982 10323 8983 10318 8983 10319 8983 10319 8984 10318 8984 11034 8984 10319 8985 11034 8985 10663 8985 10663 8986 11034 8986 10320 8986 10663 8987 10320 8987 10314 8987 10314 8988 10320 8988 10905 8988 6963 8989 10321 8989 10660 8989 10660 8990 10321 8990 10322 8990 10660 8991 10322 8991 10323 8991 10323 290 10322 290 10318 290 10439 8992 10821 8992 10435 8992 10435 8993 10821 8993 11024 8993 10435 8994 11024 8994 10667 8994 10667 8995 11024 8995 11025 8995 10667 8996 11025 8996 6963 8996 6963 8997 11025 8997 10321 8997 7212 8998 11019 8998 10431 8998 10431 8999 11019 8999 11020 8999 10431 9000 11020 9000 10324 9000 10324 9001 11020 9001 10325 9001 10324 9002 10325 9002 10439 9002 10439 9002 10325 9002 10821 9002 10326 49 10328 49 10327 49 10327 49 10328 49 10330 49 10327 49 10330 49 10329 49 10329 49 10330 49 10331 49 10329 49 10331 49 10799 49 10799 49 10331 49 10424 49 10799 49 10424 49 10332 49 10332 49 10424 49 10334 49 10332 9003 10334 9003 10333 9003 10333 9004 10334 9004 10335 9004 10333 9005 10335 9005 10336 9005 10336 9006 10335 9006 10337 9006 10336 9007 10337 9007 10338 9007 10338 9008 10337 9008 10340 9008 10338 9009 10340 9009 10339 9009 10339 9010 10340 9010 10612 9010 10339 293 10612 293 10986 293 10986 9011 10612 9011 10341 9011 10986 9012 10341 9012 10985 9012 10985 9013 10341 9013 10683 9013 10985 9014 10683 9014 10342 9014 10342 9015 10683 9015 10343 9015 4921 9016 10837 9016 10344 9016 10344 9016 10837 9016 10345 9016 10344 9017 10345 9017 10685 9017 10685 9018 10345 9018 10831 9018 10685 9019 10831 9019 10346 9019 10346 9020 10831 9020 10979 9020 10693 9021 10347 9021 10692 9021 10692 9022 10347 9022 10977 9022 10692 9023 10977 9023 10452 9023 10452 9024 10977 9024 10976 9024 10452 9025 10976 9025 4921 9025 4921 9026 10976 9026 10837 9026 10700 9027 10348 9027 10694 9027 10694 9028 10348 9028 10349 9028 10694 9029 10349 9029 10350 9029 10350 9030 10349 9030 10970 9030 10350 9031 10970 9031 10693 9031 10693 9032 10970 9032 10347 9032 10356 9033 10357 9033 10351 9033 10351 9034 10357 9034 10848 9034 10351 9035 10848 9035 10352 9035 10352 9036 10848 9036 10959 9036 10352 9037 10959 9037 10700 9037 10700 9038 10959 9038 10348 9038 10704 9039 10353 9039 10354 9039 10354 9040 10353 9040 10355 9040 10354 9041 10355 9041 10736 9041 10736 9042 10355 9042 10956 9042 10736 9043 10956 9043 10356 9043 10356 9044 10956 9044 10357 9044 10358 9045 10360 9045 10359 9045 10359 9046 10360 9046 10939 9046 10359 9047 10939 9047 10361 9047 10361 9048 10939 9048 10362 9048 10361 9049 10362 9049 10708 9049 10708 9050 10362 9050 10954 9050 10708 9051 10954 9051 10703 9051 10703 9052 10954 9052 11151 9052 10703 9053 11151 9053 10704 9053 10704 9054 11151 9054 10353 9054 10360 9055 10358 9055 10363 9055 10363 9056 10358 9056 10712 9056 10363 9057 10712 9057 10364 9057 10364 9058 10712 9058 10365 9058 10364 9059 10365 9059 11154 9059 11154 9059 10365 9059 10366 9059 11154 9060 10366 9060 11130 9060 11130 9061 10366 9061 10598 9061 11130 9062 10598 9062 10367 9062 10367 9062 10598 9062 10596 9062 10340 590 10593 590 10612 590 7212 590 10431 590 10718 590 10723 590 10650 590 10368 590 10369 590 10548 590 10310 590 10370 590 6046 590 10638 590 10646 9063 10371 9063 10648 9063 10372 9064 10373 9064 10289 9064 10289 590 10287 590 10374 590 10375 9065 10275 9065 10274 9065 10441 590 10376 590 10324 590 10377 590 10579 590 10424 590 10422 590 10378 590 10499 590 10734 590 10741 590 10733 590 10669 9066 10379 9066 10670 9066 10726 590 10380 590 10381 590 10381 9067 10380 9067 10382 9067 10381 590 10382 590 10387 590 10383 2170 10562 2170 10384 2170 10387 9068 10388 9068 10718 9068 10718 9069 10388 9069 10385 9069 10718 590 10385 590 10669 590 10382 590 10386 590 10387 590 10387 590 10386 590 10389 590 10387 590 10389 590 10388 590 10388 9070 10389 9070 10390 9070 10398 590 10391 590 10674 590 10391 590 10392 590 10674 590 10674 9071 10392 9071 10394 9071 10674 9072 10394 9072 10393 9072 10393 590 10394 590 10395 590 10393 590 10395 590 10561 590 10674 590 10396 590 10398 590 10398 9073 10396 9073 10397 9073 10398 590 10397 590 10390 590 10390 9074 10397 9074 10399 9074 10390 590 10399 590 10388 590 10742 9075 10400 9075 10732 9075 10679 590 10681 590 10401 590 10401 590 10681 590 10731 590 10401 2178 10731 2178 10402 2178 10402 590 10731 590 10403 590 10680 590 10404 590 10682 590 10405 2184 10415 2184 10410 2184 10404 9076 10406 9076 10682 9076 10682 2180 10406 2180 10407 2180 10682 590 10407 590 10408 590 10408 9077 10407 9077 10405 9077 10408 590 10405 590 10409 590 10409 590 10405 590 10410 590 10411 590 10412 590 10444 590 10444 9078 10412 9078 10413 9078 10444 9079 10413 9079 10417 9079 10405 590 10414 590 10415 590 10415 9080 10414 9080 10444 9080 10415 590 10444 590 10416 590 10416 9081 10444 9081 10417 9081 10418 590 10730 590 10419 590 10419 590 10730 590 10499 590 10419 590 10499 590 10420 590 10420 590 10499 590 10378 590 10421 590 10422 590 10586 590 10421 590 10586 590 10580 590 10424 590 10579 590 10334 590 10331 590 10423 590 10424 590 10424 9082 10423 9082 10425 9082 10424 9083 10425 9083 10377 9083 10427 590 10426 590 10728 590 10427 590 10728 590 10729 590 10330 590 10678 590 10331 590 10331 9084 10678 9084 10428 9084 10331 590 10428 590 10423 590 10717 590 10429 590 10719 590 10719 2195 10429 2195 10430 2195 10324 590 10376 590 10431 590 10431 9085 10376 9085 10432 9085 10431 2307 10432 2307 10718 2307 10518 590 10433 590 10524 590 10524 590 10433 590 10666 590 10666 9086 10434 9086 10435 9086 10435 2203 10434 2203 10436 2203 10435 9087 10436 9087 10439 9087 10436 9088 10437 9088 10439 9088 10439 2200 10437 2200 10438 2200 10439 9089 10438 9089 10324 9089 10324 9090 10438 9090 10440 9090 10324 2198 10440 2198 10441 2198 10483 590 10442 590 10481 590 10442 590 10443 590 10481 590 10481 2211 10443 2211 10445 2211 10481 590 10445 590 10444 590 10444 9091 10445 9091 10446 9091 10444 590 10446 590 10686 590 10447 9092 10449 9092 10344 9092 10344 9093 10449 9093 4921 9093 10690 9094 10448 9094 10691 9094 10449 590 10450 590 4921 590 4921 2216 10450 2216 10451 2216 4921 9095 10451 9095 10452 9095 10452 9096 10451 9096 10453 9096 10452 2213 10453 2213 10690 2213 10479 590 10455 590 10454 590 10466 2378 10464 2378 10455 2378 10466 590 10455 590 10738 590 10456 590 10457 590 10458 590 10458 2222 10457 2222 10459 2222 10458 590 10459 590 10460 590 10460 590 10461 590 10458 590 10458 2225 10461 2225 10462 2225 10458 590 10462 590 10466 590 10463 590 10464 590 10465 590 10465 590 10464 590 10466 590 10465 590 10466 590 10467 590 10467 590 10466 590 10462 590 10477 590 10468 590 10476 590 10476 9097 10468 9097 10702 9097 10351 590 10469 590 10356 590 10356 9098 10469 9098 10470 9098 10356 9099 10470 9099 10736 9099 10736 9100 10470 9100 10735 9100 10471 9101 10472 9101 10488 9101 10488 590 10472 590 10473 590 10488 2220 10473 2220 10688 2220 10689 590 10375 590 10698 590 10698 590 10375 590 10274 590 10698 590 10274 590 10474 590 10474 9102 10274 9102 10475 9102 10474 590 10475 590 10476 590 10476 590 10475 590 10272 590 10476 9103 10272 9103 10477 9103 10454 9104 10478 9104 10479 9104 10479 2228 10478 2228 10480 2228 10479 590 10480 590 10481 590 10481 9105 10480 9105 10482 9105 10481 590 10482 590 10485 590 10448 590 10483 590 10691 590 10691 590 10483 590 10481 590 10691 590 10481 590 10484 590 10484 590 10481 590 10485 590 10484 9106 10486 9106 10691 9106 10691 9107 10486 9107 10487 9107 10691 590 10487 590 10488 590 10488 9108 10487 9108 10489 9108 10488 2229 10489 2229 10471 2229 10491 590 10277 590 10280 590 10280 590 10490 590 10491 590 10491 2380 10490 2380 10492 2380 10491 2379 10492 2379 10730 2379 10492 590 10493 590 10730 590 10730 2236 10493 2236 10494 2236 10730 2235 10494 2235 10501 2235 10281 590 10283 590 10495 590 10495 590 10283 590 10496 590 10495 9109 10496 9109 10497 9109 10497 590 10496 590 10499 590 10497 590 10499 590 10498 590 10498 590 10499 590 10500 590 10501 2234 10502 2234 10730 2234 10730 590 10502 590 10503 590 10730 590 10503 590 10499 590 10499 9110 10503 9110 10504 9110 10499 2239 10504 2239 10500 2239 10276 590 10277 590 10505 590 10505 590 10277 590 10491 590 10505 2241 10491 2241 10506 2241 10506 590 10491 590 10727 590 10506 9111 10727 9111 10507 9111 10507 590 10727 590 10508 590 10516 590 10509 590 10727 590 10727 2244 10509 2244 10510 2244 10727 2243 10510 2243 10508 2243 10283 590 10284 590 10496 590 10496 590 10284 590 10511 590 10496 9112 10511 9112 10512 9112 10633 590 10513 590 10304 590 10304 2248 10513 2248 10514 2248 10304 590 10514 590 10727 590 10727 9113 10514 9113 10515 9113 10727 2246 10515 2246 10516 2246 10527 2259 10517 2259 10524 2259 10524 590 10517 590 10719 590 10524 590 10719 590 10518 590 10518 590 10719 590 10430 590 10517 590 10519 590 10719 590 10719 590 10519 590 10545 590 10719 590 10545 590 10543 590 10520 590 10521 590 10668 590 10668 590 10521 590 10522 590 10522 590 10523 590 10668 590 10668 2262 10523 2262 10525 2262 10668 590 10525 590 10524 590 10524 9114 10525 9114 10526 9114 10524 2260 10526 2260 10527 2260 10287 9115 10286 9115 10374 9115 10374 9116 10286 9116 10528 9116 10374 590 10528 590 10661 590 10715 590 10529 590 10530 590 10530 590 10531 590 10715 590 10715 9117 10531 9117 10532 9117 10715 9118 10532 9118 10657 9118 10658 590 10533 590 10656 590 10656 590 10533 590 10534 590 10534 590 10535 590 10656 590 10656 2257 10535 2257 10536 2257 10656 9119 10536 9119 10314 9119 10314 9120 10536 9120 10537 9120 10314 590 10537 590 10663 590 10663 9121 10537 9121 10538 9121 10663 2253 10538 2253 10539 2253 10540 9122 10541 9122 10542 9122 10542 590 10541 590 10543 590 10542 590 10543 590 10544 590 10544 590 10543 590 10545 590 10573 590 10575 590 10555 590 10677 590 10566 590 10568 590 10573 2299 10555 2299 10557 2299 11174 590 10546 590 11173 590 11173 9123 10546 9123 10675 9123 10725 590 10724 590 10547 590 10547 590 10724 590 10548 590 10547 590 10548 590 10549 590 10549 590 10548 590 10369 590 10549 9124 10369 9124 10550 9124 10551 2298 10555 2298 10294 2298 10551 9125 10294 9125 10675 9125 10550 590 10552 590 10549 590 10549 2304 10552 2304 10553 2304 10549 590 10553 590 10551 590 10551 9126 10553 9126 10554 9126 10551 9127 10554 9127 10555 9127 10555 9128 10554 9128 10556 9128 10555 2300 10556 2300 10557 2300 10558 9129 10673 9129 11175 9129 11175 590 10673 590 10559 590 11175 590 10559 590 11174 590 11174 590 10559 590 10560 590 11174 590 10560 590 10546 590 10672 590 10393 590 10383 590 10383 590 10393 590 10561 590 10383 590 10561 590 10562 590 10547 590 10563 590 10725 590 10725 2376 10563 2376 10564 2376 10725 590 10564 590 10383 590 10383 590 10564 590 10565 590 10383 590 10565 590 10672 590 10566 590 10567 590 10568 590 10568 2330 10567 2330 10569 2330 10568 2329 10569 2329 10638 2329 10638 2328 10569 2328 10570 2328 10638 9130 10570 9130 10647 9130 10573 590 10571 590 10572 590 10578 590 10645 590 10575 590 10575 590 10645 590 10647 590 10572 590 10574 590 10573 590 10573 2335 10574 2335 10576 2335 10573 590 10576 590 10575 590 10575 2334 10576 2334 10577 2334 10575 9131 10577 9131 10578 9131 10579 590 10580 590 10334 590 10334 9132 10580 9132 10586 9132 10334 590 10586 590 10335 590 10335 590 10586 590 10588 590 10335 590 10588 590 10337 590 10337 590 10588 590 10340 590 10588 590 10581 590 10340 590 10340 9133 10581 9133 10582 9133 10340 590 10582 590 10593 590 10593 9134 10582 9134 10583 9134 10593 590 10583 590 10594 590 10628 9135 10584 9135 10627 9135 10627 590 10584 590 10585 590 10627 590 10585 590 10595 590 10296 590 10587 590 10586 590 10586 2361 10587 2361 10589 2361 10586 2360 10589 2360 10588 2360 10588 2359 10589 2359 10590 2359 10588 590 10590 590 10581 590 10605 590 10598 590 10591 590 10591 590 10598 590 10366 590 10591 590 10366 590 10609 590 10592 590 10593 590 10585 590 10585 590 10593 590 10594 590 10585 2358 10594 2358 10595 2358 10596 590 10598 590 10597 590 10597 590 10598 590 10605 590 10597 9136 10605 9136 10599 9136 10599 590 10605 590 10600 590 10601 590 10602 590 10585 590 10585 590 10602 590 10603 590 10585 590 10603 590 10592 590 10592 9137 10603 9137 10604 9137 10592 590 10604 590 10605 590 10605 9138 10604 9138 10606 9138 10605 2371 10606 2371 10600 2371 10731 9139 10607 9139 10609 9139 10609 2377 10607 2377 10608 2377 10609 590 10608 590 10591 590 10592 9140 10610 9140 10593 9140 10593 590 10610 590 10611 590 10593 590 10611 590 10612 590 10612 9141 10611 9141 10613 9141 10612 590 10613 590 10341 590 10341 590 10613 590 10614 590 10341 590 10614 590 10683 590 10683 9142 10614 9142 10615 9142 10683 590 10615 590 10681 590 10681 2290 10615 2290 10616 2290 10681 590 10616 590 10731 590 10731 590 10616 590 10617 590 10731 590 10617 590 10607 590 10618 9143 10626 9143 10585 9143 10618 590 10585 590 10619 590 10619 9144 10585 9144 10584 9144 10619 590 10584 590 10620 590 10621 590 10623 590 10622 590 10622 9145 10623 9145 10601 9145 10622 590 10601 590 10624 590 10624 590 10601 590 10585 590 10624 590 10585 590 10625 590 10625 590 10585 590 10626 590 10627 9146 10296 9146 10628 9146 10628 590 10296 590 10586 590 10628 590 10586 590 10302 590 10302 590 10586 590 10301 590 10586 9147 10629 9147 6174 9147 6175 590 10496 590 10630 590 10630 590 10496 590 10299 590 10630 590 10299 590 6180 590 6180 9148 10299 9148 10301 9148 10422 590 10499 590 10586 590 10586 590 10499 590 6179 590 10586 9149 6179 9149 10629 9149 6174 590 6178 590 10586 590 10586 2351 6178 2351 6182 2351 10586 590 6182 590 10301 590 10301 2350 6182 2350 6181 2350 10301 9150 6181 9150 6180 9150 6175 590 6184 590 10496 590 10496 2356 6184 2356 10631 2356 10496 590 10631 590 10499 590 10499 9151 10631 9151 10632 9151 10499 2353 10632 2353 6179 2353 10512 2245 10633 2245 10496 2245 10496 590 10633 590 10304 590 10496 590 10304 590 10299 590 10299 590 10304 590 10303 590 10634 590 10643 590 10635 590 10635 590 10643 590 10636 590 10638 590 6046 590 10728 590 10640 9152 6052 9152 10637 9152 10637 2346 6052 2346 6190 2346 10637 590 6190 590 10638 590 10638 2345 6190 2345 10639 2345 10638 9153 10639 9153 10370 9153 10640 590 10637 590 10641 590 10641 9154 10637 9154 10636 9154 10641 590 10636 590 10642 590 10642 590 10636 590 10643 590 10642 590 10643 590 6048 590 6046 590 6185 590 10728 590 10728 2342 6185 2342 10644 2342 10728 9155 10644 9155 10643 9155 10643 9156 10644 9156 6050 9156 10643 2340 6050 2340 6048 2340 10645 590 10646 590 10647 590 10647 590 10646 590 10648 590 10647 590 10648 590 10638 590 10638 590 10648 590 10649 590 10638 9157 10649 9157 10637 9157 10368 590 10650 590 10308 590 10308 590 10650 590 10381 590 10308 590 10381 590 10721 590 7210 9158 7209 9158 10651 9158 7208 9159 7207 9159 10722 9159 10722 2326 7207 2326 7205 2326 10722 590 7205 590 10312 590 7205 590 10652 590 10312 590 10312 2324 10652 2324 7203 2324 10312 590 7203 590 10653 590 10653 9160 7203 9160 10654 9160 10653 9161 10654 9161 7202 9161 7202 9162 10655 9162 10653 9162 10653 590 10655 590 7201 590 10653 590 7201 590 10651 590 10651 590 7201 590 7200 590 10651 590 7200 590 7210 590 10315 590 10715 590 10656 590 10656 590 10715 590 10657 590 10656 9163 10657 9163 10658 9163 10659 590 7215 590 10374 590 10374 9164 7215 9164 7214 9164 10374 2316 7214 2316 7099 2316 7101 590 10659 590 10660 590 10660 9165 10659 9165 10374 9165 10660 590 10374 590 10668 590 10668 590 10374 590 10661 590 10668 9166 10661 9166 10520 9166 10662 590 10664 590 10319 590 7099 590 10662 590 10374 590 10374 590 10662 590 10319 590 10374 590 10319 590 10289 590 10289 590 10319 590 10663 590 10289 590 10663 590 10372 590 10372 2252 10663 2252 10539 2252 10664 590 10665 590 10319 590 10319 2315 10665 2315 7097 2315 10319 590 7097 590 10323 590 7097 590 7105 590 10323 590 10323 4207 7105 4207 7100 4207 10323 590 7100 590 10660 590 10660 9167 7100 9167 7102 9167 10660 2311 7102 2311 7101 2311 10666 590 10435 590 10524 590 10524 9168 10435 9168 10667 9168 10524 590 10667 590 10668 590 10668 9169 10667 9169 6963 9169 10668 590 6963 590 10660 590 10669 590 10670 590 10718 590 10718 590 10670 590 10671 590 10718 9170 10671 9170 7212 9170 10672 9171 10673 9171 10393 9171 10393 590 10673 590 10558 590 10393 590 10558 590 10674 590 10674 590 10558 590 11177 590 10294 9172 10676 9172 10675 9172 10675 2296 10676 2296 10677 2296 10675 590 10677 590 11173 590 11173 590 10677 590 10568 590 11173 590 10568 590 11172 590 11172 590 10568 590 10638 590 11172 590 10638 590 10328 590 10328 590 10638 590 10728 590 10328 590 10728 590 10330 590 10330 9173 10728 9173 10426 9173 10330 9174 10426 9174 10678 9174 10679 590 10680 590 10681 590 10681 590 10680 590 10682 590 10681 590 10682 590 10683 590 10683 590 10682 590 10343 590 10684 590 10411 590 10346 590 10346 590 10411 590 10444 590 10346 590 10444 590 10685 590 10685 2209 10444 2209 10686 2209 10685 9175 10686 9175 10344 9175 10344 590 10686 590 10687 590 10344 590 10687 590 10447 590 10350 590 10488 590 10698 590 10698 590 10488 590 10688 590 10698 9176 10688 9176 10689 9176 10690 590 10691 590 10452 590 10452 590 10691 590 10488 590 10452 590 10488 590 10692 590 10692 590 10488 590 10350 590 10692 9177 10350 9177 10693 9177 10701 590 10695 590 10474 590 10694 590 10350 590 10699 590 10699 590 5588 590 10694 590 10694 9178 5588 9178 5587 9178 10694 2286 5587 2286 5586 2286 10695 590 10696 590 10474 590 10474 590 10696 590 5591 590 10474 590 5591 590 10698 590 10698 590 5591 590 5590 590 5590 590 10697 590 10698 590 10698 2283 10697 2283 5589 2283 10698 590 5589 590 10350 590 10350 9179 5589 9179 5584 9179 10350 2280 5584 2280 10699 2280 10352 2277 10700 2277 10694 2277 5586 590 10701 590 10694 590 10694 590 10701 590 10474 590 10694 590 10474 590 10352 590 10352 590 10474 590 10476 590 10352 590 10476 590 10351 590 10351 590 10476 590 10702 590 10351 9180 10702 9180 10469 9180 10703 590 10704 590 10354 590 10710 2272 10706 2272 10739 2272 5488 9181 5487 9181 10705 9181 5487 9182 10708 9182 10705 9182 10705 9183 10708 9183 10703 9183 10705 590 10703 590 10737 590 10737 590 10703 590 10354 590 10737 590 10354 590 10736 590 10706 9184 5593 9184 10739 9184 10739 590 5593 590 5482 590 10739 590 5482 590 10705 590 10705 590 5482 590 5481 590 10705 590 5481 590 5488 590 5483 590 10361 590 10707 590 10707 9185 10361 9185 10708 9185 10707 590 10708 590 5486 590 5486 9186 10708 9186 5487 9186 5483 590 5598 590 10361 590 10361 2275 5598 2275 10709 2275 10361 2274 10709 2274 10710 2274 10710 2273 10739 2273 10361 2273 10361 590 10739 590 10711 590 10361 590 10711 590 10359 590 10359 590 10711 590 10358 590 10358 590 10711 590 10732 590 10358 590 10732 590 10712 590 10712 590 10732 590 10713 590 10712 590 10713 590 10365 590 10529 590 10715 590 10541 590 10541 590 10715 590 10714 590 10541 590 10714 590 10543 590 10543 590 10714 590 10716 590 10543 590 10716 590 10719 590 10316 9187 10312 9187 10315 9187 10315 590 10312 590 10653 590 10315 590 10653 590 10715 590 10715 590 10653 590 10651 590 10715 590 10651 590 10714 590 10714 590 10651 590 10720 590 10714 590 10720 590 10716 590 10432 590 10717 590 10718 590 10718 590 10717 590 10719 590 10718 590 10719 590 10387 590 10387 590 10719 590 10716 590 10387 590 10716 590 10381 590 10381 590 10716 590 10720 590 10381 590 10720 590 10721 590 10721 590 10720 590 10651 590 10721 590 10651 590 10722 590 10722 9188 10651 9188 7209 9188 10722 2318 7209 2318 7208 2318 10723 590 10724 590 10650 590 10650 590 10724 590 10725 590 10650 590 10725 590 10381 590 10381 590 10725 590 10383 590 10381 590 10383 590 10726 590 10726 590 10383 590 10384 590 10634 590 10727 590 10643 590 10643 590 10727 590 10491 590 10643 590 10491 590 10728 590 10728 590 10491 590 10730 590 10728 590 10730 590 10729 590 10729 590 10730 590 10418 590 10366 590 10365 590 10609 590 10609 590 10365 590 10713 590 10609 590 10713 590 10731 590 10731 590 10713 590 10732 590 10731 590 10732 590 10403 590 10403 590 10732 590 10400 590 10455 590 10479 590 10738 590 10738 590 10479 590 10481 590 10738 590 10481 590 10740 590 10740 590 10481 590 10444 590 10740 590 10444 590 10733 590 10733 590 10444 590 10414 590 10733 590 10414 590 10734 590 10735 590 10456 590 10736 590 10736 590 10456 590 10458 590 10736 590 10458 590 10737 590 10737 590 10458 590 10466 590 10737 590 10466 590 10705 590 10705 590 10466 590 10738 590 10705 590 10738 590 10739 590 10739 590 10738 590 10740 590 10739 590 10740 590 10711 590 10711 590 10740 590 10733 590 10711 590 10733 590 10732 590 10732 590 10733 590 10741 590 10732 590 10741 590 10742 590 10590 9189 10743 9189 10581 9189 10581 9190 10743 9190 10991 9190 10581 9191 10991 9191 10582 9191 10582 9192 10991 9192 10992 9192 10364 960 10936 960 10363 960 10744 960 11130 960 10367 960 11107 2526 10745 2526 10807 2526 10290 960 10291 960 11062 960 11002 960 10746 960 11069 960 11061 960 11062 960 10993 960 10326 960 10327 960 11080 960 10979 960 10831 960 10747 960 10970 960 10748 960 10843 960 10953 960 10940 960 10362 960 10933 960 10749 960 10934 960 10884 9193 10750 9193 10279 9193 10751 960 10752 960 10968 960 10753 960 10271 960 10967 960 10786 960 10754 960 10980 960 10755 960 11171 960 11170 960 10756 9194 11163 9194 11058 9194 10757 960 11013 960 10758 960 10758 960 11013 960 11138 960 10758 2398 11138 2398 10759 2398 10759 960 11138 960 11162 960 10755 960 11170 960 10765 960 11018 960 10760 960 10815 960 10815 960 10760 960 10761 960 10815 960 10761 960 10762 960 10763 9195 10764 9195 11014 9195 11170 960 11164 960 10765 960 10765 2406 11164 2406 10766 2406 10765 960 10766 960 10770 960 10764 960 10767 960 11014 960 11014 9196 10767 9196 10768 9196 11014 960 10768 960 10769 960 10769 9197 10768 9197 10770 9197 10769 9198 10770 9198 10771 9198 10771 960 10770 960 10766 960 10772 960 10773 960 10937 960 10937 9199 10773 9199 10774 9199 10775 2408 10776 2408 10777 2408 10775 960 10777 960 10754 960 10785 960 10778 960 10779 960 10983 2411 10780 2411 10781 2411 11153 960 10782 960 10783 960 10783 960 10784 960 10747 960 10747 9200 10784 9200 10791 9200 10790 960 10785 960 10747 960 10786 960 10980 960 10984 960 10793 960 10787 960 10791 960 10791 2410 10787 2410 10788 2410 10791 9201 10788 9201 10747 9201 10747 9202 10788 9202 10789 9202 10747 9203 10789 9203 10790 9203 10780 960 10983 960 10791 960 10791 960 10983 960 10792 960 10791 9204 10792 9204 10793 9204 11101 960 10794 960 10795 960 10795 960 10794 960 10876 960 10795 9205 10876 9205 10798 9205 11080 960 10796 960 10876 960 10876 9206 10796 9206 10797 9206 10876 9207 10797 9207 10798 9207 10811 960 10800 960 10799 960 10799 960 10800 960 10329 960 10800 960 10801 960 10329 960 10329 2419 10801 2419 10802 2419 10329 960 10802 960 10327 960 10327 9208 10802 9208 10803 9208 10327 960 10803 960 11080 960 11080 9209 10803 9209 10804 9209 11080 9210 10804 9210 10796 9210 10990 960 10807 960 10332 960 10805 9211 10806 9211 10807 9211 10807 9212 10806 9212 10808 9212 10807 960 10808 960 10332 960 10332 9213 10808 9213 10809 9213 10332 960 10809 960 10799 960 10799 9214 10809 9214 10810 9214 10799 9215 10810 9215 10811 9215 10919 960 10812 960 10930 960 10812 960 10813 960 10930 960 10930 2420 10813 2420 10814 2420 10930 960 10814 960 10815 960 10815 9216 10814 9216 10816 9216 10815 960 10816 960 11021 960 10817 9217 10918 9217 10923 9217 10325 2425 11023 2425 10818 2425 10325 960 10818 960 10821 960 10818 960 10819 960 10821 960 10821 2423 10819 2423 10820 2423 10821 960 10820 960 11024 960 11024 9218 10820 9218 10822 9218 11024 2422 10822 2422 10817 2422 10835 960 10824 960 10870 960 10870 9219 10824 9219 10823 9219 10823 960 10824 960 10825 960 10823 960 10825 960 10826 960 10837 9220 10827 9220 10345 9220 10345 960 10827 960 10828 960 10828 9221 10829 9221 10345 9221 10345 960 10829 960 10830 960 10345 960 10830 960 10831 960 10831 9222 10830 9222 10832 9222 10831 960 10832 960 10747 960 10747 960 10832 960 10833 960 10747 960 10833 960 10870 960 10870 9223 10833 9223 10834 9223 10870 2426 10834 2426 10835 2426 10826 960 10836 960 10976 960 10976 2432 10836 2432 10838 2432 10976 960 10838 960 10837 960 10837 9224 10838 9224 10839 9224 10837 2430 10839 2430 10827 2430 10845 960 10863 960 10843 960 10967 960 10273 960 10748 960 10748 960 10273 960 10840 960 10840 9225 10841 9225 10748 9225 10748 9226 10841 9226 10842 9226 10748 960 10842 960 10843 960 10843 9227 10842 9227 10844 9227 10843 2443 10844 2443 10845 2443 10751 960 10968 960 10846 960 10846 960 10848 960 10847 960 10847 9228 10848 9228 10357 9228 10847 960 10357 960 10849 960 10849 960 10357 960 10956 960 10849 2594 10956 2594 10958 2594 10857 2436 10850 2436 10855 2436 10855 2435 10850 2435 10851 2435 10855 2434 10851 2434 10957 2434 11150 960 10853 960 10852 960 10852 9229 10853 9229 10854 9229 10852 960 10854 960 10855 960 10855 960 10854 960 10856 960 10855 960 10856 960 10857 960 10858 960 10859 960 10862 960 10862 960 10859 960 11147 960 10870 960 10860 960 11147 960 11147 9230 10860 9230 10861 9230 11147 2446 10861 2446 10862 2446 10863 2441 10864 2441 10843 2441 10843 2451 10864 2451 10865 2451 10843 960 10865 960 10823 960 10823 9231 10865 9231 10866 9231 10866 960 10867 960 10823 960 10823 9232 10867 9232 10868 9232 10823 960 10868 960 10870 960 10870 9233 10868 9233 10869 9233 10870 2448 10869 2448 10860 2448 11105 960 10871 960 10282 960 10876 9234 10872 9234 10873 9234 10883 960 10874 960 10876 960 10876 2456 10874 2456 10875 2456 10876 2455 10875 2455 10872 2455 10282 9235 10877 9235 11105 9235 11105 9236 10877 9236 10878 9236 11105 9237 10878 9237 10794 9237 10794 9238 10878 9238 10879 9238 10879 960 10880 960 10794 960 10794 2460 10880 2460 10881 2460 10794 960 10881 960 10876 960 10876 9239 10881 9239 10882 9239 10876 960 10882 960 10883 960 10886 9240 11158 9240 10885 9240 10884 960 10279 960 10885 960 10885 960 10279 960 10278 960 10885 9241 10278 9241 10886 9241 11159 2461 10888 2461 10887 2461 10887 2467 10888 2467 10889 2467 10887 2466 10889 2466 10890 2466 10890 960 10891 960 10887 960 10887 2472 10891 2472 10892 2472 10887 960 10892 960 10894 960 10894 9242 10892 9242 10893 9242 10894 2470 10893 2470 11090 2470 10285 9243 10871 9243 10895 9243 10895 960 10871 960 11105 960 10895 9244 11105 9244 10896 9244 10896 960 11105 960 11091 960 10913 9245 10288 9245 10897 9245 10913 960 10897 960 10320 960 10933 9246 11166 9246 10898 9246 10898 960 11166 960 10899 960 10900 9247 10901 9247 11165 9247 11165 2484 10901 2484 10902 2484 11165 9248 10902 9248 10903 9248 10897 960 10904 960 10320 960 10320 2489 10904 2489 10906 2489 10320 960 10906 960 10905 960 10905 9249 10906 9249 10907 9249 10905 960 10907 960 11165 960 11165 9250 10907 9250 10908 9250 11165 2486 10908 2486 10900 2486 10909 960 10910 960 11027 960 10909 2475 11027 2475 10926 2475 10911 960 10912 960 10915 960 10915 2480 10912 2480 10916 2480 10320 960 11034 960 10913 960 10913 960 11034 960 10915 960 10913 960 10915 960 10914 960 10914 9251 10915 9251 10916 9251 10914 9252 10916 9252 10917 9252 10918 960 10919 960 10923 960 10923 960 10919 960 10930 960 10923 960 10930 960 10921 960 10921 960 10930 960 10920 960 10921 960 10922 960 10923 960 10923 2478 10922 2478 10924 2478 10923 960 10924 960 11027 960 11027 9253 10924 9253 10925 9253 11027 2476 10925 2476 10926 2476 10929 960 10935 960 10927 960 10927 960 10928 960 10929 960 10929 9254 10928 9254 10931 9254 10929 960 10931 960 10930 960 10930 9255 10931 9255 10932 9255 10930 2473 10932 2473 10920 2473 10933 960 10934 960 11166 960 11166 9256 10934 9256 10935 9256 11166 960 10935 960 11167 960 10363 960 10936 960 10360 960 10360 960 10936 960 10937 960 10360 960 10937 960 10939 960 10937 960 10938 960 10939 960 10939 960 10938 960 10948 960 10939 960 10948 960 10362 960 10362 9257 10940 9257 10954 9257 10954 9258 10940 9258 10941 9258 10954 9259 10941 9259 10942 9259 10942 960 10943 960 10945 960 10945 960 10943 960 10944 960 10944 9260 10946 9260 10945 9260 10945 960 10946 960 10947 960 10945 960 10947 960 10948 960 10948 960 10947 960 10949 960 10949 960 10950 960 10948 960 10948 960 10950 960 10951 960 10948 960 10951 960 10362 960 10362 2589 10951 2589 10952 2589 10362 2588 10952 2588 10953 2588 10942 960 10945 960 10954 960 10954 960 10945 960 10955 960 10954 960 10955 960 11151 960 10355 960 10855 960 10956 960 10956 960 10855 960 10957 960 10956 9261 10957 9261 10958 9261 10846 960 10968 960 10848 960 10848 960 10968 960 10966 960 10848 960 10966 960 10959 960 10959 960 10966 960 10349 960 10959 2583 10349 2583 10348 2583 10960 960 10961 960 10966 960 10966 2578 10961 2578 10962 2578 10963 960 10964 960 10349 960 10349 960 10964 960 10970 960 10965 9262 10960 9262 10748 9262 10748 960 10960 960 10966 960 10748 960 10966 960 10967 960 10967 960 10966 960 10968 960 10967 960 10968 960 10753 960 10753 960 10968 960 10752 960 10964 960 10969 960 10970 960 10970 2582 10969 2582 10971 2582 10970 9263 10971 9263 10748 9263 10748 9264 10971 9264 10972 9264 10748 2580 10972 2580 10965 2580 10962 960 10973 960 10966 960 10966 9265 10973 9265 10974 9265 10966 960 10974 960 10349 960 10349 9266 10974 9266 10975 9266 10349 2576 10975 2576 10963 2576 10826 960 10976 960 10823 960 10823 9267 10976 9267 10977 9267 10823 960 10977 960 10843 960 10843 9268 10977 9268 10347 9268 10843 9269 10347 9269 10970 9269 10785 960 10779 960 10747 960 10747 960 10779 960 10978 960 10747 9270 10978 9270 10979 9270 10985 960 10342 960 10983 960 10754 960 10777 960 10980 960 10980 960 10777 960 10981 960 10980 2519 10981 2519 10982 2519 10781 960 10984 960 10983 960 10983 9271 10984 9271 10980 9271 10983 960 10980 960 10985 960 10985 960 10980 960 10982 960 10985 9272 10982 9272 10986 9272 10986 960 10982 960 10987 960 10986 960 10987 960 10339 960 10295 960 10988 960 11110 960 11110 960 10988 960 11137 960 10987 9273 10989 9273 10339 9273 10339 9274 10989 9274 10988 9274 10339 960 10988 960 10338 960 10338 960 10988 960 10295 960 10332 960 10333 960 10990 960 10990 960 10333 960 10336 960 10990 960 10336 960 10991 960 10991 960 10336 960 10338 960 10991 9275 10338 9275 10992 9275 10992 9276 10338 9276 10295 9276 11008 9277 10993 9277 10999 9277 10996 960 10995 960 11143 960 11143 960 10995 960 10309 960 11143 960 10309 960 11141 960 10311 960 10995 960 10994 960 10994 960 10995 960 10996 960 10994 960 10996 960 10997 960 10997 960 10996 960 11006 960 11062 960 10291 960 10993 960 10993 960 10291 960 10998 960 10993 960 10998 960 10999 960 10999 2569 10998 2569 10293 2569 10999 9278 10293 9278 11000 9278 11000 960 10293 960 10292 960 11000 960 10292 960 11002 960 11069 960 11001 960 11002 960 11002 2498 11001 2498 11003 2498 11002 960 11003 960 11000 960 11000 9279 11003 9279 11004 9279 11000 9280 11004 9280 10996 9280 10996 9281 11004 9281 11005 9281 10996 2494 11005 2494 11006 2494 10999 960 11007 960 11008 960 11008 960 11007 960 11009 960 11008 9282 11009 9282 11176 9282 11176 960 11009 960 11010 960 11176 960 11010 960 11015 960 11015 9283 11010 9283 11011 9283 11015 960 11011 960 11013 960 11013 9284 11011 9284 11012 9284 11013 960 11012 960 11138 960 10757 960 10763 960 11013 960 11013 960 10763 960 11014 960 11013 960 11014 960 11015 960 11015 960 11014 960 11016 960 11017 960 11018 960 11019 960 11019 960 11018 960 10815 960 11019 960 10815 960 11020 960 11020 960 10815 960 11021 960 11020 9285 11021 9285 10325 9285 10325 960 11021 960 11022 960 10325 960 11022 960 11023 960 10817 9286 10923 9286 11024 9286 11024 960 10923 960 11027 960 11024 960 11027 960 11025 960 11025 960 11027 960 10322 960 11025 960 10322 960 10321 960 11026 9287 11028 9287 10915 9287 10910 960 10911 960 11027 960 11027 960 10911 960 10915 960 11027 960 10915 960 10322 960 10322 960 10915 960 11028 960 10322 9288 11028 9288 11029 9288 11029 9289 11030 9289 10322 9289 10322 2563 11030 2563 11031 2563 10322 9290 11031 9290 10318 9290 11031 960 11032 960 10318 960 10318 2561 11032 2561 11033 2561 10318 9291 11033 9291 11034 9291 11034 9292 11033 9292 11035 9292 11034 2559 11035 2559 11036 2559 11036 9293 11037 9293 11034 9293 11034 9294 11037 9294 11038 9294 11034 960 11038 960 10915 960 10915 9295 11038 9295 11039 9295 10915 2556 11039 2556 11026 2556 11040 960 10317 960 11165 960 11044 960 11056 960 11042 960 11055 960 11041 960 11053 960 11053 2591 11041 2591 11056 2591 11042 9296 11043 9296 11044 9296 11044 960 11043 960 11045 960 11044 960 11045 960 11040 960 11040 960 11045 960 11046 960 11040 960 11046 960 11047 960 11047 960 11048 960 11040 960 11040 960 11048 960 11049 960 11040 960 11049 960 10317 960 10317 9297 11049 9297 11050 9297 11048 960 11051 960 11049 960 11049 2551 11051 2551 11052 2551 11049 960 11052 960 11053 960 11053 9298 11052 9298 11054 9298 11053 2548 11054 2548 11055 2548 11056 960 11044 960 11053 960 11053 960 11044 960 11169 960 11053 960 11169 960 11057 960 11057 960 11169 960 10313 960 10313 960 11169 960 11058 960 10313 960 11058 960 11059 960 11059 960 11058 960 11161 960 11059 960 11161 960 11160 960 11074 960 11060 960 11083 960 11083 960 11060 960 11063 960 10326 960 11080 960 11061 960 11061 960 11080 960 11083 960 11061 960 11083 960 11062 960 11062 960 11083 960 11063 960 11062 960 11063 960 10290 960 11074 9299 11064 9299 10746 9299 10746 9300 11064 9300 11065 9300 10746 9301 11065 9301 11066 9301 11066 9302 11067 9302 10746 9302 10746 2507 11067 2507 11068 2507 10746 960 11068 960 11069 960 11069 2506 11068 2506 11070 2506 11069 9303 11070 9303 11071 9303 11071 9304 11070 9304 11072 9304 11089 2547 10306 2547 11083 2547 11083 960 10306 960 11073 960 11083 960 11073 960 11074 960 11074 960 11073 960 10307 960 11074 9305 10307 9305 11064 9305 11075 9306 11089 9306 11076 9306 11155 960 11077 960 11156 960 11156 9307 11077 9307 11078 9307 11156 2546 11078 2546 11079 2546 11079 960 11081 960 11080 960 11080 2543 11081 2543 11082 2543 11080 960 11082 960 11083 960 11083 9308 11082 9308 11084 9308 11083 9309 11084 9309 11085 9309 11085 960 11086 960 11083 960 11083 2540 11086 2540 11087 2540 11083 9310 11087 9310 11089 9310 11089 2538 11087 2538 11088 2538 11089 9311 11088 9311 11076 9311 11157 960 10305 960 11075 960 11090 960 11091 960 10894 960 10894 960 11091 960 11105 960 10894 960 11105 960 11092 960 11092 960 11105 960 10300 960 11096 960 10745 960 11093 960 11093 9312 10745 9312 10300 9312 11093 960 10300 960 11094 960 11094 960 10300 960 11105 960 11094 960 11105 960 11095 960 11096 960 11097 960 10745 960 10745 2533 11097 2533 11098 2533 10745 9313 11098 9313 10807 9313 10807 2531 11098 2531 11099 2531 10807 9314 11099 9314 11100 9314 11100 960 11102 960 10807 960 10807 960 11102 960 10794 960 10807 960 10794 960 10805 960 10805 9315 10794 9315 11101 9315 11102 960 11103 960 10794 960 10794 2537 11103 2537 11104 2537 10794 9316 11104 9316 11105 9316 11105 9317 11104 9317 11106 9317 11105 2535 11106 2535 11095 2535 11107 960 10807 960 11108 960 11108 960 10807 960 11113 960 11108 9318 11113 9318 11109 9318 11109 9319 11113 9319 10297 9319 11109 960 10297 960 11137 960 11137 960 10297 960 10298 960 11137 960 10298 960 11110 960 10991 960 10743 960 10990 960 10990 960 10743 960 11111 960 10990 960 11111 960 10807 960 10807 960 11111 960 11112 960 10807 9320 11112 9320 11113 9320 11114 9321 11116 9321 11115 9321 11115 9322 11116 9322 11122 9322 11137 9323 11123 9323 11117 9323 11117 2524 11118 2524 11137 2524 11137 9324 11118 9324 11119 9324 11137 9325 11119 9325 11109 9325 11109 9326 11119 9326 11120 9326 11109 9327 11120 9327 11121 9327 11122 960 11123 960 11115 960 11115 960 11123 960 11137 960 11115 960 11137 960 11124 960 10989 960 11125 960 10988 960 10988 960 11125 960 11126 960 10988 960 11126 960 11137 960 11137 9328 11126 9328 11127 9328 11128 960 11154 960 11129 960 11129 960 11154 960 11130 960 11129 9329 11130 9329 11132 9329 11132 960 11130 960 10744 960 11132 9330 10744 9330 11131 9330 11131 960 11133 960 11132 960 11132 2516 11133 2516 11134 2516 11132 960 11134 960 11127 960 11127 9331 11134 9331 11135 9331 11127 9332 11135 9332 11137 9332 11137 960 11135 960 11136 960 11137 2512 11136 2512 11124 2512 11012 960 11139 960 11138 960 11138 960 11139 960 11140 960 11138 960 11140 960 11141 960 11141 960 11140 960 11142 960 11141 960 11142 960 11143 960 11129 960 11144 960 11128 960 11128 960 11144 960 11145 960 11128 960 11145 960 10777 960 10777 960 11145 960 11146 960 10777 960 11146 960 10981 960 10783 960 10747 960 11153 960 11153 960 10747 960 10870 960 11153 960 10870 960 11152 960 11152 960 10870 960 11147 960 11152 960 11147 960 11148 960 11148 960 11147 960 10859 960 11148 960 10859 960 10852 960 10852 2433 10859 2433 11149 2433 10852 9333 11149 9333 11150 9333 10353 960 11151 960 10355 960 10355 960 11151 960 10955 960 10355 960 10955 960 10855 960 10855 960 10955 960 10945 960 10855 960 10945 960 10852 960 10852 960 10945 960 10948 960 10852 960 10948 960 11148 960 11148 960 10948 960 10938 960 11148 960 10938 960 11152 960 11152 960 10938 960 10937 960 11152 960 10937 960 11153 960 11153 9334 10937 9334 10774 9334 11153 960 10774 960 10782 960 10364 960 11154 960 10936 960 10936 960 11154 960 11128 960 10936 960 11128 960 10937 960 10937 960 11128 960 10777 960 10937 960 10777 960 10772 960 10772 960 10777 960 10776 960 11079 960 11080 960 11156 960 11156 960 11080 960 10876 960 11156 960 10876 960 10885 960 10885 2454 10876 2454 10873 2454 10885 2453 10873 2453 10884 2453 11076 9335 11155 9335 11075 9335 11075 960 11155 960 11156 960 11075 960 11156 960 11157 960 11157 960 11156 960 10885 960 11157 960 10885 960 10887 960 10887 2463 10885 2463 11158 2463 10887 2462 11158 2462 11159 2462 10309 9336 11160 9336 11141 9336 11141 960 11160 960 11161 960 11141 960 11161 960 11138 960 11138 960 11161 960 11058 960 11138 960 11058 960 11162 960 11162 960 11058 960 11163 960 10935 960 10929 960 11167 960 11167 960 10929 960 10930 960 11167 960 10930 960 11168 960 11168 960 10930 960 10815 960 11168 960 10815 960 11170 960 11170 960 10815 960 10762 960 11170 9337 10762 9337 11164 9337 10903 960 10899 960 11165 960 11165 960 10899 960 11166 960 11165 960 11166 960 11040 960 11040 960 11166 960 11167 960 11040 960 11167 960 11044 960 11044 960 11167 960 11168 960 11044 960 11168 960 11169 960 11169 960 11168 960 11170 960 11169 960 11170 960 11058 960 11058 960 11170 960 11171 960 11058 9338 11171 9338 10756 9338 10328 9339 10326 9339 11172 9339 11172 9340 10326 9340 11061 9340 11172 9341 11061 9341 11173 9341 11173 9342 11061 9342 10993 9342 11173 9343 10993 9343 11174 9343 11174 9344 10993 9344 11008 9344 11174 9345 11008 9345 11175 9345 11175 9346 11008 9346 11176 9346 11175 9347 11176 9347 10558 9347 10558 9348 11176 9348 11015 9348 10558 9349 11015 9349 11177 9349 11177 9350 11015 9350 11016 9350 11698 9351 12666 9351 11178 9351 11178 9352 12666 9352 12421 9352 11178 9353 12421 9353 11694 9353 11694 9353 12421 9353 12423 9353 11694 9354 12423 9354 12064 9354 12064 9355 12423 9355 11179 9355 12064 9356 11179 9356 12062 9356 12062 9356 11179 9356 12425 9356 11180 6 12438 6 11696 6 11696 6 12438 6 12419 6 11696 6 12419 6 11698 6 11698 6 12419 6 12666 6 12438 9357 11180 9357 12439 9357 12439 9358 11180 9358 11181 9358 12439 9359 11181 9359 11182 9359 11182 9360 11181 9360 11700 9360 11182 9361 11700 9361 12412 9361 12412 9362 11700 9362 11183 9362 12412 9363 11183 9363 11184 9363 11184 9364 11183 9364 11699 9364 12418 9365 11708 9365 11706 9365 12418 9365 11706 9365 11185 9365 11185 9366 11706 9366 11705 9366 11185 9367 11705 9367 11186 9367 11186 9368 11705 9368 11187 9368 11186 9369 11187 9369 11188 9369 11188 9370 11187 9370 11707 9370 11188 9371 11707 9371 11189 9371 12067 9372 11190 9372 11711 9372 11711 9372 11190 9372 12429 9372 11711 9373 12429 9373 11709 9373 11709 9374 12429 9374 12415 9374 11709 9375 12415 9375 11707 9375 11707 9376 12415 9376 11189 9376 11191 9377 11744 9377 11743 9377 11191 9377 11743 9377 12454 9377 12454 9378 11743 9378 11742 9378 12454 9378 11742 9378 12452 9378 12452 9379 11742 9379 11192 9379 12452 9379 11192 9379 11193 9379 11747 21 11196 21 11194 21 11194 21 11196 21 11195 21 11194 21 11195 21 11741 21 11741 21 11195 21 12411 21 11741 21 12411 21 11192 21 11192 21 12411 21 11193 21 11196 9380 11747 9380 11197 9380 11196 9381 11197 9381 11198 9381 11198 9382 11197 9382 11199 9382 11198 9383 11199 9383 12450 9383 12450 9384 11199 9384 11745 9384 12450 9384 11745 9384 12451 9384 12451 9385 11745 9385 11200 9385 12451 9386 11200 9386 11201 9386 11202 9387 11207 9387 11203 9387 11203 9388 11207 9388 12655 9388 11203 9389 12655 9389 11204 9389 11204 9390 12655 9390 11205 9390 11204 9391 11205 9391 11206 9391 11206 9392 11205 9392 12449 9392 11206 9393 12449 9393 11200 9393 11200 9394 12449 9394 11201 9394 11207 9395 11202 9395 11208 9395 11208 9396 11202 9396 12070 9396 11208 9397 12070 9397 12445 9397 12445 9397 12070 9397 11691 9397 12445 9398 11691 9398 12426 9398 12426 9399 11691 9399 11209 9399 12426 9400 11209 9400 11210 9400 11210 9400 11209 9400 11211 9400 11210 9401 11211 9401 11212 9401 11212 9402 11211 9402 11751 9402 11212 9403 11751 9403 11750 9403 11212 9404 11750 9404 12473 9404 12473 9405 11750 9405 11213 9405 12473 9405 11213 9405 12474 9405 12474 183 11213 183 11214 183 12474 176 11214 176 12475 176 11730 9406 12463 9406 11729 9406 11729 9407 12463 9407 12466 9407 11729 9408 12466 9408 11214 9408 11214 9409 12466 9409 12475 9409 11998 50 11216 50 12480 50 12480 50 11216 50 11215 50 11215 21 11216 21 11217 21 11217 21 11216 21 11752 21 11217 21 11752 21 11218 21 11218 21 11752 21 12387 21 12387 49 11813 49 11218 49 11218 49 11813 49 11219 49 11219 6 11813 6 11220 6 11220 6 11813 6 11753 6 11220 6 11753 6 12480 6 12480 6 11753 6 11998 6 13100 50 11221 50 13098 50 13098 50 11221 50 11757 50 13098 50 11757 50 13096 50 13096 50 11757 50 11222 50 13096 21 11222 21 13124 21 13124 21 11222 21 11755 21 13124 21 11755 21 13125 21 13125 21 11755 21 11223 21 13125 49 11223 49 11224 49 11224 49 11223 49 11225 49 11224 49 11225 49 13102 49 13102 49 11225 49 11226 49 13102 6 11226 6 13101 6 13101 6 11226 6 11759 6 13101 6 11759 6 13100 6 13100 6 11759 6 11221 6 11227 21 12364 21 11228 21 11228 21 12364 21 11229 21 11228 21 11229 21 11237 21 11237 21 11229 21 12368 21 11770 9410 11230 9410 11768 9410 11768 9411 11230 9411 11231 9411 11768 9412 11231 9412 11232 9412 11232 9413 11231 9413 11234 9413 11232 9391 11234 9391 11233 9391 11233 9392 11234 9392 12489 9392 11233 9414 12489 9414 11763 9414 11763 9414 12489 9414 11235 9414 11763 9415 11235 9415 12366 9415 12366 9416 11235 9416 11236 9416 12366 9417 11236 9417 12368 9417 12368 9418 11236 9418 11237 9418 11774 6 12484 6 11775 6 11775 6 12484 6 11238 6 11775 6 11238 6 11777 6 11777 6 11238 6 11239 6 11777 6 11239 6 11770 6 11770 6 11239 6 11230 6 11243 9419 11244 9419 11240 9419 11243 9420 11240 9420 11241 9420 11241 9421 11240 9421 12482 9421 11241 9422 12482 9422 11772 9422 11772 9423 12482 9423 12485 9423 11772 9424 12485 9424 11773 9424 11773 9425 12485 9425 12484 9425 11773 9426 12484 9426 11774 9426 11990 9427 12503 9427 11242 9427 11242 9428 12503 9428 12501 9428 11242 9429 12501 9429 11243 9429 11243 9430 12501 9430 11244 9430 11779 9431 11245 9431 11246 9431 11246 9432 11245 9432 11247 9432 11246 9433 11247 9433 11248 9433 11248 9434 11247 9434 11249 9434 11248 9435 11249 9435 11985 9435 11985 9436 11249 9436 12499 9436 11985 9437 12499 9437 11251 9437 11251 9438 12499 9438 11250 9438 11251 9439 11250 9439 11982 9439 11982 9440 11250 9440 11252 9440 11982 9441 11252 9441 11253 9441 11253 9442 11252 9442 11254 9442 11253 9443 11254 9443 11990 9443 11990 9443 11254 9443 12503 9443 11245 50 11779 50 11255 50 11255 50 11779 50 11778 50 11255 50 11778 50 11227 50 11227 50 11778 50 12364 50 12283 9444 11265 9444 12515 9444 12515 9445 11265 9445 11266 9445 12512 9446 11257 9446 12513 9446 12513 9447 11257 9447 11783 9447 12513 9448 11783 9448 12515 9448 12515 9449 11783 9449 12283 9449 12511 21 11781 21 11256 21 11256 21 11781 21 11780 21 11256 21 11780 21 12512 21 12512 21 11780 21 11257 21 11258 50 11781 50 12510 50 12510 50 11781 50 12511 50 11258 9450 12510 9450 12507 9450 11258 9451 12507 9451 11259 9451 11259 9423 12507 9423 11261 9423 11259 9452 11261 9452 11260 9452 11260 9453 11261 9453 11262 9453 11260 9453 11262 9453 12341 9453 12341 6 11262 6 11263 6 11263 6 11262 6 12516 6 11263 6 12516 6 11782 6 11782 6 12516 6 11264 6 11782 6 11264 6 11265 6 11265 6 11264 6 11266 6 12207 9454 11267 9454 11268 9454 12207 9455 11268 9455 11269 9455 11269 9456 11268 9456 12944 9456 11269 9457 12944 9457 12202 9457 12202 9458 12944 9458 11270 9458 12202 9459 11270 9459 11271 9459 11271 9460 11270 9460 11272 9460 11271 9461 11272 9461 12204 9461 12204 9462 11272 9462 11273 9462 12204 9463 11273 9463 11274 9463 11274 9464 11273 9464 11283 9464 11274 9464 11283 9464 12205 9464 12207 21 11282 21 11267 21 11267 21 11282 21 11281 21 11275 9465 12947 9465 12946 9465 11275 9466 12946 9466 11276 9466 11276 9467 12946 9467 11277 9467 11276 9468 11277 9468 12201 9468 12201 9469 11277 9469 11278 9469 12201 9469 11278 9469 11279 9469 11279 9470 11278 9470 12942 9470 11279 9471 12942 9471 11280 9471 11280 9472 12942 9472 12941 9472 11280 9473 12941 9473 12206 9473 12206 9474 12941 9474 11281 9474 12206 9475 11281 9475 11282 9475 11275 6 12205 6 12947 6 12947 6 12205 6 11283 6 11299 9476 11788 9476 11289 9476 11794 9477 11284 9477 11285 9477 11794 9477 11285 9477 11286 9477 11286 9456 11285 9456 11288 9456 11286 9457 11288 9457 11287 9457 11287 9478 11288 9478 12818 9478 11287 9479 12818 9479 11792 9479 11792 9480 12818 9480 12817 9480 11792 9481 12817 9481 11787 9481 11787 132 12817 132 12227 132 12227 131 12817 131 12491 131 12227 9482 12491 9482 11289 9482 11289 9483 12491 9483 12494 9483 11289 9484 12494 9484 11299 9484 11794 21 11297 21 11284 21 11284 21 11297 21 11296 21 11789 9485 11290 9485 12493 9485 12493 9486 11290 9486 11298 9486 11789 9487 12493 9487 11790 9487 11790 9488 12493 9488 12492 9488 11790 123 12492 123 11291 123 12492 122 12821 122 11291 122 11291 9489 12821 9489 11293 9489 11291 9490 11293 9490 11292 9490 11292 9491 11293 9491 11294 9491 11292 9491 11294 9491 11791 9491 11791 9472 11294 9472 12819 9472 11791 9473 12819 9473 11295 9473 11295 9492 12819 9492 11296 9492 11295 9493 11296 9493 11297 9493 11290 6 11788 6 11298 6 11298 6 11788 6 11299 6 12322 235 11300 235 13117 235 12322 9494 13117 9494 12323 9494 12323 145 13117 145 13116 145 12323 144 13116 144 11301 144 11301 143 13116 143 13115 143 11301 143 13115 143 12325 143 12325 142 13115 142 13114 142 12325 142 13114 142 12326 142 12326 141 13114 141 13113 141 12326 140 13113 140 12327 140 12327 9495 13113 9495 13112 9495 12327 9496 13112 9496 12328 9496 12330 9497 12402 9497 11302 9497 12330 9497 11302 9497 12331 9497 12331 154 11302 154 11303 154 12331 153 11303 153 11304 153 11304 152 11303 152 11306 152 11304 152 11306 152 11305 152 11305 151 11306 151 11308 151 11305 151 11308 151 11307 151 11307 150 11308 150 11310 150 11307 149 11310 149 11309 149 11309 237 11310 237 13118 237 11309 237 13118 237 11311 237 11313 9498 11312 9498 11314 9498 11313 9499 11314 9499 11315 9499 11315 163 11314 163 13106 163 11315 162 13106 162 11317 162 11317 9500 13106 9500 11316 9500 11317 9501 11316 9501 12317 9501 12317 142 11316 142 13105 142 12317 142 13105 142 11318 142 11318 159 13105 159 13104 159 11318 158 13104 158 12318 158 12318 9495 13104 9495 11320 9495 12318 9496 11320 9496 12319 9496 12320 50 12319 50 11319 50 11319 50 12319 50 11320 50 11795 9497 11321 9497 11322 9497 11795 9502 11322 9502 11797 9502 11797 153 11322 153 11323 153 11797 176 11323 176 11798 176 11798 175 11323 175 12673 175 11798 175 12673 175 11324 175 11324 174 12673 174 12672 174 11324 174 12672 174 11325 174 11325 173 12672 173 12671 173 11325 150 12671 150 11800 150 11800 9503 12671 9503 12664 9503 11800 237 12664 237 11796 237 11801 235 12829 235 12828 235 11801 235 12828 235 11327 235 11327 9504 12828 9504 11326 9504 11327 145 11326 145 11807 145 11807 9505 11326 9505 12826 9505 11807 9505 12826 9505 11810 9505 11810 9506 12826 9506 11328 9506 11810 9506 11328 9506 11329 9506 11329 140 11328 140 11331 140 11329 9507 11331 9507 11330 9507 11330 9496 11331 9496 12824 9496 11330 9496 12824 9496 11806 9496 11811 9497 12848 9497 11332 9497 11811 9502 11332 9502 11333 9502 11333 183 11332 183 12847 183 11333 182 12847 182 11334 182 11334 175 12847 175 12846 175 11334 175 12846 175 11335 175 11335 9508 12846 9508 12843 9508 11335 9509 12843 9509 11336 9509 11336 179 12843 179 11337 179 11336 178 11337 178 11814 178 11814 7662 11337 7662 12839 7662 11814 9510 12839 9510 11815 9510 12848 50 11811 50 11338 50 11338 50 11811 50 11819 50 11338 50 11819 50 11339 50 11339 50 11819 50 11820 50 11843 9511 11340 9511 11342 9511 11342 9512 11340 9512 11341 9512 11342 9513 11341 9513 11343 9513 11343 9514 11341 9514 12914 9514 11355 194 12153 194 11344 194 11344 193 12153 193 11345 193 11344 193 11345 193 12549 193 12549 164 11345 164 11346 164 12549 9515 11346 9515 12550 9515 12550 190 11346 190 11347 190 12550 190 11347 190 12552 190 12552 189 11347 189 11348 189 12552 189 11348 189 11349 189 11349 9516 11348 9516 12159 9516 11349 9517 12159 9517 11350 9517 11350 186 12159 186 11351 186 11350 186 11351 186 12553 186 12553 185 11351 185 12157 185 12553 203 12157 203 11352 203 11352 9518 12157 9518 11353 9518 11352 9518 11353 9518 12558 9518 12558 200 11353 200 11354 200 12558 199 11354 199 12548 199 12548 198 11354 198 12155 198 12548 197 12155 197 12547 197 12547 9519 12155 9519 12154 9519 12547 9520 12154 9520 11355 9520 11355 195 12154 195 12153 195 12749 194 12006 194 12750 194 12750 193 12006 193 12392 193 12750 208 12392 208 11356 208 11356 9521 12392 9521 12021 9521 11356 9515 12021 9515 12755 9515 12755 207 12021 207 11357 207 12755 190 11357 190 11358 190 11358 189 11357 189 12025 189 11358 206 12025 206 11359 206 11359 9516 12025 9516 11360 9516 11359 9516 11360 9516 11361 9516 11361 204 11360 204 12023 204 11361 186 12023 186 11362 186 11362 185 12023 185 11363 185 11362 185 11363 185 12753 185 12753 9522 11363 9522 11364 9522 12753 9518 11364 9518 12754 9518 12754 199 11364 199 12012 199 12754 199 12012 199 12767 199 12767 198 12012 198 12014 198 12767 198 12014 198 12748 198 12748 9519 12014 9519 11365 9519 12748 9523 11365 9523 12749 9523 12749 194 11365 194 12006 194 11366 381 12863 381 12584 381 11366 142 12584 142 11367 142 11367 9524 12584 9524 12583 9524 11367 9525 12583 9525 11368 9525 11368 138 12583 138 11369 138 11368 138 11369 138 11857 138 11857 9526 11369 9526 11370 9526 11857 155 11370 155 11371 155 11371 9527 11370 9527 12581 9527 11371 9528 12581 9528 11858 9528 11858 175 12581 175 11372 175 11858 286 11372 286 11853 286 12863 9529 11366 9529 11373 9529 11373 9530 11366 9530 11850 9530 11373 9531 11850 9531 12865 9531 12865 9532 11850 9532 11374 9532 12865 9533 11374 9533 12867 9533 12867 9534 11374 9534 11862 9534 11375 9535 11376 9535 11869 9535 11869 9536 11376 9536 12870 9536 11869 9537 12870 9537 11377 9537 11377 9538 12870 9538 12869 9538 11377 9539 12869 9539 11378 9539 11378 9540 12869 9540 11379 9540 11380 9541 11381 9541 11382 9541 11382 9541 11381 9541 11383 9541 11382 9542 11383 9542 13070 9542 13070 9543 11383 9543 11384 9543 12649 9544 11385 9544 11386 9544 11386 9544 11385 9544 11387 9544 11398 9545 11399 9545 11388 9545 11398 9545 11388 9545 11389 9545 11389 9546 11388 9546 11390 9546 11389 9546 11390 9546 11391 9546 11391 9547 11390 9547 12898 9547 11391 9548 12898 9548 11884 9548 11884 9549 12898 9549 11392 9549 11884 9550 11392 9550 11394 9550 11394 135 11392 135 11393 135 11394 9551 11393 9551 11395 9551 11395 9552 11393 9552 12892 9552 11395 9552 12892 9552 11885 9552 11893 21 11396 21 12349 21 12349 21 11396 21 12888 21 12349 21 12888 21 11397 21 11397 21 12888 21 12896 21 11397 21 12896 21 11398 21 11398 21 12896 21 11399 21 12873 6 11911 6 12875 6 12875 6 11911 6 11909 6 12875 6 11909 6 11400 6 11400 6 11909 6 11402 6 11400 6 11402 6 11401 6 11401 6 11402 6 11684 6 11942 9553 12710 9553 11941 9553 11941 9554 12710 9554 12709 9554 11941 2160 12709 2160 11929 2160 11929 8942 12709 8942 11403 8942 11404 9555 11405 9555 11406 9555 11406 9556 11405 9556 11948 9556 11406 9557 11948 9557 11407 9557 11407 9558 11948 9558 11415 9558 11408 381 12730 381 11409 381 11408 142 11409 142 11916 142 11916 9524 11409 9524 12729 9524 11916 9525 12729 9525 11410 9525 11410 138 12729 138 12733 138 11410 9559 12733 9559 11411 9559 11411 155 12733 155 11412 155 11411 155 11412 155 11413 155 11413 9527 11412 9527 12731 9527 11413 9528 12731 9528 11414 9528 11414 175 12731 175 11407 175 11414 286 11407 286 11415 286 11416 6 11975 6 12792 6 12792 6 11975 6 11417 6 12792 6 11417 6 12790 6 12790 6 11417 6 11418 6 11419 21 11976 21 12785 21 12785 21 11976 21 11420 21 12785 21 11420 21 11421 21 11421 21 11420 21 11682 21 12498 9560 11428 9560 11984 9560 11988 9561 11422 9561 11423 9561 11988 9562 11423 9562 11981 9562 11981 9563 11423 9563 11426 9563 11981 9564 11426 9564 11424 9564 11424 9565 11426 9565 11425 9565 11425 9566 11426 9566 11427 9566 11425 9567 11427 9567 11984 9567 11984 9568 11427 9568 12783 9568 11984 9569 12783 9569 12498 9569 11428 9570 12498 9570 11986 9570 11986 9571 12498 9571 12497 9571 11986 9572 12497 9572 11429 9572 12497 9573 11430 9573 11429 9573 11429 9574 11430 9574 11431 9574 11429 9575 11431 9575 11432 9575 11432 9576 11431 9576 11433 9576 11432 9577 11433 9577 11987 9577 11987 9578 11433 9578 11434 9578 11434 9579 11433 9579 11435 9579 11434 9580 11435 9580 11436 9580 11435 9581 11437 9581 11436 9581 11436 9582 11437 9582 11438 9582 11436 9583 11438 9583 11439 9583 11439 9584 11438 9584 11421 9584 11439 9585 11421 9585 11682 9585 11993 49 11440 49 11441 49 11441 49 11440 49 12780 49 11441 49 12780 49 11442 49 11442 49 12780 49 12781 49 11442 49 12781 49 11443 49 11443 49 12781 49 11444 49 12779 6 11992 6 11445 6 11445 6 11992 6 11994 6 11445 6 11994 6 11446 6 11446 6 11994 6 11447 6 11446 49 11447 49 12777 49 12777 49 11447 49 12381 49 12777 49 12381 49 12776 49 12776 49 12381 49 12382 49 12776 49 12382 49 11448 49 11448 49 12382 49 12383 49 11448 21 12383 21 12775 21 12775 21 12383 21 12384 21 12004 49 12772 49 11449 49 11449 49 12772 49 12479 49 11449 49 12479 49 12385 49 12385 49 12479 49 11450 49 12385 49 11450 49 12384 49 12384 49 11450 49 12775 49 12002 21 11455 21 12773 21 12773 21 11455 21 11454 21 11996 9586 12768 9586 12769 9586 11996 9587 12769 9587 11997 9587 11997 9588 12769 9588 12766 9588 11997 9589 12766 9589 11451 9589 11451 163 12766 163 12765 163 11451 246 12765 246 11452 246 11452 143 12765 143 11453 143 11452 143 11453 143 12000 143 12000 142 11453 142 12774 142 12000 142 12774 142 12005 142 12005 245 12774 245 11454 245 12005 158 11454 158 11455 158 12768 49 11996 49 11456 49 11456 49 11996 49 12022 49 11456 49 12022 49 11457 49 11457 49 12022 49 12024 49 12759 6 12760 6 12017 6 12017 6 12760 6 12015 6 12751 49 12016 49 11458 49 11458 49 12016 49 11459 49 11458 49 11459 49 12739 49 12739 49 11459 49 11460 49 12739 9590 11460 9590 11461 9590 11461 9591 11460 9591 12029 9591 11461 9592 12029 9592 12732 9592 12732 9593 12029 9593 11462 9593 12732 9594 11462 9594 12722 9594 12722 9595 11462 9595 6964 9595 12725 9007 12722 9007 6971 9007 6971 9596 12722 9596 6964 9596 12725 9597 6971 9597 12720 9597 12720 9598 6971 9598 11949 9598 12720 9599 11949 9599 12718 9599 12718 9600 11949 9600 11463 9600 12718 9601 11463 9601 12714 9601 12714 9602 11463 9602 11933 9602 12714 9603 11933 9603 12692 9603 12692 9604 11933 9604 11464 9604 12692 9605 11464 9605 12695 9605 12695 9606 11464 9606 11465 9606 11466 50 12695 50 7558 50 7558 50 12695 50 11465 50 11466 9607 7558 9607 12697 9607 12697 9608 7558 9608 12397 9608 12697 9609 12397 9609 11467 9609 11467 9610 12397 9610 11468 9610 11467 9611 11468 9611 12699 9611 12699 9612 11468 9612 11469 9612 12699 9613 11469 9613 12689 9613 12689 9614 11469 9614 12036 9614 12690 6 11470 6 12700 6 12700 6 11470 6 12033 6 12700 6 12033 6 11471 6 11471 6 12033 6 11472 6 12041 50 11475 50 11474 50 11474 50 11475 50 11473 50 11474 50 11473 50 11472 50 11472 50 11473 50 11471 50 12680 6 11475 6 12040 6 12040 6 11475 6 12041 6 11476 50 11477 50 11479 50 11479 50 11477 50 11478 50 11479 50 11478 50 12042 50 12042 50 11478 50 12684 50 12046 21 11480 21 12674 21 12674 21 11480 21 12675 21 11481 21 11483 21 11482 21 11482 21 11483 21 12668 21 11482 21 12668 21 12054 21 12054 21 12668 21 12669 21 12054 21 12669 21 11799 21 11799 21 12669 21 12670 21 5941 9615 12659 9615 12075 9615 12075 9616 12659 9616 12658 9616 12075 9617 12658 9617 12074 9617 12074 9618 12658 9618 12651 9618 12074 9619 12651 9619 12059 9619 12059 9619 12651 9619 12650 9619 12059 9620 12650 9620 12060 9620 12060 8935 12650 8935 12654 8935 12060 9621 12654 9621 12061 9621 12061 9621 12654 9621 12652 9621 12061 9622 12652 9622 11692 9622 11692 9623 12652 9623 11484 9623 11692 9624 11484 9624 11693 9624 11693 9624 11484 9624 12422 9624 11693 9625 12422 9625 12056 9625 12056 9626 12422 9626 11485 9626 12056 9627 11485 9627 12057 9627 12057 9628 11485 9628 12661 9628 12057 9629 12661 9629 11486 9629 11486 9630 12661 9630 11487 9630 11486 9631 11487 9631 11488 9631 11488 9631 11487 9631 11489 9631 12659 9632 5941 9632 12647 9632 12647 9633 5941 9633 11490 9633 12647 9634 11490 9634 12644 9634 12644 9635 11490 9635 12079 9635 12644 9636 12079 9636 12406 9636 12406 9637 12079 9637 12374 9637 12406 9638 12374 9638 11491 9638 11491 9639 12374 9639 11492 9639 11493 50 13071 50 12085 50 12085 50 13071 50 13068 50 12085 50 13068 50 11901 50 11901 50 13068 50 12885 50 11901 50 12885 50 11897 50 11897 50 12885 50 12640 50 11897 50 12640 50 11494 50 11494 50 12640 50 12639 50 11494 50 12639 50 11492 50 11492 50 12639 50 11491 50 13071 9640 11493 9640 13072 9640 13072 9641 11493 9641 12087 9641 13072 9642 12087 9642 11495 9642 11495 9642 12087 9642 11680 9642 11495 9643 11680 9643 12631 9643 12631 9644 11680 9644 11496 9644 12631 9645 11496 9645 12628 9645 12628 9646 11496 9646 5923 9646 12628 9647 5923 9647 11497 9647 11497 9647 5923 9647 12091 9647 11497 9648 12091 9648 11498 9648 11498 9648 12091 9648 12237 9648 11498 9649 12237 9649 11499 9649 11499 9650 12237 9650 11500 9650 11499 9651 11500 9651 12626 9651 12626 9651 11500 9651 12342 9651 12626 9652 12342 9652 11501 9652 11501 9652 12342 9652 11502 9652 11501 9653 11502 9653 11503 9653 11503 9654 11502 9654 12093 9654 11503 9655 12093 9655 11504 9655 11504 9655 12093 9655 11506 9655 11504 9656 11506 9656 11505 9656 11505 9657 11506 9657 11507 9657 11505 9658 11507 9658 13008 9658 13008 9659 11507 9659 12285 9659 13008 9660 12285 9660 13009 9660 13009 9660 12285 9660 12284 9660 11508 6 11509 6 11510 6 11510 6 11509 6 11511 6 11510 6 11511 6 13120 6 13120 6 11511 6 11512 6 13120 6 11512 6 12407 6 12407 6 11512 6 11513 6 11516 50 12613 50 12097 50 12097 50 12613 50 11514 50 12097 50 11514 50 11513 50 11513 50 11514 50 12407 50 12614 6 12613 6 11515 6 11515 6 12613 6 11516 6 12112 50 12597 50 11517 50 11517 50 12597 50 12611 50 11517 50 12611 50 12106 50 12106 50 12611 50 11518 50 12106 50 11518 50 12101 50 12101 50 11518 50 11519 50 11520 21 11522 21 11521 21 11521 21 11522 21 11523 21 12599 50 11523 50 11524 50 11524 50 11523 50 11522 50 11525 9661 11527 9661 11526 9661 11526 9661 11527 9661 12602 9661 11526 9662 12602 9662 12121 9662 12121 35 12602 35 12604 35 12121 9663 12604 9663 12118 9663 12118 9664 12604 9664 12605 9664 11527 9665 11525 9665 11528 9665 11528 9666 11525 9666 11529 9666 11528 9667 11529 9667 11530 9667 11530 9668 11529 9668 11531 9668 11530 9669 11531 9669 11533 9669 11533 9669 11531 9669 11532 9669 11533 9670 11532 9670 12593 9670 12593 9671 11532 9671 11534 9671 12593 9672 11534 9672 12410 9672 12410 9673 11534 9673 11866 9673 12410 9674 11866 9674 11535 9674 11535 9675 11866 9675 11863 9675 11535 9676 11863 9676 11536 9676 11536 9677 11863 9677 12123 9677 11536 9678 12123 9678 12592 9678 12592 9679 12123 9679 11537 9679 12592 9680 11537 9680 12591 9680 12591 9681 11537 9681 11538 9681 12591 9682 11538 9682 12582 9682 12582 9683 11538 9683 11856 9683 12582 9031 11856 9031 11539 9031 11539 9032 11856 9032 11540 9032 11539 9684 11540 9684 11541 9684 11541 9684 11540 9684 11542 9684 11541 9685 11542 9685 11543 9685 11543 9686 11542 9686 12150 9686 12567 49 11543 49 12152 49 12152 49 11543 49 12150 49 12151 21 12149 21 11544 21 11544 21 12149 21 12559 21 11545 49 12136 49 12555 49 12555 49 12136 49 12156 49 12555 49 12156 49 12554 49 12554 49 12156 49 12158 49 12554 49 12158 49 12557 49 12557 49 12158 49 11546 49 12546 6 11547 6 12164 6 12164 6 11547 6 11548 6 13097 49 12166 49 13099 49 13099 49 12166 49 11549 49 13099 49 11549 49 12539 49 12539 49 11549 49 11550 49 12539 49 11550 49 11552 49 11552 49 11550 49 11551 49 11553 6 12537 6 11551 6 11551 6 12537 6 11552 6 12537 49 11553 49 12538 49 12538 49 11553 49 12169 49 12538 49 12169 49 11554 49 11554 49 12169 49 12170 49 11554 49 12170 49 11556 49 11556 49 12170 49 11555 49 11556 49 11555 49 11557 49 11557 49 11555 49 11558 49 12336 21 12535 21 12171 21 12171 21 12535 21 12536 21 12171 21 12536 21 11558 21 11558 21 12536 21 11557 21 12533 49 12173 49 12531 49 12531 49 12173 49 11559 49 12531 49 11559 49 12530 49 12530 49 11559 49 12176 49 12814 21 12194 21 11560 21 11560 21 12194 21 11561 21 11560 21 11561 21 11562 21 11562 21 11561 21 11957 21 12520 9687 12180 9687 12181 9687 11563 9688 11573 9688 11565 9688 11563 9689 11565 9689 11564 9689 11564 9690 11565 9690 11566 9690 11564 9691 11566 9691 12193 9691 12193 9692 11566 9692 12186 9692 12186 9693 11566 9693 11567 9693 12186 9694 11567 9694 11568 9694 11567 7409 12517 7409 11568 7409 11568 9695 12517 9695 11569 9695 11568 9560 11569 9560 12188 9560 12188 9696 11569 9696 12524 9696 12188 9697 12524 9697 12190 9697 12190 9698 12524 9698 12182 9698 12182 9699 12524 9699 11570 9699 12182 9700 11570 9700 12181 9700 12181 9701 11570 9701 12522 9701 12181 9576 12522 9576 12520 9576 12180 9702 12520 9702 12179 9702 12179 9703 12520 9703 12518 9703 12179 9704 12518 9704 11571 9704 12518 9705 12529 9705 11571 9705 11571 9706 12529 9706 12528 9706 11571 9707 12528 9707 11572 9707 11572 9708 12528 9708 12526 9708 11572 9709 12526 9709 12178 9709 11573 6 11563 6 12815 6 12815 6 11563 6 11574 6 12815 6 11574 6 11575 6 11575 6 11574 6 11576 6 11575 49 11576 49 12816 49 12816 49 11576 49 11577 49 12816 49 11577 49 12814 49 12814 49 11577 49 12194 49 12945 6 12200 6 12939 6 12939 6 12200 6 12208 6 12939 6 12208 6 13126 6 13126 6 12208 6 13128 6 12200 9710 12945 9710 11578 9710 11578 9711 12945 9711 13081 9711 11578 9712 13081 9712 11579 9712 11579 9713 13081 9713 13000 9713 11579 9714 13000 9714 11580 9714 11580 9715 13000 9715 11581 9715 11580 68 11581 68 12256 68 12256 9716 11581 9716 11582 9716 12256 9010 11582 9010 11583 9010 11583 9717 11582 9717 11585 9717 11583 9718 11585 9718 11584 9718 11584 9719 11585 9719 11589 9719 12951 21 12198 21 11586 21 11586 21 12198 21 11587 21 11586 21 11587 21 12948 21 12948 21 11587 21 11588 21 12948 21 11588 21 11589 21 11589 21 11588 21 11584 21 11590 9720 12196 9720 12950 9720 12950 9721 12196 9721 12197 9721 12950 9722 12197 9722 11591 9722 11591 9723 12197 9723 12198 9723 11591 9724 12198 9724 12951 9724 12953 9725 12195 9725 11592 9725 11592 9726 12195 9726 11593 9726 11592 9727 11593 9727 11590 9727 11590 9728 11593 9728 11594 9728 11590 9420 11594 9420 12196 9420 12527 54 11595 54 11596 54 11596 9729 11595 9729 11597 9729 11596 9730 11597 9730 12953 9730 12953 958 11597 958 12195 958 11595 9731 12527 9731 12175 9731 12175 9731 12527 9731 11598 9731 12175 9732 11598 9732 12185 9732 12185 9733 11598 9733 12519 9733 12185 9734 12519 9734 12521 9734 12955 9735 12214 9735 11599 9735 11599 9736 12214 9736 11600 9736 11599 9737 11600 9737 12523 9737 12523 9738 11600 9738 12183 9738 12523 9739 12183 9739 12521 9739 12521 9740 12183 9740 12184 9740 12521 9741 12184 9741 12185 9741 12963 6 12219 6 11601 6 11601 6 12219 6 11602 6 11601 6 11602 6 11613 6 11613 6 11602 6 11603 6 11605 9742 11604 9742 12962 9742 12962 9743 11604 9743 12220 9743 12962 9744 12220 9744 12963 9744 12963 9745 12220 9745 12219 9745 11605 9683 11609 9683 11604 9683 11604 9746 11609 9746 12221 9746 11606 21 12216 21 11607 21 11607 21 12216 21 12222 21 11607 21 12222 21 12956 21 12956 21 12222 21 11608 21 12956 21 11608 21 11609 21 11609 21 11608 21 12221 21 12216 9747 11606 9747 11610 9747 12216 9747 11610 9747 11611 9747 11611 9748 11610 9748 12960 9748 11611 9721 12960 9721 12218 9721 12218 9749 12960 9749 12959 9749 12218 9458 12959 9458 11612 9458 12959 50 11613 50 11612 50 11612 50 11613 50 11603 50 12943 49 12209 49 12967 49 12967 49 12209 49 12203 49 12967 49 12203 49 12968 49 12968 49 12203 49 11614 49 12968 49 11614 49 12970 49 12970 49 11614 49 11615 49 12970 49 11615 49 12964 49 12964 49 11615 49 11786 49 12964 6 11786 6 12965 6 12965 6 11786 6 11616 6 12965 6 11616 6 11617 6 11617 6 11616 6 11618 6 11617 50 11618 50 11619 50 11619 50 11618 50 12230 50 11619 50 12230 50 11621 50 11621 50 12230 50 11620 50 11621 50 11620 50 11623 50 11623 50 11620 50 11622 50 11623 50 11622 50 12938 50 12938 50 11622 50 12228 50 12938 21 12228 21 12940 21 12940 21 12228 21 12210 21 12940 21 12210 21 12943 21 12943 21 12210 21 12209 21 12987 6 11624 6 11625 6 11625 6 11624 6 12352 6 11625 6 12352 6 11626 6 11626 6 12352 6 11628 6 11626 6 11628 6 11627 6 11627 6 11628 6 11678 6 11629 9384 12240 9384 11630 9384 11629 9750 11630 9750 11632 9750 11632 9386 11630 9386 11631 9386 11632 9386 11631 9386 12986 9386 12986 9751 11631 9751 11634 9751 12986 9752 11634 9752 11633 9752 11633 9753 11634 9753 11624 9753 11633 9754 11624 9754 12987 9754 11636 9755 12234 9755 13086 9755 13086 9756 12234 9756 12239 9756 13086 9757 12239 9757 12985 9757 12985 9758 12239 9758 11635 9758 12985 9759 11635 9759 11629 9759 11629 9760 11635 9760 12240 9760 12234 9761 11636 9761 12233 9761 12233 9762 11636 9762 11637 9762 12233 9763 11637 9763 12231 9763 12231 9763 11637 9763 13005 9763 12979 9460 11638 9460 12263 9460 12979 9764 12263 9764 11639 9764 11639 9765 12263 9765 12252 9765 11639 9766 12252 9766 11640 9766 11640 141 12252 141 11641 141 11640 159 11641 159 11642 159 12267 9767 12994 9767 12249 9767 12249 9768 12994 9768 12989 9768 12249 9769 12989 9769 11641 9769 11641 9770 12989 9770 11642 9770 12994 9771 12267 9771 12266 9771 12994 158 12266 158 12992 158 12992 9772 12266 9772 12265 9772 12992 9772 12265 9772 12993 9772 12993 9773 12265 9773 11645 9773 12993 9774 11645 9774 11643 9774 12231 9775 13005 9775 12268 9775 12268 9776 13005 9776 13007 9776 12268 9777 13007 9777 11644 9777 11644 9777 13007 9777 12996 9777 11644 9778 12996 9778 11645 9778 11645 9779 12996 9779 11643 9779 13020 9780 12275 9780 12272 9780 13020 9781 12272 9781 13021 9781 13021 9782 12272 9782 12271 9782 13021 9783 12271 9783 11646 9783 11646 9784 12271 9784 11648 9784 11646 9785 11648 9785 11647 9785 11647 9786 11648 9786 11649 9786 11647 9787 11649 9787 11651 9787 12281 9788 13013 9788 12270 9788 12270 9789 13013 9789 11650 9789 12270 9790 11650 9790 11649 9790 11649 9791 11650 9791 11651 9791 13013 9792 12281 9792 13012 9792 13012 9793 12281 9793 11652 9793 13012 9794 11652 9794 11653 9794 11653 9795 11652 9795 12279 9795 11653 21 12279 21 13010 21 13010 21 12279 21 11654 21 13010 21 11654 21 11661 21 11661 21 11654 21 11660 21 12287 9796 11655 9796 12286 9796 12286 9796 11655 9796 11656 9796 12286 9797 11656 9797 11657 9797 11657 9798 11656 9798 12624 9798 11657 9799 12624 9799 11658 9799 11658 9799 12624 9799 11659 9799 11658 9800 11659 9800 11660 9800 11660 9801 11659 9801 11661 9801 11662 9802 11663 9802 13027 9802 13027 9802 11663 9802 11664 9802 13027 9803 11664 9803 13026 9803 13026 9804 11664 9804 12274 9804 13026 9805 12274 9805 13016 9805 13016 9806 12274 9806 12277 9806 13016 9807 12277 9807 12278 9807 13016 9808 12278 9808 11665 9808 11665 175 12278 175 12273 175 11665 175 12273 175 11666 175 11666 174 12273 174 12276 174 11666 174 12276 174 13017 174 13003 9809 12254 9809 11667 9809 11667 9810 12254 9810 11668 9810 11667 9811 11668 9811 13006 9811 13006 3884 11668 3884 12232 3884 13006 9812 12232 9812 11671 9812 11671 9813 12232 9813 12269 9813 11670 9814 11669 9814 12997 9814 12997 9815 11669 9815 12255 9815 12997 9816 12255 9816 13003 9816 13003 9817 12255 9817 12254 9817 11670 9818 12998 9818 11669 9818 11669 9818 12998 9818 12257 9818 11671 9819 12269 9819 11672 9819 11672 9820 12269 9820 11679 9820 11672 9821 11679 9821 12998 9821 12998 9822 11679 9822 12257 9822 13048 9823 11673 9823 11766 9823 11766 9823 11673 9823 11767 9823 11673 9824 12427 9824 11767 9824 11767 9825 12427 9825 11690 9825 11674 9826 11765 9826 12444 9826 12444 9342 11765 9342 11675 9342 12444 9827 11675 9827 12427 9827 12427 482 11675 482 11690 482 12386 960 11824 960 11812 960 12086 960 12085 960 11901 960 11676 960 12238 960 12354 960 11309 9828 11311 9828 12280 9828 11668 960 12292 960 12232 960 11658 960 11677 960 11657 960 12267 960 12249 960 12243 960 11678 960 11628 960 12353 960 12257 960 11679 960 12246 960 12336 960 12171 960 12337 960 12087 960 12088 960 11680 960 12079 960 11681 960 12374 960 11469 9829 11468 9829 12398 9829 11439 960 11682 960 11420 960 11683 960 11684 960 11402 960 11685 960 11686 960 11860 960 11687 960 12388 960 12391 960 11248 960 11688 960 11246 960 11990 960 11242 960 11771 960 12364 960 11778 960 11979 960 11998 960 11753 960 11999 960 11710 976 11711 976 11709 976 11694 9830 12064 9830 12063 9830 12062 960 12069 960 11689 960 12066 9831 11767 9831 11690 9831 11209 9832 11691 9832 11675 9832 11727 960 11748 960 11209 960 12061 960 11692 960 12063 960 12063 960 11692 960 11693 960 12063 960 11693 960 11694 960 11694 960 11693 960 11695 960 11694 960 11695 960 11178 960 11180 960 11696 960 11697 960 11697 960 11696 960 11698 960 11704 9833 11699 9833 11718 9833 11718 960 11699 960 11183 960 11718 960 11183 960 12376 960 12376 9834 11183 9834 11700 9834 12376 960 11700 960 11808 960 11808 960 11700 960 11181 960 11808 960 11181 960 11802 960 11708 960 11701 960 11709 960 11709 9835 11701 9835 11702 9835 11709 9836 11702 9836 11718 9836 11718 960 11702 960 11703 960 11718 9837 11703 9837 11704 9837 11705 960 11706 960 11187 960 11187 960 11706 960 11708 960 11187 960 11708 960 11707 960 11707 960 11708 960 11709 960 11710 960 11709 960 11722 960 11710 9838 11712 9838 11711 9838 11711 9839 11712 9839 11713 9839 11711 9840 11713 9840 12065 9840 12065 960 11714 960 12066 960 12066 974 11714 974 11715 974 11716 960 11717 960 11718 960 11717 960 11719 960 11718 960 11718 979 11719 979 11720 979 11718 960 11720 960 11709 960 11709 978 11720 978 11721 978 11709 9841 11721 9841 11722 9841 11723 9842 11724 9842 11748 9842 11725 995 11764 995 11739 995 11739 960 11764 960 11726 960 11727 9843 11728 9843 11733 9843 11729 9844 11749 9844 11730 9844 11730 9845 11749 9845 11731 9845 11730 9846 11731 9846 11739 9846 11739 9847 11731 9847 11732 9847 11739 996 11732 996 11725 996 11733 960 11734 960 11727 960 11727 960 11734 960 11735 960 11727 9848 11735 9848 11748 9848 11748 960 11735 960 11736 960 11748 9849 11736 9849 11723 9849 11761 960 11737 960 11726 960 11726 9850 11737 9850 11738 9850 11726 9851 11738 9851 11739 9851 11740 960 11741 960 12375 960 12375 960 11741 960 11192 960 12375 960 11192 960 11762 960 11192 960 11742 960 11762 960 11762 993 11742 993 11743 993 11762 992 11743 992 11744 992 11199 960 11746 960 11745 960 11745 960 11746 960 12073 960 11199 960 11197 960 11746 960 11746 991 11197 991 11747 991 11746 960 11747 960 11740 960 11740 960 11747 960 11194 960 11740 960 11194 960 11741 960 11203 9852 11204 9852 12072 9852 12072 960 11204 960 11206 960 12072 960 11206 960 12073 960 12073 9853 11206 9853 11200 9853 12073 990 11200 990 11745 990 11214 960 11748 960 11729 960 11729 960 11748 960 11724 960 11729 9854 11724 9854 11749 9854 11213 960 11750 960 11214 960 11214 9855 11750 9855 11751 9855 11214 9856 11751 9856 11748 9856 11748 960 11751 960 11211 960 11748 960 11211 960 11209 960 12387 960 11752 960 11995 960 11995 960 11752 960 11216 960 11999 960 11753 960 11754 960 11550 960 11549 960 11757 960 11223 960 11755 960 11756 960 11756 960 11755 960 11222 960 11757 960 11549 960 11222 960 11222 960 11549 960 12166 960 11222 1285 12166 1285 11756 1285 11835 960 11758 960 11223 960 11223 960 11758 960 11225 960 11225 960 11758 960 11226 960 11226 960 11758 960 12310 960 11226 960 12310 960 11759 960 11759 960 12310 960 11760 960 11759 960 11760 960 11221 960 11229 960 11289 960 12368 960 12368 9857 11289 9857 11788 9857 11744 960 11761 960 11762 960 11762 960 11761 960 11726 960 11762 960 11726 960 11763 960 11763 960 11726 960 11233 960 11764 994 11728 994 11726 994 11726 960 11728 960 11727 960 11726 960 11727 960 11233 960 11233 9858 11727 9858 11232 9858 11675 9859 11765 9859 11209 9859 11209 9860 11765 9860 12401 9860 11209 960 12401 960 11727 960 11727 960 12401 960 11766 960 11727 9861 11766 9861 11232 9861 11232 960 11766 960 11767 960 11232 960 11767 960 11768 960 11768 960 11767 960 12066 960 11768 960 12066 960 11770 960 11770 9862 12066 9862 11769 9862 11770 960 11769 960 11777 960 11777 960 11769 960 11776 960 11242 9863 11243 9863 11771 9863 11771 9864 11243 9864 11241 9864 11771 960 11241 960 12378 960 12378 9865 11241 9865 11772 9865 11772 960 11773 960 12378 960 12378 960 11773 960 11774 960 12378 9866 11774 9866 11776 9866 11776 960 11774 960 11775 960 11776 960 11775 960 11777 960 11979 960 11778 960 11688 960 11688 960 11778 960 11779 960 11688 1011 11779 1011 11246 1011 12310 960 11780 960 11760 960 11760 960 11780 960 11781 960 11760 960 11781 960 12340 960 12340 960 11781 960 11258 960 11258 9867 11259 9867 12340 9867 12340 960 11259 960 11260 960 12340 1018 11260 1018 12341 1018 11782 960 11265 960 12334 960 12280 9868 12283 9868 12329 9868 12329 960 12283 960 11783 960 12329 960 11783 960 12310 960 12310 960 11783 960 11257 960 12310 960 11257 960 11780 960 12334 960 11784 960 11782 960 11782 960 11784 960 11785 960 11782 960 11785 960 11263 960 11618 960 11616 960 12226 960 12226 960 11616 960 11786 960 12226 9869 11786 9869 12227 9869 12227 960 11786 960 11787 960 11788 960 11290 960 12368 960 12368 960 11290 960 11789 960 12368 960 11789 960 12369 960 12369 9870 11789 9870 11790 9870 12369 1150 11790 1150 11291 1150 11292 960 11791 960 11793 960 11794 9871 11286 9871 11615 9871 11615 1151 11286 1151 11287 1151 11615 960 11287 960 11786 960 11786 960 11287 960 11792 960 11786 960 11792 960 11787 960 11791 960 11295 960 11793 960 11793 9872 11295 9872 11297 9872 11793 960 11297 960 11794 960 11805 960 11804 960 11795 960 11795 1153 11797 1153 11805 1153 11805 960 11797 960 11799 960 11805 960 11799 960 12049 960 12049 960 11799 960 12047 960 11802 960 12054 960 11796 960 11796 1079 12054 1079 11800 1079 11797 9873 11798 9873 11799 9873 11799 960 11798 960 11324 960 11799 960 11324 960 12054 960 12054 960 11324 960 11325 960 12054 1080 11325 1080 11800 1080 11327 9874 11808 9874 11801 9874 11801 960 11808 960 11802 960 11801 960 11802 960 11803 960 11803 960 11802 960 11796 960 11804 960 11805 960 11806 960 11806 960 11805 960 11809 960 11806 9875 11809 9875 11330 9875 11327 9876 11807 9876 11808 9876 11808 960 11807 960 11810 960 11808 9877 11810 9877 11809 9877 11809 1155 11810 1155 11329 1155 11809 9878 11329 9878 11330 9878 11819 960 11811 960 11812 960 11812 960 11811 960 11754 960 11812 960 11754 960 11813 960 11813 960 11754 960 11753 960 11811 960 11333 960 11754 960 11754 1166 11333 1166 11334 1166 11754 960 11334 960 12049 960 12049 9879 11334 9879 11335 9879 11335 960 11336 960 12049 960 12049 960 11336 960 11814 960 12049 960 11814 960 11805 960 11805 9880 11814 9880 11815 9880 11816 960 11809 960 11817 960 11817 960 11809 960 11805 960 11817 960 11805 960 11818 960 11818 960 11805 960 11815 960 11819 960 11812 960 11820 960 11820 960 11812 960 11824 960 11820 960 11824 960 11821 960 11816 960 11822 960 11809 960 11809 9881 11822 9881 11823 9881 11809 9882 11823 9882 11824 9882 11824 1159 11823 1159 11825 1159 11824 9883 11825 9883 11821 9883 12043 960 11826 960 11827 960 11827 960 11826 960 11828 960 11828 960 11826 960 12390 960 11828 9884 12390 9884 12389 9884 11827 960 11829 960 12043 960 12043 1193 11829 1193 11830 1193 12043 960 11830 960 12049 960 12049 9885 11830 9885 11831 9885 12049 960 11831 960 11754 960 12315 960 11833 960 11832 960 11832 960 11833 960 12105 960 12315 960 11835 960 11834 960 11834 960 11835 960 11836 960 11834 9886 11836 9886 11343 9886 11343 960 11836 960 11837 960 11838 9887 11839 9887 12104 9887 12104 1195 11839 1195 11840 1195 12104 960 11840 960 11841 960 11841 9888 11840 9888 11842 9888 11841 960 11842 960 12307 960 12307 9889 11842 9889 11843 9889 12307 960 11843 960 11837 960 11837 9890 11843 9890 11342 9890 11837 1190 11342 1190 11343 1190 11871 9891 11844 9891 11870 9891 11870 960 11844 960 12307 960 11844 9892 11845 9892 12307 9892 12307 1202 11845 1202 11846 1202 12307 9893 11846 9893 11841 9893 11841 960 11846 960 11847 960 11841 960 11847 960 11848 960 11869 960 11870 960 11375 960 11375 960 11870 960 12307 960 11375 960 12307 960 11849 960 11849 960 12307 960 12308 960 11850 9894 11366 9894 11367 9894 11862 9895 11374 9895 11851 9895 11851 960 11374 960 11850 960 11851 960 11850 960 11856 960 12306 960 12132 960 11852 960 11852 960 12132 960 12147 960 11858 960 11853 960 11542 960 11542 1048 11853 1048 11854 1048 11542 1047 11854 1047 11855 1047 11850 9896 11367 9896 11856 9896 11856 1052 11367 1052 11368 1052 11856 960 11368 960 11540 960 11540 9897 11368 9897 11857 9897 11540 960 11857 960 11542 960 11542 9898 11857 9898 11371 9898 11542 1049 11371 1049 11858 1049 11686 960 11859 960 11860 960 11860 960 11859 960 11861 960 11860 960 11861 960 11862 960 12123 963 11863 963 11866 963 11873 960 11864 960 11534 960 11534 9899 11864 9899 11865 9899 11534 9900 11865 9900 11866 9900 11866 960 11865 960 12125 960 11377 9901 11378 9901 11875 9901 11867 1170 11868 1170 11873 1170 11869 960 11377 960 11870 960 11870 960 11377 960 11876 960 11870 960 11876 960 11871 960 11871 960 11876 960 12107 960 11868 960 11872 960 11873 960 11873 1168 11872 1168 11874 1168 11873 9902 11874 9902 11864 9902 11377 960 11875 960 11876 960 11876 1173 11875 1173 11877 1173 11876 960 11877 960 11873 960 11873 9903 11877 9903 11878 9903 11873 1171 11878 1171 11867 1171 12363 960 11883 960 11879 960 11879 960 11880 960 12363 960 12363 960 11880 960 11881 960 12363 1279 11881 1279 11887 1279 11887 1210 11881 1210 11882 1210 11887 960 11882 960 12346 960 12346 960 11882 960 12347 960 12359 960 11384 960 11883 960 11883 9904 11384 9904 11383 9904 11883 960 11383 960 11879 960 11391 960 11884 960 12346 960 12346 9905 11884 9905 11394 9905 12346 9906 11394 9906 11395 9906 11397 960 11398 960 12345 960 12345 960 11398 960 11389 960 11395 960 11885 960 12346 960 12346 960 11885 960 11886 960 12346 960 11886 960 11887 960 11887 9907 11886 9907 11888 9907 11887 1186 11888 1186 11889 1186 11683 960 11908 960 11890 960 11890 9908 11908 9908 11887 9908 11890 960 11887 960 11891 960 11891 960 11887 960 11889 960 11904 960 11892 960 11901 960 11893 960 12349 960 11894 960 11894 960 12349 960 11895 960 11894 960 11895 960 12355 960 11896 1282 11897 1282 11898 1282 11898 1281 11897 1281 11910 1281 11898 960 11910 960 11899 960 11896 960 11900 960 11897 960 11897 1181 11900 1181 11902 1181 11897 960 11902 960 11901 960 11901 9909 11902 9909 11903 9909 11901 960 11903 960 11904 960 11892 960 11905 960 11901 960 11901 9910 11905 9910 11906 9910 11901 1184 11906 1184 11907 1184 11683 960 11402 960 11908 960 11908 960 11402 960 11909 960 11908 960 11909 960 11910 960 11910 960 11909 960 11911 960 11910 9911 11911 9911 11899 9911 11912 960 11917 960 11948 960 11462 960 11918 960 6964 960 6964 9912 11918 9912 11913 9912 6964 9913 11913 9913 6971 9913 6971 960 11913 960 11914 960 6971 960 11914 960 11949 960 11949 9914 11914 9914 11915 9914 11949 1108 11915 1108 11912 1108 11916 960 11462 960 11408 960 11408 1117 11462 1117 11924 1117 11948 960 11917 960 11415 960 11415 9915 11917 9915 11918 9915 11415 1113 11918 1113 11414 1113 11916 960 11410 960 11462 960 11462 1116 11410 1116 11411 1116 11462 9916 11411 9916 11918 9916 11918 9917 11411 9917 11413 9917 11918 1114 11413 1114 11414 1114 11919 960 11920 960 12026 960 12026 960 11920 960 11921 960 12026 960 11921 960 12029 960 12029 9918 11921 9918 11922 9918 12029 960 11922 960 11462 960 11462 9919 11922 9919 11923 9919 11462 1118 11923 1118 11924 1118 12400 960 11941 960 11929 960 11925 960 11926 960 11927 960 11927 9920 11926 9920 12400 9920 11927 960 12400 960 11928 960 11928 960 12400 960 11929 960 11933 960 11951 960 11930 960 11931 9921 11945 9921 11932 9921 11933 960 11930 960 11464 960 11464 9922 11930 9922 11934 9922 11464 1100 11934 1100 11935 1100 11935 960 11936 960 11464 960 11464 9923 11936 9923 11937 9923 11464 9924 11937 9924 11938 9924 11955 9925 11939 9925 12400 9925 12400 1094 11939 1094 11940 1094 12400 960 11940 960 11941 960 11941 9926 11940 9926 11943 9926 11941 960 11943 960 11942 960 11942 9927 11943 9927 11932 9927 11942 960 11932 960 11944 960 11944 1098 11932 1098 11945 1098 11950 960 11946 960 11949 960 11949 1106 11946 1106 11947 1106 11912 960 11948 960 11949 960 11949 960 11948 960 11405 960 11949 960 11405 960 11950 960 11951 960 11933 960 11947 960 11947 960 11933 960 11463 960 11947 9928 11463 9928 11949 9928 11938 9929 11931 9929 11464 9929 11464 960 11931 960 11932 960 11464 960 11932 960 11465 960 11465 9930 11932 9930 11952 9930 11465 960 11952 960 7558 960 7558 9931 11952 9931 11953 9931 7558 960 11953 960 12397 960 12397 9932 11953 9932 11954 9932 12397 9933 11954 9933 11955 9933 11955 960 11954 960 11956 960 11955 960 11956 960 11939 960 11957 960 11561 960 11958 960 11958 960 11561 960 12191 960 11958 960 12191 960 11959 960 11959 960 12191 960 12192 960 11959 960 12192 960 11960 960 12212 960 11961 960 12187 960 12229 960 11967 960 12211 960 12211 9934 11967 9934 12213 9934 11962 960 11963 960 11965 960 11965 9935 11963 9935 11964 9935 11965 960 11964 960 12229 960 12229 9936 11964 9936 11966 9936 12229 1142 11966 1142 11967 1142 12365 9937 11968 9937 11969 9937 11969 960 11968 960 11970 960 11969 960 11970 960 12225 960 11974 960 11971 960 11978 960 11978 9938 11971 9938 11980 9938 11973 960 11972 960 11417 960 11417 960 11972 960 11418 960 11977 960 11972 960 11978 960 11978 960 11972 960 11973 960 11978 960 11973 960 11974 960 11974 960 11973 960 11417 960 11974 960 11417 960 11975 960 11976 960 11977 960 11420 960 11420 960 11977 960 11978 960 11420 960 11978 960 11439 960 11439 960 11978 960 11980 960 11439 9939 11980 9939 11436 9939 11979 9940 11987 9940 11980 9940 11980 960 11987 960 11434 960 11980 960 11434 960 11436 960 11988 960 11981 960 11991 960 11991 9941 11981 9941 11983 9941 11991 960 11983 960 11253 960 11253 960 11983 960 11251 960 11253 960 11251 960 11982 960 11981 9942 11424 9942 11983 9942 11983 960 11424 960 11425 960 11983 960 11425 960 11251 960 11251 9943 11425 9943 11984 9943 11251 960 11984 960 11985 960 11985 960 11984 960 11428 960 11985 960 11428 960 11248 960 11248 1013 11428 1013 11986 1013 11248 960 11986 960 11688 960 11688 1136 11986 1136 11429 1136 11688 960 11429 960 11979 960 11979 9944 11429 9944 11432 9944 11979 960 11432 960 11987 960 11988 960 11991 960 11989 960 11989 960 11991 960 11442 960 11989 960 11442 960 11443 960 11253 9945 11990 9945 11991 9945 11991 960 11990 960 11771 960 11991 960 11771 960 11442 960 11442 960 11771 960 11441 960 11994 960 11992 960 12378 960 12378 960 11992 960 11771 960 11771 960 11992 960 11993 960 11771 960 11993 960 11441 960 12378 960 12379 960 11994 960 11994 960 12379 960 12381 960 11994 960 12381 960 11447 960 12385 960 11995 960 11449 960 11449 9946 11995 9946 11216 9946 11449 960 11216 960 12004 960 11996 960 11997 960 11999 960 11999 960 11997 960 11451 960 11999 9947 11451 9947 11452 9947 12004 9948 12000 9948 12005 9948 11216 960 11998 960 12004 960 12004 9949 11998 9949 11999 9949 12004 960 11999 960 12000 960 12000 960 11999 960 11452 960 12001 960 12003 960 12002 960 12002 9950 12003 9950 12004 9950 12002 960 12004 960 11455 960 11455 960 12004 960 12005 960 12392 960 12006 960 12013 960 12013 1122 12006 1122 11365 1122 12016 960 12007 960 11459 960 11459 9951 12007 9951 12008 9951 11459 960 12008 960 12032 960 12032 9952 12008 9952 12009 9952 12032 9953 12009 9953 12019 9953 12016 9954 12010 9954 12011 9954 11364 960 12022 960 12012 960 12012 1041 12022 1041 12013 1041 12012 1121 12013 1121 12014 1121 12014 960 12013 960 11365 960 12015 9955 12007 9955 12017 9955 12017 960 12007 960 12016 960 12017 9956 12016 9956 12018 9956 12018 960 12016 960 12011 960 12019 960 12020 960 12032 960 12032 9957 12020 9957 11357 9957 12032 1126 11357 1126 12021 1126 11364 9958 11363 9958 12022 9958 12022 1123 11363 1123 12023 1123 12022 960 12023 960 12024 960 12024 9959 12023 9959 11360 9959 12024 960 11360 960 12020 960 12020 1132 11360 1132 12025 1132 12020 1131 12025 1131 11357 1131 12393 960 12026 960 12027 960 12027 960 12026 960 12029 960 12027 960 12029 960 12028 960 12028 960 12029 960 11460 960 12028 960 11460 960 12030 960 12030 960 11460 960 11459 960 12030 960 11459 960 12031 960 12031 960 11459 960 12032 960 12031 960 12032 960 12394 960 11474 960 11472 960 12398 960 12398 960 11472 960 12033 960 12398 960 12033 960 11469 960 11469 960 12033 960 11470 960 11469 9960 11470 9960 12036 9960 12034 9961 12035 9961 12037 9961 12036 960 11470 960 12037 960 12037 960 11470 960 12038 960 12037 960 12038 960 12034 960 12039 960 12395 960 11826 960 12040 960 12041 960 12396 960 12396 960 12041 960 11474 960 11479 960 12042 960 12043 960 12043 9962 12042 9962 12044 9962 12043 960 12044 960 11826 960 11826 9963 12044 9963 12045 9963 11826 9964 12045 9964 12039 9964 11480 960 12046 960 12047 960 12047 9965 12046 9965 12048 9965 12047 960 12048 960 12049 960 12049 960 12048 960 12050 960 12049 960 12050 960 12051 960 12051 9966 12052 9966 12049 9966 12049 1083 12052 1083 12053 1083 12049 960 12053 960 12043 960 12043 1082 12053 1082 11476 1082 12043 960 11476 960 11479 960 11181 960 11180 960 11802 960 11802 9967 11180 9967 11697 9967 11802 960 11697 960 12054 960 12054 960 11697 960 11482 960 11178 960 11695 960 11698 960 11698 960 11695 960 12055 960 11698 9968 12055 9968 11697 9968 11697 960 12055 960 11481 960 11697 960 11481 960 11482 960 11693 960 12056 960 11695 960 11695 960 12056 960 12057 960 11695 960 12057 960 12055 960 12055 960 12057 960 11486 960 12055 960 11486 960 11481 960 11481 960 11486 960 11488 960 11481 9969 11488 9969 12058 9969 12059 9970 12060 9970 12071 9970 12071 960 12060 960 12061 960 12071 960 12061 960 11689 960 11689 960 12061 960 12063 960 11689 960 12063 960 12062 960 12062 960 12063 960 12064 960 12065 960 12066 960 11711 960 11711 960 12066 960 11690 960 11711 960 11690 960 12067 960 12067 960 11690 960 11675 960 12067 960 11675 960 12068 960 12068 960 11675 960 11691 960 12068 9971 11691 9971 12069 9971 12069 960 11691 960 12070 960 12069 960 12070 960 11689 960 11689 960 12070 960 11202 960 11689 9972 11202 9972 12071 9972 12071 960 11202 960 11203 960 12071 960 11203 960 12059 960 12059 960 11203 960 12072 960 12059 960 12072 960 12074 960 12074 960 12072 960 12073 960 12074 960 12073 960 12075 960 12075 960 12073 960 5941 960 5941 960 12073 960 11746 960 5941 960 11746 960 11490 960 12076 960 12373 960 12077 960 12077 960 12373 960 11681 960 12077 960 11681 960 12078 960 12078 960 11681 960 12079 960 12078 960 12079 960 12080 960 12080 9973 12079 9973 11490 9973 12080 960 11490 960 11387 960 11387 960 11490 960 11746 960 11387 960 11746 960 11386 960 12090 960 12081 960 12238 960 12238 960 12081 960 12082 960 12238 960 12082 960 12354 960 12354 960 12082 960 12089 960 12088 960 12083 960 11680 960 11680 960 12083 960 12084 960 11680 9974 12084 9974 11496 9974 11493 960 12085 960 12087 960 12087 9975 12085 9975 12086 9975 12087 960 12086 960 12088 960 12088 960 12086 960 12354 960 12088 960 12354 960 12083 960 12083 960 12354 960 12089 960 12084 960 12090 960 11496 960 11496 9976 12090 9976 12238 9976 11496 960 12238 960 5923 960 5923 9977 12238 9977 12091 9977 12342 960 12092 960 11502 960 11502 960 12092 960 12289 960 11502 960 12289 960 12093 960 12093 960 12289 960 12288 960 12093 960 12288 960 11506 960 11658 960 11660 960 12285 960 12094 960 12095 960 11509 960 11509 1068 12095 1068 12096 1068 11509 960 12096 960 11511 960 11515 960 11516 960 12098 960 12098 960 11516 960 12097 960 12098 9978 12097 9978 12100 9978 12099 960 12100 960 11832 960 11832 9979 12100 9979 12097 9979 11832 960 12097 960 12316 960 12316 960 12097 960 11513 960 12316 960 11513 960 12324 960 12324 960 11513 960 11512 960 12106 960 12101 960 12105 960 12105 1067 12101 1067 12102 1067 12105 960 12102 960 11832 960 11832 1066 12102 1066 12103 1066 11832 9980 12103 9980 12099 9980 11833 960 11838 960 12105 960 12105 960 11838 960 12104 960 12105 960 12104 960 12106 960 12106 960 12104 960 11517 960 12107 960 11529 960 12108 960 12108 9981 11529 9981 11525 9981 12108 9982 11525 9982 11848 9982 11848 9983 11525 9983 11526 9983 11848 960 11526 960 11841 960 11841 9984 11526 9984 12121 9984 11841 960 12121 960 11524 960 12109 1061 12110 1061 11841 1061 11841 9985 12110 9985 12111 9985 11841 960 12111 960 12104 960 12104 1082 12111 1082 12112 1082 12104 960 12112 960 11517 960 11522 960 11520 960 11524 960 11524 9986 11520 9986 12113 9986 11524 960 12113 960 11841 960 11841 960 12113 960 12114 960 11841 960 12114 960 12109 960 12119 960 12115 960 12120 960 12118 9987 12116 9987 12117 9987 12117 9988 12119 9988 12118 9988 12118 9989 12119 9989 12120 9989 12118 960 12120 960 12121 960 12121 960 12120 960 12122 960 12121 960 12122 960 11524 960 12107 960 11876 960 11529 960 11529 960 11876 960 11873 960 11529 960 11873 960 11531 960 11531 960 11873 960 11534 960 11531 960 11534 960 11532 960 11538 960 11537 960 12123 960 11862 960 11851 960 11860 960 11860 960 11851 960 12131 960 11860 9990 12131 9990 12124 9990 12125 960 12126 960 11866 960 11866 960 12126 960 11685 960 11866 960 11685 960 12123 960 12123 960 11685 960 11860 960 12123 960 11860 960 11538 960 11538 960 11860 960 12124 960 12124 1054 12127 1054 11538 1054 11538 960 12127 960 12128 960 11538 960 12128 960 11856 960 11856 9991 12128 9991 12129 9991 11856 9992 12129 9992 11851 9992 11851 9993 12129 9993 12130 9993 11851 9994 12130 9994 12131 9994 12137 960 12139 960 12133 960 12137 960 12133 960 12132 960 12132 960 12133 960 12134 960 12132 960 12134 960 12135 960 12145 960 12148 960 12150 960 12156 960 12136 960 12137 960 12137 960 12136 960 12138 960 12137 960 12138 960 12139 960 12139 960 12138 960 12142 960 12139 9995 12142 9995 12144 9995 12151 9996 12140 9996 12141 9996 12142 960 12143 960 12144 960 12144 1045 12143 1045 12145 1045 12144 960 12145 960 12146 960 12146 960 12145 960 12150 960 12146 960 12150 960 12135 960 12135 960 12150 960 11542 960 12135 960 11542 960 12132 960 12132 960 11542 960 11855 960 12132 9997 11855 9997 12147 9997 12148 960 12149 960 12150 960 12150 9998 12149 9998 12151 9998 12150 960 12151 960 12152 960 12152 9999 12151 9999 12141 9999 12305 1038 11347 1038 11346 1038 11346 960 11345 960 12305 960 12305 10000 11345 10000 12153 10000 12305 960 12153 960 12137 960 12137 10001 12153 10001 12154 10001 12158 10002 12159 10002 11348 10002 12154 960 12155 960 12137 960 12137 10003 12155 10003 11354 10003 12137 1041 11354 1041 12156 1041 11354 10004 11353 10004 12156 10004 12156 1035 11353 1035 12157 1035 12156 960 12157 960 12158 960 12158 10005 12157 10005 11351 10005 12158 1033 11351 1033 12159 1033 11348 960 11347 960 12158 960 12158 1039 11347 1039 12305 1039 12158 960 12305 960 11546 960 11546 960 12305 960 11756 960 12165 960 12160 960 11756 960 11756 960 12160 960 12161 960 11756 960 12161 960 11546 960 12162 960 12163 960 12166 960 12166 10006 12163 10006 12164 10006 12165 960 11756 960 12167 960 12167 960 11756 960 12166 960 12167 960 12166 960 12168 960 12168 960 12166 960 12164 960 12168 960 12164 960 11548 960 11757 960 11221 960 11550 960 11550 10007 11221 10007 11760 10007 11550 960 11760 960 11551 960 11551 960 11760 960 12340 960 11551 960 12340 960 11553 960 11553 960 12340 960 12169 960 12169 960 12340 960 12338 960 12169 960 12338 960 12170 960 12170 960 12338 960 12337 960 12170 960 12337 960 11555 960 11555 960 12337 960 12171 960 11555 960 12171 960 11558 960 12336 10008 12172 10008 12173 10008 12173 960 12172 960 12174 960 12173 960 12174 960 11559 960 12175 960 12179 960 11571 960 12175 10009 11571 10009 11595 10009 12176 960 11559 960 12177 960 12177 960 11559 960 12174 960 12177 960 12174 960 12178 960 12178 10010 12174 10010 11595 10010 12178 10011 11595 10011 11572 10011 11572 10012 11595 10012 11571 10012 12179 960 12175 960 12180 960 12180 960 12175 960 12185 960 12180 10013 12185 10013 12181 10013 12189 960 12182 960 12183 960 12183 1022 12182 1022 12181 1022 12183 960 12181 960 12184 960 12184 10014 12181 10014 12185 10014 12186 960 12187 960 12192 960 12192 960 12187 960 11961 960 12192 960 11961 960 11960 960 12186 960 11568 960 12187 960 12187 960 11568 960 12188 960 12187 960 12188 960 12189 960 12189 10015 12188 10015 12190 10015 12189 1023 12190 1023 12182 1023 11574 960 11563 960 12191 960 12191 960 11563 960 11564 960 12191 10016 11564 10016 12192 10016 12192 1148 11564 1148 12193 1148 12192 960 12193 960 12186 960 11561 960 12194 960 12191 960 12191 960 12194 960 11577 960 12191 960 11577 960 11574 960 11574 960 11577 960 11576 960 11594 960 11593 960 12172 960 12172 1222 11593 1222 12195 1222 12172 960 12195 960 12174 960 12174 10017 12195 10017 11597 10017 12174 10018 11597 10018 11595 10018 11594 10019 12172 10019 12196 10019 12196 960 12172 960 12339 960 12196 960 12339 960 12197 960 12197 960 12339 960 12198 960 12198 960 12339 960 12335 960 12198 960 12335 960 11587 960 11587 960 12335 960 12199 960 11587 960 12199 960 11588 960 11588 960 12199 960 11584 960 11584 1218 12199 1218 12303 1218 11584 10020 12303 10020 11583 10020 11580 10021 12258 10021 11579 10021 11579 960 12258 960 12358 960 11579 960 12358 960 11578 960 11279 960 11280 960 12200 960 11578 10022 12358 10022 12200 10022 12200 960 12358 960 12224 960 12200 960 12224 960 11279 960 11275 960 11276 960 12224 960 12224 10023 11276 10023 12201 10023 12224 960 12201 960 11279 960 11269 10024 12202 10024 12209 10024 12209 960 12202 960 11271 960 12209 960 11271 960 12203 960 11271 960 12204 960 12203 960 12203 1213 12204 1213 11274 1213 12203 10025 11274 10025 12205 10025 11280 960 12206 960 12200 960 12200 960 12206 960 11282 960 12200 960 11282 960 12207 960 12207 960 11269 960 12200 960 12200 10026 11269 10026 12209 10026 12200 10027 12209 10027 12208 10027 12208 960 12209 960 12210 960 12208 960 12210 960 13128 960 13128 960 12210 960 12228 960 13128 960 12228 960 12187 960 12187 960 12228 960 12211 960 12187 960 12211 960 12212 960 12212 960 12211 960 12213 960 12183 960 11600 960 12189 960 12189 1223 11600 1223 12214 1223 12189 960 12214 960 12187 960 12187 960 12214 960 12215 960 12187 960 12215 960 13128 960 12377 960 12222 960 12380 960 12380 960 12222 960 12216 960 12380 960 12216 960 12217 960 12217 1225 12216 1225 11611 1225 11611 960 12218 960 12217 960 12217 1224 12218 1224 11612 1224 12217 960 11612 960 12386 960 12386 960 11612 960 11603 960 12386 960 11603 960 11824 960 11603 960 11602 960 11824 960 11824 960 11602 960 12219 960 11824 960 12219 960 11809 960 11809 960 12219 960 12220 960 11809 960 12220 960 11808 960 11808 10028 12220 10028 11604 10028 11808 960 11604 960 12376 960 12376 960 11604 960 12221 960 12376 960 12221 960 12377 960 12377 960 12221 960 11608 960 12377 960 11608 960 12222 960 11794 960 11615 960 11793 960 11793 960 11615 960 11614 960 11793 960 11614 960 12223 960 12223 960 11614 960 12203 960 12223 960 12203 960 12224 960 12224 960 12203 960 12205 960 12224 960 12205 960 11275 960 12230 960 11618 960 12225 960 12225 960 11618 960 12226 960 12225 960 12226 960 11229 960 11229 960 12226 960 12227 960 11229 10029 12227 10029 11289 10029 12228 960 11622 960 12211 960 12211 960 11622 960 11620 960 12211 960 11620 960 12229 960 12229 960 11620 960 12230 960 12229 960 12230 960 11965 960 11965 960 12230 960 12225 960 11965 960 12225 960 11962 960 11962 960 12225 960 11970 960 12231 10030 12268 10030 12269 10030 12269 960 12232 960 12231 960 12231 960 12232 960 12292 960 12231 960 12292 960 12233 960 12233 960 12292 960 12343 960 12233 960 12343 960 12234 960 12234 960 12343 960 12235 960 12234 960 12235 960 12239 960 11634 960 11631 960 12238 960 11631 960 11630 960 12238 960 12238 960 11630 960 12236 960 12238 960 12236 960 12091 960 12091 960 12236 960 12237 960 11676 960 12352 960 12238 960 12238 960 12352 960 11624 960 12238 1244 11624 1244 11634 1244 12235 960 11500 960 12239 960 12239 10031 11500 10031 12237 10031 12239 10032 12237 10032 11635 10032 11635 960 12237 960 12236 960 11635 10033 12236 10033 12240 10033 12240 960 12236 960 11630 960 12243 1234 12241 1234 12242 1234 12248 10034 12259 10034 12246 10034 12242 960 12244 960 12243 960 12243 960 12244 960 12245 960 12243 10035 12245 10035 12246 10035 12246 960 12245 960 12247 960 12246 960 12247 960 12248 960 12241 10036 12243 10036 12250 10036 12250 960 12243 960 12249 960 12250 960 12249 960 12251 960 12251 960 12249 960 11641 960 12251 960 11641 960 12253 960 12253 960 11641 960 12252 960 12253 10037 12252 10037 12261 10037 12260 960 12356 960 12258 960 12254 960 12255 960 12291 960 12291 10038 12255 10038 11669 10038 12291 960 11669 960 12256 960 12256 960 11669 960 12257 960 12256 960 12257 960 11580 960 11580 10039 12257 10039 12246 10039 11580 960 12246 960 12258 960 12258 960 12246 960 12259 960 12258 1229 12259 1229 12262 1229 12260 960 12258 960 12264 960 11678 960 12353 960 12356 960 12261 961 12252 961 12262 961 12262 960 12252 960 12263 960 12262 960 12263 960 12258 960 12258 960 12263 960 11638 960 12258 1228 11638 1228 12264 1228 12265 960 12266 960 11645 960 11645 960 12266 960 12267 960 11645 10040 12267 10040 11644 10040 11644 960 12267 960 12243 960 11644 960 12243 960 12268 960 12268 960 12243 960 12246 960 12268 10041 12246 10041 12269 10041 12269 960 12246 960 11679 960 11648 10042 12282 10042 11649 10042 11649 960 12282 960 12270 960 11648 10043 12271 10043 12282 10043 12282 960 12271 960 12272 960 12282 10044 12272 10044 12274 10044 12276 960 12273 960 12278 960 12272 960 12275 960 12274 960 12274 1265 12275 1265 12276 1265 12274 960 12276 960 12277 960 12277 960 12276 960 12278 960 12279 10045 11652 10045 12280 10045 12280 960 11652 960 12281 960 12270 960 12282 960 12281 960 12281 10046 12282 10046 12334 10046 12281 960 12334 960 12280 960 12280 960 12334 960 11265 960 12280 960 11265 960 12283 960 11512 960 11511 960 12324 960 12324 960 11511 960 12096 960 12324 960 12096 960 11654 960 11654 960 12096 960 12095 960 11654 10047 12095 10047 11660 10047 11660 1259 12095 1259 12284 1259 11660 960 12284 960 12285 960 11658 960 12285 960 11677 960 11677 960 12285 960 11507 960 11677 960 11507 960 11657 960 11657 960 11507 960 11506 960 11657 10048 11506 10048 12286 10048 12286 960 11506 960 12288 960 12286 10049 12288 10049 12287 10049 12287 960 12288 960 12289 960 12287 960 12289 960 12290 960 12256 960 11583 960 12291 960 12291 960 11583 960 12303 960 12291 960 12303 960 12254 960 12254 960 12303 960 11664 960 12254 10050 11664 10050 11668 10050 11668 960 11664 960 11663 960 11668 1251 11663 1251 12292 1251 12292 960 11663 960 12293 960 12292 960 12293 960 12343 960 12294 960 12274 960 12295 960 12295 10051 12274 10051 11664 10051 12295 10052 11664 10052 12296 10052 12333 960 12297 960 12303 960 12303 10053 12297 10053 12298 10053 12332 960 12282 960 12299 960 12299 960 12282 960 12274 960 12299 1268 12274 1268 12300 1268 12300 960 12274 960 12294 960 12298 960 12301 960 12303 960 12303 1273 12301 1273 12302 1273 12303 960 12302 960 11664 960 11664 1272 12302 1272 12304 1272 11664 10054 12304 10054 12296 10054 11223 960 11756 960 11835 960 11835 960 11756 960 12305 960 11835 960 12305 960 11836 960 11836 960 12305 960 12137 960 11836 960 12137 960 11837 960 11837 960 12137 960 12132 960 11837 960 12132 960 12307 960 12307 960 12132 960 12306 960 12307 10055 12306 10056 12308 10057 12316 1290 11317 1290 12317 1290 12321 960 12309 960 12310 960 12310 10058 12309 10058 12311 10058 12310 10059 12311 10059 12329 10059 12329 10060 12311 10060 12312 10060 12329 960 12312 960 12313 960 12313 960 12314 960 12329 960 12329 960 12314 960 11313 960 12329 960 11313 960 12316 960 12316 1287 11313 1287 11315 1287 12316 960 11315 960 11317 960 12315 960 11832 960 11835 960 11835 960 11832 960 12316 960 11835 960 12316 960 11758 960 11758 10061 12316 10061 12317 10061 11758 10062 12317 10062 11318 10062 11318 960 12318 960 11758 960 11758 10063 12318 10063 12319 10063 11758 960 12319 960 12310 960 12310 960 12319 960 12320 960 12310 10064 12320 10064 12321 10064 12322 10065 12323 10065 12324 10065 12331 960 11304 960 12329 960 12329 1294 11304 1294 11305 1294 12329 10066 11305 10066 12280 10066 12280 960 11305 960 11307 960 12280 10067 11307 10067 11309 10067 11654 960 12279 960 12324 960 12324 960 12279 960 12280 960 12324 960 12280 960 12322 960 12322 960 12280 960 11311 960 12323 1300 11301 1300 12324 1300 12324 960 11301 960 12325 960 12324 10068 12325 10068 12316 10068 12316 10069 12325 10069 12326 10069 12326 960 12327 960 12316 960 12316 10070 12327 10070 12328 10070 12316 960 12328 960 12329 960 12329 960 12328 960 12330 960 12329 10071 12330 10071 12331 10071 12332 960 12333 960 12282 960 12282 960 12333 960 12303 960 12282 960 12303 960 12334 960 12334 960 12303 960 12199 960 12334 960 12199 960 11784 960 11784 960 12199 960 12335 960 11784 960 12335 960 11785 960 11785 960 12335 960 12339 960 12336 960 12337 960 12172 960 12172 960 12337 960 12338 960 12172 960 12338 960 12339 960 12339 960 12338 960 12340 960 12339 960 12340 960 11785 960 11785 960 12340 960 12341 960 11785 960 12341 960 11263 960 12342 960 11500 960 12092 960 12092 960 11500 960 12235 960 12092 960 12235 960 12289 960 12289 960 12235 960 12343 960 12289 960 12343 960 12290 960 12290 960 12343 960 12293 960 12357 960 12344 960 12359 960 12359 10072 12344 10072 12348 10072 12359 960 12348 960 11384 960 11389 960 11391 960 12345 960 12345 10073 11391 10073 12346 10073 12345 960 12346 960 12344 960 12344 960 12346 960 12347 960 12344 10074 12347 10074 12348 10074 12349 960 11397 960 11895 960 11895 960 11397 960 12345 960 11895 960 12345 960 12350 960 12350 960 12345 960 12344 960 12350 960 12344 960 12351 960 12351 960 12344 960 12357 960 12351 960 12357 960 12353 960 11628 960 12352 960 12353 960 12353 960 12352 960 11676 960 12353 960 11676 960 12351 960 12351 960 11676 960 12354 960 12351 960 12354 960 12350 960 12350 960 12354 960 12086 960 12350 960 12086 960 11895 960 11895 960 12086 960 11901 960 11895 960 11901 960 12355 960 12355 960 11901 960 11907 960 12356 960 12353 960 12258 960 12258 960 12353 960 12357 960 12258 960 12357 960 12358 960 12358 960 12357 960 12359 960 12358 960 12359 960 12224 960 12224 960 12359 960 11883 960 12224 960 11883 960 12223 960 12223 960 11883 960 12363 960 12223 960 12363 960 11793 960 11897 960 11494 960 11910 960 11910 960 11494 960 12360 960 11910 960 12360 960 11908 960 11908 960 12360 960 12361 960 11908 960 12361 960 11887 960 11887 960 12361 960 12362 960 11887 960 12362 960 12363 960 12363 960 12362 960 12371 960 12363 960 12371 960 11793 960 11793 960 12371 960 12369 960 11793 960 12369 960 11292 960 11292 960 12369 960 11291 960 11229 10075 12364 10075 12225 10075 12225 960 12364 960 11979 960 12225 960 11979 960 11969 960 11969 960 11979 960 11980 960 11969 960 11980 960 12365 960 12365 10076 11980 10076 11971 10076 12366 10077 12368 10077 12367 10077 12367 960 12368 960 12369 960 12367 960 12369 960 12370 960 12370 960 12369 960 12371 960 12370 960 12371 960 12372 960 12372 960 12371 960 12362 960 12372 960 12362 960 12373 960 12373 960 12362 960 12361 960 12373 960 12361 960 11681 960 11681 960 12361 960 12360 960 11681 960 12360 960 12374 960 12374 960 12360 960 11494 960 12374 960 11494 960 11492 960 12076 960 11386 960 12373 960 12373 960 11386 960 11746 960 12373 960 11746 960 12372 960 12372 960 11746 960 11740 960 12372 960 11740 960 12370 960 12370 960 11740 960 12375 960 12370 960 12375 960 12367 960 12367 960 12375 960 11762 960 12367 960 11762 960 12366 960 12366 960 11762 960 11763 960 11715 960 11716 960 12066 960 12066 960 11716 960 11718 960 12066 960 11718 960 11769 960 11769 960 11718 960 12376 960 11769 960 12376 960 11776 960 11776 960 12376 960 12377 960 11776 960 12377 960 12378 960 12378 960 12377 960 12380 960 12378 960 12380 960 12379 960 12379 960 12380 960 12217 960 12379 960 12217 960 12381 960 12381 960 12217 960 12382 960 12383 960 12382 960 12384 960 12384 960 12382 960 12217 960 12384 960 12217 960 12385 960 12385 960 12217 960 12386 960 12385 960 12386 960 11995 960 11995 960 12386 960 11812 960 11995 10078 11812 10078 12387 10078 12387 960 11812 960 11813 960 11831 10079 11687 10079 11754 10079 11754 960 11687 960 12391 960 11754 960 12391 960 11999 960 11999 960 12391 960 12013 960 11999 960 12013 960 11996 960 11996 960 12013 960 12022 960 12388 10080 12389 10080 12391 10080 12391 960 12389 960 12390 960 12391 960 12390 960 12013 960 12013 960 12390 960 12032 960 12013 960 12032 960 12392 960 12392 960 12032 960 12021 960 12393 960 12394 960 12026 960 12026 960 12394 960 12032 960 12026 960 12032 960 12399 960 12399 960 12032 960 12390 960 12399 960 12390 960 12398 960 12398 960 12390 960 11826 960 12398 960 11826 960 11474 960 11474 10081 11826 10081 12395 10081 11474 10082 12395 10082 12396 10082 11468 960 12397 960 12398 960 12398 960 12397 960 11955 960 12398 960 11955 960 12399 960 12399 960 11955 960 12400 960 12399 960 12400 960 12026 960 12026 960 12400 960 11926 960 12026 960 11926 960 11919 960 11919 960 11926 960 11925 960 13048 10083 11766 10083 13049 10083 13049 10084 11766 10084 12401 10084 13049 10085 12401 10085 11674 10085 11674 10086 12401 10086 11765 10086 11302 590 12402 590 13108 590 12403 590 12660 590 12642 590 12404 590 12971 590 11640 590 12523 590 12954 590 11599 590 11582 590 12949 590 11585 590 12405 590 13042 590 12736 590 12690 590 12700 590 12699 590 12406 590 12643 590 12644 590 12406 590 11491 590 12639 590 11495 590 12634 590 13072 590 11498 590 12629 590 11497 590 12407 590 11514 590 12616 590 12408 590 12409 590 12849 590 12410 590 11535 590 11536 590 12587 590 12585 590 12582 590 11565 10087 11573 10087 12815 10087 12475 590 12466 590 12476 590 11193 590 12411 590 13059 590 12666 590 12419 590 12667 590 11189 590 12415 590 12418 590 11182 590 12412 590 12440 590 12440 590 12412 590 11184 590 12440 10088 11184 10088 12413 10088 12413 590 12414 590 12440 590 12440 590 12414 590 12416 590 12440 597 12416 597 12415 597 12415 590 12416 590 12417 590 12415 598 12417 598 12418 598 11185 590 11186 590 12418 590 12418 10089 11186 10089 11188 10089 12418 590 11188 590 11189 590 12667 590 12419 590 12663 590 12663 10090 12419 10090 12438 10090 12663 590 12438 590 12827 590 12665 590 12420 590 12421 590 11485 590 12422 590 12423 590 12423 590 12422 590 11179 590 11179 10091 12424 10091 12425 10091 12425 590 12424 590 12448 590 12425 590 12448 590 12447 590 12444 10092 12445 10092 11674 10092 11674 590 12445 590 12426 590 12427 590 11673 590 13047 590 12443 590 12428 590 12429 590 12442 590 12430 590 13047 590 13047 601 12430 601 12431 601 12428 590 12432 590 12429 590 12429 10093 12432 10093 12433 10093 12429 594 12433 594 12415 594 12415 10094 12433 10094 12434 10094 12434 590 12435 590 12415 590 12415 605 12435 605 12436 605 12415 604 12436 604 12440 604 12440 603 12436 603 12437 603 12440 10095 12437 10095 12441 10095 12438 590 12439 590 12827 590 12827 596 12439 596 11182 596 12827 590 11182 590 13046 590 13046 590 11182 590 12440 590 13046 590 12440 590 13047 590 13047 590 12440 590 12441 590 13047 10096 12441 10096 12442 10096 12431 590 12443 590 13047 590 13047 590 12443 590 12429 590 13047 10097 12429 10097 12427 10097 12427 10098 12429 10098 11190 10098 12427 10099 11190 10099 12444 10099 12444 590 11190 590 12446 590 12444 590 12446 590 12445 590 12445 590 12446 590 12447 590 12445 590 12447 590 11208 590 11208 590 12447 590 12448 590 11208 590 12448 590 11207 590 11207 794 12448 794 12653 794 11207 590 12653 590 12655 590 11201 590 12449 590 12657 590 12657 10100 12449 10100 11205 10100 11198 10101 12450 10101 12660 10101 12660 590 12450 590 12657 590 12657 10102 12450 10102 12451 10102 12657 621 12451 621 11201 621 12403 590 11195 590 12660 590 12660 10103 11195 10103 11196 10103 12660 617 11196 617 11198 617 11193 10104 13059 10104 12452 10104 12453 590 11191 590 12488 590 12488 614 11191 614 12454 614 12488 615 12454 615 12452 615 12459 590 12456 590 12455 590 12455 590 12456 590 12490 590 12455 590 12490 590 12472 590 12453 590 12488 590 12457 590 12457 590 12488 590 12456 590 12457 590 12456 590 12458 590 12458 590 12456 590 12459 590 12458 590 12459 590 12460 590 12459 10105 12461 10105 12460 10105 12460 609 12461 609 12462 609 12460 590 12462 590 12463 590 12463 10106 12462 10106 12464 10106 12463 590 12464 590 12466 590 12466 590 12464 590 12465 590 12466 590 12465 590 12476 590 12476 10107 12465 10107 12467 10107 12476 10108 12467 10108 12468 10108 12468 590 12469 590 12476 590 12476 611 12469 611 12470 611 12476 590 12470 590 12490 590 12490 610 12470 610 12471 610 12490 590 12471 590 12472 590 12473 590 12474 590 11212 590 11212 590 12474 590 12475 590 11212 10109 12475 10109 11210 10109 11210 590 12475 590 12476 590 11210 590 12476 590 12426 590 12426 590 12476 590 12490 590 12426 10110 12490 10110 11674 10110 12845 590 12478 590 11219 590 11219 590 12478 590 11218 590 11219 590 11220 590 12477 590 12477 590 11220 590 12480 590 11218 590 12478 590 11217 590 11217 590 12478 590 13043 590 11217 590 13043 590 11215 590 11215 590 13043 590 12479 590 11215 590 12479 590 12480 590 12480 590 12479 590 12772 590 12480 590 12772 590 12477 590 13125 590 11224 590 12481 590 12481 590 11224 590 13102 590 12482 10111 11240 10111 12483 10111 12483 590 11240 590 12500 590 12486 590 11238 590 13044 590 13044 590 11238 590 12484 590 13044 10112 12484 10112 12483 10112 12483 590 12484 590 12485 590 12483 590 12485 590 12482 590 11231 10113 11230 10113 12486 10113 12486 590 11230 590 11239 590 12486 590 11239 590 11238 590 11237 590 11236 590 12487 590 12487 590 11236 590 11235 590 12487 590 11235 590 12488 590 12488 590 11235 590 12489 590 12488 590 12489 590 12456 590 12456 10114 12489 10114 11234 10114 12456 590 11234 590 12490 590 12494 10115 12491 10115 12495 10115 12487 590 13064 590 11237 590 11237 590 13064 590 12492 590 11237 10116 12492 10116 12493 10116 12493 10117 11298 10117 11237 10117 11237 590 11298 590 11299 590 11237 590 11299 590 11228 590 11299 590 12494 590 11228 590 11228 590 12494 590 12495 590 11228 590 12495 590 11227 590 11227 10118 12495 10118 12966 10118 11255 590 12784 590 11245 590 11245 590 12784 590 12496 590 11245 590 12496 590 11247 590 11247 590 12496 590 11249 590 12498 590 12783 590 11250 590 11250 590 12783 590 12504 590 12496 590 12497 590 11249 590 11249 749 12497 749 12498 749 11249 590 12498 590 12499 590 12499 10119 12498 10119 11250 10119 11240 590 11244 590 12500 590 12500 10120 11244 10120 12501 10120 12500 590 12501 590 12502 590 12502 10121 12501 10121 12503 10121 12502 10122 12503 10122 12504 10122 12504 590 12503 590 11254 590 12504 590 11254 590 11250 590 11250 10123 11254 10123 11252 10123 12505 590 12516 590 12506 590 12506 590 12516 590 11262 590 12506 590 11262 590 12508 590 12508 590 11262 590 11261 590 11261 590 12507 590 12508 590 12508 10124 12507 10124 12510 10124 12508 590 12510 590 12509 590 12509 590 12510 590 12511 590 12509 590 12511 590 13093 590 12511 590 11256 590 13093 590 13093 590 11256 590 12512 590 13093 590 12512 590 13108 590 13108 590 12512 590 12513 590 13108 590 12513 590 12514 590 12514 10125 12513 10125 12515 10125 12514 590 12515 590 13014 590 13014 590 12515 590 11266 590 13014 10126 11266 10126 12505 10126 12505 590 11266 590 11264 590 12505 590 11264 590 12516 590 11567 590 12808 590 12517 590 12517 590 12808 590 12525 590 11598 590 12518 590 12519 590 12519 10127 12518 10127 12520 10127 12519 590 12520 590 12521 590 12521 10128 12520 10128 12522 10128 12521 590 12522 590 12523 590 12523 851 12522 851 11570 851 12523 590 11570 590 12954 590 12954 855 11570 855 12524 855 12954 590 12524 590 12525 590 12525 10129 12524 10129 11569 10129 12525 853 11569 853 12517 853 11596 590 12526 590 12527 590 12527 10130 12526 10130 12528 10130 12527 590 12528 590 11598 590 11598 10131 12528 10131 12529 10131 11598 590 12529 590 12518 590 12530 590 12952 590 12531 590 12531 590 12952 590 12532 590 12531 590 12532 590 12533 590 12533 590 12532 590 12535 590 12532 590 13082 590 12535 590 12535 590 13082 590 12534 590 12535 590 12534 590 12536 590 12536 590 12534 590 11556 590 12536 590 11556 590 11557 590 12537 590 12538 590 11552 590 11552 590 12538 590 12508 590 11552 590 12508 590 12539 590 12539 590 12508 590 12509 590 13095 842 12556 842 12540 842 12540 590 12541 590 13095 590 13095 10132 12541 10132 12542 10132 13095 10133 12542 10133 13097 10133 13097 10134 12542 10134 12543 10134 12544 590 12545 590 12546 590 12546 10135 12545 10135 13097 10135 12546 590 13097 590 11547 590 11547 10136 13097 10136 12543 10136 11344 590 12551 590 11355 590 11355 590 12551 590 12572 590 11355 590 12572 590 12547 590 12547 10137 12572 10137 12548 10137 11344 590 12549 590 12551 590 12551 10138 12549 10138 12550 10138 12551 834 12550 834 12552 834 11349 10139 11350 10139 12554 10139 12554 841 11350 841 12553 841 12554 590 12553 590 12555 590 12555 10140 12553 10140 11352 10140 12555 839 11352 839 12558 839 12556 590 13095 590 12557 590 12557 590 13095 590 12551 590 12557 590 12551 590 12554 590 12554 590 12551 590 12552 590 12554 10141 12552 10141 11349 10141 12558 590 12548 590 12555 590 12555 590 12548 590 12572 590 12555 590 12572 590 11545 590 11544 10142 12559 10142 12560 10142 12561 10143 12572 10143 12562 10143 12562 590 12572 590 12576 590 12562 590 12576 590 12563 590 12563 10144 12576 10144 12564 10144 12565 590 12566 590 12567 590 12567 590 12566 590 11544 590 12567 590 11544 590 11543 590 11543 590 11544 590 12560 590 11543 10145 12560 10145 12568 10145 11541 590 11543 590 12577 590 12577 830 11543 830 12568 830 12577 590 12568 590 12569 590 12569 829 12568 829 12570 829 12569 590 12570 590 12561 590 12561 10146 12570 10146 12571 10146 12561 590 12571 590 12572 590 12572 10147 12571 10147 12573 10147 12572 826 12573 826 11545 826 13122 590 12574 590 12576 590 12576 590 12574 590 12575 590 12575 590 12578 590 12576 590 12576 590 12578 590 11541 590 12576 590 11541 590 12564 590 12564 590 11541 590 12577 590 12578 590 12579 590 11541 590 11541 682 12579 682 12580 682 11541 681 12580 681 11372 681 11372 590 12581 590 11541 590 11541 680 12581 680 11370 680 11541 590 11370 590 11539 590 11539 10148 11370 10148 11369 10148 11539 10149 11369 10149 12582 10149 12582 10150 11369 10150 12583 10150 12582 677 12583 677 12584 677 12582 590 12585 590 12591 590 12591 819 12585 819 12586 819 12591 590 12586 590 12590 590 12587 590 12582 590 12588 590 12588 590 12582 590 12864 590 12588 10151 12864 10151 12589 10151 12589 590 12864 590 12866 590 12589 10152 12866 10152 12590 10152 12590 590 12866 590 12591 590 12591 590 12866 590 11536 590 12591 590 11536 590 12592 590 12593 10153 12410 10153 12594 10153 11530 590 11533 590 12593 590 12594 590 12408 590 12593 590 12593 590 12408 590 12849 590 12593 590 12849 590 11530 590 11530 590 12849 590 12855 590 11530 590 12855 590 11528 590 12925 10154 12599 10154 12603 10154 12595 10155 12925 10155 12596 10155 12596 590 12925 590 12917 590 12596 10156 12917 10156 12597 10156 11521 590 11523 590 12598 590 12598 590 11523 590 12599 590 12598 590 12599 590 12600 590 12600 590 12599 590 12925 590 12600 590 12925 590 12601 590 12601 810 12925 810 12595 810 12602 590 12925 590 12604 590 12604 590 12925 590 12603 590 12604 590 12603 590 12605 590 12605 590 12603 590 12610 590 12606 590 12607 590 12608 590 12608 10108 12607 10108 12605 10108 12608 590 12605 590 12609 590 12609 10157 12605 10157 12610 10157 12597 590 12917 590 12611 590 12611 590 12917 590 12612 590 12611 590 12612 590 11518 590 12613 590 12614 590 11514 590 11514 10158 12614 10158 12615 10158 11514 10159 12615 10159 12616 10159 12616 10160 12615 10160 12617 10160 12616 590 12617 590 12618 590 12618 10161 12619 10161 12616 10161 12616 805 12619 805 12620 805 12616 590 12620 590 12612 590 12612 804 12620 804 11519 804 12612 590 11519 590 11518 590 12621 590 12622 590 11508 590 12621 590 11508 590 13119 590 11504 10162 11505 10162 12623 10162 12623 590 11505 590 13008 590 12623 590 13008 590 11661 590 11661 590 11659 590 12623 590 12623 590 11659 590 12624 590 12623 590 12624 590 11504 590 11504 590 12624 590 12625 590 11504 590 12625 590 11503 590 11501 590 12627 590 12626 590 12626 590 12627 590 13085 590 12626 10163 13085 10163 11499 10163 11499 590 13085 590 11498 590 11498 590 13085 590 13086 590 11498 590 13086 590 12629 590 11497 590 12629 590 12628 590 12628 590 12629 590 12630 590 12628 590 12630 590 12631 590 12632 590 13078 590 12633 590 12633 590 13078 590 12634 590 12633 10164 12634 10164 12635 10164 12635 590 12634 590 11495 590 12635 10165 11495 10165 12636 10165 12636 10166 11495 10166 12631 10166 12636 10167 12631 10167 12637 10167 12637 590 12631 590 12630 590 12637 590 12630 590 13077 590 12638 590 13068 590 13071 590 12643 590 12406 590 13060 590 13060 10168 12406 10168 12639 10168 13060 590 12639 590 12640 590 12660 590 12649 590 12642 590 12642 590 12649 590 12641 590 12642 590 12641 590 12645 590 13060 590 12642 590 12643 590 12643 590 12642 590 12645 590 12643 590 12645 590 12644 590 12644 10169 12645 10169 12646 10169 12644 10170 12646 10170 12647 10170 12647 10171 12646 10171 12648 10171 12647 10172 12648 10172 12660 10172 12660 590 12648 590 11385 590 12660 590 11385 590 12649 590 12650 590 12651 590 12656 590 12656 10173 12651 10173 12658 10173 11179 590 12422 590 12424 590 12424 590 12422 590 11484 590 12424 590 11484 590 12448 590 12448 10174 11484 10174 12652 10174 12448 590 12652 590 12653 590 12653 590 12652 590 12654 590 12653 590 12654 590 12655 590 12655 590 12654 590 12650 590 12655 590 12650 590 11205 590 11205 590 12650 590 12656 590 11205 590 12656 590 12657 590 12657 590 12656 590 12658 590 12657 590 12658 590 12660 590 12660 590 12658 590 12659 590 12660 10175 12659 10175 12647 10175 11487 590 12661 590 12665 590 12665 10176 12661 10176 11485 10176 12665 590 11485 590 12420 590 12420 590 11485 590 12423 590 12420 590 12423 590 12421 590 12668 590 11483 590 12665 590 11487 590 12665 590 11489 590 11489 590 12665 590 11483 590 11489 590 11483 590 12662 590 12663 590 12830 590 12664 590 12421 590 12666 590 12665 590 12665 590 12666 590 12667 590 12665 590 12667 590 12668 590 12668 590 12667 590 12663 590 12668 590 12663 590 12669 590 12669 590 12663 590 12664 590 11323 590 11322 590 12670 590 12670 10177 11322 10177 12822 10177 12670 590 12822 590 12841 590 12664 590 12671 590 12669 590 12669 648 12671 648 12672 648 12669 590 12672 590 12670 590 12670 590 12672 590 12673 590 12670 590 12673 590 11323 590 12678 590 12840 590 12844 590 11477 787 12676 787 12911 787 12674 590 12675 590 12842 590 12842 590 12675 590 12841 590 12911 590 12676 590 12844 590 12844 786 12676 786 12677 786 12844 590 12677 590 12678 590 12679 10178 12681 10178 13034 10178 11473 590 11475 590 12680 590 12681 590 12682 590 13034 590 13034 590 12682 590 12683 590 13034 10179 12683 10179 12902 10179 12902 10180 12684 10180 12911 10180 12911 590 12684 590 11478 590 12911 590 11478 590 11477 590 12680 590 12679 590 11473 590 11473 10181 12679 10181 13034 10181 11473 590 13034 590 11471 590 11471 590 13034 590 12698 590 12687 590 12685 590 12690 590 12686 590 12687 590 12688 590 12688 10182 12687 10182 12690 10182 12688 10183 12690 10183 12689 10183 12689 590 12690 590 12699 590 12696 590 13036 590 12691 590 12703 590 12692 590 12693 590 12693 590 12692 590 12695 590 12693 590 12695 590 12694 590 12694 590 12695 590 11466 590 12694 590 11466 590 12691 590 12691 590 11466 590 12697 590 12691 590 12697 590 12696 590 12696 590 12697 590 11467 590 12696 590 11467 590 12698 590 12698 10184 11467 10184 12699 10184 12698 10185 12699 10185 11471 10185 11471 590 12699 590 12700 590 12900 590 12701 590 13041 590 13041 725 12701 725 13035 725 12708 590 12704 590 12692 590 12714 590 12692 590 12713 590 12711 590 12702 590 12703 590 12704 590 12705 590 12692 590 12692 10186 12705 10186 12706 10186 12692 721 12706 721 12713 721 12703 590 12702 590 12692 590 12692 10187 12702 10187 12707 10187 12692 10188 12707 10188 12708 10188 12900 590 12709 590 12703 590 12703 10189 12709 10189 12710 10189 12703 10190 12710 10190 12711 10190 11404 590 11406 590 12712 590 12712 590 11406 590 12720 590 12713 10191 12715 10191 12714 10191 12714 590 12715 590 12716 590 12714 590 12716 590 12718 590 12718 10192 12716 10192 12717 10192 12718 590 12717 590 12720 590 12720 729 12717 729 12719 729 12720 10193 12719 10193 12712 10193 12721 590 12732 590 12727 590 12727 10194 12732 10194 12722 10194 12727 590 12722 590 12725 590 11406 590 12723 590 12720 590 12720 712 12723 712 12724 712 12720 10195 12724 10195 12725 10195 12725 590 12724 590 12726 590 12725 590 12726 590 12727 590 11407 590 12721 590 11406 590 11406 10196 12721 10196 12728 10196 11406 10197 12728 10197 12723 10197 12729 590 11409 590 12732 590 12732 10198 11409 10198 12730 10198 11407 590 12731 590 12721 590 12721 714 12731 714 11412 714 12721 590 11412 590 12732 590 12732 10199 11412 10199 12733 10199 12732 713 12733 713 12729 713 12730 590 12734 590 12732 590 12732 719 12734 719 12735 719 12732 10200 12735 10200 11461 10200 11461 10201 12735 10201 12740 10201 12736 590 13042 590 12737 590 12737 590 13042 590 12744 590 12737 590 12744 590 12741 590 13038 10202 11458 10202 12742 10202 12742 590 11458 590 12738 590 12738 590 11458 590 12739 590 12738 590 12739 590 12747 590 12747 10203 12739 10203 11461 10203 12747 590 11461 590 12744 590 12744 590 11461 590 12740 590 12744 590 12740 590 12741 590 12742 10204 12743 10204 13038 10204 13038 10205 12743 10205 12745 10205 13038 590 12745 590 12744 590 12744 952 12745 952 12746 952 12744 10206 12746 10206 12747 10206 11457 590 12764 590 11361 590 11457 590 11361 590 11456 590 12767 767 12748 767 13037 767 12748 590 12749 590 13037 590 13037 764 12749 764 12750 764 13037 590 12750 590 13038 590 12760 10207 12751 10207 12752 10207 12752 590 12751 590 11458 590 12752 590 11458 590 12761 590 11361 590 11362 590 11456 590 11456 769 11362 769 12753 769 11456 10208 12753 10208 12754 10208 12750 590 11356 590 13038 590 13038 10209 11356 10209 12755 10209 13038 10210 12755 10210 11358 10210 12756 590 12757 590 12758 590 12758 10211 12757 10211 12751 10211 12758 590 12751 590 12759 590 12759 590 12751 590 12760 590 12761 590 11458 590 12762 590 12762 590 11458 590 13038 590 12762 590 13038 590 12763 590 12763 590 13038 590 11358 590 12763 590 11358 590 12764 590 12764 10212 11358 10212 11359 10212 12764 771 11359 771 11361 771 12765 590 12766 590 12477 590 12754 590 12767 590 11456 590 11456 590 12767 590 13037 590 11456 590 13037 590 12768 590 12768 590 13037 590 12477 590 12768 590 12477 590 12769 590 12769 590 12477 590 12766 590 12770 590 12771 590 12772 590 12772 590 12771 590 12773 590 12765 590 12477 590 11453 590 11453 590 12477 590 12772 590 11453 590 12772 590 12774 590 12774 590 12772 590 12773 590 12774 590 12773 590 11454 590 11450 590 12957 590 12775 590 12775 590 12957 590 12958 590 12775 590 12958 590 11448 590 11448 590 12958 590 12776 590 11446 590 12777 590 11445 590 11445 590 12777 590 12778 590 11445 590 12778 590 12779 590 12779 590 12778 590 12483 590 12779 10213 12483 10213 11440 10213 11440 590 12483 590 12500 590 11440 590 12500 590 12780 590 12780 590 12500 590 12502 590 12780 590 12502 590 12781 590 12781 590 12502 590 12782 590 12781 590 12782 590 11444 590 11422 10214 12782 10214 11423 10214 11423 590 12782 590 12502 590 11423 10215 12502 10215 11426 10215 11426 10216 12502 10216 12504 10216 11426 590 12504 590 11427 590 11427 590 12504 590 12783 590 12784 590 12795 590 11435 590 11435 590 11433 590 12784 590 12784 752 11433 752 11431 752 12784 590 11431 590 12496 590 12496 10217 11431 10217 11430 10217 12496 750 11430 750 12497 750 12785 590 11421 590 12786 590 12786 10218 11421 10218 11438 10218 12786 590 11438 590 12795 590 12795 10219 11438 10219 11437 10219 12795 590 11437 590 11435 590 12787 590 11419 590 12785 590 12785 590 12786 590 12787 590 12787 590 12786 590 12789 590 12787 590 12789 590 12788 590 12788 590 12789 590 12792 590 12788 590 12792 590 12790 590 11416 590 12792 590 12791 590 12791 590 12792 590 12789 590 12791 590 12789 590 12793 590 12793 590 12789 590 12786 590 12793 10220 12786 10220 12794 10220 12794 10221 12786 10221 12795 10221 12794 10222 12795 10222 12796 10222 12801 590 12797 590 12805 590 12798 590 13050 590 12799 590 12799 590 13050 590 12966 590 12799 590 12966 590 12800 590 12800 590 12966 590 12801 590 12800 10223 12801 10223 12802 10223 12802 10224 12801 10224 12805 10224 12811 590 12803 590 12797 590 12797 10225 12803 10225 12804 10225 12797 742 12804 742 12805 742 11562 10226 12806 10226 12807 10226 12807 590 12806 590 12808 590 12806 10227 12809 10227 12808 10227 12808 590 12809 590 12810 590 12808 590 12810 590 12525 590 12525 590 12810 590 12812 590 12525 590 12812 590 12811 590 12811 10228 12812 10228 12813 10228 12811 10229 12813 10229 12803 10229 11562 590 12807 590 11560 590 11560 590 12807 590 12816 590 11560 590 12816 590 12814 590 11567 590 11566 590 12808 590 12808 857 11566 857 11565 857 12808 590 11565 590 12807 590 12807 590 11565 590 12815 590 12807 590 12815 590 12816 590 12816 590 12815 590 11575 590 12491 590 12817 590 12964 590 12964 644 12817 644 12818 644 12964 590 12818 590 12970 590 11296 645 12819 645 12820 645 12819 10230 11294 10230 12820 10230 12820 10231 11294 10231 11293 10231 12820 590 11293 590 13064 590 13064 10232 11293 10232 12821 10232 13064 590 12821 590 12492 590 12818 590 11288 590 12970 590 12970 642 11288 642 11285 642 12970 10233 11285 10233 11284 10233 11322 590 11321 590 12822 590 12822 590 11321 590 12823 590 12822 590 12823 590 12825 590 12825 590 12823 590 12824 590 12825 10234 12824 10234 11331 10234 11331 590 11328 590 12825 590 12825 650 11328 650 12826 650 12825 590 12826 590 12827 590 12826 590 11326 590 12827 590 12827 10235 11326 10235 12828 10235 12827 590 12828 590 12663 590 12663 590 12828 590 12829 590 12663 590 12829 590 12830 590 11339 658 12832 658 12831 658 11339 590 12831 590 11338 590 12832 10236 12833 10236 12831 10236 12831 661 12833 661 12834 661 12831 10237 12834 10237 12825 10237 12834 10238 12835 10238 12825 10238 12825 10239 12835 10239 12836 10239 12825 590 12836 590 12822 590 12822 10240 12836 10240 12837 10240 12822 590 12837 590 12838 590 12839 590 11337 590 12844 590 12838 590 12839 590 12822 590 12822 590 12839 590 12844 590 12822 590 12844 590 12841 590 12841 10241 12844 10241 12840 10241 12841 10242 12840 10242 12842 10242 11337 590 12843 590 12844 590 12844 10243 12843 10243 12846 10243 12844 10244 12846 10244 12845 10244 12846 590 12847 590 12845 590 12845 653 12847 653 11332 653 12845 590 11332 590 12478 590 12478 10245 11332 10245 12848 10245 12409 590 12850 590 12849 590 12849 689 12850 689 12851 689 12849 10246 12851 10246 12852 10246 12852 590 12853 590 12849 590 12849 693 12853 693 12854 693 12849 590 12854 590 12855 590 12855 10247 12854 10247 12856 10247 12855 691 12856 691 12857 691 12858 590 12859 590 12866 590 12866 10248 12859 10248 12860 10248 12866 590 12860 590 11536 590 11536 10249 12860 10249 12861 10249 11536 10250 12861 10250 12410 10250 12410 590 12861 590 12862 590 12410 590 12862 590 12594 590 12584 10251 12863 10251 12582 10251 12582 10252 12863 10252 11373 10252 12582 590 11373 590 12864 590 12864 590 11373 590 12865 590 12864 590 12865 590 12866 590 12866 590 12865 590 12867 590 12866 684 12867 684 12858 684 12868 590 13122 590 12872 590 12857 590 11379 590 12855 590 12855 10253 11379 10253 12869 10253 12855 590 12869 590 12871 590 12871 590 12869 590 12870 590 12871 590 12870 590 12872 590 12872 590 12870 590 11376 590 12872 10254 11376 10254 12868 10254 12873 10255 12875 10255 12874 10255 12874 590 12875 590 13061 590 12874 590 13061 590 13062 590 12640 10256 12876 10256 13063 10256 12877 590 12885 590 12878 590 12878 590 12885 590 12879 590 12877 590 12880 590 12885 590 12885 590 12880 590 12881 590 12885 590 12881 590 12640 590 12640 10257 12881 10257 12882 10257 12640 703 12882 703 12876 703 11396 590 12883 590 12884 590 12884 590 12883 590 12886 590 12884 945 12886 945 12885 945 12885 10258 12886 10258 12887 10258 12885 706 12887 706 12879 706 11396 590 12884 590 12888 590 12888 590 12884 590 12897 590 12888 590 12897 590 12896 590 11400 590 11401 590 13056 590 13056 10259 11401 10259 12889 10259 12890 701 12891 701 13053 701 12892 590 11393 590 12933 590 12933 590 11393 590 11392 590 12891 702 12893 702 13053 702 13053 590 12893 590 12894 590 13053 590 12894 590 12933 590 12933 590 12894 590 12895 590 12933 590 12895 590 12892 590 11399 590 12896 590 11388 590 11388 590 12896 590 12897 590 11388 590 12897 590 11390 590 11390 590 12897 590 12933 590 11390 699 12933 699 12898 699 12898 10260 12933 10260 11392 10260 13041 10261 12899 10261 12901 10261 12900 590 13041 590 12709 590 12709 590 13041 590 12901 590 12709 10262 12901 10262 11403 10262 12902 590 12911 590 13034 590 13034 590 12911 590 12912 590 13034 10263 12912 10263 12903 10263 12903 10264 12904 10264 13039 10264 13039 590 12904 590 12906 590 13039 590 12906 590 12905 590 12905 590 12906 590 12907 590 12905 590 12907 590 12845 590 12845 10265 12907 10265 12908 10265 12845 590 12908 590 12844 590 12844 10266 12908 10266 12909 10266 12844 590 12909 590 12911 590 12911 10267 12909 10267 12910 10267 12911 590 12910 590 12912 590 12913 590 12914 590 13123 590 13123 590 12914 590 11341 590 13123 590 11341 590 12872 590 12872 10268 11341 10268 11340 10268 12872 590 11340 590 12925 590 12925 670 11340 670 12915 670 12925 590 12915 590 12917 590 12915 10269 12916 10269 12917 10269 12917 590 12916 590 12918 590 12917 590 12918 590 12612 590 12612 590 12918 590 12919 590 12612 590 12919 590 12616 590 12616 10270 12919 10270 12920 10270 12616 590 12920 590 13121 590 13121 10271 12920 10271 12921 10271 13121 590 12921 590 12913 590 12913 10272 12921 10272 12922 10272 12913 590 12922 590 12914 590 12923 590 12924 590 12925 590 12925 590 12924 590 12926 590 12925 10273 12926 10273 12872 10273 12872 673 12926 673 12927 673 12872 590 12927 590 12871 590 12871 10274 12927 10274 12928 10274 12871 10275 12928 10275 12855 10275 12855 590 12928 590 12929 590 12855 590 12929 590 11528 590 11528 10276 12929 10276 12930 10276 11528 590 12930 590 11527 590 11527 10277 12930 10277 12931 10277 11527 590 12931 590 12602 590 12602 10278 12931 10278 12923 10278 12602 10279 12923 10279 12925 10279 13051 696 13053 696 12932 696 12932 590 13053 590 12933 590 12932 590 12933 590 12934 590 12934 10280 12933 10280 12935 10280 13066 590 13052 590 12937 590 13066 590 12937 590 12936 590 12936 590 12937 590 11382 590 12936 590 11382 590 13075 590 12938 590 12940 590 12939 590 12939 590 12940 590 12943 590 11281 10281 12941 10281 12945 10281 12941 10282 12942 10282 12945 10282 12945 590 12942 590 11278 590 12945 590 11278 590 13067 590 13067 866 11278 866 11277 866 11283 590 11273 590 12967 590 12967 868 11273 868 11272 868 12967 590 11272 590 12943 590 11272 590 11270 590 12943 590 12943 867 11270 867 12944 867 12943 590 12944 590 12939 590 12939 10283 12944 10283 11268 10283 12939 590 11268 590 12945 590 12945 10284 11268 10284 11267 10284 12945 590 11267 590 11281 590 11277 590 12946 590 13067 590 13067 864 12946 864 12947 864 13067 879 12947 879 11283 879 12999 590 11672 590 12998 590 13089 590 12948 590 13088 590 13088 590 12948 590 11589 590 11585 590 12949 590 11589 590 11589 590 12949 590 13087 590 11589 861 13087 861 13088 861 11590 590 12950 590 13090 590 12950 590 11591 590 13090 590 13090 590 11591 590 12951 590 13090 10285 12951 10285 13089 10285 13089 590 12951 590 11586 590 13089 590 11586 590 12948 590 12952 590 12526 590 12532 590 12532 590 12526 590 11596 590 12532 590 11596 590 13082 590 13082 10286 11596 10286 12953 10286 13082 858 12953 858 11592 858 12811 590 13126 590 12525 590 12525 590 13126 590 13127 590 12525 590 13127 590 12954 590 12954 590 13127 590 12955 590 12954 874 12955 874 11599 874 12956 10287 11609 10287 13046 10287 12831 590 11601 590 12957 590 12957 590 11601 590 11613 590 12957 590 11613 590 12958 590 12958 590 11613 590 12959 590 12958 875 12959 875 12960 875 12960 590 11610 590 12958 590 12958 590 11610 590 11606 590 12958 590 11606 590 12961 590 13046 590 11609 590 12827 590 12827 590 11609 590 11605 590 12827 10288 11605 10288 12825 10288 12825 590 11605 590 12962 590 12825 590 12962 590 12831 590 12831 590 12962 590 12963 590 12831 590 12963 590 11601 590 12491 638 12964 638 12495 638 12495 590 12964 590 12965 590 12495 590 12965 590 12966 590 12966 590 12965 590 11617 590 12966 590 11617 590 12801 590 11283 590 12967 590 13067 590 13067 590 12967 590 12968 590 13067 590 12968 590 12969 590 12969 590 12968 590 12970 590 12969 590 12970 590 12820 590 12820 10289 12970 10289 11284 10289 12820 646 11284 646 11296 646 11617 590 11619 590 12801 590 12801 590 11619 590 11621 590 12801 590 11621 590 12797 590 12797 590 11621 590 11623 590 12797 590 11623 590 12811 590 12811 590 11623 590 12938 590 12811 590 12938 590 13126 590 13126 590 12938 590 12939 590 11640 590 12971 590 11639 590 12999 892 12974 892 12980 892 11639 590 12971 590 13080 590 13080 590 12971 590 12972 590 13080 590 12972 590 12999 590 12999 590 12972 590 12973 590 12999 590 12973 590 12974 590 12988 590 11626 590 12975 590 12975 590 11626 590 11627 590 12975 590 11627 590 13080 590 13080 590 11627 590 12976 590 13080 896 12976 896 12977 896 12977 590 12978 590 13080 590 13080 899 12978 899 12979 899 13080 898 12979 898 11639 898 12980 590 12981 590 12995 590 12995 590 12981 590 12982 590 12995 888 12982 888 12990 888 12989 10290 12991 10290 11642 10290 11642 10291 12991 10291 12983 10291 11642 590 12983 590 11640 590 11640 590 12983 590 12984 590 11640 10292 12984 10292 12404 10292 13086 590 12985 590 12629 590 12629 886 12985 886 11629 886 12629 590 11629 590 12630 590 12630 10293 11629 10293 11632 10293 12630 10294 11632 10294 12986 10294 12986 590 11633 590 12630 590 12630 885 11633 885 12987 885 12630 10295 12987 10295 12988 10295 12988 590 12987 590 11625 590 12988 590 11625 590 11626 590 13005 590 11637 590 13084 590 13084 590 11637 590 11636 590 12980 590 12995 590 12999 590 12999 590 12995 590 13007 590 12999 590 13007 590 11672 590 12994 590 12995 590 12989 590 12989 590 12995 590 12990 590 12989 10296 12990 10296 12991 10296 12992 590 12993 590 12994 590 12994 10297 12993 10297 11643 10297 12994 10298 11643 10298 12995 10298 12995 10299 11643 10299 12996 10299 12995 590 12996 590 13007 590 13003 10300 13087 10300 12997 10300 12997 590 13087 590 12949 590 12997 590 12949 590 11670 590 11670 590 12949 590 11582 590 11670 590 11582 590 12998 590 12998 590 11582 590 11581 590 12998 590 11581 590 12999 590 12999 10301 11581 10301 13000 10301 12999 590 13000 590 13080 590 13004 590 13001 590 13002 590 13002 590 13001 590 11662 590 13006 590 13002 590 11667 590 11667 913 13002 913 11662 913 11667 10302 11662 10302 13003 10302 13003 10303 11662 10303 13027 10303 13003 590 13027 590 13087 590 12624 590 11656 590 12625 590 12625 10304 11656 10304 11655 10304 12625 590 11655 590 13083 590 13083 590 11655 590 13004 590 13083 590 13004 590 13084 590 13084 590 13004 590 13002 590 13084 590 13002 590 13005 590 13005 590 13002 590 13006 590 13005 590 13006 590 13007 590 13007 10305 13006 10305 11671 10305 13007 10306 11671 10306 11672 10306 11646 590 11647 590 13015 590 11646 590 13015 590 13021 590 13008 10307 13009 10307 11661 10307 11661 908 13009 908 12621 908 11661 590 12621 590 13010 590 13010 590 12621 590 13119 590 13010 590 13119 590 11653 590 11653 590 13119 590 13011 590 11653 590 13011 590 13012 590 13012 590 13011 590 12514 590 13012 906 12514 906 13013 906 13013 590 12514 590 13014 590 13013 590 13014 590 11650 590 11650 590 13014 590 13015 590 11650 590 13015 590 11651 590 11651 10308 13015 10308 11647 10308 11665 590 11666 590 13016 590 13016 590 11666 590 13017 590 13016 590 13017 590 13026 590 13026 905 13017 905 13020 905 13018 590 13019 590 13015 590 13015 940 13019 940 13022 940 13020 590 13021 590 13026 590 13026 904 13021 904 13015 904 13026 10309 13015 10309 13023 10309 13023 590 13015 590 13022 590 13023 590 13024 590 13026 590 13026 10310 13024 10310 13025 10310 13026 590 13025 590 13027 590 13027 10311 13025 10311 13028 10311 13027 10312 13028 10312 13029 10312 13029 590 13030 590 13027 590 13027 918 13030 918 13031 918 13027 590 13031 590 13087 590 13087 917 13031 917 13032 917 13087 10313 13032 10313 13033 10313 12903 590 13039 590 13034 590 13034 590 13039 590 13040 590 13034 590 13040 590 12698 590 12698 590 13040 590 13041 590 12698 590 13041 590 12696 590 12696 724 13041 724 13035 724 12696 590 13035 590 13036 590 11219 590 12477 590 12845 590 12845 590 12477 590 13037 590 12845 590 13037 590 12905 590 12905 590 13037 590 13038 590 12905 590 13038 590 13039 590 13039 590 13038 590 12744 590 13039 590 12744 590 13040 590 13040 590 12744 590 13042 590 13040 590 13042 590 13041 590 13041 590 13042 590 12405 590 13041 10314 12405 10314 12899 10314 12848 590 11338 590 12478 590 12478 590 11338 590 12831 590 12478 590 12831 590 13043 590 13043 590 12831 590 12957 590 13043 590 12957 590 12479 590 12479 590 12957 590 11450 590 12777 590 12776 590 12778 590 12778 590 12776 590 12958 590 12778 590 12958 590 12483 590 12483 590 12958 590 12961 590 12483 590 12961 590 13044 590 13044 590 12961 590 13045 590 13044 590 13045 590 12486 590 11606 590 11607 590 12961 590 12961 590 11607 590 12956 590 12961 590 12956 590 13045 590 13045 590 12956 590 13046 590 13045 590 13046 590 12486 590 12486 590 13046 590 13047 590 12486 590 13047 590 11231 590 11231 590 13047 590 11673 590 11231 10315 11673 10315 11234 10315 11234 590 11673 590 13048 590 11234 10316 13048 10316 12490 10316 12490 590 13048 590 13049 590 12490 590 13049 590 11674 590 11255 590 11227 590 12784 590 12784 590 11227 590 12966 590 12784 590 12966 590 12795 590 12795 590 12966 590 13050 590 12795 590 13050 590 12796 590 12796 590 13050 590 12798 590 13065 590 13053 590 13066 590 13066 695 13053 695 13051 695 13066 694 13051 694 13052 694 12889 590 12890 590 13056 590 13056 590 12890 590 13053 590 13056 590 13053 590 13054 590 13054 590 13053 590 13065 590 13054 590 13065 590 13058 590 12875 590 11400 590 13061 590 13061 590 11400 590 13056 590 13061 590 13056 590 13055 590 13055 590 13056 590 13054 590 13055 590 13054 590 13057 590 13057 590 13054 590 13058 590 13057 590 13058 590 13059 590 12411 590 11195 590 13059 590 13059 590 11195 590 12403 590 13059 590 12403 590 13057 590 13057 590 12403 590 12642 590 13057 590 12642 590 13055 590 13055 590 12642 590 13060 590 13055 590 13060 590 13061 590 13061 590 13060 590 12640 590 13061 590 12640 590 13062 590 13062 590 12640 590 13063 590 12452 590 13059 590 12488 590 12488 590 13059 590 13058 590 12488 590 13058 590 12487 590 12487 590 13058 590 13065 590 12487 590 13065 590 13064 590 13064 590 13065 590 13066 590 13064 590 13066 590 12820 590 12820 590 13066 590 12936 590 12820 590 12936 590 12969 590 12969 590 12936 590 13075 590 12969 590 13075 590 13067 590 12885 590 13068 590 12884 590 12884 590 13068 590 12638 590 12884 590 12638 590 12897 590 12897 590 12638 590 13073 590 12897 590 13073 590 12933 590 12933 590 13073 590 13069 590 12933 590 13069 590 12935 590 12935 942 13069 942 13075 942 12935 10317 13075 10317 13070 10317 13070 590 13075 590 11382 590 13071 10318 13072 10318 12638 10318 12638 590 13072 590 12634 590 12638 590 12634 590 13073 590 13073 590 12634 590 13078 590 13073 590 13078 590 13069 590 13069 590 13078 590 13079 590 13069 590 13079 590 13075 590 13075 590 13079 590 13074 590 13075 590 13074 590 13067 590 13067 590 13074 590 13076 590 13067 590 13076 590 12945 590 12945 590 13076 590 13081 590 12632 590 13077 590 13078 590 13078 590 13077 590 12630 590 13078 590 12630 590 13079 590 13079 590 12630 590 12988 590 13079 590 12988 590 13074 590 13074 590 12988 590 12975 590 13074 590 12975 590 13076 590 13076 590 12975 590 13080 590 13076 590 13080 590 13081 590 13081 590 13080 590 13000 590 11592 590 11590 590 13082 590 13082 590 11590 590 13090 590 13082 590 13090 590 12534 590 12534 590 13090 590 13091 590 12534 590 13091 590 11556 590 11556 590 13091 590 11554 590 11503 590 12625 590 11501 590 11501 590 12625 590 13083 590 11501 590 13083 590 12627 590 12627 590 13083 590 13084 590 12627 590 13084 590 13085 590 13085 881 13084 881 11636 881 13085 590 11636 590 13086 590 13033 590 13018 590 13087 590 13087 590 13018 590 13015 590 13087 590 13015 590 13088 590 13088 590 13015 590 13014 590 13088 590 13014 590 13089 590 13089 590 13014 590 12505 590 13089 590 12505 590 13090 590 13090 590 12505 590 12506 590 13090 590 12506 590 13091 590 13091 590 12506 590 12508 590 13091 590 12508 590 11554 590 11554 590 12508 590 12538 590 11319 10319 13093 10319 13092 10319 13092 922 13093 922 13094 922 13124 590 13095 590 13096 590 13096 590 13095 590 13097 590 13096 590 13097 590 13098 590 13098 590 13097 590 13099 590 13098 590 13099 590 13100 590 13100 590 13099 590 12539 590 13100 590 12539 590 13101 590 13101 590 12539 590 12509 590 13101 590 12509 590 13102 590 13102 590 12509 590 13093 590 13102 590 13093 590 12481 590 12481 590 13093 590 11319 590 12481 590 11319 590 11320 590 13094 590 13093 590 13103 590 13103 590 13093 590 13108 590 13103 10320 13108 10320 13110 10320 13106 590 11314 590 13111 590 13111 927 11314 927 11312 927 11320 10321 13104 10321 12481 10321 12481 10322 13104 10322 13105 10322 12481 590 13105 590 13111 590 13111 10323 13105 10323 11316 10323 13111 921 11316 921 13106 921 11312 590 13107 590 13108 590 13108 10324 13107 10324 13109 10324 13108 926 13109 926 13110 926 11312 590 13108 590 13111 590 13111 590 13108 590 12402 590 13111 590 12402 590 13112 590 11310 10325 11308 10325 12514 10325 12514 590 11308 590 11306 590 12514 590 11306 590 13108 590 13108 934 11306 934 11303 934 13108 10326 11303 10326 11302 10326 13112 590 13113 590 13111 590 13111 10327 13113 10327 13114 10327 13111 10328 13114 10328 13011 10328 13011 10329 13114 10329 13115 10329 13011 590 13115 590 13116 590 13116 936 13117 936 13011 936 13011 590 13117 590 11300 590 13011 590 11300 590 12514 590 12514 590 11300 590 13118 590 12514 590 13118 590 11310 590 11508 590 11510 590 13119 590 13119 590 11510 590 13120 590 13119 590 13120 590 13011 590 13011 590 13120 590 12407 590 13011 10330 12407 10330 13111 10330 13111 590 12407 590 12616 590 13111 590 12616 590 12481 590 12481 590 12616 590 13121 590 12481 590 13121 590 13125 590 13122 590 12576 590 12872 590 12872 590 12576 590 12572 590 12872 590 12572 590 13123 590 13123 590 12572 590 12551 590 13123 590 12551 590 12913 590 12913 590 12551 590 13095 590 12913 590 13095 590 13121 590 13121 590 13095 590 13124 590 13121 590 13124 590 13125 590 13126 50 13128 50 13127 50 13127 50 13128 50 12215 50 13127 50 12215 50 12955 50 12955 50 12215 50 12214 50 13141 590 13129 590 13130 590 13130 10331 13129 10331 13131 10331 13130 10332 13131 10332 13178 10332 13145 10333 13147 10333 13133 10333 13133 590 13147 590 13132 590 13133 590 13132 590 13134 590 13134 590 13132 590 13159 590 13134 590 13159 590 13161 590 13174 590 13135 590 13137 590 13137 10334 13135 10334 13136 10334 13137 590 13136 590 13138 590 13166 10335 13167 10335 13139 10335 13139 10336 13167 10336 13140 10336 13139 590 13140 590 13141 590 13141 10337 13140 10337 13142 10337 13141 10338 13142 10338 13129 10338 13152 590 13154 590 13144 590 13144 10339 13154 10339 13143 10339 13144 590 13143 590 13145 590 13145 10340 13143 10340 13146 10340 13145 10341 13146 10341 13147 10341 13136 10342 13148 10342 13138 10342 13138 590 13148 590 13149 590 13138 10343 13149 10343 13151 10343 13151 10344 13149 10344 13150 10344 13151 10345 13150 10345 13152 10345 13152 10346 13150 10346 13153 10346 13152 10336 13153 10336 13154 10336 13192 10347 13155 10347 13157 10347 13157 10348 13155 10348 13156 10348 13157 10349 13156 10349 13158 10349 13159 10350 13160 10350 13161 10350 13161 590 13160 590 13163 590 13161 10351 13163 10351 13162 10351 13162 10352 13163 10352 13164 10352 13162 10353 13164 10353 13166 10353 13166 590 13164 590 13165 590 13166 10354 13165 10354 13167 10354 13156 590 13168 590 13158 590 13158 10355 13168 10355 13170 10355 13158 10356 13170 10356 13169 10356 13169 10357 13170 10357 13171 10357 13169 10358 13171 10358 13172 10358 13172 10359 13171 10359 13173 10359 13172 10360 13173 10360 13174 10360 13174 10361 13173 10361 13175 10361 13174 10362 13175 10362 13135 10362 13131 590 13176 590 13178 590 13178 10334 13176 10334 13177 10334 13178 590 13177 590 13179 590 13179 10363 13177 10363 13180 10363 13179 10364 13180 10364 13181 10364 13181 590 13180 590 13182 590 13181 10365 13182 10365 13185 10365 13182 590 13183 590 13185 590 13185 590 13183 590 13184 590 13185 590 13184 590 13186 590 13186 10366 13184 10366 13187 10366 13186 10367 13187 10367 13189 10367 13187 590 13188 590 13189 590 13189 10368 13188 10368 13190 10368 13189 590 13190 590 13191 590 13191 590 13190 590 13193 590 13191 590 13193 590 13192 590 13192 590 13193 590 13194 590 13192 10369 13194 10369 13155 10369 13231 10370 13240 10370 13195 10370 13195 10371 13240 10371 13196 10371 13195 10372 13196 10372 13197 10372 13197 10373 13196 10373 13198 10373 13197 10374 13198 10374 13199 10374 13199 10375 13198 10375 13233 10375 13199 10376 13233 10376 13200 10376 13200 10377 13233 10377 13234 10377 13200 10377 13234 10377 13201 10377 13201 10378 13234 10378 13239 10378 13201 10379 13239 10379 13202 10379 13202 10380 13239 10380 13245 10380 13202 10381 13245 10381 13203 10381 13203 10382 13245 10382 13246 10382 13203 10383 13246 10383 13204 10383 13204 10384 13246 10384 13242 10384 13204 10385 13242 10385 13205 10385 13205 10386 13242 10386 13206 10386 13205 10387 13206 10387 13207 10387 13207 10388 13206 10388 13253 10388 13207 10388 13253 10388 13208 10388 13208 10389 13253 10389 13209 10389 13208 10390 13209 10390 13210 10390 13210 10391 13209 10391 13255 10391 13210 10392 13255 10392 13211 10392 13211 10393 13255 10393 13212 10393 13211 10393 13212 10393 13213 10393 13213 10394 13212 10394 13259 10394 13213 10395 13259 10395 13214 10395 13214 10396 13259 10396 13215 10396 13214 10397 13215 10397 13216 10397 13216 10398 13215 10398 13250 10398 13216 10399 13250 10399 13218 10399 13218 10400 13250 10400 13217 10400 13218 10401 13217 10401 13219 10401 13219 10402 13217 10402 13221 10402 13219 10403 13221 10403 13220 10403 13220 10404 13221 10404 13222 10404 13220 10404 13222 10404 13223 10404 13223 10405 13222 10405 13224 10405 13223 10406 13224 10406 13225 10406 13225 10407 13224 10407 13226 10407 13225 10408 13226 10408 13227 10408 13227 10409 13226 10409 13228 10409 13227 10410 13228 10410 13229 10410 13229 10411 13228 10411 13249 10411 13229 10412 13249 10412 13230 10412 13230 10413 13249 10413 13232 10413 13230 10414 13232 10414 13231 10414 13231 10415 13232 10415 13240 10415 13198 590 13334 590 13233 590 13233 10416 13334 10416 13237 10416 13233 590 13237 590 13234 590 13240 590 13241 590 13196 590 13196 10417 13241 10417 13235 10417 13196 590 13235 590 13198 590 13198 10418 13235 10418 13236 10418 13198 10419 13236 10419 13334 10419 13237 590 13333 590 13234 590 13234 590 13333 590 13332 590 13234 590 13332 590 13239 590 13239 10420 13332 10420 13238 10420 13239 590 13238 590 13245 590 13232 590 13340 590 13240 590 13240 590 13340 590 13339 590 13240 10421 13339 10421 13241 10421 13242 10422 13243 10422 13206 10422 13206 10423 13243 10423 13325 10423 13206 590 13325 590 13253 590 13224 10424 13244 10424 13226 10424 13226 590 13244 590 13248 590 13226 10425 13248 10425 13228 10425 13238 10426 13330 10426 13245 10426 13245 10427 13330 10427 13328 10427 13245 10428 13328 10428 13246 10428 13246 10429 13328 10429 13327 10429 13246 10430 13327 10430 13242 10430 13242 590 13327 590 13247 590 13242 590 13247 590 13243 590 13248 10431 13345 10431 13228 10431 13228 590 13345 590 13344 590 13228 590 13344 590 13249 590 13249 590 13344 590 13342 590 13249 10432 13342 10432 13232 10432 13232 590 13342 590 13341 590 13232 10433 13341 10433 13340 10433 13250 10434 13251 10434 13217 10434 13217 10435 13251 10435 13252 10435 13217 10436 13252 10436 13221 10436 13255 590 13358 590 13212 590 13212 10437 13358 10437 13356 10437 13212 590 13356 590 13259 590 13325 590 13324 590 13253 590 13253 10438 13324 10438 13323 10438 13253 590 13323 590 13209 590 13209 590 13323 590 13254 590 13209 590 13254 590 13255 590 13255 10439 13254 10439 13321 10439 13255 10440 13321 10440 13358 10440 13252 590 13349 590 13221 590 13221 10441 13349 10441 13256 10441 13221 10442 13256 10442 13222 10442 13222 590 13256 590 13257 590 13222 590 13257 590 13224 590 13224 10443 13257 10443 13258 10443 13224 590 13258 590 13244 590 13356 590 13354 590 13259 590 13259 10444 13354 10444 13260 10444 13259 10445 13260 10445 13215 10445 13215 10446 13260 10446 13353 10446 13215 590 13353 590 13250 590 13250 10447 13353 10447 13352 10447 13250 10448 13352 10448 13251 10448 13320 10449 13319 10449 13357 10449 13357 10450 13319 10450 13261 10450 13357 10451 13261 10451 13355 10451 13355 10452 13261 10452 13262 10452 13355 10453 13262 10453 13263 10453 13263 10454 13262 10454 13264 10454 13263 10455 13264 10455 13265 10455 13265 10456 13264 10456 13266 10456 13265 10457 13266 10457 13351 10457 13351 10458 13266 10458 13268 10458 13351 10459 13268 10459 13267 10459 13267 10460 13268 10460 13269 10460 13267 10461 13269 10461 13350 10461 13350 10462 13269 10462 13270 10462 13350 10463 13270 10463 13271 10463 13271 10464 13270 10464 13272 10464 13271 10464 13272 10464 13273 10464 13273 10465 13272 10465 13274 10465 13273 10465 13274 10465 13348 10465 13348 10466 13274 10466 13276 10466 13348 10467 13276 10467 13275 10467 13275 10468 13276 10468 13277 10468 13275 10469 13277 10469 13347 10469 13347 10470 13277 10470 13278 10470 13347 10471 13278 10471 13279 10471 13279 10472 13278 10472 13280 10472 13279 10472 13280 10472 13281 10472 13281 10473 13280 10473 13282 10473 13281 10474 13282 10474 13346 10474 13346 10475 13282 10475 13283 10475 13346 10476 13283 10476 13284 10476 13284 10477 13283 10477 13285 10477 13284 10478 13285 10478 13343 10478 13343 10479 13285 10479 13286 10479 13343 10480 13286 10480 13287 10480 13287 10481 13286 10481 13288 10481 13287 10482 13288 10482 13290 10482 13290 10483 13288 10483 13289 10483 13290 10483 13289 10483 13338 10483 13338 10484 13289 10484 13291 10484 13338 10485 13291 10485 13337 10485 13337 10486 13291 10486 13292 10486 13337 10487 13292 10487 13336 10487 13336 10488 13292 10488 13293 10488 13336 10489 13293 10489 13335 10489 13335 10490 13293 10490 13294 10490 13335 10491 13294 10491 13295 10491 13295 10492 13294 10492 13297 10492 13295 10493 13297 10493 13296 10493 13296 10494 13297 10494 13299 10494 13296 10495 13299 10495 13298 10495 13298 10496 13299 10496 13300 10496 13298 10497 13300 10497 13331 10497 13331 10498 13300 10498 13301 10498 13331 10499 13301 10499 13302 10499 13302 10500 13301 10500 13303 10500 13302 10501 13303 10501 13329 10501 13329 10502 13303 10502 13304 10502 13329 10503 13304 10503 13305 10503 13305 10504 13304 10504 13306 10504 13305 10505 13306 10505 13307 10505 13307 10506 13306 10506 13308 10506 13307 10507 13308 10507 13326 10507 13326 10508 13308 10508 13309 10508 13326 10509 13309 10509 13310 10509 13310 10510 13309 10510 13311 10510 13310 10511 13311 10511 13312 10511 13312 10512 13311 10512 13313 10512 13312 10513 13313 10513 13322 10513 13322 10514 13313 10514 13314 10514 13322 10515 13314 10515 13315 10515 13315 10516 13314 10516 13316 10516 13315 10517 13316 10517 13318 10517 13318 10518 13316 10518 13317 10518 13318 10518 13317 10518 13320 10518 13320 10519 13317 10519 13319 10519 13320 10520 13321 10520 13318 10520 13318 10521 13321 10521 13254 10521 13318 10522 13254 10522 13315 10522 13315 10523 13254 10523 13323 10523 13315 10524 13323 10524 13322 10524 13322 10525 13323 10525 13324 10525 13322 10526 13324 10526 13312 10526 13312 10527 13324 10527 13325 10527 13312 10528 13325 10528 13310 10528 13310 10529 13325 10529 13243 10529 13310 10530 13243 10530 13326 10530 13326 10531 13243 10531 13247 10531 13326 10532 13247 10532 13307 10532 13307 10533 13247 10533 13327 10533 13307 10534 13327 10534 13305 10534 13305 10535 13327 10535 13328 10535 13305 10536 13328 10536 13329 10536 13329 10537 13328 10537 13330 10537 13329 10538 13330 10538 13302 10538 13302 10539 13330 10539 13238 10539 13302 10540 13238 10540 13331 10540 13331 10541 13238 10541 13332 10541 13331 10542 13332 10542 13298 10542 13298 10543 13332 10543 13333 10543 13298 10544 13333 10544 13296 10544 13296 10545 13333 10545 13237 10545 13296 10546 13237 10546 13295 10546 13295 10547 13237 10547 13334 10547 13295 10548 13334 10548 13335 10548 13335 10549 13334 10549 13236 10549 13335 10550 13236 10550 13336 10550 13336 10551 13236 10551 13235 10551 13336 10552 13235 10552 13337 10552 13337 10553 13235 10553 13241 10553 13337 10554 13241 10554 13338 10554 13338 10555 13241 10555 13339 10555 13338 10556 13339 10556 13290 10556 13290 10557 13339 10557 13340 10557 13290 10558 13340 10558 13287 10558 13287 10559 13340 10559 13341 10559 13287 10560 13341 10560 13343 10560 13343 10561 13341 10561 13342 10561 13343 10562 13342 10562 13284 10562 13284 10563 13342 10563 13344 10563 13284 10564 13344 10564 13346 10564 13346 10565 13344 10565 13345 10565 13346 10566 13345 10566 13281 10566 13281 10567 13345 10567 13248 10567 13281 10568 13248 10568 13279 10568 13279 10569 13248 10569 13244 10569 13279 10570 13244 10570 13347 10570 13347 10571 13244 10571 13258 10571 13347 10572 13258 10572 13275 10572 13275 10573 13258 10573 13257 10573 13275 10574 13257 10574 13348 10574 13348 10575 13257 10575 13256 10575 13348 10576 13256 10576 13273 10576 13273 10577 13256 10577 13349 10577 13273 10578 13349 10578 13271 10578 13271 10579 13349 10579 13252 10579 13271 10580 13252 10580 13350 10580 13350 10581 13252 10581 13251 10581 13350 10582 13251 10582 13267 10582 13267 10583 13251 10583 13352 10583 13267 10584 13352 10584 13351 10584 13351 10585 13352 10585 13353 10585 13351 10586 13353 10586 13265 10586 13265 10587 13353 10587 13260 10587 13265 10588 13260 10588 13263 10588 13263 10589 13260 10589 13354 10589 13263 10590 13354 10590 13355 10590 13355 10591 13354 10591 13356 10591 13355 10592 13356 10592 13357 10592 13357 10593 13356 10593 13358 10593 13357 10594 13358 10594 13320 10594 13320 10595 13358 10595 13321 10595 13359 10596 13404 10596 13361 10596 13361 10597 13404 10597 13360 10597 13361 10597 13360 10597 13362 10597 13362 10598 13360 10598 13417 10598 13362 10598 13417 10598 13363 10598 13363 10599 13417 10599 13412 10599 13363 10600 13412 10600 13364 10600 13364 10601 13412 10601 13413 10601 13364 10602 13413 10602 13365 10602 13365 10603 13413 10603 13410 10603 13365 10604 13410 10604 13366 10604 13366 10605 13410 10605 13411 10605 13366 10605 13411 10605 13367 10605 13367 10606 13411 10606 13368 10606 13367 10607 13368 10607 13369 10607 13369 10608 13368 10608 13393 10608 13369 10609 13393 10609 13370 10609 13370 10610 13393 10610 13394 10610 13370 10611 13394 10611 13371 10611 13371 10612 13394 10612 13396 10612 13371 10613 13396 10613 13372 10613 13372 10614 13396 10614 13397 10614 13372 10614 13397 10614 13373 10614 13373 10615 13397 10615 13374 10615 13373 10616 13374 10616 13375 10616 13375 10617 13374 10617 13377 10617 13375 10617 13377 10617 13376 10617 13376 10618 13377 10618 13378 10618 13376 10619 13378 10619 13379 10619 13379 10620 13378 10620 13380 10620 13379 10621 13380 10621 13381 10621 13381 10622 13380 10622 13418 10622 13381 10622 13418 10622 13382 10622 13382 10623 13418 10623 13383 10623 13382 10623 13383 10623 13384 10623 13384 10624 13383 10624 13406 10624 13384 10625 13406 10625 13385 10625 13385 10626 13406 10626 13400 10626 13385 10627 13400 10627 13386 10627 13386 10628 13400 10628 13398 10628 13386 10629 13398 10629 13387 10629 13387 10630 13398 10630 13388 10630 13387 10631 13388 10631 13389 10631 13389 10632 13388 10632 13399 10632 13389 10632 13399 10632 13390 10632 13390 10633 13399 10633 13391 10633 13390 10633 13391 10633 13392 10633 13392 10634 13391 10634 13403 10634 13392 10635 13403 10635 13359 10635 13359 10636 13403 10636 13404 10636 13399 590 13509 590 13391 590 13391 10637 13509 10637 13508 10637 13391 10638 13508 10638 13403 10638 13393 10639 13489 10639 13394 10639 13394 10640 13489 10640 13395 10640 13394 590 13395 590 13396 590 13395 590 13488 590 13396 590 13396 10641 13488 10641 13486 10641 13396 590 13486 590 13397 590 13397 10642 13486 10642 13485 10642 13397 10643 13485 10643 13374 10643 13398 10644 13512 10644 13388 10644 13388 10645 13512 10645 13511 10645 13388 590 13511 590 13399 590 13399 10646 13511 10646 13510 10646 13399 10647 13510 10647 13509 10647 13406 10648 13407 10648 13400 10648 13400 590 13407 590 13401 590 13400 590 13401 590 13398 590 13398 590 13401 590 13402 590 13398 10649 13402 10649 13512 10649 13508 590 13507 590 13403 590 13403 10650 13507 10650 13506 10650 13403 10651 13506 10651 13404 10651 13418 590 13419 590 13383 590 13383 10652 13419 10652 13513 10652 13383 10653 13513 10653 13406 10653 13406 590 13513 590 13405 590 13406 590 13405 590 13407 590 13411 10654 13408 10654 13368 10654 13368 10655 13408 10655 13491 10655 13368 590 13491 590 13393 590 13393 10656 13491 10656 13490 10656 13393 10657 13490 10657 13489 10657 13413 10658 13409 10658 13410 10658 13410 590 13409 590 13496 590 13410 10659 13496 10659 13411 10659 13411 10660 13496 10660 13494 10660 13411 590 13494 590 13408 590 13417 590 13500 590 13412 590 13412 10661 13500 10661 13414 10661 13412 590 13414 590 13413 590 13413 10662 13414 10662 13498 10662 13413 590 13498 590 13409 590 13506 10663 13505 10663 13404 10663 13404 10664 13505 10664 13503 10664 13404 590 13503 590 13360 590 13360 10665 13503 10665 13415 10665 13360 590 13415 590 13417 590 13417 10666 13415 10666 13416 10666 13417 10667 13416 10667 13500 10667 13378 590 13518 590 13380 590 13380 590 13518 590 13516 590 13380 590 13516 590 13418 590 13418 10668 13516 10668 13515 10668 13418 10669 13515 10669 13419 10669 13485 590 13522 590 13374 590 13374 10670 13522 10670 13420 10670 13374 590 13420 590 13377 590 13377 10671 13420 10671 13521 10671 13377 590 13521 590 13378 590 13378 10672 13521 10672 13519 10672 13378 590 13519 590 13518 590 13482 10673 13484 10673 13422 10673 13422 10674 13484 10674 13421 10674 13422 10675 13421 10675 13520 10675 13520 10676 13421 10676 13423 10676 13520 10676 13423 10676 13424 10676 13424 10677 13423 10677 13426 10677 13424 10678 13426 10678 13425 10678 13425 10679 13426 10679 13427 10679 13425 10680 13427 10680 13517 10680 13517 10681 13427 10681 13428 10681 13517 10682 13428 10682 13429 10682 13429 10683 13428 10683 13430 10683 13429 10684 13430 10684 13514 10684 13514 10685 13430 10685 13431 10685 13514 10686 13431 10686 13432 10686 13432 10687 13431 10687 13433 10687 13432 10687 13433 10687 13434 10687 13434 10688 13433 10688 13435 10688 13434 10689 13435 10689 13436 10689 13436 10690 13435 10690 13437 10690 13436 10690 13437 10690 13439 10690 13439 10691 13437 10691 13438 10691 13439 10691 13438 10691 13440 10691 13440 10692 13438 10692 13442 10692 13440 10693 13442 10693 13441 10693 13441 10694 13442 10694 13444 10694 13441 10695 13444 10695 13443 10695 13443 10696 13444 10696 13446 10696 13443 10697 13446 10697 13445 10697 13445 10698 13446 10698 13448 10698 13445 10699 13448 10699 13447 10699 13447 10700 13448 10700 13449 10700 13447 10701 13449 10701 13450 10701 13450 10702 13449 10702 13451 10702 13450 10703 13451 10703 13452 10703 13452 10704 13451 10704 13453 10704 13452 10705 13453 10705 13455 10705 13455 10706 13453 10706 13454 10706 13455 10707 13454 10707 13504 10707 13504 10708 13454 10708 13456 10708 13504 10709 13456 10709 13457 10709 13457 10710 13456 10710 13458 10710 13457 10711 13458 10711 13502 10711 13502 10712 13458 10712 13459 10712 13502 10713 13459 10713 13501 10713 13501 10714 13459 10714 13460 10714 13501 10714 13460 10714 13499 10714 13499 10715 13460 10715 13461 10715 13499 10716 13461 10716 13462 10716 13462 10717 13461 10717 13463 10717 13462 10718 13463 10718 13465 10718 13465 10719 13463 10719 13464 10719 13465 10720 13464 10720 13497 10720 13497 10721 13464 10721 13466 10721 13497 10722 13466 10722 13495 10722 13495 10723 13466 10723 13467 10723 13495 10724 13467 10724 13493 10724 13493 10725 13467 10725 13468 10725 13493 10726 13468 10726 13492 10726 13492 10727 13468 10727 13470 10727 13492 10728 13470 10728 13469 10728 13469 10729 13470 10729 13471 10729 13469 10730 13471 10730 13473 10730 13473 10731 13471 10731 13472 10731 13473 10732 13472 10732 13474 10732 13474 10733 13472 10733 13476 10733 13474 10734 13476 10734 13475 10734 13475 10735 13476 10735 13477 10735 13475 10736 13477 10736 13487 10736 13487 10737 13477 10737 13478 10737 13487 10737 13478 10737 13480 10737 13480 10738 13478 10738 13479 10738 13480 10739 13479 10739 13481 10739 13481 10740 13479 10740 13483 10740 13481 10741 13483 10741 13482 10741 13482 10742 13483 10742 13484 10742 13482 10743 13522 10743 13481 10743 13481 10744 13522 10744 13485 10744 13481 10745 13485 10745 13480 10745 13480 10746 13485 10746 13486 10746 13480 10747 13486 10747 13487 10747 13487 10748 13486 10748 13488 10748 13487 10749 13488 10749 13475 10749 13475 10750 13488 10750 13395 10750 13475 10751 13395 10751 13474 10751 13474 10752 13395 10752 13489 10752 13474 10753 13489 10753 13473 10753 13473 10754 13489 10754 13490 10754 13473 10755 13490 10755 13469 10755 13469 10756 13490 10756 13491 10756 13469 10757 13491 10757 13492 10757 13492 10758 13491 10758 13408 10758 13492 10759 13408 10759 13493 10759 13493 10760 13408 10760 13494 10760 13493 10761 13494 10761 13495 10761 13495 10762 13494 10762 13496 10762 13495 10763 13496 10763 13497 10763 13497 10764 13496 10764 13409 10764 13497 10765 13409 10765 13465 10765 13465 10766 13409 10766 13498 10766 13465 10767 13498 10767 13462 10767 13462 10768 13498 10768 13414 10768 13462 10769 13414 10769 13499 10769 13499 10770 13414 10770 13500 10770 13499 10771 13500 10771 13501 10771 13501 10772 13500 10772 13416 10772 13501 10773 13416 10773 13502 10773 13502 10774 13416 10774 13415 10774 13502 10775 13415 10775 13457 10775 13457 10776 13415 10776 13503 10776 13457 10777 13503 10777 13504 10777 13504 10778 13503 10778 13505 10778 13504 10779 13505 10779 13455 10779 13455 10780 13505 10780 13506 10780 13455 10781 13506 10781 13452 10781 13452 10782 13506 10782 13507 10782 13452 10783 13507 10783 13450 10783 13450 10784 13507 10784 13508 10784 13450 10785 13508 10785 13447 10785 13447 10786 13508 10786 13509 10786 13447 10787 13509 10787 13445 10787 13445 10788 13509 10788 13510 10788 13445 10789 13510 10789 13443 10789 13443 10790 13510 10790 13511 10790 13443 10791 13511 10791 13441 10791 13441 10792 13511 10792 13512 10792 13441 10793 13512 10793 13440 10793 13440 10794 13512 10794 13402 10794 13440 10795 13402 10795 13439 10795 13439 10796 13402 10796 13401 10796 13439 10797 13401 10797 13436 10797 13436 10798 13401 10798 13407 10798 13436 10799 13407 10799 13434 10799 13434 10800 13407 10800 13405 10800 13434 10801 13405 10801 13432 10801 13432 10802 13405 10802 13513 10802 13432 10803 13513 10803 13514 10803 13514 10804 13513 10804 13419 10804 13514 10805 13419 10805 13429 10805 13429 10806 13419 10806 13515 10806 13429 10807 13515 10807 13517 10807 13517 10808 13515 10808 13516 10808 13517 10809 13516 10809 13425 10809 13425 10810 13516 10810 13518 10810 13425 10811 13518 10811 13424 10811 13424 10812 13518 10812 13519 10812 13424 10813 13519 10813 13520 10813 13520 10814 13519 10814 13521 10814 13520 10815 13521 10815 13422 10815 13422 10816 13521 10816 13420 10816 13422 10817 13420 10817 13482 10817 13482 10818 13420 10818 13522 10818 13523 10819 13524 10819 13525 10819 13525 590 13524 590 13648 590 13525 10820 13648 10820 13541 10820 13534 10821 13536 10821 13527 10821 13526 10822 13652 10822 13527 10822 13527 10823 13652 10823 13528 10823 13527 590 13528 590 13534 590 13529 590 13655 590 13530 590 13530 10824 13655 10824 13654 10824 13530 590 13654 590 13526 590 13526 10825 13654 10825 13531 10825 13526 590 13531 590 13652 590 13547 10826 13658 10826 13532 10826 13532 10827 13658 10827 13533 10827 13532 590 13533 590 13529 590 13529 10828 13533 10828 13656 10828 13529 10829 13656 10829 13655 10829 13534 590 13535 590 13536 590 13536 590 13535 590 13651 590 13536 590 13651 590 13523 590 13523 590 13651 590 13537 590 13523 10830 13537 10830 13524 10830 13538 10831 13637 10831 13539 10831 13539 590 13637 590 13635 590 13539 590 13635 590 13540 590 13648 590 13646 590 13541 590 13541 10832 13646 10832 13542 10832 13541 590 13542 590 13543 590 13543 10833 13542 10833 13645 10833 13543 590 13645 590 13544 590 13561 590 13562 590 13545 590 13545 590 13562 590 13546 590 13545 590 13546 590 13547 590 13547 10834 13546 10834 13660 10834 13547 10835 13660 10835 13658 10835 13635 10836 13634 10836 13540 10836 13540 590 13634 590 13548 590 13540 10837 13548 10837 13549 10837 13549 590 13548 590 13665 590 13549 10838 13665 10838 13563 10838 13550 10839 13639 10839 13551 10839 13551 10840 13639 10840 13552 10840 13551 590 13552 590 13538 590 13538 10841 13552 10841 13553 10841 13538 590 13553 590 13637 590 13554 590 13555 590 13550 590 13550 10842 13555 10842 13641 10842 13550 10843 13641 10843 13639 10843 13645 590 13556 590 13544 590 13544 10844 13556 10844 13557 10844 13544 10845 13557 10845 13558 10845 13558 10835 13557 10835 13559 10835 13558 590 13559 590 13554 590 13554 10846 13559 10846 13643 10846 13554 10847 13643 10847 13555 10847 13566 10848 13560 10848 13561 10848 13561 10843 13560 10843 13662 10843 13561 10849 13662 10849 13562 10849 13665 10850 13664 10850 13563 10850 13563 590 13664 590 13564 590 13563 10831 13564 10831 13565 10831 13565 590 13564 590 13567 590 13565 590 13567 590 13566 590 13566 590 13567 590 13568 590 13566 10851 13568 10851 13560 10851 13650 10852 13569 10852 13570 10852 13570 10853 13569 10853 13631 10853 13570 10854 13571 10854 13650 10854 13650 10855 13571 10855 13572 10855 13650 10856 13572 10856 13649 10856 13649 10857 13572 10857 13573 10857 13649 10858 13573 10858 13574 10858 13574 10859 13573 10859 13575 10859 13574 10860 13575 10860 13576 10860 13576 10861 13575 10861 13577 10861 13576 10862 13577 10862 13647 10862 13647 10863 13577 10863 13579 10863 13647 10864 13579 10864 13578 10864 13578 10865 13579 10865 13580 10865 13578 10866 13580 10866 13582 10866 13582 10867 13580 10867 13581 10867 13582 10868 13581 10868 13583 10868 13583 10869 13581 10869 13584 10869 13583 10870 13584 10870 13644 10870 13644 10871 13584 10871 13586 10871 13644 10872 13586 10872 13585 10872 13585 10873 13586 10873 13587 10873 13585 10873 13587 10873 13642 10873 13642 10874 13587 10874 13588 10874 13642 10874 13588 10874 13589 10874 13589 10875 13588 10875 13590 10875 13589 10875 13590 10875 13640 10875 13640 10876 13590 10876 13591 10876 13640 10876 13591 10876 13592 10876 13592 10877 13591 10877 13593 10877 13592 10878 13593 10878 13638 10878 13638 10879 13593 10879 13595 10879 13638 10879 13595 10879 13594 10879 13594 10880 13595 10880 13596 10880 13594 10881 13596 10881 13636 10881 13636 10882 13596 10882 13597 10882 13636 10883 13597 10883 13633 10883 13633 10884 13597 10884 13598 10884 13633 10885 13598 10885 13667 10885 13667 10886 13598 10886 13599 10886 13667 10887 13599 10887 13666 10887 13666 10888 13599 10888 13600 10888 13666 10889 13600 10889 13663 10889 13663 10890 13600 10890 13601 10890 13663 10891 13601 10891 13602 10891 13602 10892 13601 10892 13604 10892 13602 10893 13604 10893 13603 10893 13603 10894 13604 10894 13605 10894 13603 10895 13605 10895 13607 10895 13607 10896 13605 10896 13606 10896 13607 10896 13606 10896 13608 10896 13608 10897 13606 10897 13609 10897 13608 10898 13609 10898 13610 10898 13610 10899 13609 10899 13611 10899 13610 10899 13611 10899 13661 10899 13661 10900 13611 10900 13612 10900 13661 10900 13612 10900 13613 10900 13613 10901 13612 10901 13615 10901 13613 10901 13615 10901 13614 10901 13614 10902 13615 10902 13616 10902 13614 10903 13616 10903 13659 10903 13659 10904 13616 10904 13617 10904 13659 10905 13617 10905 13657 10905 13657 10906 13617 10906 13618 10906 13657 10907 13618 10907 13620 10907 13620 10908 13618 10908 13619 10908 13620 10909 13619 10909 13621 10909 13621 10910 13619 10910 13622 10910 13621 10911 13622 10911 13623 10911 13623 10912 13622 10912 13624 10912 13623 10913 13624 10913 13653 10913 13653 10914 13624 10914 13625 10914 13653 10914 13625 10914 13626 10914 13626 10915 13625 10915 13627 10915 13626 10916 13627 10916 13628 10916 13628 10917 13627 10917 13630 10917 13628 10918 13630 10918 13629 10918 13629 10919 13630 10919 13631 10919 13629 10920 13631 10920 13632 10920 13632 10921 13631 10921 13569 10921 13667 10922 13634 10922 13633 10922 13633 10923 13634 10923 13635 10923 13633 10924 13635 10924 13636 10924 13636 10925 13635 10925 13637 10925 13636 10926 13637 10926 13594 10926 13594 10927 13637 10927 13553 10927 13594 10928 13553 10928 13638 10928 13638 10929 13553 10929 13552 10929 13638 10930 13552 10930 13592 10930 13592 10931 13552 10931 13639 10931 13592 10932 13639 10932 13640 10932 13640 10933 13639 10933 13641 10933 13640 10934 13641 10934 13589 10934 13589 10935 13641 10935 13555 10935 13589 10936 13555 10936 13642 10936 13642 10937 13555 10937 13643 10937 13642 10938 13643 10938 13585 10938 13585 10939 13643 10939 13559 10939 13585 10940 13559 10940 13644 10940 13644 10941 13559 10941 13557 10941 13644 10942 13557 10942 13583 10942 13583 10943 13557 10943 13556 10943 13583 10944 13556 10944 13582 10944 13582 10945 13556 10945 13645 10945 13582 10946 13645 10946 13578 10946 13578 10947 13645 10947 13542 10947 13578 10948 13542 10948 13647 10948 13647 10949 13542 10949 13646 10949 13647 10950 13646 10950 13576 10950 13576 10951 13646 10951 13648 10951 13576 10952 13648 10952 13574 10952 13574 10953 13648 10953 13524 10953 13574 10954 13524 10954 13649 10954 13649 10955 13524 10955 13537 10955 13649 10956 13537 10956 13650 10956 13650 10957 13537 10957 13651 10957 13650 10958 13651 10958 13569 10958 13569 10959 13651 10959 13535 10959 13569 10960 13535 10960 13632 10960 13632 10961 13535 10961 13534 10961 13632 10962 13534 10962 13629 10962 13629 10963 13534 10963 13528 10963 13629 10964 13528 10964 13628 10964 13628 10965 13528 10965 13652 10965 13628 10966 13652 10966 13626 10966 13626 10967 13652 10967 13531 10967 13626 10968 13531 10968 13653 10968 13653 10969 13531 10969 13654 10969 13653 10970 13654 10970 13623 10970 13623 10971 13654 10971 13655 10971 13623 10972 13655 10972 13621 10972 13621 10973 13655 10973 13656 10973 13621 10974 13656 10974 13620 10974 13620 10975 13656 10975 13533 10975 13620 10976 13533 10976 13657 10976 13657 10977 13533 10977 13658 10977 13657 10978 13658 10978 13659 10978 13659 10979 13658 10979 13660 10979 13659 10980 13660 10980 13614 10980 13614 10981 13660 10981 13546 10981 13614 10982 13546 10982 13613 10982 13613 10983 13546 10983 13562 10983 13613 10984 13562 10984 13661 10984 13661 10985 13562 10985 13662 10985 13661 10986 13662 10986 13610 10986 13610 10987 13662 10987 13560 10987 13610 10988 13560 10988 13608 10988 13608 10989 13560 10989 13568 10989 13608 10990 13568 10990 13607 10990 13607 10991 13568 10991 13567 10991 13607 10992 13567 10992 13603 10992 13603 10993 13567 10993 13564 10993 13603 10994 13564 10994 13602 10994 13602 10995 13564 10995 13664 10995 13602 10996 13664 10996 13663 10996 13663 10997 13664 10997 13665 10997 13663 10998 13665 10998 13666 10998 13666 10999 13665 10999 13548 10999 13666 11000 13548 11000 13667 11000 13667 11001 13548 11001 13634 11001 13698 11002 13699 11002 13668 11002 13668 11003 13699 11003 13727 11003 13668 11004 13727 11004 13669 11004 13669 11005 13727 11005 13671 11005 13669 11006 13671 11006 13670 11006 13670 11007 13671 11007 13724 11007 13670 11008 13724 11008 13672 11008 13672 11009 13724 11009 13721 11009 13672 11009 13721 11009 13673 11009 13673 11010 13721 11010 13722 11010 13673 11011 13722 11011 13674 11011 13674 11012 13722 11012 13714 11012 13674 11013 13714 11013 13675 11013 13675 11014 13714 11014 13677 11014 13675 11015 13677 11015 13676 11015 13676 11016 13677 11016 13679 11016 13676 11017 13679 11017 13678 11017 13678 11018 13679 11018 13680 11018 13678 11019 13680 11019 13681 11019 13681 11020 13680 11020 13704 11020 13681 11020 13704 11020 13682 11020 13682 11021 13704 11021 13700 11021 13682 11022 13700 11022 13683 11022 13683 11023 13700 11023 13710 11023 13683 11024 13710 11024 13684 11024 13684 11025 13710 11025 13711 11025 13684 11025 13711 11025 13685 11025 13685 11026 13711 11026 13712 11026 13685 11027 13712 11027 13686 11027 13686 11028 13712 11028 13706 11028 13686 11029 13706 11029 13687 11029 13687 11030 13706 11030 13708 11030 13687 11031 13708 11031 13689 11031 13689 11032 13708 11032 13688 11032 13689 11033 13688 11033 13690 11033 13690 11034 13688 11034 13717 11034 13690 11035 13717 11035 13691 11035 13691 11036 13717 11036 13719 11036 13691 11036 13719 11036 13692 11036 13692 11037 13719 11037 13720 11037 13692 11038 13720 11038 13693 11038 13693 11039 13720 11039 13716 11039 13693 11040 13716 11040 13694 11040 13694 11041 13716 11041 13695 11041 13694 11042 13695 11042 13696 11042 13696 11043 13695 11043 13725 11043 13696 11044 13725 11044 13697 11044 13697 11045 13725 11045 13728 11045 13697 11046 13728 11046 13698 11046 13698 11047 13728 11047 13699 11047 13704 590 13787 590 13700 590 13700 590 13787 590 13785 590 13700 590 13785 590 13710 590 13708 11048 13701 11048 13688 11048 13688 11049 13701 11049 13821 11049 13688 11050 13821 11050 13717 11050 13679 11051 13702 11051 13680 11051 13680 11052 13702 11052 13703 11052 13680 590 13703 590 13704 590 13704 590 13703 590 13788 590 13704 11053 13788 11053 13787 11053 13712 11054 13705 11054 13706 11054 13706 11055 13705 11055 13707 11055 13706 590 13707 590 13708 590 13708 11056 13707 11056 13824 11056 13708 11057 13824 11057 13701 11057 13785 590 13831 590 13710 590 13710 11058 13831 11058 13709 11058 13710 590 13709 590 13711 590 13711 11059 13709 11059 13829 11059 13711 590 13829 590 13712 590 13712 11060 13829 11060 13713 11060 13712 11061 13713 11061 13705 11061 13714 11062 13792 11062 13677 11062 13677 11063 13792 11063 13715 11063 13677 11064 13715 11064 13679 11064 13679 590 13715 590 13790 590 13679 590 13790 590 13702 590 13720 11065 13813 11065 13716 11065 13716 590 13813 590 13812 590 13716 11066 13812 11066 13695 11066 13821 590 13718 590 13717 590 13717 11067 13718 11067 13819 11067 13717 11068 13819 11068 13719 11068 13719 590 13819 590 13818 590 13719 590 13818 590 13720 590 13720 11069 13818 11069 13815 11069 13720 590 13815 590 13813 590 13721 590 13795 590 13722 590 13722 11070 13795 11070 13723 11070 13722 590 13723 590 13714 590 13714 11071 13723 11071 13794 11071 13714 11072 13794 11072 13792 11072 13671 590 13802 590 13724 590 13724 11073 13802 11073 13799 11073 13724 590 13799 590 13721 590 13721 11074 13799 11074 13798 11074 13721 590 13798 590 13795 590 13812 11075 13811 11075 13695 11075 13695 590 13811 590 13810 590 13695 590 13810 590 13725 590 13725 590 13810 590 13808 590 13725 11076 13808 11076 13728 11076 13699 590 13726 590 13727 590 13727 11077 13726 11077 13805 11077 13727 590 13805 590 13671 590 13671 11078 13805 11078 13804 11078 13671 11079 13804 11079 13802 11079 13808 590 13807 590 13728 590 13728 11080 13807 11080 13729 11080 13728 590 13729 590 13699 590 13699 590 13729 590 13730 590 13699 11081 13730 11081 13726 11081 13783 11082 13784 11082 13830 11082 13830 11083 13784 11083 13731 11083 13830 11084 13731 11084 13828 11084 13828 11085 13731 11085 13732 11085 13828 11086 13732 11086 13827 11086 13827 11087 13732 11087 13733 11087 13827 11088 13733 11088 13826 11088 13826 11089 13733 11089 13734 11089 13826 11090 13734 11090 13825 11090 13825 11091 13734 11091 13735 11091 13825 11092 13735 11092 13823 11092 13823 10494 13735 10494 13736 10494 13823 10495 13736 10495 13822 10495 13822 11093 13736 11093 13737 11093 13822 11094 13737 11094 13820 11094 13820 10498 13737 10498 13738 10498 13820 10498 13738 10498 13739 10498 13739 11095 13738 11095 13740 11095 13739 11095 13740 11095 13817 11095 13817 11096 13740 11096 13741 11096 13817 10503 13741 10503 13816 10503 13816 11097 13741 11097 13742 11097 13816 11098 13742 11098 13814 11098 13814 11099 13742 11099 13743 11099 13814 10507 13743 10507 13745 10507 13745 10508 13743 10508 13744 10508 13745 10508 13744 10508 13746 10508 13746 11100 13744 11100 13747 11100 13746 11101 13747 11101 13749 11101 13749 10512 13747 10512 13748 10512 13749 10513 13748 10513 13750 10513 13750 11102 13748 11102 13751 11102 13750 11103 13751 11103 13809 11103 13809 11104 13751 11104 13752 11104 13809 11105 13752 11105 13753 11105 13753 11106 13752 11106 13754 11106 13753 11107 13754 11107 13756 11107 13756 11108 13754 11108 13755 11108 13756 11108 13755 11108 13757 11108 13757 11109 13755 11109 13759 11109 13757 11110 13759 11110 13758 11110 13758 11111 13759 11111 13760 11111 13758 11112 13760 11112 13806 11112 13806 11113 13760 11113 13761 11113 13806 11114 13761 11114 13803 11114 13803 11115 13761 11115 13762 11115 13803 11116 13762 11116 13801 11116 13801 11117 13762 11117 13763 11117 13801 11118 13763 11118 13800 11118 13800 10460 13763 10460 13764 10460 13800 10461 13764 10461 13797 10461 13797 11119 13764 11119 13765 11119 13797 11120 13765 11120 13796 11120 13796 10464 13765 10464 13767 10464 13796 11121 13767 11121 13766 11121 13766 11122 13767 11122 13769 11122 13766 11123 13769 11123 13768 11123 13768 11124 13769 11124 13770 11124 13768 10467 13770 10467 13793 10467 13793 11125 13770 11125 13771 11125 13793 11126 13771 11126 13791 11126 13791 11127 13771 11127 13772 11127 13791 10471 13772 10471 13789 10471 13789 10472 13772 10472 13773 10472 13789 11128 13773 11128 13774 11128 13774 11129 13773 11129 13775 11129 13774 11130 13775 11130 13776 11130 13776 10475 13775 10475 13777 10475 13776 10476 13777 10476 13778 10476 13778 11131 13777 11131 13779 11131 13778 11132 13779 11132 13786 11132 13786 11133 13779 11133 13780 11133 13786 11134 13780 11134 13781 11134 13781 11135 13780 11135 13782 11135 13781 11135 13782 11135 13783 11135 13783 11136 13782 11136 13784 11136 13783 11137 13831 11137 13781 11137 13781 11138 13831 11138 13785 11138 13781 11139 13785 11139 13786 11139 13786 11140 13785 11140 13787 11140 13786 11141 13787 11141 13778 11141 13778 11142 13787 11142 13788 11142 13778 11143 13788 11143 13776 11143 13776 11144 13788 11144 13703 11144 13776 11145 13703 11145 13774 11145 13774 11146 13703 11146 13702 11146 13774 11147 13702 11147 13789 11147 13789 11148 13702 11148 13790 11148 13789 11149 13790 11149 13791 11149 13791 11150 13790 11150 13715 11150 13791 11151 13715 11151 13793 11151 13793 11152 13715 11152 13792 11152 13793 11153 13792 11153 13768 11153 13768 11154 13792 11154 13794 11154 13768 11155 13794 11155 13766 11155 13766 11156 13794 11156 13723 11156 13766 11157 13723 11157 13796 11157 13796 11158 13723 11158 13795 11158 13796 11159 13795 11159 13797 11159 13797 11160 13795 11160 13798 11160 13797 11161 13798 11161 13800 11161 13800 11162 13798 11162 13799 11162 13800 11163 13799 11163 13801 11163 13801 11164 13799 11164 13802 11164 13801 11165 13802 11165 13803 11165 13803 11166 13802 11166 13804 11166 13803 11167 13804 11167 13806 11167 13806 11168 13804 11168 13805 11168 13806 11169 13805 11169 13758 11169 13758 11170 13805 11170 13726 11170 13758 11171 13726 11171 13757 11171 13757 11172 13726 11172 13730 11172 13757 11173 13730 11173 13756 11173 13756 11174 13730 11174 13729 11174 13756 11175 13729 11175 13753 11175 13753 11176 13729 11176 13807 11176 13753 11177 13807 11177 13809 11177 13809 11178 13807 11178 13808 11178 13809 11179 13808 11179 13750 11179 13750 11180 13808 11180 13810 11180 13750 11181 13810 11181 13749 11181 13749 11182 13810 11182 13811 11182 13749 11183 13811 11183 13746 11183 13746 11184 13811 11184 13812 11184 13746 11185 13812 11185 13745 11185 13745 11186 13812 11186 13813 11186 13745 11187 13813 11187 13814 11187 13814 11188 13813 11188 13815 11188 13814 11189 13815 11189 13816 11189 13816 11190 13815 11190 13818 11190 13816 11191 13818 11191 13817 11191 13817 11192 13818 11192 13819 11192 13817 11193 13819 11193 13739 11193 13739 11194 13819 11194 13718 11194 13739 11195 13718 11195 13820 11195 13820 11196 13718 11196 13821 11196 13820 11197 13821 11197 13822 11197 13822 11198 13821 11198 13701 11198 13822 11199 13701 11199 13823 11199 13823 11200 13701 11200 13824 11200 13823 11201 13824 11201 13825 11201 13825 11202 13824 11202 13707 11202 13825 11203 13707 11203 13826 11203 13826 11204 13707 11204 13705 11204 13826 11205 13705 11205 13827 11205 13827 11206 13705 11206 13713 11206 13827 11207 13713 11207 13828 11207 13828 11208 13713 11208 13829 11208 13828 11209 13829 11209 13830 11209 13830 11210 13829 11210 13709 11210 13830 11211 13709 11211 13783 11211 13783 11212 13709 11212 13831 11212 13857 590 13858 590 13832 590 13832 11213 13858 11213 13941 11213 13832 590 13941 590 13834 590 13837 11214 13973 11214 13833 11214 13833 590 13973 590 13972 590 13833 590 13972 590 13845 590 13941 590 13940 590 13834 590 13834 590 13940 590 13976 590 13834 590 13976 590 13835 590 13835 11215 13976 11215 13836 11215 13835 11216 13836 11216 13837 11216 13837 11217 13836 11217 13838 11217 13837 11218 13838 11218 13973 11218 13839 590 13840 590 13841 590 13841 11219 13840 11219 13842 11219 13841 590 13842 590 13843 590 13847 590 13849 590 13844 590 13844 11220 13849 11220 13968 11220 13844 590 13968 590 13839 590 13839 11221 13968 11221 13967 11221 13839 11222 13967 11222 13840 11222 13972 590 13846 590 13845 590 13845 11223 13846 11223 13848 11223 13845 590 13848 590 13847 590 13847 11224 13848 11224 13969 11224 13847 11225 13969 11225 13849 11225 13853 590 13955 590 13850 590 13850 590 13955 590 13954 590 13850 590 13954 590 13862 590 13867 11226 13868 11226 13851 11226 13851 590 13868 590 13852 590 13851 11227 13852 11227 13853 11227 13853 11228 13852 11228 13956 11228 13853 11229 13956 11229 13955 11229 13854 590 13946 590 13855 590 13855 590 13946 590 13856 590 13855 590 13856 590 13857 590 13857 11230 13856 11230 13944 11230 13857 590 13944 590 13858 590 13861 11231 13859 11231 13860 11231 13873 11232 13963 11232 13860 11232 13860 11233 13963 11233 13962 11233 13860 11234 13962 11234 13861 11234 13865 590 13949 590 13854 590 13854 11235 13949 11235 13947 11235 13854 11236 13947 11236 13946 11236 13954 11237 13953 11237 13862 11237 13862 11238 13953 11238 13863 11238 13862 590 13863 590 13864 590 13864 11239 13863 11239 13951 11239 13864 11240 13951 11240 13865 11240 13865 11241 13951 11241 13950 11241 13865 590 13950 590 13949 590 13861 590 13959 590 13859 590 13859 590 13959 590 13866 590 13859 590 13866 590 13867 590 13867 590 13866 590 13957 590 13867 11242 13957 11242 13868 11242 13842 590 13869 590 13843 590 13843 11243 13869 11243 13870 11243 13843 590 13870 590 13871 590 13871 11244 13870 11244 13872 11244 13871 590 13872 590 13873 590 13873 11245 13872 11245 13964 11245 13873 590 13964 590 13963 590 13877 11246 13875 11246 13874 11246 13874 11247 13875 11247 13939 11247 13874 11246 13876 11246 13877 11246 13877 11248 13876 11248 13878 11248 13877 11249 13878 11249 13958 11249 13958 11250 13878 11250 13879 11250 13958 11251 13879 11251 13880 11251 13880 11252 13879 11252 13881 11252 13880 11252 13881 11252 13882 11252 13882 11253 13881 11253 13883 11253 13882 11254 13883 11254 13884 11254 13884 11255 13883 11255 13886 11255 13884 11256 13886 11256 13885 11256 13885 11257 13886 11257 13888 11257 13885 11258 13888 11258 13887 11258 13887 11259 13888 11259 13890 11259 13887 11260 13890 11260 13889 11260 13889 11261 13890 11261 13891 11261 13889 11262 13891 11262 13952 11262 13952 11263 13891 11263 13892 11263 13952 11264 13892 11264 13894 11264 13894 11265 13892 11265 13893 11265 13894 11266 13893 11266 13948 11266 13948 11267 13893 11267 13895 11267 13948 11268 13895 11268 13896 11268 13896 11269 13895 11269 13897 11269 13896 11270 13897 11270 13945 11270 13945 11271 13897 11271 13898 11271 13945 11271 13898 11271 13899 11271 13899 11272 13898 11272 13901 11272 13899 11273 13901 11273 13900 11273 13900 11274 13901 11274 13902 11274 13900 11275 13902 11275 13943 11275 13943 11276 13902 11276 13903 11276 13943 11277 13903 11277 13904 11277 13904 11278 13903 11278 13905 11278 13904 11279 13905 11279 13942 11279 13942 11280 13905 11280 13906 11280 13942 11281 13906 11281 13907 11281 13907 11282 13906 11282 13908 11282 13907 11283 13908 11283 13975 11283 13975 11284 13908 11284 13909 11284 13975 11285 13909 11285 13910 11285 13910 11286 13909 11286 13911 11286 13910 11287 13911 11287 13974 11287 13974 11288 13911 11288 13912 11288 13974 11289 13912 11289 13971 11289 13971 11290 13912 11290 13913 11290 13971 11291 13913 11291 13970 11291 13970 11292 13913 11292 13914 11292 13970 11293 13914 11293 13916 11293 13916 11294 13914 11294 13915 11294 13916 11295 13915 11295 13917 11295 13917 11296 13915 11296 13918 11296 13917 11296 13918 11296 13919 11296 13919 11297 13918 11297 13920 11297 13919 11298 13920 11298 13921 11298 13921 11299 13920 11299 13922 11299 13921 11300 13922 11300 13923 11300 13923 11301 13922 11301 13924 11301 13923 11302 13924 11302 13925 11302 13925 11303 13924 11303 13926 11303 13925 11304 13926 11304 13966 11304 13966 11305 13926 11305 13927 11305 13966 11306 13927 11306 13928 11306 13928 11307 13927 11307 13929 11307 13928 11308 13929 11308 13930 11308 13930 11309 13929 11309 13931 11309 13930 11310 13931 11310 13965 11310 13965 11311 13931 11311 13933 11311 13965 11312 13933 11312 13932 11312 13932 11313 13933 11313 13934 11313 13932 11314 13934 11314 13935 11314 13935 11315 13934 11315 13936 11315 13935 11316 13936 11316 13938 11316 13938 11317 13936 11317 13937 11317 13938 11318 13937 11318 13961 11318 13961 11319 13937 11319 13939 11319 13961 11320 13939 11320 13960 11320 13960 11247 13939 11247 13875 11247 13907 11321 13940 11321 13942 11321 13942 11322 13940 11322 13941 11322 13942 11323 13941 11323 13904 11323 13904 11324 13941 11324 13858 11324 13904 11325 13858 11325 13943 11325 13943 11326 13858 11326 13944 11326 13943 11327 13944 11327 13900 11327 13900 11328 13944 11328 13856 11328 13900 11329 13856 11329 13899 11329 13899 11330 13856 11330 13946 11330 13899 11331 13946 11331 13945 11331 13945 11332 13946 11332 13947 11332 13945 11333 13947 11333 13896 11333 13896 11334 13947 11334 13949 11334 13896 11335 13949 11335 13948 11335 13948 11336 13949 11336 13950 11336 13948 11337 13950 11337 13894 11337 13894 11338 13950 11338 13951 11338 13894 11339 13951 11339 13952 11339 13952 11340 13951 11340 13863 11340 13952 11341 13863 11341 13889 11341 13889 11342 13863 11342 13953 11342 13889 11343 13953 11343 13887 11343 13887 11344 13953 11344 13954 11344 13887 11345 13954 11345 13885 11345 13885 11346 13954 11346 13955 11346 13885 11347 13955 11347 13884 11347 13884 11348 13955 11348 13956 11348 13884 11349 13956 11349 13882 11349 13882 11350 13956 11350 13852 11350 13882 11351 13852 11351 13880 11351 13880 11352 13852 11352 13868 11352 13880 11353 13868 11353 13958 11353 13958 11354 13868 11354 13957 11354 13958 11355 13957 11355 13877 11355 13877 11356 13957 11356 13866 11356 13877 11357 13866 11357 13875 11357 13875 11358 13866 11358 13959 11358 13875 11359 13959 11359 13960 11359 13960 11360 13959 11360 13861 11360 13960 11361 13861 11361 13961 11361 13961 11362 13861 11362 13962 11362 13961 11363 13962 11363 13938 11363 13938 11364 13962 11364 13963 11364 13938 11365 13963 11365 13935 11365 13935 11366 13963 11366 13964 11366 13935 11367 13964 11367 13932 11367 13932 11368 13964 11368 13872 11368 13932 11369 13872 11369 13965 11369 13965 11370 13872 11370 13870 11370 13965 11371 13870 11371 13930 11371 13930 11372 13870 11372 13869 11372 13930 11373 13869 11373 13928 11373 13928 11374 13869 11374 13842 11374 13928 11375 13842 11375 13966 11375 13966 11376 13842 11376 13840 11376 13966 11377 13840 11377 13925 11377 13925 11378 13840 11378 13967 11378 13925 11379 13967 11379 13923 11379 13923 11380 13967 11380 13968 11380 13923 11381 13968 11381 13921 11381 13921 11382 13968 11382 13849 11382 13921 11383 13849 11383 13919 11383 13919 11384 13849 11384 13969 11384 13919 11385 13969 11385 13917 11385 13917 11386 13969 11386 13848 11386 13917 11387 13848 11387 13916 11387 13916 11388 13848 11388 13846 11388 13916 11389 13846 11389 13970 11389 13970 11390 13846 11390 13972 11390 13970 11391 13972 11391 13971 11391 13971 11392 13972 11392 13973 11392 13971 11393 13973 11393 13974 11393 13974 11394 13973 11394 13838 11394 13974 11395 13838 11395 13910 11395 13910 11396 13838 11396 13836 11396 13910 11397 13836 11397 13975 11397 13975 11398 13836 11398 13976 11398 13975 11399 13976 11399 13907 11399 13907 11400 13976 11400 13940 11400 13993 11401 13977 11401 14082 11401 13984 590 14091 590 13979 590 13979 11402 14091 11402 13978 11402 13979 590 13978 590 13997 590 13980 590 13981 590 13983 590 13983 11403 13981 11403 13982 11403 13983 590 13982 590 13984 590 13984 11404 13982 11404 14093 11404 13984 11405 14093 11405 14091 11405 13985 590 13986 590 13987 590 13988 590 14113 590 13989 590 13989 590 14113 590 13990 590 13989 590 13990 590 14005 590 13995 11406 13991 11406 13992 11406 13992 11407 13991 11407 14078 11407 13992 590 14078 590 14012 590 14082 11408 14081 11408 13993 11408 13993 590 14081 590 14080 590 13993 11409 14080 11409 13994 11409 13994 590 14080 590 14079 590 13994 11410 14079 11410 13995 11410 13995 590 14079 590 13996 590 13995 11411 13996 11411 13991 11411 13978 590 14087 590 13997 590 13997 11412 14087 11412 13998 11412 13997 590 13998 590 13999 590 13999 11413 13998 11413 14000 11413 13999 590 14000 590 13977 590 13977 11414 14000 11414 14084 11414 13977 10851 14084 10851 14082 10851 13987 590 14101 590 13985 590 13985 11415 14101 11415 14099 11415 13985 590 14099 590 14001 590 14099 590 14097 590 14001 590 14001 11416 14097 11416 14096 11416 14001 590 14096 590 13980 590 13980 11417 14096 11417 14095 11417 13980 11418 14095 11418 13981 11418 14002 11419 14106 11419 14003 11419 14003 590 14106 590 14004 590 14003 11420 14004 11420 13986 11420 13986 590 14004 590 14104 590 13986 590 14104 590 13987 590 13990 590 14112 590 14005 590 14005 590 14112 590 14111 590 14005 11421 14111 11421 14006 11421 14006 11422 14111 11422 14110 11422 14006 590 14110 590 14002 590 14002 590 14110 590 14107 590 14002 590 14107 590 14106 590 14008 11423 14010 11423 13988 11423 13988 11424 14010 11424 14114 11424 13988 590 14114 590 14113 590 14014 590 14117 590 14007 590 14007 11425 14117 11425 14115 11425 14007 590 14115 590 14008 590 14008 590 14115 590 14009 590 14008 11426 14009 11426 14010 11426 14078 590 14077 590 14012 590 14012 590 14077 590 14011 590 14012 590 14011 590 14013 590 14013 11427 14011 11427 14119 11427 14013 590 14119 590 14014 590 14014 11428 14119 11428 14118 11428 14014 11429 14118 11429 14117 11429 14018 11430 14076 11430 14016 11430 14016 11431 14076 11431 14015 11431 14016 11432 14017 11432 14018 11432 14018 11433 14017 11433 14019 11433 14018 11434 14019 11434 14094 11434 14094 10901 14019 10901 14020 10901 14094 10901 14020 10901 14022 10901 14022 11435 14020 11435 14021 11435 14022 11436 14021 11436 14092 11436 14092 11437 14021 11437 14023 11437 14092 11438 14023 11438 14024 11438 14024 11439 14023 11439 14025 11439 14024 11440 14025 11440 14090 11440 14090 11441 14025 11441 14026 11441 14090 11442 14026 11442 14089 11442 14089 11443 14026 11443 14027 11443 14089 11444 14027 11444 14088 11444 14088 11445 14027 11445 14028 11445 14088 11446 14028 11446 14086 11446 14086 11447 14028 11447 14029 11447 14086 11448 14029 11448 14085 11448 14085 11449 14029 11449 14030 11449 14085 11450 14030 11450 14083 11450 14083 11451 14030 11451 14031 11451 14083 11452 14031 11452 14032 11452 14032 11453 14031 11453 14034 11453 14032 11454 14034 11454 14033 11454 14033 21 14034 21 14035 21 14033 21 14035 21 14036 21 14036 11455 14035 11455 14037 11455 14036 11456 14037 11456 14039 11456 14039 11457 14037 11457 14038 11457 14039 11458 14038 11458 14040 11458 14040 10859 14038 10859 14041 10859 14040 10859 14041 10859 14042 10859 14042 11459 14041 11459 14043 11459 14042 11460 14043 11460 14045 11460 14045 11461 14043 11461 14044 11461 14045 11462 14044 11462 14121 11462 14121 11463 14044 11463 14046 11463 14121 11464 14046 11464 14120 11464 14120 11465 14046 11465 14047 11465 14120 11466 14047 11466 14048 11466 14048 11467 14047 11467 14049 11467 14048 11468 14049 11468 14050 11468 14050 11469 14049 11469 14051 11469 14050 11470 14051 11470 14116 11470 14116 11471 14051 11471 14053 11471 14116 10873 14053 10873 14052 10873 14052 11472 14053 11472 14054 11472 14052 11472 14054 11472 14055 11472 14055 11473 14054 11473 14057 11473 14055 11474 14057 11474 14056 11474 14056 11475 14057 11475 14059 11475 14056 10876 14059 10876 14058 10876 14058 11476 14059 11476 14060 11476 14058 11477 14060 11477 14061 11477 14061 11478 14060 11478 14063 11478 14061 11478 14063 11478 14062 11478 14062 11479 14063 11479 14064 11479 14062 11480 14064 11480 14065 11480 14065 11481 14064 11481 14066 11481 14065 11482 14066 11482 14067 11482 14067 11483 14066 11483 14068 11483 14067 11484 14068 11484 14109 11484 14109 11485 14068 11485 14069 11485 14109 11486 14069 11486 14108 11486 14108 11487 14069 11487 14071 11487 14108 11488 14071 11488 14070 11488 14070 11489 14071 11489 14072 11489 14070 11490 14072 11490 14105 11490 14105 11491 14072 11491 14073 11491 14105 11492 14073 11492 14103 11492 14103 11493 14073 11493 14074 11493 14103 11494 14074 11494 14102 11494 14102 11495 14074 11495 14075 11495 14102 11495 14075 11495 14100 11495 14100 11496 14075 11496 14015 11496 14100 11497 14015 11497 14098 11497 14098 11498 14015 11498 14076 11498 14121 11499 14077 11499 14045 11499 14045 11500 14077 11500 14078 11500 14045 11501 14078 11501 14042 11501 14042 11502 14078 11502 13991 11502 14042 11503 13991 11503 14040 11503 14040 11504 13991 11504 13996 11504 14040 11505 13996 11505 14039 11505 14039 11506 13996 11506 14079 11506 14039 11507 14079 11507 14036 11507 14036 11508 14079 11508 14080 11508 14036 11509 14080 11509 14033 11509 14033 11510 14080 11510 14081 11510 14033 11511 14081 11511 14032 11511 14032 11512 14081 11512 14082 11512 14032 11513 14082 11513 14083 11513 14083 11514 14082 11514 14084 11514 14083 11515 14084 11515 14085 11515 14085 10967 14084 10967 14000 10967 14085 11516 14000 11516 14086 11516 14086 11517 14000 11517 13998 11517 14086 11518 13998 11518 14088 11518 14088 11519 13998 11519 14087 11519 14088 11520 14087 11520 14089 11520 14089 11521 14087 11521 13978 11521 14089 11522 13978 11522 14090 11522 14090 11523 13978 11523 14091 11523 14090 11524 14091 11524 14024 11524 14024 11525 14091 11525 14093 11525 14024 11526 14093 11526 14092 11526 14092 11527 14093 11527 13982 11527 14092 11528 13982 11528 14022 11528 14022 11529 13982 11529 13981 11529 14022 10982 13981 10982 14094 10982 14094 11530 13981 11530 14095 11530 14094 11531 14095 11531 14018 11531 14018 11532 14095 11532 14096 11532 14018 11533 14096 11533 14076 11533 14076 11534 14096 11534 14097 11534 14076 11535 14097 11535 14098 11535 14098 11536 14097 11536 14099 11536 14098 11537 14099 11537 14100 11537 14100 11538 14099 11538 14101 11538 14100 11539 14101 11539 14102 11539 14102 11540 14101 11540 13987 11540 14102 11541 13987 11541 14103 11541 14103 11542 13987 11542 14104 11542 14103 11543 14104 11543 14105 11543 14105 11544 14104 11544 14004 11544 14105 11545 14004 11545 14070 11545 14070 11546 14004 11546 14106 11546 14070 11547 14106 11547 14108 11547 14108 11548 14106 11548 14107 11548 14108 11549 14107 11549 14109 11549 14109 11550 14107 11550 14110 11550 14109 11551 14110 11551 14067 11551 14067 11552 14110 11552 14111 11552 14067 11553 14111 11553 14065 11553 14065 11554 14111 11554 14112 11554 14065 11555 14112 11555 14062 11555 14062 11556 14112 11556 13990 11556 14062 11557 13990 11557 14061 11557 14061 11558 13990 11558 14113 11558 14061 11559 14113 11559 14058 11559 14058 11560 14113 11560 14114 11560 14058 11561 14114 11561 14056 11561 14056 11562 14114 11562 14010 11562 14056 11563 14010 11563 14055 11563 14055 11564 14010 11564 14009 11564 14055 11565 14009 11565 14052 11565 14052 11566 14009 11566 14115 11566 14052 11567 14115 11567 14116 11567 14116 11568 14115 11568 14117 11568 14116 11569 14117 11569 14050 11569 14050 11570 14117 11570 14118 11570 14050 11571 14118 11571 14048 11571 14048 11572 14118 11572 14119 11572 14048 11573 14119 11573 14120 11573 14120 11574 14119 11574 14011 11574 14120 11575 14011 11575 14121 11575 14121 11576 14011 11576 14077 11576 14197 11577 14140 11577 14122 11577 14127 590 14129 590 14122 590 14122 11578 14129 11578 14123 11578 14122 11579 14123 11579 14197 11579 14124 590 14158 590 14125 590 14125 11580 14158 11580 14126 11580 14125 590 14126 590 14127 590 14127 11581 14126 11581 14128 11581 14127 11582 14128 11582 14129 11582 14145 590 14146 590 14130 590 14130 11583 14146 11583 14174 11583 14130 590 14174 590 14131 590 14174 590 14132 590 14131 590 14131 11584 14132 11584 14171 11584 14131 11585 14171 11585 14134 11585 14134 11586 14171 11586 14133 11586 14134 590 14133 590 14136 590 14133 590 14135 590 14136 590 14136 590 14135 590 14137 590 14136 590 14137 590 14138 590 14138 11587 14137 11587 14224 11587 14138 11588 14224 11588 14141 11588 14197 590 14139 590 14140 590 14140 11589 14139 11589 14149 11589 14140 590 14149 590 14151 590 14224 590 14222 590 14141 590 14141 590 14222 590 14219 590 14141 590 14219 590 14142 590 14142 590 14219 590 14143 590 14142 590 14143 590 14167 590 14161 590 14144 590 14145 590 14145 11590 14144 11590 14178 11590 14145 11591 14178 11591 14146 11591 14154 590 14188 590 14147 590 14147 590 14188 590 14148 590 14147 590 14148 590 14159 590 14149 590 14150 590 14151 590 14151 11578 14150 11578 14152 11578 14151 590 14152 590 14153 590 14153 11592 14152 11592 14193 11592 14153 11593 14193 11593 14154 11593 14154 11594 14193 11594 14190 11594 14154 590 14190 590 14188 590 14166 590 14155 590 14156 590 14156 11595 14155 11595 14157 11595 14156 590 14157 590 14124 590 14124 11596 14157 11596 14205 11596 14124 11597 14205 11597 14158 11597 14148 590 14185 590 14159 590 14159 11598 14185 11598 14183 11598 14159 11599 14183 11599 14160 11599 14160 11600 14183 11600 14162 11600 14160 11601 14162 11601 14161 11601 14161 11602 14162 11602 14180 11602 14161 11220 14180 11220 14144 11220 14163 11603 14212 11603 14164 11603 14164 590 14212 590 14165 590 14164 590 14165 590 14166 590 14166 590 14165 590 14209 590 14166 590 14209 590 14155 590 14143 11604 14217 11604 14167 11604 14167 590 14217 590 14215 590 14167 11605 14215 11605 14163 11605 14163 11606 14215 11606 14168 11606 14163 11607 14168 11607 14212 11607 14226 11608 14135 11608 14169 11608 14169 11609 14135 11609 14133 11609 14169 11610 14133 11610 14170 11610 14170 11611 14133 11611 14171 11611 14170 11612 14171 11612 14172 11612 14172 11613 14171 11613 14132 11613 14172 11614 14132 11614 14173 11614 14173 11615 14132 11615 14174 11615 14173 11616 14174 11616 14175 11616 14175 11617 14174 11617 14146 11617 14175 11618 14146 11618 14176 11618 14176 11619 14146 11619 14178 11619 14176 11620 14178 11620 14177 11620 14177 11621 14178 11621 14144 11621 14177 11622 14144 11622 14179 11622 14179 11623 14144 11623 14180 11623 14179 11624 14180 11624 14181 11624 14181 11625 14180 11625 14162 11625 14181 11626 14162 11626 14182 11626 14182 11627 14162 11627 14183 11627 14182 11628 14183 11628 14184 11628 14184 11629 14183 11629 14185 11629 14184 11630 14185 11630 14186 11630 14186 11631 14185 11631 14148 11631 14186 11632 14148 11632 14187 11632 14187 11633 14148 11633 14188 11633 14187 11634 14188 11634 14189 11634 14189 11635 14188 11635 14190 11635 14189 11636 14190 11636 14191 11636 14191 11637 14190 11637 14193 11637 14191 11638 14193 11638 14192 11638 14192 11639 14193 11639 14152 11639 14192 11640 14152 11640 14194 11640 14194 11641 14152 11641 14150 11641 14194 11642 14150 11642 14195 11642 14195 11643 14150 11643 14149 11643 14195 11644 14149 11644 14196 11644 14196 11645 14149 11645 14139 11645 14196 11646 14139 11646 14198 11646 14198 11647 14139 11647 14197 11647 14198 11648 14197 11648 14199 11648 14199 11649 14197 11649 14123 11649 14199 11650 14123 11650 14200 11650 14200 11651 14123 11651 14129 11651 14200 11652 14129 11652 14201 11652 14201 11653 14129 11653 14128 11653 14201 11654 14128 11654 14202 11654 14202 11655 14128 11655 14126 11655 14202 11656 14126 11656 14203 11656 14203 11657 14126 11657 14158 11657 14203 11658 14158 11658 14204 11658 14204 11659 14158 11659 14205 11659 14204 11660 14205 11660 14206 11660 14206 11661 14205 11661 14157 11661 14206 11662 14157 11662 14207 11662 14207 11663 14157 11663 14155 11663 14207 11664 14155 11664 14208 11664 14208 11665 14155 11665 14209 11665 14208 11666 14209 11666 14210 11666 14210 11667 14209 11667 14165 11667 14210 11668 14165 11668 14211 11668 14211 11669 14165 11669 14212 11669 14211 11670 14212 11670 14213 11670 14213 11671 14212 11671 14168 11671 14213 11672 14168 11672 14214 11672 14214 11673 14168 11673 14215 11673 14214 11674 14215 11674 14216 11674 14216 11675 14215 11675 14217 11675 14216 11676 14217 11676 14218 11676 14218 11677 14217 11677 14143 11677 14218 11678 14143 11678 14220 11678 14220 11679 14143 11679 14219 11679 14220 11680 14219 11680 14221 11680 14221 11681 14219 11681 14222 11681 14221 11682 14222 11682 14223 11682 14223 11683 14222 11683 14224 11683 14223 11684 14224 11684 14225 11684 14225 11685 14224 11685 14137 11685 14225 11686 14137 11686 14226 11686 14226 11687 14137 11687 14135 11687 14227 590 14228 590 14356 590 14239 11688 14357 11688 14228 11688 14228 590 14357 590 14229 590 14228 590 14229 590 14356 590 14236 590 14230 590 14231 590 14231 11689 14230 11689 14364 11689 14231 590 14364 590 14232 590 14233 590 14245 590 14234 590 14234 11690 14245 11690 14360 11690 14234 590 14360 590 14235 590 14265 590 14366 590 14236 590 14236 10843 14366 10843 14365 10843 14236 11691 14365 11691 14230 11691 14360 590 14237 590 14235 590 14235 590 14237 590 14238 590 14235 10822 14238 10822 14239 10822 14239 11692 14238 11692 14240 11692 14239 11693 14240 11693 14357 11693 14364 590 14241 590 14232 590 14232 11694 14241 11694 14242 11694 14232 590 14242 590 14243 590 14243 11695 14242 11695 14244 11695 14243 590 14244 590 14233 590 14233 11696 14244 11696 14362 11696 14233 11697 14362 11697 14245 11697 14246 590 14343 590 14247 590 14247 590 14343 590 14251 590 14247 590 14251 590 14253 590 14248 590 14249 590 14250 590 14250 11698 14249 11698 14369 11698 14250 11699 14369 11699 14261 11699 14251 11700 14252 11700 14253 11700 14253 590 14252 590 14254 590 14253 590 14254 590 14255 590 14255 11701 14254 11701 14256 11701 14255 590 14256 590 14248 590 14248 590 14256 590 14257 590 14248 590 14257 590 14249 590 14258 590 14352 590 14259 590 14259 590 14352 590 14351 590 14259 590 14351 590 14273 590 14369 11702 14260 11702 14261 11702 14261 11703 14260 11703 14262 11703 14261 11704 14262 11704 14263 11704 14263 590 14262 590 14264 590 14263 590 14264 590 14265 590 14265 11705 14264 11705 14266 11705 14265 11706 14266 11706 14366 11706 14267 590 14344 590 14246 590 14246 11707 14344 11707 14268 11707 14246 11708 14268 11708 14343 11708 14356 11709 14269 11709 14227 11709 14227 11710 14269 11710 14355 11710 14227 11711 14355 11711 14270 11711 14270 590 14355 590 14271 590 14270 11712 14271 11712 14258 11712 14258 11713 14271 11713 14272 11713 14258 11714 14272 11714 14352 11714 14351 11715 14349 11715 14273 11715 14273 11716 14349 11716 14348 11716 14273 590 14348 590 14274 590 14274 11717 14348 11717 14347 11717 14274 11718 14347 11718 14267 11718 14267 11719 14347 11719 14346 11719 14267 590 14346 590 14344 590 14279 11720 14276 11720 14275 11720 14275 11721 14276 11721 14277 11721 14275 11720 14278 11720 14279 11720 14279 11722 14278 11722 14280 11722 14279 11723 14280 11723 14281 11723 14281 11457 14280 11457 14282 11457 14281 11458 14282 11458 14354 11458 14354 10859 14282 10859 14283 10859 14354 10859 14283 10859 14353 10859 14353 11459 14283 11459 14284 11459 14353 11724 14284 11724 14285 11724 14285 10863 14284 10863 14286 10863 14285 10864 14286 10864 14287 10864 14287 10865 14286 10865 14288 10865 14287 11725 14288 11725 14350 11725 14350 11726 14288 11726 14290 11726 14350 11727 14290 11727 14289 11727 14289 11467 14290 11467 14291 11467 14289 11468 14291 11468 14292 11468 14292 11469 14291 11469 14293 11469 14292 11470 14293 11470 14294 11470 14294 11471 14293 11471 14295 11471 14294 11728 14295 11728 14296 11728 14296 11729 14295 11729 14297 11729 14296 11472 14297 11472 14345 11472 14345 11473 14297 11473 14298 11473 14345 11474 14298 11474 14300 11474 14300 10876 14298 10876 14299 10876 14300 10876 14299 10876 14301 10876 14301 11477 14299 11477 14302 11477 14301 11476 14302 11476 14303 11476 14303 11478 14302 11478 14304 11478 14303 11730 14304 11730 14342 11730 14342 11731 14304 11731 14305 11731 14342 11732 14305 11732 14341 11732 14341 11733 14305 11733 14306 11733 14341 11734 14306 11734 14340 11734 14340 11483 14306 11483 14307 11483 14340 11484 14307 11484 14371 11484 14371 10887 14307 10887 14308 10887 14371 10886 14308 10886 14370 10886 14370 11735 14308 11735 14309 11735 14370 11736 14309 11736 14368 11736 14368 11489 14309 11489 14310 11489 14368 11490 14310 11490 14367 11490 14367 11737 14310 11737 14311 11737 14367 11738 14311 11738 14312 11738 14312 11739 14311 11739 14313 11739 14312 11740 14313 11740 14314 11740 14314 11741 14313 11741 14315 11741 14314 11495 14315 11495 14316 11495 14316 11497 14315 11497 14317 11497 14316 11496 14317 11496 14318 11496 14318 10899 14317 10899 14319 10899 14318 10899 14319 10899 14320 10899 14320 11433 14319 11433 14321 11433 14320 11434 14321 11434 14322 11434 14322 10901 14321 10901 14323 10901 14322 11742 14323 11742 14324 11742 14324 11743 14323 11743 14325 11743 14324 11436 14325 11436 14363 11436 14363 11437 14325 11437 14326 11437 14363 11438 14326 11438 14327 11438 14327 11439 14326 11439 14328 11439 14327 11440 14328 11440 14329 11440 14329 11744 14328 11744 14331 11744 14329 11745 14331 11745 14330 11745 14330 11746 14331 11746 14332 11746 14330 11747 14332 11747 14361 11747 14361 11446 14332 11446 14333 11446 14361 11445 14333 11445 14359 11445 14359 11748 14333 11748 14334 11748 14359 11448 14334 11448 14336 11448 14336 11449 14334 11449 14335 11449 14336 11450 14335 11450 14338 11450 14338 11451 14335 11451 14337 11451 14338 11452 14337 11452 14358 11452 14358 11749 14337 11749 14277 11749 14358 11750 14277 11750 14339 11750 14339 11721 14277 11721 14276 11721 14371 11551 14257 11551 14340 11551 14340 11751 14257 11751 14256 11751 14340 11752 14256 11752 14341 11752 14341 11753 14256 11753 14254 11753 14341 11754 14254 11754 14342 11754 14342 11755 14254 11755 14252 11755 14342 11756 14252 11756 14303 11756 14303 11757 14252 11757 14251 11757 14303 11758 14251 11758 14301 11758 14301 11759 14251 11759 14343 11759 14301 11760 14343 11760 14300 11760 14300 11761 14343 11761 14268 11761 14300 11563 14268 11563 14345 11563 14345 11762 14268 11762 14344 11762 14345 11763 14344 11763 14296 11763 14296 11566 14344 11566 14346 11566 14296 11764 14346 11764 14294 11764 14294 11765 14346 11765 14347 11765 14294 10940 14347 10940 14292 10940 14292 11766 14347 11766 14348 11766 14292 11767 14348 11767 14289 11767 14289 11768 14348 11768 14349 11768 14289 11769 14349 11769 14350 11769 14350 11574 14349 11574 14351 11574 14350 11770 14351 11770 14287 11770 14287 11771 14351 11771 14352 11771 14287 11772 14352 11772 14285 11772 14285 11773 14352 11773 14272 11773 14285 11774 14272 11774 14353 11774 14353 11775 14272 11775 14271 11775 14353 11776 14271 11776 14354 11776 14354 11777 14271 11777 14355 11777 14354 11505 14355 11505 14281 11505 14281 11778 14355 11778 14269 11778 14281 11779 14269 11779 14279 11779 14279 11780 14269 11780 14356 11780 14279 11781 14356 11781 14276 11781 14276 11782 14356 11782 14229 11782 14276 11783 14229 11783 14339 11783 14339 11784 14229 11784 14357 11784 14339 11785 14357 11785 14358 11785 14358 11786 14357 11786 14240 11786 14358 11513 14240 11513 14338 11513 14338 11787 14240 11787 14238 11787 14338 11515 14238 11515 14336 11515 14336 11788 14238 11788 14237 11788 14336 11789 14237 11789 14359 11789 14359 11790 14237 11790 14360 11790 14359 11791 14360 11791 14361 11791 14361 11792 14360 11792 14245 11792 14361 11793 14245 11793 14330 11793 14330 11794 14245 11794 14362 11794 14330 11795 14362 11795 14329 11795 14329 11796 14362 11796 14244 11796 14329 11797 14244 11797 14327 11797 14327 11798 14244 11798 14242 11798 14327 11799 14242 11799 14363 11799 14363 11800 14242 11800 14241 11800 14363 11801 14241 11801 14324 11801 14324 11802 14241 11802 14364 11802 14324 10982 14364 10982 14322 10982 14322 11530 14364 11530 14230 11530 14322 11803 14230 11803 14320 11803 14320 11532 14230 11532 14365 11532 14320 11804 14365 11804 14318 11804 14318 11805 14365 11805 14366 11805 14318 11806 14366 11806 14316 11806 14316 11807 14366 11807 14266 11807 14316 11808 14266 11808 14314 11808 14314 11809 14266 11809 14264 11809 14314 11810 14264 11810 14312 11810 14312 11811 14264 11811 14262 11811 14312 11812 14262 11812 14367 11812 14367 11544 14262 11544 14260 11544 14367 11545 14260 11545 14368 11545 14368 11813 14260 11813 14369 11813 14368 11814 14369 11814 14370 11814 14370 11815 14369 11815 14249 11815 14370 11816 14249 11816 14371 11816 14371 11817 14249 11817 14257 11817 14372 11818 14373 11818 14374 11818 14374 590 14373 590 14414 590 14374 11819 14414 11819 14375 11819 14379 590 14376 590 14372 590 14372 11820 14376 11820 14491 11820 14372 590 14491 590 14373 590 14401 590 14377 590 14378 590 14378 11821 14377 11821 14494 11821 14378 590 14494 590 14379 590 14379 11822 14494 11822 14380 11822 14379 11823 14380 11823 14376 11823 14381 590 14383 590 14382 590 14382 11824 14383 11824 14384 11824 14382 590 14384 590 14385 590 14391 11825 14386 11825 14387 11825 14387 590 14386 590 14510 590 14387 11826 14510 11826 14403 11826 14388 11827 14397 11827 14389 11827 14389 11828 14397 11828 14390 11828 14389 590 14390 590 14391 590 14391 590 14390 590 14392 590 14391 590 14392 590 14386 590 14407 590 14393 590 14394 590 14394 590 14393 590 14395 590 14394 590 14395 590 14388 590 14388 590 14395 590 14396 590 14388 590 14396 590 14397 590 14413 590 14515 590 14398 590 14398 11829 14515 11829 14513 11829 14398 590 14513 590 14406 590 14384 590 14399 590 14385 590 14385 11830 14399 11830 14499 11830 14385 590 14499 590 14400 590 14400 11831 14499 11831 14497 11831 14400 590 14497 590 14401 590 14401 11832 14497 11832 14496 11832 14401 11833 14496 11833 14377 11833 14504 11834 14402 11834 14405 11834 14510 590 14508 590 14403 590 14403 590 14508 590 14404 590 14403 590 14404 590 14405 590 14405 11835 14404 11835 14507 11835 14405 11836 14507 11836 14504 11836 14513 590 14512 590 14406 590 14406 11837 14512 11837 14408 11837 14406 11838 14408 11838 14407 11838 14407 11839 14408 11839 14511 11839 14407 590 14511 590 14393 590 14416 590 14409 590 14410 590 14410 11840 14409 11840 14411 11840 14410 590 14411 590 14413 590 14413 11841 14411 11841 14412 11841 14413 10348 14412 10348 14515 10348 14414 590 14489 590 14375 590 14375 11842 14489 11842 14488 11842 14375 11843 14488 11843 14415 11843 14415 11844 14488 11844 14487 11844 14415 590 14487 590 14416 590 14416 11845 14487 11845 14417 11845 14416 590 14417 590 14409 590 14504 590 14418 590 14402 590 14402 11846 14418 11846 14502 11846 14402 590 14502 590 14381 590 14381 11847 14502 11847 14501 11847 14381 11848 14501 11848 14383 11848 14423 11849 14420 11849 14419 11849 14419 11850 14420 11850 14421 11850 14419 11851 14422 11851 14423 11851 14423 11297 14422 11297 14424 11297 14423 11298 14424 11298 14425 11298 14425 11299 14424 11299 14426 11299 14425 11299 14426 11299 14500 11299 14500 11852 14426 11852 14427 11852 14500 11302 14427 11302 14428 11302 14428 11303 14427 11303 14429 11303 14428 11304 14429 11304 14431 11304 14431 11305 14429 11305 14430 11305 14431 11306 14430 11306 14498 11306 14498 11853 14430 11853 14432 11853 14498 11854 14432 11854 14433 11854 14433 11855 14432 11855 14434 11855 14433 11856 14434 11856 14435 11856 14435 11312 14434 11312 14436 11312 14435 11311 14436 11311 14495 11311 14495 11857 14436 11857 14437 11857 14495 11314 14437 11314 14438 11314 14438 11315 14437 11315 14439 11315 14438 11316 14439 11316 14493 11316 14493 11317 14439 11317 14440 11317 14493 11318 14440 11318 14492 11318 14492 11858 14440 11858 14442 11858 14492 11859 14442 11859 14441 11859 14441 6 14442 6 14443 6 14441 6 14443 6 14490 6 14490 11860 14443 11860 14444 11860 14490 11861 14444 11861 14445 11861 14445 11250 14444 11250 14446 11250 14445 11251 14446 11251 14447 11251 14447 11252 14446 11252 14448 11252 14447 11252 14448 11252 14449 11252 14449 11253 14448 11253 14450 11253 14449 11862 14450 11862 14486 11862 14486 11863 14450 11863 14451 11863 14486 11864 14451 11864 14452 11864 14452 11865 14451 11865 14453 11865 14452 11866 14453 11866 14454 11866 14454 11867 14453 11867 14455 11867 14454 11868 14455 11868 14516 11868 14516 11261 14455 11261 14456 11261 14516 11262 14456 11262 14514 11262 14514 11263 14456 11263 14457 11263 14514 11264 14457 11264 14459 11264 14459 11265 14457 11265 14458 11265 14459 11869 14458 11869 14460 11869 14460 11268 14458 11268 14461 11268 14460 11268 14461 11268 14462 11268 14462 11269 14461 11269 14464 11269 14462 11270 14464 11270 14463 11270 14463 11870 14464 11870 14465 11870 14463 11271 14465 11271 14466 11271 14466 11273 14465 11273 14467 11273 14466 11272 14467 11272 14468 11272 14468 11274 14467 11274 14470 11274 14468 11274 14470 11274 14469 11274 14469 11871 14470 11871 14472 11871 14469 11872 14472 11872 14471 11872 14471 11873 14472 11873 14473 11873 14471 11874 14473 11874 14474 11874 14474 11280 14473 11280 14476 11280 14474 11281 14476 11281 14475 11281 14475 11875 14476 11875 14477 11875 14475 11876 14477 11876 14479 11876 14479 11877 14477 11877 14478 11877 14479 11878 14478 11878 14509 11878 14509 11286 14478 11286 14480 11286 14509 11287 14480 11287 14481 11287 14481 11879 14480 11879 14482 11879 14481 11880 14482 11880 14483 11880 14483 11881 14482 11881 14484 11881 14483 11882 14484 11882 14506 11882 14506 11293 14484 11293 14485 11293 14506 11293 14485 11293 14505 11293 14505 11295 14485 11295 14421 11295 14505 11294 14421 11294 14503 11294 14503 11883 14421 11883 14420 11883 14452 11884 14417 11884 14486 11884 14486 11885 14417 11885 14487 11885 14486 11886 14487 11886 14449 11886 14449 11887 14487 11887 14488 11887 14449 11888 14488 11888 14447 11888 14447 11889 14488 11889 14489 11889 14447 11353 14489 11353 14445 11353 14445 11890 14489 11890 14414 11890 14445 11891 14414 11891 14490 11891 14490 11892 14414 11892 14373 11892 14490 11893 14373 11893 14441 11893 14441 11894 14373 11894 14491 11894 14441 11895 14491 11895 14492 11895 14492 11896 14491 11896 14376 11896 14492 11363 14376 11363 14493 11363 14493 11897 14376 11897 14380 11897 14493 11365 14380 11365 14438 11365 14438 11898 14380 11898 14494 11898 14438 11899 14494 11899 14495 11899 14495 11900 14494 11900 14377 11900 14495 11901 14377 11901 14435 11901 14435 11902 14377 11902 14496 11902 14435 11903 14496 11903 14433 11903 14433 11904 14496 11904 14497 11904 14433 11905 14497 11905 14498 11905 14498 11906 14497 11906 14499 11906 14498 11907 14499 11907 14431 11907 14431 11908 14499 11908 14399 11908 14431 11909 14399 11909 14428 11909 14428 11910 14399 11910 14384 11910 14428 11911 14384 11911 14500 11911 14500 11912 14384 11912 14383 11912 14500 11381 14383 11381 14425 11381 14425 11382 14383 11382 14501 11382 14425 11913 14501 11913 14423 11913 14423 11384 14501 11384 14502 11384 14423 11914 14502 11914 14420 11914 14420 11915 14502 11915 14418 11915 14420 11916 14418 11916 14503 11916 14503 11917 14418 11917 14504 11917 14503 11918 14504 11918 14505 11918 14505 11919 14504 11919 14507 11919 14505 11920 14507 11920 14506 11920 14506 11921 14507 11921 14404 11921 14506 11922 14404 11922 14483 11922 14483 11923 14404 11923 14508 11923 14483 11924 14508 11924 14481 11924 14481 11394 14508 11394 14510 11394 14481 11395 14510 11395 14509 11395 14509 11925 14510 11925 14386 11925 14509 11926 14386 11926 14479 11926 14479 11927 14386 11927 14392 11927 14479 11928 14392 11928 14475 11928 14475 11929 14392 11929 14390 11929 14475 11321 14390 11321 14474 11321 14474 11930 14390 11930 14397 11930 14474 11931 14397 11931 14471 11931 14471 11932 14397 11932 14396 11932 14471 11933 14396 11933 14469 11933 14469 11934 14396 11934 14395 11934 14469 11935 14395 11935 14468 11935 14468 11936 14395 11936 14393 11936 14468 11937 14393 11937 14466 11937 14466 11938 14393 11938 14511 11938 14466 11939 14511 11939 14463 11939 14463 11940 14511 11940 14408 11940 14463 11333 14408 11333 14462 11333 14462 11941 14408 11941 14512 11941 14462 11942 14512 11942 14460 11942 14460 11336 14512 11336 14513 11336 14460 11943 14513 11943 14459 11943 14459 11944 14513 11944 14515 11944 14459 11945 14515 11945 14514 11945 14514 11946 14515 11946 14412 11946 14514 11947 14412 11947 14516 11947 14516 11948 14412 11948 14411 11948 14516 11949 14411 11949 14454 11949 14454 11344 14411 11344 14409 11344 14454 11950 14409 11950 14452 11950 14452 11951 14409 11951 14417 11951 14517 11952 14590 11952 14518 11952 14518 11953 14590 11953 14555 11953 14518 11954 14555 11954 14519 11954 14519 11955 14555 11955 14582 11955 14519 11956 14582 11956 14520 11956 14520 11957 14582 11957 14584 11957 14520 11958 14584 11958 14521 11958 14521 11959 14584 11959 14586 11959 14521 11960 14586 11960 14522 11960 14522 11961 14586 11961 14578 11961 14522 11962 14578 11962 14523 11962 14523 11963 14578 11963 14524 11963 14523 11964 14524 11964 14526 11964 14526 11965 14524 11965 14525 11965 14526 11966 14525 11966 14527 11966 14527 11967 14525 11967 14528 11967 14527 11968 14528 11968 14529 11968 14529 11969 14528 11969 14575 11969 14529 11970 14575 11970 14531 11970 14531 11971 14575 11971 14530 11971 14531 11972 14530 11972 14533 11972 14533 11973 14530 11973 14532 11973 14533 11974 14532 11974 14534 11974 14534 11975 14532 11975 14572 11975 14534 11976 14572 11976 14535 11976 14535 6 14572 6 14552 6 14535 6 14552 6 14536 6 14536 11977 14552 11977 14565 11977 14536 11978 14565 11978 14537 11978 14537 11979 14565 11979 14538 11979 14537 11980 14538 11980 14539 11980 14539 11981 14538 11981 14567 11981 14539 11982 14567 11982 14540 11982 14540 11983 14567 11983 14560 11983 14540 11984 14560 11984 14541 11984 14541 11985 14560 11985 14556 11985 14541 11986 14556 11986 14542 11986 14542 11987 14556 11987 14543 11987 14542 11988 14543 11988 14544 11988 14544 11989 14543 11989 14546 11989 14544 11990 14546 11990 14545 11990 14545 11991 14546 11991 14559 11991 14545 11992 14559 11992 14548 11992 14548 11993 14559 11993 14547 11993 14548 11994 14547 11994 14550 11994 14550 11995 14547 11995 14549 11995 14550 11996 14549 11996 14551 11996 14551 11997 14549 11997 14588 11997 14551 11998 14588 11998 14517 11998 14517 11999 14588 11999 14590 11999 14572 590 14680 590 14552 590 14552 12000 14680 12000 14553 12000 14552 12001 14553 12001 14565 12001 14590 12002 14554 12002 14555 12002 14555 590 14554 590 14581 590 14555 12003 14581 12003 14582 12003 14556 590 14564 590 14543 590 14543 590 14564 590 14557 590 14543 590 14557 590 14546 590 14557 590 14669 590 14546 590 14546 12004 14669 12004 14558 12004 14546 12005 14558 12005 14559 12005 14559 12006 14558 12006 14667 12006 14559 590 14667 590 14547 590 14567 590 14561 590 14560 590 14560 12007 14561 12007 14562 12007 14560 590 14562 590 14556 590 14556 12008 14562 12008 14563 12008 14556 590 14563 590 14564 590 14553 590 14678 590 14565 590 14565 12009 14678 12009 14566 12009 14565 590 14566 590 14538 590 14538 590 14566 590 14677 590 14538 12010 14677 12010 14567 12010 14567 12011 14677 12011 14568 12011 14567 12012 14568 12012 14561 12012 14524 12013 14658 12013 14525 12013 14525 590 14658 590 14569 590 14525 590 14569 590 14528 590 14667 590 14570 590 14547 590 14547 12014 14570 12014 14571 12014 14547 12015 14571 12015 14549 12015 14549 12016 14571 12016 14664 12016 14549 590 14664 590 14588 590 14530 590 14655 590 14532 590 14532 12017 14655 12017 14653 12017 14532 590 14653 590 14572 590 14572 590 14653 590 14573 590 14572 12018 14573 12018 14680 12018 14569 590 14657 590 14528 590 14528 12019 14657 12019 14574 12019 14528 590 14574 590 14575 590 14575 12020 14574 12020 14576 12020 14575 590 14576 590 14530 590 14530 12021 14576 12021 14577 12021 14530 590 14577 590 14655 590 14586 590 14659 590 14578 590 14578 10661 14659 10661 14579 10661 14578 12022 14579 12022 14524 12022 14524 590 14579 590 14580 590 14524 590 14580 590 14658 590 14581 590 14661 590 14582 590 14582 12023 14661 12023 14583 12023 14582 12024 14583 12024 14584 12024 14584 12025 14583 12025 14585 12025 14584 12026 14585 12026 14586 12026 14586 12027 14585 12027 14587 12027 14586 12028 14587 12028 14659 12028 14664 12029 14663 12029 14588 12029 14588 590 14663 590 14589 590 14588 590 14589 590 14590 590 14590 590 14589 590 14591 590 14590 590 14591 590 14554 590 14592 12030 14652 12030 14593 12030 14593 12031 14652 12031 14594 12031 14593 12032 14594 12032 14679 12032 14679 12033 14594 12033 14595 12033 14679 12034 14595 12034 14596 12034 14596 12035 14595 12035 14597 12035 14596 12036 14597 12036 14676 12036 14676 12037 14597 12037 14598 12037 14676 12038 14598 12038 14675 12038 14675 12039 14598 12039 14599 12039 14675 12040 14599 12040 14674 12040 14674 12041 14599 12041 14600 12041 14674 12042 14600 12042 14673 12042 14673 12043 14600 12043 14601 12043 14673 12044 14601 12044 14672 12044 14672 12045 14601 12045 14602 12045 14672 12046 14602 12046 14671 12046 14671 12047 14602 12047 14603 12047 14671 12047 14603 12047 14604 12047 14604 50 14603 50 14605 50 14604 50 14605 50 14670 50 14670 12048 14605 12048 14606 12048 14670 12048 14606 12048 14668 12048 14668 12049 14606 12049 14607 12049 14668 12050 14607 12050 14608 12050 14608 12051 14607 12051 14609 12051 14608 12052 14609 12052 14666 12052 14666 12053 14609 12053 14610 12053 14666 12054 14610 12054 14612 12054 14612 12055 14610 12055 14611 12055 14612 12056 14611 12056 14665 12056 14665 12057 14611 12057 14613 12057 14665 12058 14613 12058 14614 12058 14614 12059 14613 12059 14615 12059 14614 12060 14615 12060 14616 12060 14616 12061 14615 12061 14617 12061 14616 12062 14617 12062 14618 12062 14618 12063 14617 12063 14619 12063 14618 12064 14619 12064 14620 12064 14620 12065 14619 12065 14621 12065 14620 12065 14621 12065 14623 12065 14623 12066 14621 12066 14622 12066 14623 12067 14622 12067 14662 12067 14662 12068 14622 12068 14624 12068 14662 12069 14624 12069 14625 12069 14625 12070 14624 12070 14627 12070 14625 12071 14627 12071 14626 12071 14626 12072 14627 12072 14628 12072 14626 12073 14628 12073 14660 12073 14660 12074 14628 12074 14629 12074 14660 12075 14629 12075 14630 12075 14630 12076 14629 12076 14631 12076 14630 12077 14631 12077 14632 12077 14632 12078 14631 12078 14633 12078 14632 12079 14633 12079 14634 12079 14634 12080 14633 12080 14635 12080 14634 12081 14635 12081 14636 12081 14636 49 14635 49 14638 49 14636 49 14638 49 14637 49 14637 12082 14638 12082 14640 12082 14637 12083 14640 12083 14639 12083 14639 12084 14640 12084 14641 12084 14639 12085 14641 12085 14642 12085 14642 12086 14641 12086 14643 12086 14642 12087 14643 12087 14644 12087 14644 12088 14643 12088 14645 12088 14644 12089 14645 12089 14656 12089 14656 12090 14645 12090 14646 12090 14656 12091 14646 12091 14647 12091 14647 12092 14646 12092 14648 12092 14647 12092 14648 12092 14654 12092 14654 12093 14648 12093 14649 12093 14654 12094 14649 12094 14650 12094 14650 12095 14649 12095 14651 12095 14650 12096 14651 12096 14592 12096 14592 12030 14651 12030 14652 12030 14592 12097 14573 12097 14650 12097 14650 12098 14573 12098 14653 12098 14650 12099 14653 12099 14654 12099 14654 12100 14653 12100 14655 12100 14654 12101 14655 12101 14647 12101 14647 12102 14655 12102 14577 12102 14647 12103 14577 12103 14656 12103 14656 12104 14577 12104 14576 12104 14656 12105 14576 12105 14644 12105 14644 12106 14576 12106 14574 12106 14644 12107 14574 12107 14642 12107 14642 12108 14574 12108 14657 12108 14642 12109 14657 12109 14639 12109 14639 12110 14657 12110 14569 12110 14639 12111 14569 12111 14637 12111 14637 12112 14569 12112 14658 12112 14637 12113 14658 12113 14636 12113 14636 12114 14658 12114 14580 12114 14636 12115 14580 12115 14634 12115 14634 12116 14580 12116 14579 12116 14634 12117 14579 12117 14632 12117 14632 12118 14579 12118 14659 12118 14632 12119 14659 12119 14630 12119 14630 12120 14659 12120 14587 12120 14630 12121 14587 12121 14660 12121 14660 12122 14587 12122 14585 12122 14660 12123 14585 12123 14626 12123 14626 12124 14585 12124 14583 12124 14626 12125 14583 12125 14625 12125 14625 12126 14583 12126 14661 12126 14625 12127 14661 12127 14662 12127 14662 12128 14661 12128 14581 12128 14662 12129 14581 12129 14623 12129 14623 12130 14581 12130 14554 12130 14623 12131 14554 12131 14620 12131 14620 12132 14554 12132 14591 12132 14620 12133 14591 12133 14618 12133 14618 12134 14591 12134 14589 12134 14618 12135 14589 12135 14616 12135 14616 12136 14589 12136 14663 12136 14616 12137 14663 12137 14614 12137 14614 12138 14663 12138 14664 12138 14614 12139 14664 12139 14665 12139 14665 12140 14664 12140 14571 12140 14665 12141 14571 12141 14612 12141 14612 12142 14571 12142 14570 12142 14612 12143 14570 12143 14666 12143 14666 12144 14570 12144 14667 12144 14666 12145 14667 12145 14608 12145 14608 12146 14667 12146 14558 12146 14608 12147 14558 12147 14668 12147 14668 12148 14558 12148 14669 12148 14668 12149 14669 12149 14670 12149 14670 12150 14669 12150 14557 12150 14670 12151 14557 12151 14604 12151 14604 12152 14557 12152 14564 12152 14604 12153 14564 12153 14671 12153 14671 12154 14564 12154 14563 12154 14671 12155 14563 12155 14672 12155 14672 12156 14563 12156 14562 12156 14672 12157 14562 12157 14673 12157 14673 12158 14562 12158 14561 12158 14673 12159 14561 12159 14674 12159 14674 12160 14561 12160 14568 12160 14674 12161 14568 12161 14675 12161 14675 12162 14568 12162 14677 12162 14675 12163 14677 12163 14676 12163 14676 12164 14677 12164 14566 12164 14676 12165 14566 12165 14596 12165 14596 12166 14566 12166 14678 12166 14596 12167 14678 12167 14679 12167 14679 12168 14678 12168 14553 12168 14679 12169 14553 12169 14593 12169 14593 12170 14553 12170 14680 12170 14593 12171 14680 12171 14592 12171 14592 12172 14680 12172 14573 12172 14717 12173 14685 12173 14715 12173 14705 590 14681 590 14682 590 14682 590 14681 590 14814 590 14682 590 14814 590 14699 590 14688 590 14683 590 14684 590 14684 12174 14683 12174 14797 12174 14684 590 14797 590 14685 590 14685 12175 14797 12175 14796 12175 14685 590 14796 590 14715 590 14690 590 14691 590 14686 590 14686 12176 14691 12176 14687 12176 14686 590 14687 590 14688 590 14688 12177 14687 12177 14800 12177 14688 12178 14800 12178 14683 12178 14693 590 14695 590 14689 590 14689 12179 14695 12179 14805 12179 14689 12180 14805 12180 14690 12180 14690 12181 14805 12181 14803 12181 14690 12182 14803 12182 14691 12182 14692 590 14698 590 14693 590 14693 12183 14698 12183 14694 12183 14693 590 14694 590 14695 590 14709 590 14696 590 14692 590 14692 12184 14696 12184 14697 12184 14692 12185 14697 12185 14698 12185 14814 12186 14700 12186 14699 12186 14699 590 14700 590 14811 590 14699 12187 14811 12187 14701 12187 14701 590 14811 590 14706 590 14701 12188 14706 12188 14702 12188 14711 590 14712 590 14703 590 14703 590 14712 590 14704 590 14703 590 14704 590 14705 590 14705 590 14704 590 14815 590 14705 12189 14815 12189 14681 12189 14706 590 14707 590 14702 590 14702 590 14707 590 14708 590 14702 12190 14708 12190 14709 12190 14709 590 14708 590 14808 590 14709 12191 14808 12191 14696 12191 14710 12192 14721 12192 14711 12192 14711 12193 14721 12193 14818 12193 14711 12194 14818 12194 14712 12194 14719 590 14790 590 14713 590 14713 12195 14790 12195 14789 12195 14713 590 14789 590 14714 590 14715 12196 14795 12196 14717 12196 14717 590 14795 590 14716 590 14717 12197 14716 12197 14718 12197 14718 590 14716 590 14792 590 14718 12198 14792 12198 14719 12198 14719 12199 14792 12199 14791 12199 14719 590 14791 590 14790 590 14725 590 14821 590 14720 590 14720 12200 14821 12200 14820 12200 14720 590 14820 590 14710 590 14710 12201 14820 12201 14819 12201 14710 12202 14819 12202 14721 12202 14789 12203 14722 12203 14714 12203 14714 12204 14722 12204 14723 12204 14714 590 14723 590 14724 590 14724 590 14723 590 14726 590 14724 590 14726 590 14725 590 14725 12205 14726 12205 14824 12205 14725 12206 14824 12206 14821 12206 14732 12207 14728 12207 14727 12207 14727 12208 14728 12208 14729 12208 14727 12209 14730 12209 14732 12209 14732 10900 14730 10900 14731 10900 14732 10900 14731 10900 14733 10900 14733 11742 14731 11742 14734 11742 14733 10901 14734 10901 14804 10901 14804 10902 14734 10902 14735 10902 14804 12210 14735 12210 14736 12210 14736 12211 14735 12211 14737 12211 14736 12212 14737 12212 14802 12212 14802 12213 14737 12213 14739 12213 14802 12214 14739 12214 14738 12214 14738 12215 14739 12215 14740 12215 14738 12215 14740 12215 14801 12215 14801 12216 14740 12216 14741 12216 14801 12217 14741 12217 14742 12217 14742 12218 14741 12218 14743 12218 14742 12219 14743 12219 14799 12219 14799 10914 14743 10914 14744 10914 14799 12220 14744 12220 14798 12220 14798 10916 14744 10916 14746 10916 14798 10916 14746 10916 14745 10916 14745 10917 14746 10917 14747 10917 14745 10918 14747 10918 14748 10918 14748 12221 14747 12221 14749 12221 14748 12222 14749 12222 14794 12222 14794 21 14749 21 14750 21 14794 21 14750 21 14793 21 14793 12223 14750 12223 14752 12223 14793 12224 14752 12224 14751 12224 14751 10857 14752 10857 14753 10857 14751 10858 14753 10858 14754 10858 14754 10859 14753 10859 14755 10859 14754 10859 14755 10859 14788 10859 14788 12225 14755 12225 14756 12225 14788 10862 14756 10862 14787 10862 14787 11461 14756 11461 14757 11461 14787 11462 14757 11462 14758 11462 14758 11463 14757 11463 14759 11463 14758 11464 14759 11464 14825 11464 14825 12226 14759 12226 14760 12226 14825 12226 14760 12226 14823 12226 14823 12227 14760 12227 14761 12227 14823 12228 14761 12228 14822 12228 14822 12229 14761 12229 14763 12229 14822 12230 14763 12230 14762 12230 14762 12231 14763 12231 14764 12231 14762 10873 14764 10873 14766 10873 14766 10874 14764 10874 14765 10874 14766 12232 14765 12232 14767 12232 14767 10875 14765 10875 14769 10875 14767 10875 14769 10875 14768 10875 14768 10876 14769 10876 14770 10876 14768 10876 14770 10876 14817 10876 14817 10878 14770 10878 14771 10878 14817 12233 14771 12233 14816 12233 14816 12234 14771 12234 14773 12234 14816 12235 14773 12235 14772 12235 14772 12236 14773 12236 14775 12236 14772 12237 14775 12237 14774 12237 14774 12238 14775 12238 14776 12238 14774 12239 14776 12239 14777 12239 14777 12240 14776 12240 14778 12240 14777 12241 14778 12241 14813 12241 14813 11485 14778 11485 14779 11485 14813 12242 14779 12242 14812 12242 14812 12243 14779 12243 14780 12243 14812 12244 14780 12244 14810 12244 14810 12245 14780 12245 14781 12245 14810 12246 14781 12246 14782 12246 14782 12247 14781 12247 14783 12247 14782 12248 14783 12248 14784 12248 14784 12249 14783 12249 14785 12249 14784 12250 14785 12250 14809 12250 14809 12251 14785 12251 14786 12251 14809 12252 14786 12252 14807 12252 14807 12253 14786 12253 14729 12253 14807 10897 14729 10897 14806 10897 14806 12254 14729 12254 14728 12254 14758 12255 14722 12255 14787 12255 14787 12256 14722 12256 14789 12256 14787 12257 14789 12257 14788 12257 14788 12258 14789 12258 14790 12258 14788 12259 14790 12259 14754 12259 14754 12260 14790 12260 14791 12260 14754 10954 14791 10954 14751 10954 14751 12261 14791 12261 14792 12261 14751 12262 14792 12262 14793 12262 14793 12263 14792 12263 14716 12263 14793 12264 14716 12264 14794 12264 14794 11510 14716 11510 14795 11510 14794 12265 14795 12265 14748 12265 14748 12266 14795 12266 14715 12266 14748 10964 14715 10964 14745 10964 14745 12267 14715 12267 14796 12267 14745 10966 14796 10966 14798 10966 14798 12268 14796 12268 14797 12268 14798 12269 14797 12269 14799 12269 14799 12270 14797 12270 14683 12270 14799 12271 14683 12271 14742 12271 14742 12272 14683 12272 14800 12272 14742 12273 14800 12273 14801 12273 14801 12274 14800 12274 14687 12274 14801 12275 14687 12275 14738 12275 14738 12276 14687 12276 14691 12276 14738 12277 14691 12277 14802 12277 14802 12278 14691 12278 14803 12278 14802 12279 14803 12279 14736 12279 14736 12280 14803 12280 14805 12280 14736 12281 14805 12281 14804 12281 14804 12282 14805 12282 14695 12282 14804 12283 14695 12283 14733 12283 14733 12284 14695 12284 14694 12284 14733 12285 14694 12285 14732 12285 14732 12286 14694 12286 14698 12286 14732 12287 14698 12287 14728 12287 14728 12288 14698 12288 14697 12288 14728 12289 14697 12289 14806 12289 14806 12290 14697 12290 14696 12290 14806 12291 14696 12291 14807 12291 14807 12292 14696 12292 14808 12292 14807 10990 14808 10990 14809 10990 14809 12293 14808 12293 14708 12293 14809 12294 14708 12294 14784 12294 14784 12295 14708 12295 14707 12295 14784 12296 14707 12296 14782 12296 14782 12297 14707 12297 14706 12297 14782 12298 14706 12298 14810 12298 14810 12299 14706 12299 14811 12299 14810 12300 14811 12300 14812 12300 14812 12301 14811 12301 14700 12301 14812 12302 14700 12302 14813 12302 14813 12303 14700 12303 14814 12303 14813 12304 14814 12304 14777 12304 14777 12305 14814 12305 14681 12305 14777 12306 14681 12306 14774 12306 14774 12307 14681 12307 14815 12307 14774 12308 14815 12308 14772 12308 14772 12309 14815 12309 14704 12309 14772 12310 14704 12310 14816 12310 14816 12311 14704 12311 14712 12311 14816 12312 14712 12312 14817 12312 14817 12313 14712 12313 14818 12313 14817 10932 14818 10932 14768 10932 14768 12314 14818 12314 14721 12314 14768 12315 14721 12315 14767 12315 14767 12316 14721 12316 14819 12316 14767 12317 14819 12317 14766 12317 14766 10937 14819 10937 14820 10937 14766 12318 14820 12318 14762 12318 14762 12319 14820 12319 14821 12319 14762 10940 14821 10940 14822 10940 14822 12320 14821 12320 14824 12320 14822 12321 14824 12321 14823 12321 14823 12322 14824 12322 14726 12322 14823 12323 14726 12323 14825 12323 14825 12324 14726 12324 14723 12324 14825 12325 14723 12325 14758 12325 14758 12326 14723 12326 14722 12326 14862 12327 14869 12327 14826 12327 14826 12328 14869 12328 14827 12328 14826 12328 14827 12328 14828 12328 14828 12329 14827 12329 14879 12329 14828 12329 14879 12329 14829 12329 14829 12330 14879 12330 14830 12330 14829 12331 14830 12331 14831 12331 14831 12332 14830 12332 14832 12332 14831 12333 14832 12333 14833 12333 14833 10603 14832 10603 14876 10603 14833 12334 14876 12334 14834 12334 14834 12335 14876 12335 14877 12335 14834 10605 14877 10605 14835 10605 14835 12336 14877 12336 14836 12336 14835 12337 14836 12337 14838 12337 14838 12338 14836 12338 14837 12338 14838 12339 14837 12339 14839 12339 14839 12340 14837 12340 14840 12340 14839 12341 14840 12341 14841 12341 14841 12342 14840 12342 14842 12342 14841 12343 14842 12343 14843 12343 14843 10614 14842 10614 14872 10614 14843 12344 14872 12344 14844 12344 14844 12345 14872 12345 14892 12345 14844 12346 14892 12346 14845 12346 14845 12347 14892 12347 14893 12347 14845 12347 14893 12347 14846 12347 14846 12348 14893 12348 14895 12348 14846 12349 14895 12349 14847 12349 14847 12350 14895 12350 14849 12350 14847 12350 14849 12350 14848 12350 14848 12351 14849 12351 14888 12351 14848 12352 14888 12352 14850 12352 14850 12353 14888 12353 14890 12353 14850 12354 14890 12354 14851 12354 14851 12355 14890 12355 14852 12355 14851 12356 14852 12356 14853 12356 14853 12357 14852 12357 14854 12357 14853 12358 14854 12358 14855 12358 14855 12359 14854 12359 14884 12359 14855 12360 14884 12360 14857 12360 14857 12361 14884 12361 14856 12361 14857 12362 14856 12362 14858 12362 14858 12363 14856 12363 14863 12363 14858 12363 14863 12363 14859 12363 14859 12364 14863 12364 14861 12364 14859 12364 14861 12364 14860 12364 14860 12365 14861 12365 14864 12365 14860 12366 14864 12366 14862 12366 14862 12367 14864 12367 14869 12367 14863 590 14882 590 14861 590 14861 12368 14882 12368 14867 12368 14861 12369 14867 12369 14864 12369 14837 12370 14865 12370 14840 12370 14840 12371 14865 12371 14870 12371 14840 590 14870 590 14842 590 14869 590 14866 590 14827 590 14827 12372 14866 12372 14975 12372 14827 590 14975 590 14879 590 14867 590 14979 590 14864 590 14864 12373 14979 12373 14868 12373 14864 12374 14868 12374 14869 12374 14869 12375 14868 12375 14978 12375 14869 12376 14978 12376 14866 12376 14870 590 14871 590 14842 590 14842 12377 14871 12377 14961 12377 14842 590 14961 590 14872 590 14872 12378 14961 12378 14873 12378 14872 12379 14873 12379 14892 12379 14877 11827 14874 11827 14836 11827 14836 12380 14874 12380 14965 12380 14836 590 14965 590 14837 590 14837 12381 14965 12381 14963 12381 14837 12382 14963 12382 14865 12382 14895 590 14897 590 14849 590 14849 590 14897 590 14875 590 14849 590 14875 590 14888 590 14832 12383 14970 12383 14876 12383 14876 590 14970 590 14968 590 14876 10659 14968 10659 14877 10659 14877 12384 14968 12384 14966 12384 14877 590 14966 590 14874 590 14975 12385 14878 12385 14879 12385 14879 12386 14878 12386 14973 12386 14879 590 14973 590 14830 590 14830 10661 14973 10661 14880 10661 14830 590 14880 590 14832 590 14832 10662 14880 10662 14971 10662 14832 590 14971 590 14970 590 14884 12387 14887 12387 14856 12387 14856 12388 14887 12388 14881 12388 14856 590 14881 590 14863 590 14863 12389 14881 12389 14982 12389 14863 12390 14982 12390 14882 12390 14852 10424 14883 10424 14854 10424 14854 590 14883 590 14885 590 14854 590 14885 590 14884 590 14884 590 14885 590 14886 590 14884 12391 14886 12391 14887 12391 14875 12392 14987 12392 14888 12392 14888 12393 14987 12393 14889 12393 14888 590 14889 590 14890 590 14890 12394 14889 12394 14891 12394 14890 10653 14891 10653 14852 10653 14852 590 14891 590 14983 590 14852 590 14983 590 14883 590 14873 590 14960 590 14892 590 14892 12395 14960 12395 14894 12395 14892 590 14894 590 14893 590 14893 12396 14894 12396 14989 12396 14893 590 14989 590 14895 590 14895 12397 14989 12397 14896 12397 14895 590 14896 590 14897 590 14958 12398 14957 12398 14898 12398 14898 12399 14957 12399 14899 12399 14898 12400 14899 12400 14900 12400 14900 12401 14899 12401 14901 12401 14900 12402 14901 12402 14988 12402 14988 12403 14901 12403 14902 12403 14988 12404 14902 12404 14903 12404 14903 12405 14902 12405 14905 12405 14903 12405 14905 12405 14904 12405 14904 12406 14905 12406 14906 12406 14904 12407 14906 12407 14986 12407 14986 12408 14906 12408 14907 12408 14986 12409 14907 12409 14985 12409 14985 12410 14907 12410 14908 12410 14985 12411 14908 12411 14984 12411 14984 12412 14908 12412 14910 12412 14984 12413 14910 12413 14909 12413 14909 12414 14910 12414 14911 12414 14909 12415 14911 12415 14912 12415 14912 12416 14911 12416 14913 12416 14912 12417 14913 12417 14915 12417 14915 12418 14913 12418 14914 12418 14915 12419 14914 12419 14916 12419 14916 12420 14914 12420 14917 12420 14916 12421 14917 12421 14918 12421 14918 12422 14917 12422 14920 12422 14918 12423 14920 12423 14919 12423 14919 12424 14920 12424 14921 12424 14919 12425 14921 12425 14981 12425 14981 12426 14921 12426 14922 12426 14981 12427 14922 12427 14980 12427 14980 12428 14922 12428 14924 12428 14980 12428 14924 12428 14923 12428 14923 12429 14924 12429 14925 12429 14923 12430 14925 12430 14926 12430 14926 12431 14925 12431 14927 12431 14926 12432 14927 12432 14977 12432 14977 12433 14927 12433 14928 12433 14977 12434 14928 12434 14929 12434 14929 12435 14928 12435 14930 12435 14929 12436 14930 12436 14976 12436 14976 12437 14930 12437 14931 12437 14976 12437 14931 12437 14933 12437 14933 12438 14931 12438 14932 12438 14933 12439 14932 12439 14974 12439 14974 12440 14932 12440 14934 12440 14974 12441 14934 12441 14935 12441 14935 12442 14934 12442 14936 12442 14935 12443 14936 12443 14972 12443 14972 12444 14936 12444 14938 12444 14972 12445 14938 12445 14937 12445 14937 12446 14938 12446 14939 12446 14937 12447 14939 12447 14969 12447 14969 12448 14939 12448 14940 12448 14969 12448 14940 12448 14967 12448 14967 12449 14940 12449 14941 12449 14967 12450 14941 12450 14942 12450 14942 12451 14941 12451 14943 12451 14942 12451 14943 12451 14964 12451 14964 12452 14943 12452 14944 12452 14964 12453 14944 12453 14946 12453 14946 12454 14944 12454 14945 12454 14946 12455 14945 12455 14947 12455 14947 12456 14945 12456 14948 12456 14947 12457 14948 12457 14949 12457 14949 12458 14948 12458 14950 12458 14949 12459 14950 12459 14962 12459 14962 12460 14950 12460 14952 12460 14962 12461 14952 12461 14951 12461 14951 12462 14952 12462 14953 12462 14951 12463 14953 12463 14954 12463 14954 12464 14953 12464 14955 12464 14954 12465 14955 12465 14959 12465 14959 12466 14955 12466 14956 12466 14959 12467 14956 12467 14958 12467 14958 12468 14956 12468 14957 12468 14958 12469 14960 12469 14959 12469 14959 12470 14960 12470 14873 12470 14959 12471 14873 12471 14954 12471 14954 12472 14873 12472 14961 12472 14954 12473 14961 12473 14951 12473 14951 12474 14961 12474 14871 12474 14951 12475 14871 12475 14962 12475 14962 12476 14871 12476 14870 12476 14962 12477 14870 12477 14949 12477 14949 12478 14870 12478 14865 12478 14949 12479 14865 12479 14947 12479 14947 12480 14865 12480 14963 12480 14947 12481 14963 12481 14946 12481 14946 12482 14963 12482 14965 12482 14946 12483 14965 12483 14964 12483 14964 12484 14965 12484 14874 12484 14964 12485 14874 12485 14942 12485 14942 12486 14874 12486 14966 12486 14942 12487 14966 12487 14967 12487 14967 12488 14966 12488 14968 12488 14967 12489 14968 12489 14969 12489 14969 12490 14968 12490 14970 12490 14969 12491 14970 12491 14937 12491 14937 12492 14970 12492 14971 12492 14937 12493 14971 12493 14972 12493 14972 12494 14971 12494 14880 12494 14972 12495 14880 12495 14935 12495 14935 12496 14880 12496 14973 12496 14935 12497 14973 12497 14974 12497 14974 12498 14973 12498 14878 12498 14974 12499 14878 12499 14933 12499 14933 12500 14878 12500 14975 12500 14933 12501 14975 12501 14976 12501 14976 12502 14975 12502 14866 12502 14976 12503 14866 12503 14929 12503 14929 12504 14866 12504 14978 12504 14929 12505 14978 12505 14977 12505 14977 12506 14978 12506 14868 12506 14977 12507 14868 12507 14926 12507 14926 12508 14868 12508 14979 12508 14926 12509 14979 12509 14923 12509 14923 12510 14979 12510 14867 12510 14923 12511 14867 12511 14980 12511 14980 12512 14867 12512 14882 12512 14980 12513 14882 12513 14981 12513 14981 12514 14882 12514 14982 12514 14981 12515 14982 12515 14919 12515 14919 12516 14982 12516 14881 12516 14919 12517 14881 12517 14918 12517 14918 12518 14881 12518 14887 12518 14918 12519 14887 12519 14916 12519 14916 12520 14887 12520 14886 12520 14916 12521 14886 12521 14915 12521 14915 12522 14886 12522 14885 12522 14915 12523 14885 12523 14912 12523 14912 12524 14885 12524 14883 12524 14912 12525 14883 12525 14909 12525 14909 12526 14883 12526 14983 12526 14909 12527 14983 12527 14984 12527 14984 12528 14983 12528 14891 12528 14984 12529 14891 12529 14985 12529 14985 12530 14891 12530 14889 12530 14985 12531 14889 12531 14986 12531 14986 12532 14889 12532 14987 12532 14986 12533 14987 12533 14904 12533 14904 12534 14987 12534 14875 12534 14904 12535 14875 12535 14903 12535 14903 12536 14875 12536 14897 12536 14903 12537 14897 12537 14988 12537 14988 12538 14897 12538 14896 12538 14988 12539 14896 12539 14900 12539 14900 12540 14896 12540 14989 12540 14900 12541 14989 12541 14898 12541 14898 12542 14989 12542 14894 12542 14898 12543 14894 12543 14958 12543 14958 12544 14894 12544 14960 12544 14990 12545 14992 12545 14991 12545 14991 590 14992 590 15011 590 14991 590 15011 590 15072 590 15065 590 14993 590 15066 590 15066 12546 14993 12546 14994 12546 15066 12547 14994 12547 14990 12547 14990 12548 14994 12548 14995 12548 14990 12549 14995 12549 14992 12549 15025 590 14996 590 14997 590 14997 590 14996 590 14998 590 14997 590 14998 590 15038 590 15005 590 14999 590 15000 590 15000 590 14999 590 15018 590 15000 590 15018 590 15020 590 15008 590 15010 590 15001 590 15001 590 15010 590 15002 590 15001 12550 15002 12550 15043 12550 15043 590 15002 590 15003 590 15043 590 15003 590 15005 590 15005 12551 15003 12551 15004 12551 15005 590 15004 590 14999 590 15015 590 15006 590 15076 590 15076 12552 15006 12552 15007 12552 15076 590 15007 590 15008 590 15008 590 15007 590 15009 590 15008 12553 15009 12553 15010 12553 15011 590 15012 590 15072 590 15072 590 15012 590 15013 590 15072 12554 15013 12554 15073 12554 15073 12555 15013 12555 15014 12555 15073 590 15014 590 15015 590 15015 12556 15014 12556 15016 12556 15015 12557 15016 12557 15006 12557 15056 590 15036 590 15058 590 15058 590 15036 590 15017 590 15058 12558 15017 12558 15060 12558 15060 590 15017 590 15026 590 15060 590 15026 590 15062 590 15018 590 15019 590 15020 590 15020 12559 15019 12559 15021 12559 15020 590 15021 590 15022 590 15022 12560 15021 12560 15023 12560 15022 590 15023 590 15025 590 15025 12561 15023 12561 15024 12561 15025 12562 15024 12562 14996 12562 15026 12563 15027 12563 15062 12563 15062 590 15027 590 15028 590 15062 590 15028 590 15029 590 15029 12564 15028 12564 15030 12564 15029 590 15030 590 15065 590 15065 12565 15030 12565 15031 12565 15065 12566 15031 12566 14993 12566 15052 590 15032 590 15033 590 15033 12567 15032 12567 15034 12567 15033 590 15034 590 15056 590 15056 590 15034 590 15035 590 15056 590 15035 590 15036 590 14998 590 15037 590 15038 590 15038 590 15037 590 15040 590 15038 590 15040 590 15039 590 15039 12568 15040 12568 15041 12568 15039 590 15041 590 15052 590 15052 12569 15041 12569 15042 12569 15052 12570 15042 12570 15032 12570 15079 12571 15043 12571 15044 12571 15044 12572 15043 12572 15005 12572 15044 12573 15005 12573 15045 12573 15045 12574 15005 12574 15000 12574 15045 12575 15000 12575 15046 12575 15046 12576 15000 12576 15020 12576 15046 12577 15020 12577 15047 12577 15047 12578 15020 12578 15022 12578 15047 12579 15022 12579 15048 12579 15048 12580 15022 12580 15025 12580 15048 12581 15025 12581 15049 12581 15049 12582 15025 12582 14997 12582 15049 12583 14997 12583 15050 12583 15050 49 14997 49 15038 49 15050 49 15038 49 15051 49 15051 12584 15038 12584 15039 12584 15051 12585 15039 12585 15053 12585 15053 12586 15039 12586 15052 12586 15053 12587 15052 12587 15054 12587 15054 12588 15052 12588 15033 12588 15054 12589 15033 12589 15055 12589 15055 12590 15033 12590 15056 12590 15055 12591 15056 12591 15057 12591 15057 12592 15056 12592 15058 12592 15057 12593 15058 12593 15059 12593 15059 12594 15058 12594 15060 12594 15059 12594 15060 12594 15061 12594 15061 12595 15060 12595 15062 12595 15061 12595 15062 12595 15063 12595 15063 12596 15062 12596 15029 12596 15063 12597 15029 12597 15064 12597 15064 12598 15029 12598 15065 12598 15064 12599 15065 12599 15067 12599 15067 12600 15065 12600 15066 12600 15067 12600 15066 12600 15068 12600 15068 12601 15066 12601 14990 12601 15068 12601 14990 12601 15069 12601 15069 12602 14990 12602 14991 12602 15069 12602 14991 12602 15070 12602 15070 50 14991 50 15072 50 15070 50 15072 50 15071 50 15071 12603 15072 12603 15073 12603 15071 12604 15073 12604 15074 12604 15074 12605 15073 12605 15015 12605 15074 12605 15015 12605 15075 12605 15075 12606 15015 12606 15076 12606 15075 12606 15076 12606 15077 12606 15077 12607 15076 12607 15008 12607 15077 12607 15008 12607 15078 12607 15078 12608 15008 12608 15001 12608 15078 12609 15001 12609 15079 12609 15079 12610 15001 12610 15043 12610 15081 11720 15159 11720 15080 11720 15080 12611 15159 12611 15158 12611 15080 12612 15082 12612 15081 12612 15081 12613 15082 12613 15084 12613 15081 12614 15084 12614 15083 12614 15083 10857 15084 10857 15086 10857 15083 12615 15086 12615 15085 12615 15085 10860 15086 10860 15087 10860 15085 10860 15087 10860 15088 10860 15088 12616 15087 12616 15089 12616 15088 10862 15089 10862 15090 10862 15090 12617 15089 12617 15091 12617 15090 12618 15091 12618 15093 12618 15093 10865 15091 10865 15092 10865 15093 11725 15092 11725 15095 11725 15095 12619 15092 12619 15094 12619 15095 10868 15094 10868 15096 10868 15096 11468 15094 11468 15098 11468 15096 12620 15098 12620 15097 12620 15097 12621 15098 12621 15099 12621 15097 12622 15099 12622 15100 12622 15100 12623 15099 12623 15101 12623 15100 12624 15101 12624 15102 12624 15102 11729 15101 11729 15103 11729 15102 11472 15103 11472 15105 11472 15105 12625 15103 12625 15104 12625 15105 12625 15104 12625 15106 12625 15106 10876 15104 10876 15107 10876 15106 10876 15107 10876 15108 10876 15108 10877 15107 10877 15109 10877 15108 12233 15109 12233 15111 12233 15111 12626 15109 12626 15110 12626 15111 12626 15110 12626 15112 12626 15112 12627 15110 12627 15113 12627 15112 12628 15113 12628 15114 12628 15114 11733 15113 11733 15115 11733 15114 11734 15115 11734 15116 11734 15116 12629 15115 12629 15118 12629 15116 12630 15118 12630 15117 12630 15117 12631 15118 12631 15119 12631 15117 12631 15119 12631 15120 12631 15120 12632 15119 12632 15122 12632 15120 12632 15122 12632 15121 12632 15121 12633 15122 12633 15124 12633 15121 12634 15124 12634 15123 12634 15123 12635 15124 12635 15125 12635 15123 12636 15125 12636 15126 12636 15126 10894 15125 10894 15127 10894 15126 12637 15127 12637 15129 12637 15129 12638 15127 12638 15128 12638 15129 12638 15128 12638 15130 12638 15130 11497 15128 11497 15131 11497 15130 12639 15131 12639 15132 12639 15132 10899 15131 10899 15133 10899 15132 10899 15133 10899 15135 10899 15135 12640 15133 12640 15134 12640 15135 12640 15134 12640 15136 12640 15136 12641 15134 12641 15137 12641 15136 12642 15137 12642 15138 12642 15138 11435 15137 11435 15139 11435 15138 11743 15139 11743 15140 11743 15140 12643 15139 12643 15141 12643 15140 12644 15141 12644 15142 12644 15142 12645 15141 12645 15143 12645 15142 12646 15143 12646 15144 12646 15144 10908 15143 10908 15145 10908 15144 12647 15145 12647 15146 12647 15146 11746 15145 11746 15147 11746 15146 11747 15147 11747 15149 11747 15149 12648 15147 12648 15148 12648 15149 12649 15148 12649 15150 12649 15150 12650 15148 12650 15151 12650 15150 12651 15151 12651 15153 12651 15153 10915 15151 10915 15152 10915 15153 10915 15152 10915 15154 10915 15154 10918 15152 10918 15155 10918 15154 10918 15155 10918 15156 10918 15156 10919 15155 10919 15158 10919 15156 12222 15158 12222 15157 12222 15157 12652 15158 12652 15159 12652 15176 590 15160 590 15161 590 15161 590 15160 590 15162 590 15161 590 15162 590 15207 590 15191 10351 15163 10351 15164 10351 15164 12653 15163 12653 15165 12653 15164 12654 15165 12654 15179 12654 15166 590 15167 590 15169 590 15169 12655 15167 12655 15168 12655 15169 12656 15168 12656 15170 12656 15197 590 15198 590 15172 590 15172 12657 15198 12657 15171 12657 15172 590 15171 590 15184 590 15217 590 15174 590 15173 590 15173 12658 15174 12658 15175 12658 15173 10367 15175 10367 15176 10367 15176 590 15175 590 15177 590 15176 10368 15177 10368 15160 10368 15165 590 15178 590 15179 590 15179 12659 15178 12659 15180 12659 15179 12660 15180 12660 15181 12660 15181 12661 15180 12661 15182 12661 15181 590 15182 590 15166 590 15166 12662 15182 12662 15183 12662 15166 11840 15183 11840 15167 11840 15171 12663 15185 12663 15184 12663 15184 12664 15185 12664 15186 12664 15184 10333 15186 10333 15188 10333 15188 590 15186 590 15187 590 15188 590 15187 590 15189 590 15189 590 15187 590 15190 590 15189 590 15190 590 15191 590 15191 590 15190 590 15192 590 15191 590 15192 590 15163 590 15224 12665 15193 12665 15194 12665 15194 12666 15193 12666 15195 12666 15194 12667 15195 12667 15197 12667 15197 12668 15195 12668 15196 12668 15197 12661 15196 12661 15198 12661 15199 12669 15201 12669 15200 12669 15200 12670 15201 12670 15202 12670 15200 12671 15202 12671 15203 12671 15203 12672 15202 12672 15204 12672 15203 12673 15204 12673 15219 12673 15162 12674 15205 12674 15207 12674 15207 12675 15205 12675 15206 12675 15207 12676 15206 12676 15208 12676 15208 10348 15206 10348 15209 10348 15208 10349 15209 10349 15199 10349 15199 590 15209 590 15210 590 15199 12677 15210 12677 15201 12677 15168 590 15211 590 15170 590 15170 12678 15211 12678 15213 12678 15170 590 15213 590 15212 590 15212 12679 15213 12679 15214 12679 15212 12680 15214 12680 15215 12680 15215 590 15214 590 15216 590 15215 10365 15216 10365 15217 10365 15217 12681 15216 12681 15218 12681 15217 590 15218 590 15174 590 15204 590 15220 590 15219 590 15219 12682 15220 12682 15221 12682 15219 590 15221 590 15222 590 15222 10334 15221 10334 15223 10334 15222 590 15223 590 15224 590 15224 12683 15223 12683 15225 12683 15224 590 15225 590 15193 590 15238 590 15226 590 15227 590 15227 12684 15226 12684 15228 12684 15227 12685 15228 12685 15232 12685 15254 12686 15229 12686 15230 12686 15230 590 15229 590 15231 590 15230 12687 15231 12687 15248 12687 15228 12688 15365 12688 15232 12688 15232 12689 15365 12689 15233 12689 15232 12690 15233 12690 15234 12690 15235 590 15236 590 15237 590 15237 590 15236 590 15369 590 15237 590 15369 590 15238 590 15238 12691 15369 12691 15239 12691 15238 12692 15239 12692 15226 12692 15240 590 15344 590 15241 590 15241 12693 15344 12693 15242 12693 15241 590 15242 590 15235 590 15235 12694 15242 12694 15243 12694 15235 12695 15243 12695 15236 12695 15256 11818 15257 11818 15244 11818 15244 590 15257 590 15245 590 15244 12696 15245 12696 15240 12696 15240 590 15245 590 15246 590 15240 12697 15246 12697 15344 12697 15274 12698 15247 12698 15249 12698 15231 590 15359 590 15248 590 15248 12699 15359 12699 15357 12699 15248 590 15357 590 15249 590 15249 12700 15357 12700 15355 12700 15249 12701 15355 12701 15274 12701 15267 12702 15250 12702 15251 12702 15251 12703 15250 12703 15252 12703 15251 590 15252 590 15254 590 15254 590 15252 590 15253 590 15254 590 15253 590 15229 590 15272 590 15273 590 15256 590 15256 12704 15273 12704 15255 12704 15256 590 15255 590 15257 590 15258 590 15351 590 15259 590 15259 12705 15351 12705 15349 12705 15259 590 15349 590 15268 590 15277 590 15260 590 15261 590 15261 12706 15260 12706 15262 12706 15261 590 15262 590 15258 590 15258 12707 15262 12707 15263 12707 15258 12708 15263 12708 15351 12708 15233 590 15363 590 15234 590 15234 12709 15363 12709 15264 12709 15234 590 15264 590 15266 590 15266 590 15264 590 15265 590 15266 590 15265 590 15267 590 15267 12710 15265 12710 15361 12710 15267 590 15361 590 15250 590 15349 590 15348 590 15268 590 15268 12711 15348 12711 15269 12711 15268 590 15269 590 15270 590 15270 590 15269 590 15271 590 15270 590 15271 590 15272 590 15272 12712 15271 12712 15346 12712 15272 12713 15346 12713 15273 12713 15274 590 15275 590 15247 590 15247 12714 15275 12714 15276 12714 15247 590 15276 590 15277 590 15277 12715 15276 12715 15278 12715 15277 12716 15278 12716 15260 12716 15281 12717 15342 12717 15279 12717 15279 12718 15342 12718 15341 12718 15279 12719 15280 12719 15281 12719 15281 12720 15280 12720 15282 12720 15281 12721 15282 12721 15283 12721 15283 12722 15282 12722 15284 12722 15283 12723 15284 12723 15353 12723 15353 11852 15284 11852 15285 11852 15353 11852 15285 11852 15352 11852 15352 12724 15285 12724 15286 12724 15352 12725 15286 12725 15287 12725 15287 11306 15286 11306 15288 11306 15287 12726 15288 12726 15350 12726 15350 12727 15288 12727 15289 12727 15350 11854 15289 11854 15290 11854 15290 12728 15289 12728 15291 12728 15290 12729 15291 12729 15292 12729 15292 12730 15291 12730 15293 12730 15292 12731 15293 12731 15347 12731 15347 12732 15293 12732 15294 12732 15347 12733 15294 12733 15296 12733 15296 12734 15294 12734 15295 12734 15296 12735 15295 12735 15297 12735 15297 12736 15295 12736 15298 12736 15297 11318 15298 11318 15300 11318 15300 12737 15298 12737 15299 12737 15300 12738 15299 12738 15301 12738 15301 6 15299 6 15302 6 15301 6 15302 6 15303 6 15303 12739 15302 12739 15304 12739 15303 12740 15304 12740 15345 12740 15345 11250 15304 11250 15305 11250 15345 12741 15305 12741 15306 12741 15306 11252 15305 11252 15307 11252 15306 12742 15307 12742 15343 12742 15343 12743 15307 12743 15308 12743 15343 12744 15308 12744 15309 12744 15309 12745 15308 12745 15310 12745 15309 12746 15310 12746 15370 12746 15370 11865 15310 11865 15311 11865 15370 12747 15311 12747 15312 12747 15312 11867 15311 11867 15313 11867 15312 12748 15313 12748 15368 12748 15368 12749 15313 12749 15314 12749 15368 11261 15314 11261 15367 11261 15367 12750 15314 12750 15315 12750 15367 12751 15315 12751 15366 12751 15366 11869 15315 11869 15316 11869 15366 11869 15316 11869 15364 11869 15364 12752 15316 12752 15317 12752 15364 12753 15317 12753 15318 12753 15318 12754 15317 12754 15319 12754 15318 12755 15319 12755 15362 12755 15362 12756 15319 12756 15320 12756 15362 12757 15320 12757 15321 12757 15321 12758 15320 12758 15322 12758 15321 12758 15322 12758 15323 12758 15323 12759 15322 12759 15324 12759 15323 12760 15324 12760 15325 12760 15325 12761 15324 12761 15326 12761 15325 12762 15326 12762 15327 12762 15327 12763 15326 12763 15329 12763 15327 12764 15329 12764 15328 12764 15328 12765 15329 12765 15330 12765 15328 12766 15330 12766 15331 12766 15331 11876 15330 11876 15332 11876 15331 12767 15332 12767 15333 12767 15333 12768 15332 12768 15334 12768 15333 11877 15334 11877 15360 11877 15360 12769 15334 12769 15335 12769 15360 12770 15335 12770 15358 12770 15358 12771 15335 12771 15337 12771 15358 12772 15337 12772 15336 12772 15336 12773 15337 12773 15338 12773 15336 12774 15338 12774 15356 12774 15356 12775 15338 12775 15339 12775 15356 12776 15339 12776 15340 12776 15340 12777 15339 12777 15341 12777 15340 12777 15341 12777 15354 12777 15354 12718 15341 12718 15342 12718 15370 12778 15243 12778 15309 12778 15309 12779 15243 12779 15242 12779 15309 12780 15242 12780 15343 12780 15343 12781 15242 12781 15344 12781 15343 12782 15344 12782 15306 12782 15306 12783 15344 12783 15246 12783 15306 12784 15246 12784 15345 12784 15345 12785 15246 12785 15245 12785 15345 12786 15245 12786 15303 12786 15303 12787 15245 12787 15257 12787 15303 11893 15257 11893 15301 11893 15301 11894 15257 11894 15255 11894 15301 12788 15255 12788 15300 12788 15300 12789 15255 12789 15273 12789 15300 12790 15273 12790 15297 12790 15297 12791 15273 12791 15346 12791 15297 12792 15346 12792 15296 12792 15296 12793 15346 12793 15271 12793 15296 12794 15271 12794 15347 12794 15347 12795 15271 12795 15269 12795 15347 12796 15269 12796 15292 12796 15292 12797 15269 12797 15348 12797 15292 12798 15348 12798 15290 12798 15290 12799 15348 12799 15349 12799 15290 12800 15349 12800 15350 12800 15350 12801 15349 12801 15351 12801 15350 11907 15351 11907 15287 11907 15287 11908 15351 11908 15263 11908 15287 12802 15263 12802 15352 12802 15352 12803 15263 12803 15262 12803 15352 12804 15262 12804 15353 12804 15353 12805 15262 12805 15260 12805 15353 12806 15260 12806 15283 12806 15283 12807 15260 12807 15278 12807 15283 12808 15278 12808 15281 12808 15281 12809 15278 12809 15276 12809 15281 12810 15276 12810 15342 12810 15342 12811 15276 12811 15275 12811 15342 12812 15275 12812 15354 12812 15354 12813 15275 12813 15274 12813 15354 12814 15274 12814 15340 12814 15340 12815 15274 12815 15355 12815 15340 12816 15355 12816 15356 12816 15356 12817 15355 12817 15357 12817 15356 12818 15357 12818 15336 12818 15336 12819 15357 12819 15359 12819 15336 12820 15359 12820 15358 12820 15358 12821 15359 12821 15231 12821 15358 12822 15231 12822 15360 12822 15360 12823 15231 12823 15229 12823 15360 12824 15229 12824 15333 12824 15333 12825 15229 12825 15253 12825 15333 11928 15253 11928 15331 11928 15331 12826 15253 12826 15252 12826 15331 12827 15252 12827 15328 12827 15328 12828 15252 12828 15250 12828 15328 12829 15250 12829 15327 12829 15327 12830 15250 12830 15361 12830 15327 12831 15361 12831 15325 12831 15325 12832 15361 12832 15265 12832 15325 12833 15265 12833 15323 12833 15323 12834 15265 12834 15264 12834 15323 12835 15264 12835 15321 12835 15321 12836 15264 12836 15363 12836 15321 12837 15363 12837 15362 12837 15362 12838 15363 12838 15233 12838 15362 12839 15233 12839 15318 12839 15318 12840 15233 12840 15365 12840 15318 12841 15365 12841 15364 12841 15364 12842 15365 12842 15228 12842 15364 12843 15228 12843 15366 12843 15366 12844 15228 12844 15226 12844 15366 12845 15226 12845 15367 12845 15367 12846 15226 12846 15239 12846 15367 12847 15239 12847 15368 12847 15368 12848 15239 12848 15369 12848 15368 12849 15369 12849 15312 12849 15312 12850 15369 12850 15236 12850 15312 12851 15236 12851 15370 12851 15370 12852 15236 12852 15243 12852 15371 12853 15372 12853 15373 12853 15373 12853 15372 12853 15374 12853 15414 12854 15375 12854 15376 12854 15414 12855 15376 12855 15377 12855 15377 12856 15376 12856 15378 12856 15377 12856 15378 12856 15435 12856 15435 12857 15378 12857 15379 12857 15435 12858 15379 12858 15380 12858 15380 12859 15379 12859 15381 12859 15380 12860 15381 12860 15437 12860 15437 12861 15381 12861 15382 12861 15437 12862 15382 12862 15383 12862 15383 12863 15382 12863 15384 12863 15383 12864 15384 12864 15423 12864 15423 12865 15384 12865 15385 12865 15423 12866 15385 12866 15386 12866 15386 12867 15385 12867 15388 12867 15386 12868 15388 12868 15387 12868 15387 12869 15388 12869 15389 12869 15387 12869 15389 12869 15425 12869 15425 12870 15389 12870 15374 12870 15425 12871 15374 12871 15372 12871 15390 12872 15432 12872 15391 12872 15391 12872 15432 12872 15392 12872 15406 960 15393 960 15394 960 15406 960 15394 960 15395 960 15395 12873 15394 12873 15396 12873 15395 960 15396 960 15397 960 15398 12874 15399 12874 15371 12874 15397 12875 15396 12875 15400 12875 15400 12876 15396 12876 15401 12876 15400 960 15401 960 15402 960 15402 12877 15401 12877 15404 12877 15402 960 15404 960 15403 960 15403 960 15404 960 15405 960 15405 12878 15404 12878 15417 12878 15405 960 15417 960 15416 960 15393 960 15406 960 15408 960 15408 960 15406 960 15407 960 15408 960 15407 960 15430 960 15371 960 15399 960 15372 960 15436 960 15412 960 15435 960 15399 960 15409 960 15372 960 15372 960 15409 960 15410 960 15372 960 15410 960 15425 960 15425 12879 15410 12879 15411 12879 15435 960 15412 960 15377 960 15377 12879 15412 12879 15413 12879 15377 960 15413 960 15414 960 15414 960 15413 960 15415 960 15414 960 15415 960 15427 960 15416 960 15417 960 15418 960 15418 12880 15417 12880 15420 12880 15418 960 15420 960 15419 960 15419 12873 15420 12873 15421 12873 15419 960 15421 960 15390 960 15390 960 15421 960 15422 960 15390 12881 15422 12881 15432 12881 15438 12882 15423 12882 15424 12882 15424 960 15423 960 15386 960 15424 7380 15386 7380 15411 7380 15411 12883 15386 12883 15387 12883 15411 12884 15387 12884 15425 12884 15415 12885 15426 12885 15427 12885 15427 12886 15426 12886 15428 12886 15427 960 15428 960 15407 960 15407 12887 15428 12887 15429 12887 15407 12888 15429 12888 15430 12888 15430 960 15429 960 15434 960 15422 960 15431 960 15432 960 15432 12889 15431 12889 15433 12889 15432 960 15433 960 15371 960 15371 12890 15433 12890 15434 12890 15371 12891 15434 12891 15398 12891 15398 960 15434 960 15429 960 15435 12892 15380 12892 15436 12892 15436 960 15380 960 15437 960 15436 12893 15437 12893 15438 12893 15438 960 15437 960 15383 960 15438 960 15383 960 15423 960 15441 960 15486 960 15439 960 15439 12894 15440 12894 15441 12894 15441 12895 15440 12895 15442 12895 15441 12896 15442 12896 15443 12896 15443 960 15442 960 15447 960 15481 960 15483 960 15444 960 15444 960 15483 960 15445 960 15444 960 15445 960 15447 960 15447 960 15445 960 15446 960 15447 960 15446 960 15443 960 15467 12897 15469 12897 15453 12897 15453 960 15469 960 15450 960 15448 960 15456 960 15449 960 15449 960 15456 960 15451 960 15449 960 15451 960 15450 960 15450 960 15451 960 15452 960 15450 960 15452 960 15453 960 15454 960 15465 960 15448 960 15448 12898 15465 12898 15455 12898 15448 12899 15455 12899 15456 12899 15457 12900 15491 12900 15458 12900 15458 12901 15491 12901 15459 12901 15458 12902 15459 12902 15460 12902 15460 12903 15459 12903 15461 12903 15460 12904 15461 12904 15462 12904 15462 960 15461 960 15463 960 15462 960 15463 960 15454 960 15454 12905 15463 12905 15464 12905 15454 12906 15464 12906 15465 12906 15488 12907 15466 12907 15467 12907 15467 960 15466 960 15468 960 15467 960 15468 960 15469 960 15470 12908 15471 12908 15472 12908 15472 960 15471 960 15473 960 15472 960 15473 960 15475 960 15475 12909 15473 12909 15474 12909 15475 960 15474 960 15477 960 15477 960 15474 960 15476 960 15477 960 15476 960 15480 960 15476 960 15478 960 15480 960 15480 12910 15478 12910 15479 12910 15480 960 15479 960 15481 960 15481 12911 15479 12911 15482 12911 15481 12912 15482 12912 15483 12912 15491 960 15484 960 15486 960 15486 12913 15484 12913 15485 12913 15486 12914 15485 12914 15439 12914 15471 12915 15487 12915 15488 12915 15488 12916 15487 12916 15489 12916 15488 12917 15489 12917 15466 12917 15457 960 15490 960 15491 960 15491 12918 15490 12918 15487 12918 15491 12919 15487 12919 15484 12919 15484 960 15487 960 15471 960 15484 960 15471 960 15492 960 15492 960 15471 960 15470 960 15493 12920 15494 12920 15495 12920 15493 12921 15495 12921 15496 12921 15496 12922 15495 12922 15497 12922 15496 12923 15497 12923 15499 12923 15499 12924 15497 12924 15498 12924 15499 12925 15498 12925 15500 12925 15500 12926 15498 12926 15501 12926 15500 12927 15501 12927 15502 12927 15502 12928 15501 12928 15503 12928 15502 12929 15503 12929 15504 12929 15504 12930 15503 12930 15506 12930 15504 12931 15506 12931 15505 12931 15505 12932 15506 12932 15507 12932 15505 12933 15507 12933 15508 12933 15508 12934 15507 12934 15509 12934 15508 12935 15509 12935 15510 12935 15510 12936 15509 12936 15511 12936 15510 12937 15511 12937 15513 12937 15513 12938 15511 12938 15512 12938 15513 12939 15512 12939 15514 12939 15514 12940 15512 12940 15515 12940 15514 12941 15515 12941 15517 12941 15517 12942 15515 12942 15516 12942 15517 12943 15516 12943 15518 12943 15518 12944 15516 12944 15519 12944 15518 12945 15519 12945 15520 12945 15520 12946 15519 12946 15521 12946 15520 12947 15521 12947 15522 12947 15522 12948 15521 12948 15523 12948 15522 12949 15523 12949 15525 12949 15525 12950 15523 12950 15524 12950 15525 12951 15524 12951 15526 12951 15526 12952 15524 12952 15528 12952 15526 12953 15528 12953 15527 12953 15527 12954 15528 12954 15529 12954 15527 12955 15529 12955 15530 12955 15530 12956 15529 12956 15531 12956 15530 12957 15531 12957 15532 12957 15532 12958 15531 12958 15533 12958 15532 12959 15533 12959 15534 12959 15535 12960 15537 12960 15536 12960 15536 12961 15537 12961 15538 12961 15589 12962 15540 12962 15539 12962 15539 12962 15540 12962 15541 12962 15542 12963 15555 12963 15543 12963 15543 12963 15555 12963 15544 12963 15552 12882 15546 12882 15545 12882 15545 960 15546 960 15547 960 15545 7380 15547 7380 15548 7380 15540 960 15549 960 15566 960 15566 12873 15549 12873 15550 12873 15551 12893 15553 12893 15552 12893 15552 960 15553 960 15554 960 15552 960 15554 960 15546 960 15594 12964 15555 12964 15556 12964 15556 12965 15555 12965 15542 12965 15556 960 15542 960 15557 960 15557 12966 15542 12966 15558 12966 15557 960 15558 960 15559 960 15559 12884 15558 12884 15560 12884 15559 960 15560 960 15551 960 15551 12967 15560 12967 15561 12967 15551 960 15561 960 15553 960 15567 12968 15563 12968 15562 12968 15562 960 15563 960 15564 960 15562 4639 15564 4639 15550 4639 15550 12969 15564 12969 15565 12969 15550 12970 15565 12970 15566 12970 15576 12971 15568 12971 15567 12971 15567 960 15568 960 15569 960 15567 960 15569 960 15563 960 15583 960 15586 960 15584 960 15570 12964 15592 12964 15571 12964 15571 960 15592 960 15572 960 15571 960 15572 960 15573 960 15573 12972 15572 12972 15574 12972 15573 960 15574 960 15575 960 15575 12970 15574 12970 50382 12970 15575 960 50382 960 15576 960 15589 960 15577 960 15540 960 15540 12973 15577 12973 15578 12973 15540 960 15578 960 15549 960 15547 960 15579 960 15548 960 15548 12884 15579 12884 15581 12884 15548 960 15581 960 15580 960 15580 12974 15581 12974 15583 12974 15580 960 15583 960 15582 960 15582 960 15583 960 15584 960 15592 960 15585 960 15586 960 15586 12975 15585 12975 15587 12975 15586 12886 15587 12886 15584 12886 15555 960 15588 960 15589 960 15589 12976 15588 12976 15590 12976 15589 12889 15590 12889 15577 12889 15570 960 15591 960 15592 960 15592 12977 15591 12977 15588 12977 15592 960 15588 960 15585 960 15585 960 15588 960 15555 960 15585 12978 15555 12978 15593 12978 15593 12874 15555 12874 15594 12874 15637 12979 15603 12979 15595 12979 15595 12980 15603 12980 15596 12980 15597 12981 15598 12981 15634 12981 15634 12982 15598 12982 15599 12982 15634 12983 15599 12983 15636 12983 15603 960 15637 960 15600 960 15601 12984 15602 12984 15617 12984 15600 960 15604 960 15603 960 15603 960 15604 960 15605 960 15603 12985 15605 12985 15607 12985 15607 960 15605 960 15606 960 15607 960 15606 960 15608 960 15608 960 15606 960 15609 960 15609 960 15606 960 15610 960 15609 960 15610 960 15611 960 15611 960 15610 960 15640 960 15611 960 15640 960 15639 960 15614 12986 15612 12986 15625 12986 15625 960 15612 960 15623 960 15601 960 15617 960 15619 960 15613 12987 15615 12987 15614 12987 15614 12988 15615 12988 15616 12988 15614 12989 15616 12989 15612 12989 15617 960 15618 960 15619 960 15619 12990 15618 12990 15620 12990 15619 960 15620 960 15621 960 15621 960 15620 960 15622 960 15621 960 15622 960 15623 960 15623 960 15622 960 15624 960 15623 960 15624 960 15625 960 15602 960 15601 960 15626 960 15626 12991 15601 12991 15627 12991 15626 960 15627 960 15629 960 15629 12992 15627 12992 15628 12992 15629 960 15628 960 15630 960 15630 960 15628 960 15631 960 15630 960 15631 960 15635 960 15635 12993 15631 12993 15632 12993 15635 12994 15632 12994 15633 12994 15633 960 15634 960 15635 960 15635 960 15634 960 15636 960 15635 12995 15636 12995 15637 12995 15637 12996 15636 12996 15638 12996 15637 12997 15638 12997 15600 12997 15639 960 15640 960 15642 960 15642 12998 15640 12998 15641 12998 15642 960 15641 960 15643 960 15643 960 15641 960 15644 960 15644 12999 15641 12999 15645 12999 15644 960 15645 960 15647 960 15647 13000 15645 13000 15646 13000 15647 13001 15646 13001 15648 13001 15648 13002 15646 13002 15597 13002 15648 13003 15597 13003 15649 13003 15649 960 15597 960 15634 960 15649 960 15634 960 15613 960 15613 13004 15634 13004 15650 13004 15613 13005 15650 13005 15615 13005 15651 13006 15653 13006 15652 13006 15652 13007 15653 13007 15654 13007 15652 13008 15654 13008 15656 13008 15656 13009 15654 13009 15655 13009 15656 13009 15655 13009 15657 13009 15657 13010 15655 13010 15658 13010 15657 13011 15658 13011 15659 13011 15659 13012 15658 13012 15661 13012 15659 13013 15661 13013 15660 13013 15660 13014 15661 13014 15662 13014 15660 13015 15662 13015 15663 13015 15663 13016 15662 13016 15664 13016 15663 13017 15664 13017 15666 13017 15666 13018 15664 13018 15665 13018 15666 13019 15665 13019 15667 13019 15667 13020 15665 13020 15668 13020 15667 13020 15668 13020 15669 13020 15669 13021 15668 13021 15670 13021 15669 13022 15670 13022 15672 13022 15672 13023 15670 13023 15671 13023 15672 13023 15671 13023 15673 13023 15673 13024 15671 13024 15674 13024 15673 13025 15674 13025 15675 13025 15675 13026 15674 13026 15676 13026 15675 13027 15676 13027 15677 13027 15677 13028 15676 13028 15678 13028 15677 13029 15678 13029 15680 13029 15680 13030 15678 13030 15679 13030 15680 13031 15679 13031 15681 13031 15681 13032 15679 13032 15682 13032 15681 13032 15682 13032 15683 13032 15683 13033 15682 13033 15684 13033 15683 13034 15684 13034 15685 13034 15685 13035 15684 13035 15686 13035 15685 13036 15686 13036 15687 13036 15687 13037 15686 13037 15688 13037 15687 13038 15688 13038 15689 13038 15689 13039 15688 13039 15690 13039 15689 13040 15690 13040 15691 13040 15691 13041 15690 13041 15692 13041 15691 13042 15692 13042 15694 13042 15694 13043 15692 13043 15693 13043 15694 13044 15693 13044 15696 13044 15696 13045 15693 13045 15695 13045 15696 13046 15695 13046 15697 13046 15697 13047 15695 13047 15699 13047 15697 13047 15699 13047 15698 13047 15698 13048 15699 13048 15700 13048 15698 13049 15700 13049 15702 13049 15702 13050 15700 13050 15701 13050 15702 13051 15701 13051 15703 13051 15703 13052 15701 13052 15704 13052 15703 13053 15704 13053 15705 13053 15705 13054 15704 13054 15706 13054 15705 13055 15706 13055 15707 13055 15707 13056 15706 13056 15708 13056 15707 13057 15708 13057 15709 13057 15709 13058 15708 13058 15711 13058 15709 13059 15711 13059 15710 13059 15710 13060 15711 13060 15712 13060 15710 13061 15712 13061 15713 13061 15713 13062 15712 13062 15715 13062 15713 13063 15715 13063 15714 13063 15714 13064 15715 13064 15716 13064 15714 13064 15716 13064 15717 13064 15717 13065 15716 13065 15718 13065 15717 13066 15718 13066 15720 13066 15720 13067 15718 13067 15719 13067 15720 13068 15719 13068 15721 13068 15721 13069 15719 13069 15723 13069 15721 13070 15723 13070 15722 13070 15722 13071 15723 13071 15724 13071 15722 13072 15724 13072 15725 13072 15725 13073 15724 13073 15727 13073 15725 13074 15727 13074 15726 13074 15726 13075 15727 13075 15728 13075 15726 13076 15728 13076 15651 13076 15651 13077 15728 13077 15653 13077 15803 13078 15729 13078 15730 13078 15730 13079 15729 13079 15731 13079 15730 13080 15731 13080 15732 13080 15732 13081 15731 13081 15734 13081 15732 13082 15734 13082 15733 13082 15733 13083 15734 13083 15735 13083 15733 13084 15735 13084 15736 13084 15736 13085 15735 13085 15738 13085 15736 13086 15738 13086 15737 13086 15737 13087 15738 13087 15740 13087 15737 13088 15740 13088 15739 13088 15739 13089 15740 13089 15742 13089 15739 13090 15742 13090 15741 13090 15741 13091 15742 13091 15743 13091 15741 13092 15743 13092 15744 13092 15744 13093 15743 13093 15745 13093 15744 13094 15745 13094 15746 13094 15746 13095 15745 13095 15748 13095 15746 13096 15748 13096 15747 13096 15747 13097 15748 13097 15749 13097 15747 13098 15749 13098 15750 13098 15750 13099 15749 13099 15751 13099 15750 13100 15751 13100 15752 13100 15752 13101 15751 13101 15754 13101 15752 13102 15754 13102 15753 13102 15753 13103 15754 13103 15756 13103 15753 13104 15756 13104 15755 13104 15755 13105 15756 13105 15757 13105 15755 13106 15757 13106 15758 13106 15758 13107 15757 13107 15759 13107 15758 13108 15759 13108 15760 13108 15760 13109 15759 13109 15762 13109 15760 13110 15762 13110 15761 13110 15761 13111 15762 13111 15763 13111 15761 13112 15763 13112 15764 13112 15764 13113 15763 13113 15765 13113 15764 13114 15765 13114 15766 13114 15766 13115 15765 13115 15767 13115 15766 13116 15767 13116 15768 13116 15768 13117 15767 13117 15769 13117 15768 13118 15769 13118 15770 13118 15770 13119 15769 13119 15771 13119 15770 13120 15771 13120 15773 13120 15773 13121 15771 13121 15772 13121 15773 13122 15772 13122 15774 13122 15774 13123 15772 13123 15775 13123 15774 13124 15775 13124 15776 13124 15776 13125 15775 13125 15777 13125 15776 13126 15777 13126 15778 13126 15778 13127 15777 13127 15779 13127 15778 13128 15779 13128 15780 13128 15780 13129 15779 13129 15782 13129 15780 13130 15782 13130 15781 13130 15781 13131 15782 13131 15783 13131 15781 13132 15783 13132 15784 13132 15784 13133 15783 13133 15786 13133 15784 13134 15786 13134 15785 13134 15785 13135 15786 13135 15787 13135 15785 13136 15787 13136 15788 13136 15788 13137 15787 13137 15789 13137 15788 13138 15789 13138 15790 13138 15790 13139 15789 13139 15792 13139 15790 13140 15792 13140 15791 13140 15791 13141 15792 13141 15794 13141 15791 13142 15794 13142 15793 13142 15793 13143 15794 13143 15795 13143 15793 13144 15795 13144 15796 13144 15796 13145 15795 13145 15797 13145 15796 13146 15797 13146 15798 13146 15798 13147 15797 13147 15799 13147 15798 13148 15799 13148 15800 13148 15800 13149 15799 13149 15801 13149 15800 13150 15801 13150 15802 13150 15802 13151 15801 13151 15804 13151 15802 13152 15804 13152 15803 13152 15803 13153 15804 13153 15729 13153 15805 13154 15806 13154 15807 13154 15807 13155 15806 13155 15808 13155 15807 13156 15808 13156 15809 13156 15809 13157 15808 13157 16165 13157 15809 13158 16165 13158 15818 13158 15816 13159 16168 13159 15810 13159 15810 13160 16168 13160 16167 13160 15810 13161 16167 13161 15805 13161 15805 13162 16167 13162 15811 13162 15805 13163 15811 13163 15806 13163 15812 13164 15825 13164 15813 13164 15813 13165 15825 13165 16160 13165 15813 13166 16160 13166 15814 13166 15814 13167 16160 13167 15815 13167 15814 13168 15815 13168 15816 13168 15816 13169 15815 13169 15817 13169 15816 13170 15817 13170 16168 13170 16165 13171 16164 13171 15818 13171 15818 13172 16164 13172 16163 13172 15818 13173 16163 13173 15819 13173 15819 13174 16163 13174 15821 13174 15819 13175 15821 13175 15820 13175 15820 13176 15821 13176 15823 13176 15820 13177 15823 13177 15822 13177 15822 13178 15823 13178 15824 13178 15822 13179 15824 13179 15812 13179 15812 13180 15824 13180 16161 13180 15812 13181 16161 13181 15825 13181 15962 13182 16102 13182 16099 13182 15962 590 16099 590 15826 590 15826 13183 16099 13183 15827 13183 15826 13184 15827 13184 15963 13184 15963 13185 15827 13185 16096 13185 15963 13186 16096 13186 15828 13186 15828 590 16096 590 15959 590 15959 13187 16096 13187 15829 13187 15959 590 15829 590 15957 590 15957 590 15829 590 16108 590 15957 590 16108 590 16107 590 15839 13188 16094 13188 15935 13188 15935 13189 16094 13189 15830 13189 15935 13190 15830 13190 15831 13190 15831 13191 15830 13191 15832 13191 15831 13192 15832 13192 15833 13192 15833 13193 15832 13193 16103 13193 15833 13194 16103 13194 15961 13194 15961 13195 16103 13195 16102 13195 15961 13196 16102 13196 15962 13196 15843 13197 16090 13197 15834 13197 15834 13198 16090 13198 15836 13198 15834 13199 15836 13199 15835 13199 15835 13200 15836 13200 15837 13200 15835 13201 15837 13201 15933 13201 15933 13202 15837 13202 15838 13202 15933 13203 15838 13203 15934 13203 15934 13204 15838 13204 16089 13204 15934 13205 16089 13205 15839 13205 15839 13206 16089 13206 15840 13206 15839 13207 15840 13207 16094 13207 15932 13208 15841 13208 15842 13208 15842 13209 15841 13209 16092 13209 15842 13210 16092 13210 15843 13210 15843 13211 16092 13211 15844 13211 15843 13212 15844 13212 16090 13212 15845 13213 16323 13213 15846 13213 15846 13214 16323 13214 15847 13214 15846 13215 15847 13215 15932 13215 15932 13216 15847 13216 16093 13216 15932 13217 16093 13218 15841 13219 15848 13220 16083 13220 15979 13220 15979 13221 16083 13221 16327 13221 15979 13222 16327 13222 16326 13222 15864 13223 15849 13223 15850 13223 15850 13224 15849 13224 16088 13224 15850 13225 16088 13225 15851 13225 15851 13226 16088 13226 15852 13226 15851 13227 15852 13227 15977 13227 15977 13228 15852 13228 16087 13228 15977 13229 16087 13229 15853 13229 15853 13230 16087 13230 15855 13230 15853 13231 15855 13231 15854 13231 15854 13232 15855 13232 15856 13232 15854 13233 15856 13233 15857 13233 15857 13234 15856 13234 15858 13234 15857 13235 15858 13235 15859 13235 15859 13236 15858 13236 16086 13236 15859 13237 16086 13237 15995 13237 15995 13238 16086 13238 15861 13238 15995 13239 15861 13239 15860 13239 15860 13240 15861 13240 16085 13240 15860 13241 16085 13241 15862 13241 15862 13242 16085 13242 16084 13242 15862 13243 16084 13243 15978 13243 15978 13244 16084 13244 15863 13244 15978 13245 15863 13245 15848 13245 15848 13246 15863 13246 16082 13246 15848 13247 16082 13247 16083 13247 15849 590 15864 590 15865 590 15865 13248 15864 13248 15980 13248 15865 13249 15980 13249 15866 13249 15866 590 15980 590 15867 590 15866 590 15867 590 16080 590 16080 590 15867 590 15868 590 16080 590 15868 590 15869 590 15869 590 15868 590 15870 590 15869 590 15870 590 16077 590 16077 13250 15870 13250 15984 13250 16077 590 15984 590 15882 590 15968 13251 16068 13251 15871 13251 15871 13252 16068 13252 15872 13252 15871 13253 15872 13253 15873 13253 15873 13254 15872 13254 16074 13254 15873 13255 16074 13255 15875 13255 15875 13256 16074 13256 15874 13256 15875 13257 15874 13257 15876 13257 15876 13258 15874 13258 16073 13258 15876 13259 16073 13259 15877 13259 15877 13260 16073 13260 15879 13260 15877 13261 15879 13261 15878 13261 15878 13262 15879 13262 15880 13262 15878 13263 15880 13263 15969 13263 15969 13264 15880 13264 16072 13264 15969 13265 16072 13265 15881 13265 15881 13266 16072 13266 16071 13266 15881 13267 16071 13267 15983 13267 15983 13268 16071 13268 15882 13268 15983 13269 15882 13269 15984 13269 16353 13270 16351 13270 15883 13270 15883 13271 16351 13271 15884 13271 15883 13272 15884 13272 15885 13272 15885 13273 15884 13273 15886 13273 15885 13274 15886 13274 15888 13274 15888 13275 15886 13275 15887 13275 15888 13276 15887 13276 15968 13276 15968 13277 15887 13277 16069 13277 15968 13278 16069 13278 16068 13278 15963 13279 16047 13279 16046 13279 16318 13280 15936 13280 15943 13280 15889 13281 15893 13281 15890 13281 15890 13282 15893 13282 15891 13282 15890 13283 15891 13283 16379 13283 15889 13284 15892 13284 15893 13284 15893 13285 15892 13286 15894 13286 15893 13287 15894 13287 15895 13287 15994 13288 15896 13289 15897 13290 15897 13291 15896 13291 15898 13291 15897 13292 15898 13292 15899 13292 15899 13293 15900 13293 15897 13293 15897 13294 15900 13294 15901 13294 15897 13295 15901 13295 15926 13295 15902 13296 16153 13296 15891 13296 15891 13297 16153 13297 16380 13297 15891 13298 16380 13298 16379 13298 15903 13299 16366 13299 15902 13299 15902 13300 16366 13300 16365 13300 15902 13301 16365 13301 16153 13301 15906 13302 16370 13302 15903 13302 15903 13303 16370 13303 16368 13303 15903 13304 16368 13304 16366 13304 15917 13305 16375 13305 15904 13305 15904 13306 16375 13306 16373 13306 15904 13307 16373 13307 15906 13307 15906 13308 16373 13308 15905 13308 15906 13309 15905 13309 16370 13309 15907 13310 15908 13310 16009 13310 15909 13311 16007 13311 16008 13311 15909 13312 16008 13312 15913 13312 15910 13313 15911 13313 16008 13313 16008 13314 15911 13314 15912 13314 16008 13315 15912 13315 15913 13315 15908 13316 15914 13316 16009 13316 16009 13317 15914 13317 15915 13317 16009 13318 15915 13318 15917 13318 15917 13319 15915 13319 15916 13319 15917 13320 15916 13320 16272 13320 16272 13321 16377 13321 15917 13321 15917 13322 16377 13322 15918 13322 15917 13323 15918 13323 16375 13323 15919 13324 15920 13324 15910 13324 15910 13325 15920 13326 15921 13327 15910 13328 15921 13328 15911 13328 15928 13329 15922 13329 16028 13329 16028 13330 15922 13330 15923 13330 16028 13331 15923 13331 15924 13331 15924 13332 15923 13332 15919 13332 15924 13333 15919 13333 15925 13333 15925 13334 15919 13334 15910 13334 15901 13335 15927 13335 15926 13335 15926 13336 15927 13336 15929 13336 15926 13337 15929 13337 15928 13337 15928 13338 15929 13338 15930 13338 15928 13339 15930 13339 15922 13339 15846 13340 15932 13340 16006 13340 15846 13341 16006 13341 15845 13341 15845 13342 16006 13342 15931 13342 15845 13343 15931 13343 16321 13343 15932 13344 15842 13344 16006 13344 16006 13345 15842 13345 15843 13345 16006 13346 15843 13346 15834 13346 16005 13347 15835 13347 15933 13347 15933 13348 15934 13348 16005 13348 16005 13349 15934 13349 15839 13349 16005 13350 15839 13350 15935 13350 15935 13351 15831 13351 16005 13351 16005 13352 15831 13352 15833 13352 16005 13353 15833 13353 15960 13353 15936 13354 16318 13354 15937 13354 15937 13355 16318 13355 15939 13355 15937 13356 15939 13356 15938 13356 15938 13357 15939 13357 15941 13357 15938 13358 15941 13358 15940 13358 15940 13359 15941 13359 16308 13359 15940 13360 16308 13360 15931 13360 15931 13361 16308 13361 16322 13361 15931 13362 16322 13362 16321 13362 15956 13363 15942 13363 15955 13363 15955 13364 15942 13364 16314 13364 15955 13365 16314 13365 15943 13365 15943 13366 16314 13366 16317 13366 15943 13367 16317 13367 16318 13367 15944 13368 15951 13368 15987 13368 15945 13369 15986 13369 15947 13369 15945 13370 15947 13370 15950 13370 15946 13371 15948 13371 15947 13371 15947 13372 15948 13372 15949 13372 15947 13373 15949 13373 15950 13373 15951 13374 15952 13374 15987 13374 15987 13375 15952 13375 15953 13375 15987 13376 15953 13376 15955 13376 15955 13377 15953 13377 15954 13377 15955 13378 15954 13378 15956 13378 15959 13379 15957 13379 15946 13379 15946 13380 15957 13380 15958 13380 15946 13381 15958 13381 15948 13381 15946 13382 16020 13382 15959 13382 15959 13383 16020 13383 16019 13383 15959 13384 16019 13384 15828 13384 15828 13385 16019 13385 15963 13385 15963 13386 16019 13386 16018 13386 15963 13387 16018 13387 16047 13387 15833 13388 15961 13388 15960 13388 15960 13389 15961 13389 15962 13389 15960 13390 15962 13390 16046 13390 16046 13391 15962 13391 15826 13391 16046 13392 15826 13392 15963 13392 15964 13393 15965 13393 15966 13393 15966 13394 15965 13394 16353 13394 15966 13395 16353 13395 15967 13395 15967 13396 16353 13396 15883 13396 15967 13397 15883 13397 15885 13397 15885 13398 15888 13398 15967 13398 15967 13399 15888 13399 15968 13399 15967 13400 15968 13401 15871 13402 16017 13403 15873 13403 15875 13403 15875 13404 15876 13404 16017 13404 16017 13405 15876 13405 15877 13405 16017 13406 15877 13406 15878 13406 15878 13407 15969 13407 16017 13407 16017 13408 15969 13408 15881 13408 16017 13409 15881 13409 16038 13409 15970 13410 16203 13410 15964 13410 15964 13411 16203 13411 15971 13411 15964 13412 15971 13412 15965 13412 15972 13413 16155 13413 15970 13413 15970 13414 16155 13414 16202 13414 15970 13415 16202 13415 16203 13415 15970 13416 15973 13416 15972 13416 15972 13417 15973 13417 15974 13417 15972 13418 15974 13418 16208 13418 16208 13419 15974 13419 16207 13419 16207 13420 15974 13420 15975 13420 16207 13421 15975 13421 16330 13421 15857 13422 15859 13422 15976 13422 15977 13423 15853 13423 15976 13423 15976 13424 15853 13424 15854 13424 15976 13425 15854 13425 15857 13425 15995 13426 15860 13426 15996 13426 15996 13427 15860 13427 15862 13427 15996 13428 15862 13428 15978 13428 15978 13429 15848 13429 15996 13429 15996 13430 15848 13430 15979 13430 15996 13431 15979 13431 15975 13431 15975 13432 15979 13432 16326 13432 15975 13433 16326 13433 16330 13433 15980 13434 15864 13434 16042 13434 16042 13435 15864 13436 15850 13437 16042 13438 15850 13438 15976 13438 15976 13439 15850 13439 15851 13439 15976 13440 15851 13440 15977 13440 15985 13441 15868 13441 15981 13441 15981 13442 15868 13442 15867 13442 15981 13443 15867 13443 16040 13443 16040 13444 15867 13444 15980 13444 16040 13445 15980 13445 15982 13445 15982 13446 15980 13446 16042 13446 15881 13447 15983 13447 16038 13447 16038 13448 15983 13448 15984 13448 16038 13449 15984 13449 15985 13449 15985 13450 15984 13450 15870 13450 15985 13451 15870 13451 15868 13451 15986 13452 15944 13452 15947 13452 15947 13453 15944 13453 15987 13453 15947 13454 15987 13454 16021 13454 16021 13455 15987 13455 15989 13455 16021 13456 15989 13456 15988 13456 15988 13457 15989 13457 15990 13457 15988 13458 15990 13458 16023 13458 16023 13459 15990 13459 15991 13459 16023 13460 15991 13460 16024 13460 16024 13461 15991 13461 15992 13461 16024 13462 15992 13462 16025 13462 16025 13463 15992 13463 15993 13463 16025 13464 15993 13464 15897 13464 15897 13465 15993 13465 15893 13465 15897 13466 15893 13466 15994 13466 15994 13467 15893 13467 15895 13467 15859 13468 15995 13468 15976 13468 15976 13469 15995 13469 15996 13469 15976 13470 15996 13470 15997 13470 15997 13471 15996 13471 15998 13471 15997 13472 15998 13472 16044 13472 16044 13473 15998 13473 15999 13473 16044 13474 15999 13474 16045 13474 16045 13475 15999 13475 16000 13475 16045 13476 16000 13476 16001 13476 16001 13477 16000 13477 16002 13477 16001 13478 16002 13478 16003 13478 16003 13479 16002 13479 16004 13479 16003 13480 16004 13480 16005 13480 16005 13481 16004 13481 16006 13481 16005 13482 16006 13482 15835 13482 15835 13483 16006 13483 15834 13483 16007 13484 15907 13484 16008 13484 16008 13485 15907 13485 16009 13485 16008 13486 16009 13486 16010 13486 16010 13487 16009 13487 16012 13487 16010 13488 16012 13488 16011 13488 16011 13489 16012 13489 16013 13489 16011 13490 16013 13490 16033 13490 16033 13491 16013 13491 16014 13491 16033 13492 16014 13492 16035 13492 16035 13493 16014 13493 16015 13493 16035 13494 16015 13494 16036 13494 16036 13495 16015 13495 16016 13495 16036 13496 16016 13496 16017 13496 16017 13497 16016 13497 15967 13497 16017 13498 15967 13498 15873 13498 15873 13499 15967 13499 15871 13499 16047 960 16018 960 16097 960 16097 960 16018 960 16019 960 16097 960 16019 960 16095 960 16095 960 16019 960 16020 960 16095 960 16020 960 16106 960 16106 960 16020 960 15946 960 16106 960 15946 960 16104 960 16104 960 15946 960 15947 960 16104 960 15947 960 16110 960 16110 960 15947 960 16021 960 16110 960 16021 960 16139 960 16139 13500 16021 13500 15988 13500 16139 960 15988 960 16022 960 16022 960 15988 960 16023 960 16022 960 16023 960 16135 960 16135 960 16023 960 16024 960 16135 13501 16024 13501 16134 13501 16134 960 16024 960 16025 960 16134 13502 16025 13502 16133 13502 16133 960 16025 960 15897 960 16133 13503 15897 13503 16126 13503 16126 960 15897 960 15926 960 16126 13504 15926 13504 16026 13504 16026 960 15926 960 15928 960 16026 960 15928 960 16027 960 16027 960 15928 960 16028 960 16027 960 16028 960 16051 960 16051 13505 16028 13505 15924 13505 16051 13506 15924 13506 16053 13506 16053 13507 15924 13507 15925 13507 16053 13508 15925 13508 16029 13508 16029 960 15925 960 15910 960 16029 960 15910 960 16030 960 16030 960 15910 960 16008 960 16030 960 16008 960 16031 960 16031 13509 16008 13509 16010 13509 16031 960 16010 960 16032 960 16032 960 16010 960 16011 960 16032 960 16011 960 16151 960 16151 960 16011 960 16033 960 16151 960 16033 960 16034 960 16034 960 16033 960 16035 960 16034 960 16035 960 16037 960 16037 13510 16035 13510 16036 13510 16037 13511 16036 13511 16070 13511 16070 960 16036 960 16017 960 16070 960 16017 960 16076 960 16076 960 16017 960 16038 960 16076 960 16038 960 16078 960 16078 960 16038 960 15985 960 16078 960 15985 960 16079 960 16079 960 15985 960 15981 960 16079 13512 15981 13512 16039 13512 16039 960 15981 960 16040 960 16039 960 16040 960 16041 960 16041 960 16040 960 15982 960 16041 13513 15982 13513 16081 13513 16081 960 15982 960 16042 960 16081 13514 16042 13514 16147 13514 16147 13515 16042 13515 15976 13515 16147 960 15976 960 16148 960 16148 960 15976 960 15997 960 16148 960 15997 960 16043 960 16043 13516 15997 13516 16044 13516 16043 960 16044 960 16144 960 16144 960 16044 960 16045 960 16144 960 16045 960 16142 960 16142 960 16045 960 16001 960 16142 960 16001 960 16141 960 16141 960 16001 960 16003 960 16141 13517 16003 13517 16101 13517 16101 960 16003 960 16005 960 16101 960 16005 960 16100 960 16100 960 16005 960 15960 960 16100 960 15960 960 16098 960 16098 13518 15960 13518 16046 13518 16098 960 16046 960 16097 960 16097 960 16046 960 16047 960 15847 13519 16323 13519 16159 13519 16126 13520 16026 13520 16048 13520 16048 13521 16026 13521 16027 13521 16048 13522 16027 13522 16049 13522 16049 13523 16027 13523 16051 13523 16049 13524 16051 13524 16050 13524 16050 13525 16051 13525 16053 13525 16050 13526 16053 13526 16052 13526 16052 13527 16053 13527 16029 13527 16052 13528 16029 13528 16054 13528 16061 13529 16055 13529 16030 13529 16056 13530 16057 13530 16058 13530 16058 13531 16057 13531 16059 13531 16058 13532 16059 13532 16060 13532 16060 13533 16059 13533 16279 13533 16061 13534 16030 13535 16062 13536 16056 13537 16063 13537 16057 13537 16057 13538 16063 13538 16064 13538 16057 13539 16064 13539 16132 13539 16055 13540 16065 13540 16030 13540 16030 13541 16065 13541 16066 13541 16030 13542 16066 13542 16029 13542 16029 13543 16066 13543 16067 13543 16029 13544 16067 13544 16054 13544 16068 13545 16069 13545 16356 13545 16068 13546 16356 13546 15872 13546 16070 13547 16071 13547 16072 13547 16072 13548 15880 13548 16070 13548 16070 13549 15880 13549 15879 13549 16070 13550 15879 13550 16073 13550 16073 13551 15874 13551 16070 13551 16070 13552 15874 13553 16074 13554 16070 13555 16074 13555 15872 13555 16069 13556 15887 13556 16356 13556 16356 13557 15887 13557 15886 13557 16356 13558 15886 13558 16075 13558 16075 13559 15886 13559 15884 13559 16075 13560 15884 13560 16351 13560 16071 13561 16070 13561 15882 13561 15882 13562 16070 13562 16076 13562 15882 13563 16076 13563 16077 13563 16077 13564 16076 13564 16078 13564 16077 13565 16078 13565 15869 13565 15869 13566 16078 13566 16079 13566 15869 13567 16079 13567 16080 13567 16080 13568 16079 13568 16039 13568 16080 13569 16039 13569 15866 13569 15866 13570 16039 13570 16041 13570 15866 13571 16041 13571 15865 13571 15865 13572 16041 13572 15849 13572 15849 13573 16041 13573 16081 13573 15849 13574 16081 13574 16088 13574 16082 13575 16343 13575 16083 13575 16083 13576 16343 13576 16327 13576 16082 13577 15863 13577 16343 13577 16343 13578 15863 13578 16084 13578 16343 13579 16084 13579 16085 13579 15861 13580 16086 13581 16147 13582 16147 13583 16086 13583 15858 13583 16147 13584 15858 13584 15856 13584 15856 13585 15855 13585 16147 13585 16147 13586 15855 13586 16087 13586 16147 13587 16087 13587 16081 13587 16081 13588 16087 13588 15852 13588 16081 13589 15852 13589 16088 13589 15847 13590 16159 13590 16093 13590 16101 13591 15840 13591 16141 13591 16141 13592 15840 13592 16089 13592 16141 13593 16089 13593 15838 13593 15837 13594 15836 13594 16162 13594 16162 13595 15836 13595 16090 13595 16162 13596 16090 13596 16091 13596 16090 13597 15844 13597 16091 13597 16091 13598 15844 13598 16092 13598 16091 13599 16092 13599 16159 13599 16159 13600 16092 13600 15841 13600 16159 13601 15841 13601 16093 13601 15832 13602 15830 13602 16101 13602 16101 13603 15830 13603 16094 13603 16101 13604 16094 13604 15840 13604 16106 13605 15829 13605 16095 13605 16095 13606 15829 13606 16096 13606 16095 13607 16096 13607 16097 13607 16097 13608 16096 13608 15827 13608 16097 13609 15827 13609 16098 13609 16098 13610 15827 13610 16099 13610 16098 13611 16099 13611 16100 13611 16100 13612 16099 13612 16102 13612 16100 13613 16102 13613 16101 13613 16101 13614 16102 13614 16103 13614 16101 13615 16103 13615 15832 13615 16113 13616 16105 13616 16104 13616 16104 13617 16105 13617 16107 13617 16104 13618 16107 13618 16106 13618 16106 13619 16107 13619 16108 13619 16106 13620 16108 13620 15829 13620 16137 13621 16109 13622 16110 13623 16110 13624 16109 13624 16111 13624 16110 13625 16111 13625 16104 13625 16104 13626 16111 13626 16112 13626 16104 13627 16112 13627 16113 13627 16169 13628 16114 13628 16115 13628 16115 13629 16114 13629 16117 13629 16115 13630 16117 13630 16116 13630 16116 13631 16117 13631 16118 13631 16116 13632 16118 13632 16389 13632 16389 13633 16118 13633 16119 13633 16389 13634 16119 13634 16390 13634 16120 13635 16128 13635 16378 13635 16121 13636 16122 13636 16133 13636 16121 13637 16133 13637 16123 13637 16048 13638 16124 13638 16126 13638 16126 13639 16124 13639 16125 13639 16126 13640 16125 13640 16133 13640 16133 13641 16125 13641 16127 13641 16133 13642 16127 13642 16123 13642 16120 13643 16378 13643 16122 13643 16128 13644 16129 13644 16378 13644 16378 13645 16129 13645 16130 13645 16378 13646 16130 13646 16131 13646 16132 13647 16062 13647 16057 13647 16057 13648 16062 13648 16030 13648 16057 13649 16030 13649 16276 13649 16276 13650 16030 13650 16031 13650 16276 13651 16031 13651 16229 13651 16229 13652 16031 13652 16032 13652 16229 13653 16032 13653 16231 13653 16122 13654 16378 13654 16133 13654 16133 13655 16378 13655 16382 13655 16133 13656 16382 13656 16134 13656 16383 13657 16135 13657 16290 13657 16290 13658 16135 13658 16134 13658 16290 13659 16134 13659 16136 13659 16136 13660 16134 13660 16382 13660 16119 13661 16137 13661 16390 13661 16390 13662 16137 13662 16110 13662 16390 13663 16110 13663 16138 13663 16138 13664 16110 13664 16139 13664 16138 13665 16139 13665 16386 13665 16386 13666 16139 13666 16022 13666 16386 13667 16022 13667 16140 13667 16140 13668 16022 13668 16135 13668 16140 13669 16135 13669 16152 13669 16152 13670 16135 13670 16383 13670 15838 13671 15837 13671 16141 13671 16141 13672 15837 13672 16162 13672 16141 13673 16162 13673 16142 13673 16142 13674 16162 13674 16143 13674 16142 13675 16143 13675 16144 13675 16325 13676 16043 13676 16145 13676 16145 13677 16043 13677 16144 13677 16145 13678 16144 13678 16146 13678 16146 13679 16144 13679 16143 13679 16085 13680 15861 13680 16343 13680 16343 13681 15861 13681 16147 13681 16343 13682 16147 13682 16342 13682 16342 13683 16147 13683 16148 13683 16342 13684 16148 13684 16339 13684 16339 13685 16148 13685 16043 13685 16339 13686 16043 13686 16149 13686 16149 13687 16043 13687 16325 13687 15872 13688 16356 13688 16070 13688 16070 13689 16356 13689 16358 13689 16070 13690 16358 13690 16037 13690 16358 13691 16359 13691 16037 13691 16037 13692 16359 13692 16214 13692 16037 13693 16214 13693 16034 13693 16214 13694 16362 13694 16034 13694 16034 13695 16362 13695 16150 13695 16034 13696 16150 13696 16151 13696 16151 13697 16150 13697 16364 13697 16151 13698 16364 13698 16032 13698 16032 13699 16364 13699 16363 13699 16032 13700 16363 13700 16231 13700 16152 13701 16384 13701 16172 13701 16383 960 16290 960 16293 960 16380 13702 16153 13702 16285 13702 16364 13703 16150 13703 16362 13703 16154 960 16197 960 16329 960 16202 960 16155 960 16354 960 16201 960 16156 960 16357 960 16157 960 16158 960 16384 960 16159 960 16323 960 16161 960 16159 13704 16161 13704 16091 13704 16324 13705 16160 13705 16323 13705 16323 13706 16160 13706 15825 13706 16323 960 15825 960 16161 960 16166 960 15817 960 16324 960 16324 960 15817 960 15815 960 16324 960 15815 960 16160 960 16161 13707 15824 13707 16091 13707 16091 13708 15824 13708 15823 13708 16091 960 15823 960 16162 960 16162 13709 15823 13709 15821 13709 16162 13710 15821 13710 16143 13710 16143 13711 15821 13711 16163 13711 16143 13712 16163 13712 16146 13712 16146 960 16163 960 16164 960 16146 960 16164 960 16145 960 16145 13713 16164 13713 16165 13713 16145 960 16165 960 16325 960 16325 960 16165 960 15808 960 15806 960 15811 960 16253 960 16253 13714 15811 13714 16167 13714 16253 960 16167 960 16166 960 16166 13715 16167 13715 16168 13715 16166 13716 16168 13716 15817 13716 15956 960 16169 960 15942 960 15942 960 16169 960 16238 960 15942 960 16238 960 16314 960 16116 13717 16387 13717 16179 13717 16158 13718 16170 13718 16384 13718 16384 960 16170 960 16171 960 16384 13719 16171 13719 16172 13719 16172 960 16171 960 16173 960 16172 960 16173 960 16388 960 16174 13720 16176 13720 16175 13720 16175 960 16176 960 16177 960 16177 13721 16176 13721 16178 13721 16177 960 16178 960 16184 960 16116 960 16179 960 16115 960 16115 13722 16179 13722 16180 13722 16115 960 16180 960 16169 960 16169 13723 16180 13723 16181 13723 16169 13724 16181 13724 16238 13724 16238 13725 16181 13725 16182 13725 16238 13726 16182 13726 16183 13726 16187 13727 16234 13727 16235 13727 16178 13728 16185 13728 16184 13728 16184 13729 16185 13729 16187 13729 16184 13730 16187 13730 16186 13730 16186 960 16187 960 16235 960 16217 13731 16188 13731 16189 13731 16217 13732 16189 13732 16190 13732 16190 960 16189 960 16192 960 16190 960 16192 960 16191 960 16191 960 16192 960 16194 960 16191 13733 16194 13733 16193 13733 16193 960 16194 960 16196 960 16193 960 16196 960 16195 960 16195 13734 16196 13734 16198 13734 16195 960 16198 960 16197 960 16197 13735 16198 13735 16204 13735 16197 13736 16204 13736 16329 13736 16188 13737 16217 13737 16156 13737 16156 960 16217 960 16360 960 16156 960 16360 960 16357 960 16352 13738 16355 13738 16199 13738 16352 960 16199 960 16357 960 16357 13739 16199 13739 16200 13739 16357 960 16200 960 16201 960 16202 13740 16354 13740 16203 13740 16204 960 16205 960 16329 960 16329 13741 16205 13741 16206 13741 16329 13742 16206 13742 16207 13742 16207 13743 16206 13743 16209 13743 16207 960 16209 960 16208 960 16208 13744 16209 13744 16210 13744 16208 13745 16210 13745 15972 13745 15972 960 16210 960 16155 960 16155 960 16210 960 16211 960 16155 13746 16211 13746 16354 13746 16217 13747 16225 13747 16216 13747 16216 960 16225 960 16227 960 16212 960 16213 960 16214 960 16221 960 16215 960 16360 960 16273 960 16222 960 16274 960 16216 960 16218 960 16217 960 16217 13748 16218 13748 16219 13748 16217 13749 16219 13749 16360 13749 16360 960 16219 960 16220 960 16360 13750 16220 13750 16221 13750 16222 13751 16223 13751 16274 13751 16274 960 16223 960 16224 960 16274 13752 16224 13752 16225 13752 16225 960 16224 960 16226 960 16225 960 16226 960 16227 960 16214 960 16213 960 16362 960 16228 960 16229 960 16230 960 16230 13753 16229 13753 16231 13753 16230 960 16231 960 16361 960 16213 13754 16232 13754 16362 13754 16362 960 16232 960 16233 960 16362 13755 16233 13755 16361 13755 16239 960 16238 960 16234 960 16234 13756 16238 13756 16183 13756 16234 960 16183 960 16235 960 16257 960 16258 960 16236 960 16236 13757 16258 13757 16238 13757 16236 13758 16238 13758 16237 13758 16237 960 16238 960 16239 960 16295 960 16240 960 16174 960 16174 13759 16240 13759 16241 13759 16174 960 16241 960 16176 960 16265 960 16242 960 16267 960 16267 13760 16242 13760 16296 13760 16248 960 16243 960 16225 960 16225 13761 16243 13761 16244 13761 16190 13762 16245 13762 16217 13762 16217 13763 16245 13763 16246 13763 16217 13764 16246 13764 16225 13764 16225 960 16246 960 16247 960 16225 13765 16247 13765 16248 13765 16256 960 16249 960 16348 960 16348 960 16249 960 16250 960 16348 960 16250 960 16329 960 16329 960 16250 960 16251 960 16329 13766 16251 13766 16154 13766 16166 960 16252 960 16253 960 16253 13767 16252 13767 16254 13767 16253 13768 16254 13768 16348 13768 16348 13769 16254 13769 16255 13769 16348 13770 16255 13770 16256 13770 16257 960 16259 960 16258 960 16258 13771 16259 13771 16260 13771 16258 960 16260 960 16324 960 16324 13772 16260 13772 16261 13772 16324 13773 16261 13773 16166 13773 16166 13774 16261 13774 16262 13774 16166 960 16262 960 16252 960 16267 960 16298 960 16270 960 16244 960 16264 960 16263 960 16263 13775 16264 13775 16265 13775 16263 960 16265 960 16266 960 16266 960 16265 960 16267 960 16266 960 16267 960 16268 960 16268 960 16267 960 16270 960 16285 960 16367 960 16298 960 16298 13776 16367 13776 16269 13776 16298 13777 16269 13777 16270 13777 16271 13778 16376 13778 16377 13778 16377 960 16272 960 16279 960 16228 960 16273 960 16229 960 16229 960 16273 960 16274 960 16229 960 16274 960 16276 960 16276 13779 16274 13779 16275 13779 16276 13780 16275 13780 16277 13780 16271 13781 16377 13781 16278 13781 16278 13782 16377 13782 16279 13782 16278 960 16279 960 16280 960 16280 13783 16279 13783 16059 13783 16280 13784 16059 13784 16277 13784 16277 13785 16059 13785 16057 13785 16277 13786 16057 13786 16276 13786 16263 960 16281 960 16244 960 16244 13787 16281 13787 16282 13787 16244 13788 16282 13788 16225 13788 16225 13789 16282 13789 16283 13789 16225 13790 16283 13790 16274 13790 16274 13791 16283 13791 16284 13791 16274 13792 16284 13792 16275 13792 16298 960 16408 960 16286 960 16413 960 16381 960 16285 960 16413 960 16285 960 16288 960 16298 960 16286 960 16285 960 16285 13793 16286 13793 16287 13793 16285 13794 16287 13794 16288 13794 16418 960 16293 960 16289 960 16289 960 16293 960 16290 960 16289 960 16290 960 16291 960 16291 13795 16290 13795 16136 13795 16291 960 16136 960 16292 960 16292 960 16136 960 16382 960 16292 960 16382 960 16392 960 16418 13796 16421 13796 16293 13796 16293 13797 16421 13797 16399 13797 16293 960 16399 960 16174 960 16174 13798 16399 13798 16400 13798 16174 13799 16400 13799 16294 13799 16294 960 16404 960 16174 960 16174 960 16404 960 16267 960 16174 13800 16267 13800 16295 13800 16295 960 16267 960 16296 960 16404 960 16297 960 16267 960 16267 13801 16297 13801 16405 13801 16267 960 16405 960 16298 960 16298 13802 16405 13802 16299 13802 16298 960 16299 960 16408 960 16302 960 16258 960 16300 960 16300 13803 16258 13803 16301 13803 16302 960 16303 960 16258 960 16258 960 16303 960 16304 960 16258 13804 16304 13804 16238 13804 16238 13805 16304 13805 16305 13805 16238 13806 16305 13806 16311 13806 16318 960 16320 960 15939 960 15939 13807 16320 13807 16306 13807 15939 960 16306 960 15941 960 15941 13808 16306 13808 16307 13808 15941 960 16307 960 16308 960 16308 960 16307 960 16309 960 16308 13809 16309 13809 16310 13809 16311 960 16312 960 16238 960 16238 960 16312 960 16313 960 16238 960 16313 960 16314 960 16314 960 16313 960 16315 960 16314 960 16315 960 16317 960 16317 13810 16315 13810 16316 13810 16317 960 16316 960 16318 960 16318 13811 16316 13811 16319 13811 16318 960 16319 960 16320 960 15845 960 16321 960 16323 960 16323 13812 16321 13812 16322 13812 16323 13813 16322 13813 16324 13813 16324 13814 16322 13814 16308 13814 16324 960 16308 960 16258 960 16258 13815 16308 13815 16310 13815 16258 13816 16310 13816 16301 13816 15808 960 15806 960 16325 960 16325 13817 15806 13817 16253 13817 16325 960 16253 960 16149 960 16149 960 16253 960 16348 960 16149 960 16348 960 16339 960 16330 13818 16326 13818 16327 13818 16327 13819 16343 13819 16346 13819 16336 960 16328 960 16329 960 16207 13820 16330 13820 16331 13820 16331 13821 16330 13821 16327 13821 16331 13822 16327 13822 16332 13822 16332 960 16327 960 16346 960 16331 960 16333 960 16207 960 16207 960 16333 960 16334 960 16207 960 16334 960 16329 960 16329 13823 16334 13823 16335 13823 16329 13824 16335 13824 16336 13824 16337 960 16338 960 16348 960 16348 960 16338 960 16340 960 16348 960 16340 960 16339 960 16339 13825 16340 13825 16341 13825 16339 13826 16341 13826 16342 13826 16342 13827 16341 13827 16344 13827 16342 13828 16344 13828 16343 13828 16343 960 16344 960 16345 960 16343 13829 16345 13829 16346 13829 16328 960 16347 960 16329 960 16329 13830 16347 13830 16349 13830 16329 960 16349 960 16348 960 16348 13831 16349 13831 16350 13831 16348 960 16350 960 16337 960 16075 960 16351 960 16352 960 16352 13832 16351 13832 16353 13832 16352 13833 16353 13833 15965 13833 16354 960 16355 960 16203 960 16203 960 16355 960 16352 960 16203 13834 16352 13834 15971 13834 15971 13835 16352 13835 15965 13835 16075 960 16352 960 16356 960 16356 13836 16352 13836 16357 13836 16356 960 16357 960 16358 960 16358 960 16357 960 16359 960 16359 13837 16357 13837 16360 13837 16359 13838 16360 13838 16214 13838 16214 960 16360 960 16215 960 16214 13839 16215 13839 16212 13839 16361 960 16231 960 16362 960 16362 13840 16231 13840 16363 13840 16362 13841 16363 13841 16364 13841 16153 960 16365 960 16285 960 16285 960 16365 960 16366 960 16285 960 16366 960 16367 960 16367 960 16366 960 16368 960 16367 13842 16368 13842 16369 13842 16369 960 16368 960 16370 960 16369 960 16370 960 16371 960 16371 960 16370 960 15905 960 16371 13843 15905 13843 16372 13843 16372 13844 15905 13844 16373 13844 16372 13845 16373 13845 16374 13845 16374 960 16373 960 16375 960 16374 960 16375 960 16376 960 16376 13846 16375 13846 15918 13846 16376 13847 15918 13847 16377 13847 16382 960 16378 960 16131 960 16379 13848 16380 13848 16131 13848 16131 960 16380 960 16285 960 16131 13849 16285 13849 16382 13849 16382 13850 16285 13850 16381 13850 16382 960 16381 960 16392 960 16152 960 16383 960 16384 960 16384 13851 16383 13851 16293 13851 16384 960 16293 960 16157 960 16157 13852 16293 13852 16174 13852 16157 13853 16174 13853 16385 13853 16385 960 16174 960 16175 960 16138 960 16386 960 16172 960 16172 13854 16386 13854 16140 13854 16172 13855 16140 13855 16152 13855 16387 960 16116 960 16388 960 16388 13856 16116 13856 16389 13856 16388 960 16389 960 16172 960 16172 13857 16389 13857 16390 13857 16172 960 16390 960 16138 960 16391 13858 16415 13858 16292 13858 16292 13859 16415 13859 16291 13859 16381 13860 16397 13860 16392 13860 16392 13861 16397 13861 16393 13861 16392 13862 16393 13862 16292 13862 16292 13863 16393 13863 16394 13863 16292 13864 16394 13864 16391 13864 16413 13865 16395 13865 16381 13865 16381 13866 16395 13866 16396 13866 16381 13867 16396 13867 16397 13867 16420 13868 16398 13868 16399 13868 16399 13869 16398 13869 16400 13869 16400 13870 16398 13870 16401 13870 16400 13871 16401 13871 16294 13871 16294 13872 16401 13872 16402 13872 16294 13873 16402 13873 16404 13873 16404 13874 16402 13874 16403 13874 16404 13875 16403 13875 16297 13875 16297 13876 16403 13876 16406 13876 16297 13877 16406 13877 16405 13877 16405 13878 16406 13878 16299 13878 16299 13879 16406 13879 16407 13879 16299 13880 16407 13880 16408 13880 16408 13881 16407 13881 16409 13881 16408 13882 16409 13882 16286 13882 16286 13883 16409 13883 16410 13883 16286 13884 16410 13884 16287 13884 16287 13885 16410 13885 16411 13885 16287 13886 16411 13886 16288 13886 16288 13887 16411 13887 16412 13887 16288 13888 16412 13888 16413 13888 16413 13889 16412 13889 16414 13889 16413 13890 16414 13890 16395 13890 16415 13891 16416 13891 16291 13891 16291 13892 16416 13892 16417 13892 16291 13893 16417 13893 16289 13893 16289 13894 16417 13894 16419 13894 16289 13894 16419 13894 16418 13894 16418 13895 16419 13895 16420 13895 16418 13896 16420 13896 16421 13896 16421 13897 16420 13897 16399 13897 16422 13898 16579 13898 16646 13898 16422 13899 16646 13899 16514 13899 16579 13900 16422 13900 16424 13900 16424 13901 16422 13901 16423 13901 16424 13902 16423 13902 16425 13902 16426 13903 16427 13903 16423 13903 16423 13904 16427 13904 16582 13904 16423 13905 16582 13905 16425 13905 16431 13906 16585 13906 16426 13906 16426 13907 16585 13907 16428 13907 16426 13908 16428 13909 16427 13910 16588 13911 16429 13912 16433 13913 16433 13914 16429 13914 16430 13914 16433 13915 16430 13915 16431 13915 16431 13916 16430 13916 16432 13916 16431 13917 16432 13917 16585 13917 16588 13918 16433 13918 16589 13918 16589 13919 16433 13919 16434 13919 16589 13920 16434 13920 16590 13920 16590 13921 16434 13921 16435 13921 16435 13922 16434 13922 16438 13922 16435 13923 16438 13923 16436 13923 16443 13924 16437 13924 16438 13924 16438 13925 16437 13925 16439 13925 16438 13926 16439 13926 16436 13926 16592 13927 16441 13927 16440 13927 16440 13928 16441 13928 16442 13928 16440 13929 16442 13929 16443 13929 16443 13930 16442 13930 16444 13930 16443 13931 16444 13931 16437 13931 16592 13932 16440 13932 16445 13932 16445 13933 16440 13933 16446 13933 16445 13934 16446 13934 16594 13934 16594 13935 16446 13935 16447 13935 16447 13936 16446 13936 16448 13936 16447 13937 16448 13937 16595 13937 16595 13938 16448 13938 16596 13938 16596 13939 16448 13939 16451 13939 16596 13940 16451 13940 16449 13940 16449 13941 16451 13941 16450 13941 16450 13942 16451 13942 16453 13942 16450 13943 16453 13943 16452 13943 16456 13944 16599 13944 16453 13944 16453 13945 16599 13945 16598 13945 16453 13946 16598 13946 16452 13946 16603 13947 16454 13947 16455 13947 16455 13948 16454 13948 16602 13948 16455 13949 16602 13949 16456 13949 16456 13950 16602 13950 16600 13950 16456 13951 16600 13951 16599 13951 16603 13952 16455 13952 16605 13952 16605 13953 16455 13953 16458 13953 16605 13954 16458 13954 16457 13954 16457 13955 16458 13955 16459 13955 16459 13956 16458 13956 16462 13956 16459 13957 16462 13957 16460 13957 16460 13958 16462 13958 16461 13958 16461 13959 16462 13959 16463 13959 16461 13960 16463 13960 16466 13960 16464 13961 16465 13961 16463 13961 16463 13962 16465 13962 16608 13962 16463 13963 16608 13963 16466 13963 16471 13964 16467 13964 16468 13964 16468 13965 16467 13965 16469 13965 16468 13966 16469 13966 16464 13966 16464 13967 16469 13967 16470 13967 16464 13968 16470 13968 16465 13968 16471 13969 16468 13969 16611 13969 16611 13970 16468 13970 16472 13970 16611 13971 16472 13971 16612 13971 16612 13972 16472 13972 16613 13972 16613 13973 16472 13973 16473 13973 16613 13974 16473 13974 16615 13974 16477 13975 16616 13975 16473 13975 16473 13976 16616 13976 16474 13976 16473 13977 16474 13978 16615 13979 16475 13980 16482 13980 16477 13980 16477 13981 16482 13981 16476 13981 16477 13982 16476 13982 16616 13982 16618 13983 16478 13983 16480 13983 16480 13984 16478 13984 16479 13984 16480 13985 16479 13985 16475 13985 16475 13986 16479 13986 16481 13986 16475 13987 16481 13987 16482 13987 16618 13988 16480 13988 16620 13988 16620 13989 16480 13989 16484 13989 16620 13990 16484 13990 16483 13990 16483 13991 16484 13991 16486 13991 16486 13992 16484 13992 16485 13992 16486 13993 16485 13993 16621 13993 16487 13994 16625 13994 16485 13994 16485 13995 16625 13995 16623 13995 16485 13996 16623 13996 16621 13996 16491 13997 16488 13997 16487 13997 16487 13998 16488 13998 16626 13998 16487 13999 16626 13999 16625 13999 16629 14000 16489 14000 16490 14000 16490 14001 16489 14001 16627 14001 16490 14002 16627 14002 16491 14002 16491 14003 16627 14003 16492 14003 16491 14004 16492 14004 16488 14004 16629 14005 16490 14005 16631 14005 16631 14006 16490 14006 16494 14006 16631 14007 16494 14007 16493 14007 16493 14008 16494 14008 16495 14008 16495 14009 16494 14009 16496 14009 16495 14010 16496 14010 16497 14010 16500 14011 16634 14011 16496 14011 16496 14012 16634 14012 16498 14012 16496 14013 16498 14013 16497 14013 16502 14014 16504 14014 16500 14014 16500 14015 16504 14015 16499 14015 16500 14016 16499 14016 16634 14016 16505 14017 16501 14017 16507 14017 16507 14018 16501 14018 16636 14018 16507 14019 16636 14019 16502 14019 16502 14020 16636 14020 16503 14020 16502 14021 16503 14021 16504 14021 16505 14022 16507 14022 16506 14022 16506 14023 16507 14023 16509 14023 16506 14024 16509 14024 16638 14024 16511 14025 16508 14025 16509 14025 16509 14026 16508 14026 16510 14026 16509 14027 16510 14027 16638 14027 16515 14028 16512 14028 16511 14028 16511 14029 16512 14029 16513 14029 16511 14030 16513 14030 16508 14030 16646 14031 16644 14031 16514 14031 16514 14032 16644 14032 16642 14032 16514 14033 16642 14033 16515 14033 16515 14034 16642 14034 16640 14034 16515 14035 16640 14035 16512 14035 16537 960 16516 960 16517 960 16517 960 16516 960 16775 960 16517 960 16775 960 16531 960 16518 14036 16519 14036 16808 14036 16550 14037 16520 14037 16521 14037 16521 960 16520 960 16539 960 16521 14038 16539 14038 16540 14038 16527 960 16529 960 16522 960 16522 960 16529 960 16523 960 16522 960 16523 960 16524 960 16808 960 16525 960 16518 960 16518 14039 16525 14039 16807 14039 16518 960 16807 960 16526 960 16526 14040 16807 14040 16528 14040 16526 14041 16528 14041 16527 14041 16527 14042 16528 14042 16806 14042 16527 960 16806 960 16529 960 16775 14043 16530 14043 16531 14043 16531 960 16530 960 16532 960 16531 14044 16532 14044 16533 14044 16533 960 16532 960 16773 960 16533 960 16773 960 16534 960 16546 960 16777 960 16536 960 16536 960 16777 960 16535 960 16536 960 16535 960 16537 960 16537 960 16535 960 16538 960 16537 960 16538 960 16516 960 16539 960 16541 960 16540 960 16540 14045 16541 14045 16796 14045 16540 14046 16796 14046 16542 14046 16542 14047 16796 14047 16794 14047 16542 960 16794 960 16573 960 16523 960 16803 960 16524 960 16524 960 16803 960 16802 960 16524 960 16802 960 16543 960 16543 14048 16802 14048 16544 14048 16543 960 16544 960 16563 960 16773 14049 16545 14049 16534 14049 16534 14050 16545 14050 16554 14050 16534 14051 16554 14051 16555 14051 16568 960 16570 960 16546 960 16546 960 16570 960 16778 960 16546 960 16778 960 16777 960 16565 14052 16547 14052 16548 14052 16548 14053 16547 14053 16549 14053 16548 14054 16549 14054 16550 14054 16550 960 16549 960 16551 960 16550 960 16551 960 16520 960 16558 960 16559 960 16552 960 16552 960 16559 960 16767 960 16552 14055 16767 14055 16553 14055 16554 960 16771 960 16555 960 16555 14056 16771 14056 16770 14056 16555 960 16770 960 16556 960 16556 14057 16770 14057 16557 14057 16556 14058 16557 14058 16558 14058 16558 960 16557 960 16769 960 16558 14059 16769 14059 16559 14059 16572 960 16788 960 16560 960 16560 14060 16788 14060 16785 14060 16560 14061 16785 14061 16561 14061 16544 960 16562 960 16563 960 16563 960 16562 960 16564 960 16563 960 16564 960 16565 960 16565 960 16564 960 16566 960 16565 14062 16566 14062 16547 14062 16785 960 16784 960 16561 960 16561 960 16784 960 16783 960 16561 960 16783 960 16567 960 16567 14063 16783 14063 16780 14063 16567 960 16780 960 16568 960 16568 14064 16780 14064 16569 14064 16568 960 16569 960 16570 960 16576 960 16577 960 16571 960 16571 14065 16577 14065 16791 14065 16571 960 16791 960 16572 960 16572 14066 16791 14066 16790 14066 16572 14067 16790 14067 16788 14067 16794 14068 16574 14068 16573 14068 16573 960 16574 960 16575 960 16573 960 16575 960 16576 960 16576 14069 16575 14069 16792 14069 16576 14070 16792 14070 16577 14070 16767 960 16766 960 16553 960 16553 14071 16766 14071 16765 14071 16553 960 16765 960 16578 960 16578 14072 16765 14072 16764 14072 16578 14073 16764 14073 16519 14073 16519 14074 16764 14074 16763 14074 16519 14075 16763 14075 16808 14075 16645 14076 16579 14076 16580 14076 16580 14077 16579 14077 16424 14077 16580 14078 16424 14078 16581 14078 16424 14079 16425 14079 16581 14079 16581 14080 16425 14080 16582 14080 16581 14081 16582 14081 16583 14081 16582 14082 16427 14082 16583 14082 16583 14083 16427 14083 16428 14083 16583 14084 16428 14084 16584 14084 16584 14085 16428 14085 16585 14085 16584 14086 16585 14086 16586 14086 16585 14087 16432 14087 16586 14087 16586 14088 16432 14088 16430 14088 16586 14089 16430 14089 16587 14089 16430 14090 16429 14090 16587 14090 16587 14091 16429 14091 16588 14091 16587 14092 16588 14092 16690 14092 16588 14093 16589 14093 16690 14093 16690 14094 16589 14094 16590 14094 16690 14095 16590 14095 16591 14095 16590 14096 16435 14096 16591 14096 16591 14097 16435 14097 16436 14097 16591 14098 16436 14098 16687 14098 16687 14099 16436 14099 16439 14099 16687 14100 16439 14100 16686 14100 16439 14101 16437 14101 16686 14101 16686 14102 16437 14102 16444 14102 16686 14103 16444 14103 16684 14103 16684 14104 16444 14104 16442 14104 16684 14105 16442 14105 16682 14105 16442 14106 16441 14106 16682 14106 16682 14107 16441 14108 16592 14109 16682 14110 16592 14110 16593 14110 16592 14111 16445 14111 16593 14111 16593 14112 16445 14112 16594 14112 16593 14113 16594 14113 16681 14113 16681 14114 16594 14114 16447 14114 16681 14115 16447 14115 16680 14115 16680 14116 16447 14116 16595 14116 16595 14117 16596 14117 16680 14117 16680 14118 16596 14118 16449 14118 16680 14119 16449 14119 16679 14119 16679 14120 16449 14120 16450 14120 16679 14121 16450 14121 16597 14121 16450 14122 16452 14122 16597 14122 16597 14123 16452 14123 16598 14123 16597 14124 16598 14124 16677 14124 16677 14125 16598 14125 16599 14125 16677 14126 16599 14126 16601 14126 16599 14127 16600 14127 16601 14127 16601 14128 16600 14128 16602 14128 16601 14129 16602 14129 16676 14129 16602 14130 16454 14130 16676 14130 16676 14131 16454 14131 16603 14131 16676 14132 16603 14132 16604 14132 16604 14133 16603 14133 16605 14133 16604 14134 16605 14134 16606 14134 16606 14135 16605 14135 16457 14135 16457 14136 16459 14136 16606 14136 16606 14137 16459 14137 16460 14137 16606 14138 16460 14138 16607 14138 16607 14139 16460 14139 16461 14139 16607 14140 16461 14140 16674 14140 16461 14141 16466 14141 16674 14141 16674 14142 16466 14142 16608 14142 16674 14143 16608 14143 16609 14143 16609 14144 16608 14144 16465 14144 16609 14145 16465 14145 16610 14145 16465 14146 16470 14146 16610 14146 16610 14147 16470 14147 16469 14147 16610 14148 16469 14148 16672 14148 16469 14149 16467 14149 16672 14149 16672 14150 16467 14150 16471 14150 16672 14151 16471 14151 16671 14151 16671 14152 16471 14152 16611 14152 16671 14153 16611 14153 16614 14153 16611 14154 16612 14154 16614 14154 16614 14155 16612 14156 16613 14157 16614 14158 16613 14158 16668 14158 16613 14159 16615 14159 16668 14159 16668 14160 16615 14161 16474 14162 16668 14163 16474 14163 16617 14163 16474 14164 16616 14164 16617 14164 16617 14165 16616 14165 16476 14165 16617 14166 16476 14166 16667 14166 16476 14167 16482 14167 16667 14167 16667 14168 16482 14168 16481 14168 16667 14169 16481 14169 16666 14169 16666 14170 16481 14171 16479 14170 16666 14172 16479 14172 16663 14172 16479 14173 16478 14173 16663 14173 16663 14174 16478 14174 16618 14174 16663 14175 16618 14175 16619 14175 16619 14176 16618 14176 16620 14176 16619 14177 16620 14177 16662 14177 16620 14178 16483 14178 16662 14178 16662 14179 16483 14179 16486 14179 16662 14180 16486 14180 16622 14180 16486 14181 16621 14181 16622 14181 16622 14182 16621 14182 16623 14182 16622 14183 16623 14183 16624 14183 16623 14184 16625 14184 16624 14184 16624 14185 16625 14185 16626 14185 16624 14186 16626 14186 16660 14186 16626 14187 16488 14187 16660 14187 16660 14188 16488 14188 16492 14188 16660 14189 16492 14189 16658 14189 16658 14190 16492 14190 16627 14190 16658 14191 16627 14191 16628 14191 16627 14192 16489 14192 16628 14192 16628 14193 16489 14193 16629 14193 16628 14194 16629 14194 16656 14194 16656 14195 16629 14195 16631 14195 16656 14196 16631 14196 16630 14196 16631 14197 16493 14197 16630 14197 16630 14198 16493 14198 16495 14198 16630 14199 16495 14199 16632 14199 16495 14200 16497 14200 16632 14200 16632 14201 16497 14201 16498 14201 16632 14202 16498 14202 16633 14202 16633 14203 16498 14203 16634 14203 16633 14204 16634 14204 16635 14204 16635 14205 16634 14205 16499 14205 16499 14206 16504 14206 16635 14206 16635 14207 16504 14207 16503 14207 16635 14208 16503 14208 16652 14208 16652 14209 16503 14209 16636 14209 16652 14210 16636 14210 16637 14210 16636 14211 16501 14211 16637 14211 16637 14212 16501 14212 16505 14212 16637 14213 16505 14213 16649 14213 16649 14214 16505 14214 16506 14214 16649 14215 16506 14215 16648 14215 16506 14216 16638 14216 16648 14216 16648 14217 16638 14217 16510 14217 16648 14218 16510 14218 16639 14218 16510 14219 16508 14219 16639 14219 16639 14220 16508 14220 16513 14220 16639 14221 16513 14221 16647 14221 16647 14222 16513 14222 16512 14222 16647 14223 16512 14223 16641 14223 16512 14224 16640 14224 16641 14224 16641 14225 16640 14225 16642 14225 16641 14226 16642 14226 16643 14226 16643 14227 16642 14227 16644 14227 16643 14228 16644 14228 16645 14228 16645 14229 16644 14229 16646 14229 16645 14230 16646 14230 16579 14230 16641 14231 16760 14231 16647 14231 16647 14232 16760 14232 16694 14232 16647 14233 16694 14233 16639 14233 16639 14234 16694 14234 16695 14234 16639 14235 16695 14235 16648 14235 16648 14236 16695 14236 16697 14236 16648 14237 16697 14237 16649 14237 16649 14238 16697 14238 16650 14238 16649 14239 16650 14239 16637 14239 16637 14240 16650 14240 16651 14240 16637 14241 16651 14241 16652 14241 16652 14242 16651 14242 16701 14242 16652 14243 16701 14243 16635 14243 16635 14244 16701 14244 16653 14244 16635 14245 16653 14245 16633 14245 16633 14246 16653 14246 16703 14246 16633 14247 16703 14247 16632 14247 16632 14248 16703 14248 16654 14248 16632 14249 16654 14249 16630 14249 16630 14250 16654 14250 16655 14250 16630 14251 16655 14251 16656 14251 16656 14252 16655 14252 16657 14252 16656 14253 16657 14253 16628 14253 16628 14254 16657 14254 16708 14254 16628 14255 16708 14255 16658 14255 16658 14256 16708 14256 16659 14256 16658 14257 16659 14257 16660 14257 16660 14258 16659 14258 16661 14258 16660 14259 16661 14259 16624 14259 16624 14260 16661 14260 16710 14260 16624 14261 16710 14261 16622 14261 16622 14262 16710 14262 16713 14262 16622 14263 16713 14263 16662 14263 16662 14264 16713 14264 16714 14264 16662 14265 16714 14265 16619 14265 16619 14266 16714 14266 16664 14266 16619 14267 16664 14267 16663 14267 16663 14268 16664 14268 16665 14268 16663 14269 16665 14269 16666 14269 16666 14270 16665 14270 16718 14270 16666 14271 16718 14271 16667 14271 16667 14272 16718 14272 16719 14272 16667 14273 16719 14273 16617 14273 16617 14274 16719 14274 16669 14274 16617 14275 16669 14275 16668 14275 16668 14276 16669 14276 16722 14276 16668 14277 16722 14277 16614 14277 16614 14278 16722 14278 16670 14278 16614 14279 16670 14279 16671 14279 16671 14280 16670 14280 16723 14280 16671 14281 16723 14281 16672 14281 16672 14282 16723 14282 16725 14282 16672 14283 16725 14283 16610 14283 16610 14284 16725 14284 16726 14284 16610 14285 16726 14285 16609 14285 16609 14286 16726 14286 16673 14286 16609 14287 16673 14287 16674 14287 16674 14288 16673 14288 16727 14288 16674 14289 16727 14289 16607 14289 16607 14290 16727 14290 16728 14290 16607 14291 16728 14291 16606 14291 16606 14292 16728 14292 16675 14292 16606 14293 16675 14293 16604 14293 16604 14294 16675 14294 16730 14294 16604 14295 16730 14295 16676 14295 16676 14296 16730 14297 16733 14298 16676 14299 16733 14299 16601 14299 16601 14300 16733 14300 16735 14300 16601 14301 16735 14301 16677 14301 16677 14302 16735 14302 16678 14302 16677 14303 16678 14303 16597 14303 16597 14304 16678 14304 16736 14304 16597 14305 16736 14305 16679 14305 16679 14306 16736 14306 16739 14306 16679 14307 16739 14307 16680 14307 16680 14308 16739 14308 16740 14308 16680 14309 16740 14309 16681 14309 16681 14310 16740 14310 16741 14310 16681 14311 16741 14311 16593 14311 16593 14312 16741 14312 16683 14312 16593 14313 16683 14313 16682 14313 16682 14314 16683 14314 16743 14314 16682 14315 16743 14315 16684 14315 16684 14316 16743 14316 16685 14316 16684 14317 16685 14317 16686 14317 16686 14318 16685 14318 16688 14318 16686 14319 16688 14319 16687 14319 16687 14320 16688 14320 16745 14320 16687 14321 16745 14321 16591 14321 16591 14322 16745 14322 16689 14322 16591 14323 16689 14323 16690 14323 16690 14324 16689 14324 16747 14324 16690 14325 16747 14325 16587 14325 16587 14326 16747 14326 16749 14326 16587 14327 16749 14327 16586 14327 16586 14328 16749 14328 16751 14328 16586 14329 16751 14329 16584 14329 16584 14330 16751 14330 16691 14330 16584 14331 16691 14331 16583 14331 16583 14332 16691 14332 16692 14332 16583 14333 16692 14333 16581 14333 16581 14334 16692 14334 16693 14334 16581 14335 16693 14335 16580 14335 16580 14336 16693 14336 16753 14336 16580 14337 16753 14337 16645 14337 16645 14338 16753 14338 16756 14338 16645 14339 16756 14339 16643 14339 16643 14340 16756 14340 16758 14340 16643 14341 16758 14341 16641 14341 16641 14342 16758 14342 16760 14342 16760 14343 16761 14343 16694 14343 16694 14344 16761 14344 16762 14344 16694 14345 16762 14345 16695 14345 16695 14346 16762 14346 16696 14346 16695 14347 16696 14347 16697 14347 16697 14348 16696 14348 16698 14348 16697 14349 16698 14349 16650 14349 16650 14350 16698 14350 16699 14350 16650 14351 16699 14351 16651 14351 16651 14352 16699 14352 16700 14352 16651 14353 16700 14353 16701 14353 16701 14354 16700 14354 16768 14354 16701 14355 16768 14355 16653 14355 16653 14356 16768 14356 16702 14356 16653 14357 16702 14357 16703 14357 16703 14358 16702 14358 16704 14358 16703 14359 16704 14359 16654 14359 16654 14360 16704 14360 16705 14360 16654 14361 16705 14361 16655 14361 16655 14362 16705 14362 16706 14362 16655 14363 16706 14363 16657 14363 16657 14364 16706 14364 16707 14364 16657 14365 16707 14365 16708 14365 16708 14366 16707 14366 16772 14366 16708 14367 16772 14367 16659 14367 16659 14368 16772 14368 16709 14368 16659 14369 16709 14369 16661 14369 16661 14370 16709 14370 16711 14370 16661 14371 16711 14371 16710 14371 16710 14372 16711 14372 16712 14372 16710 14373 16712 14373 16713 14373 16713 14374 16712 14374 16774 14374 16713 14375 16774 14375 16714 14375 16714 14376 16774 14376 16715 14376 16714 14377 16715 14377 16664 14377 16664 14378 16715 14378 16716 14378 16664 14379 16716 14379 16665 14379 16665 14380 16716 14380 16776 14380 16665 14381 16776 14381 16718 14381 16718 14382 16776 14382 16717 14382 16718 14383 16717 14383 16719 14383 16719 14384 16717 14384 16720 14384 16719 14385 16720 14385 16669 14385 16669 14386 16720 14386 16721 14386 16669 14387 16721 14387 16722 14387 16722 14388 16721 14388 16779 14388 16722 14389 16779 14389 16670 14389 16670 14390 16779 14390 16781 14390 16670 14391 16781 14391 16723 14391 16723 14392 16781 14392 16724 14392 16723 14393 16724 14393 16725 14393 16725 14394 16724 14394 16782 14394 16725 14395 16782 14395 16726 14395 16726 14396 16782 14396 16786 14396 16726 14397 16786 14397 16673 14397 16673 14398 16786 14398 16787 14398 16673 14399 16787 14399 16727 14399 16727 14400 16787 14400 16789 14400 16727 14401 16789 14401 16728 14401 16728 14402 16789 14402 16729 14402 16728 14403 16729 14403 16675 14403 16675 14404 16729 14404 16731 14404 16675 14405 16731 14405 16730 14405 16730 14406 16731 14406 16732 14406 16730 14407 16732 14407 16733 14407 16733 14408 16732 14408 16734 14408 16733 14409 16734 14409 16735 14409 16735 14410 16734 14410 16793 14410 16735 14411 16793 14411 16678 14411 16678 14412 16793 14412 16737 14412 16678 14413 16737 14413 16736 14413 16736 14414 16737 14414 16738 14414 16736 14415 16738 14415 16739 14415 16739 14416 16738 14416 16795 14416 16739 14417 16795 14417 16740 14417 16740 14418 16795 14418 16797 14418 16740 14419 16797 14419 16741 14419 16741 14420 16797 14420 16798 14420 16741 14421 16798 14421 16683 14421 16683 14422 16798 14422 16742 14422 16683 14423 16742 14423 16743 14423 16743 14424 16742 14424 16799 14424 16743 14425 16799 14425 16685 14425 16685 14426 16799 14426 16744 14426 16685 14427 16744 14427 16688 14427 16688 14428 16744 14428 16800 14428 16688 14429 16800 14429 16745 14429 16745 14430 16800 14430 16746 14430 16745 14431 16746 14431 16689 14431 16689 14432 16746 14432 16801 14432 16689 14433 16801 14433 16747 14433 16747 14434 16801 14434 16748 14434 16747 14435 16748 14435 16749 14435 16749 14436 16748 14436 16750 14436 16749 14437 16750 14437 16751 14437 16751 14438 16750 14438 16752 14438 16751 14439 16752 14439 16691 14439 16691 14440 16752 14440 16804 14440 16691 14441 16804 14441 16692 14441 16692 14442 16804 14442 16805 14442 16692 14443 16805 14443 16693 14443 16693 14444 16805 14444 16754 14444 16693 14445 16754 14445 16753 14445 16753 14446 16754 14446 16755 14446 16753 14447 16755 14447 16756 14447 16756 14448 16755 14448 16757 14448 16756 14449 16757 14449 16758 14449 16758 14450 16757 14450 16759 14450 16758 14451 16759 14451 16760 14451 16760 14452 16759 14452 16761 14452 16761 14453 16808 14453 16762 14453 16762 14454 16808 14454 16763 14454 16762 14455 16763 14455 16696 14455 16696 14456 16763 14456 16764 14456 16696 14457 16764 14457 16698 14457 16698 14458 16764 14458 16765 14458 16698 14459 16765 14459 16699 14459 16699 14460 16765 14460 16766 14460 16699 14461 16766 14461 16700 14461 16700 14462 16766 14462 16767 14462 16700 14463 16767 14463 16768 14463 16768 14464 16767 14464 16559 14464 16768 14465 16559 14465 16702 14465 16702 14466 16559 14466 16769 14466 16702 14467 16769 14467 16704 14467 16704 14468 16769 14468 16557 14468 16704 14469 16557 14469 16705 14469 16705 14470 16557 14470 16770 14470 16705 14471 16770 14471 16706 14471 16706 14472 16770 14472 16771 14472 16706 14473 16771 14473 16707 14473 16707 14474 16771 14474 16554 14474 16707 14475 16554 14475 16772 14475 16772 14476 16554 14476 16545 14476 16772 14477 16545 14477 16709 14477 16709 14478 16545 14478 16773 14478 16709 14479 16773 14479 16711 14479 16711 14480 16773 14480 16532 14480 16711 14481 16532 14481 16712 14481 16712 14482 16532 14482 16530 14482 16712 14483 16530 14483 16774 14483 16774 14484 16530 14484 16775 14484 16774 14485 16775 14485 16715 14485 16715 14486 16775 14486 16516 14486 16715 14487 16516 14487 16716 14487 16716 14488 16516 14488 16538 14488 16716 14489 16538 14489 16776 14489 16776 14490 16538 14490 16535 14490 16776 14491 16535 14491 16717 14491 16717 14492 16535 14492 16777 14492 16717 14493 16777 14493 16720 14493 16720 14494 16777 14494 16778 14494 16720 14495 16778 14495 16721 14495 16721 14496 16778 14496 16570 14496 16721 14497 16570 14497 16779 14497 16779 14498 16570 14498 16569 14498 16779 14499 16569 14499 16781 14499 16781 14500 16569 14500 16780 14500 16781 14501 16780 14501 16724 14501 16724 14502 16780 14502 16783 14502 16724 14503 16783 14503 16782 14503 16782 14504 16783 14504 16784 14504 16782 14505 16784 14505 16786 14505 16786 14506 16784 14506 16785 14506 16786 14507 16785 14507 16787 14507 16787 14508 16785 14508 16788 14508 16787 14509 16788 14509 16789 14509 16789 14510 16788 14510 16790 14510 16789 14511 16790 14511 16729 14511 16729 14512 16790 14512 16791 14512 16729 14513 16791 14513 16731 14513 16731 14514 16791 14514 16577 14514 16731 14515 16577 14515 16732 14515 16732 14516 16577 14516 16792 14516 16732 14517 16792 14517 16734 14517 16734 14518 16792 14518 16575 14518 16734 14519 16575 14519 16793 14519 16793 14520 16575 14520 16574 14520 16793 14521 16574 14521 16737 14521 16737 14522 16574 14522 16794 14522 16737 14523 16794 14523 16738 14523 16738 14524 16794 14524 16796 14524 16738 14525 16796 14525 16795 14525 16795 14526 16796 14526 16541 14526 16795 14527 16541 14527 16797 14527 16797 14528 16541 14528 16539 14528 16797 14529 16539 14529 16798 14529 16798 14530 16539 14530 16520 14530 16798 14531 16520 14531 16742 14531 16742 14532 16520 14532 16551 14532 16742 14533 16551 14533 16799 14533 16799 14534 16551 14534 16549 14534 16799 14535 16549 14535 16744 14535 16744 14536 16549 14536 16547 14536 16744 14537 16547 14537 16800 14537 16800 14538 16547 14538 16566 14538 16800 14539 16566 14539 16746 14539 16746 14540 16566 14540 16564 14540 16746 14541 16564 14541 16801 14541 16801 14542 16564 14542 16562 14542 16801 14543 16562 14543 16748 14543 16748 14544 16562 14544 16544 14544 16748 14545 16544 14545 16750 14545 16750 14546 16544 14546 16802 14546 16750 14547 16802 14547 16752 14547 16752 14548 16802 14548 16803 14548 16752 14549 16803 14549 16804 14549 16804 14550 16803 14550 16523 14550 16804 14551 16523 14551 16805 14551 16805 14552 16523 14552 16529 14552 16805 14553 16529 14553 16754 14553 16754 14554 16529 14554 16806 14554 16754 14555 16806 14555 16755 14555 16755 14556 16806 14556 16528 14556 16755 14557 16528 14557 16757 14557 16757 14558 16528 14558 16807 14558 16757 14559 16807 14559 16759 14559 16759 14560 16807 14560 16525 14560 16759 14561 16525 14561 16761 14561 16761 14562 16525 14562 16808 14562 16848 14563 16809 14563 16849 14563 16810 14564 16811 14564 16812 14564 16884 14565 16813 14565 16887 14565 16814 14566 16810 14566 16830 14566 16869 14567 16815 14567 16816 14567 16816 14568 16815 14568 16818 14568 16816 14568 16818 14568 16817 14568 16817 14569 16818 14569 16820 14569 16817 14570 16820 14570 16819 14570 16819 14571 16820 14571 16821 14571 16819 14572 16821 14572 16823 14572 16823 14573 16821 14573 16822 14573 16823 14574 16822 14574 16824 14574 16824 14575 16822 14575 16826 14575 16824 14576 16826 14576 16825 14576 16825 14577 16826 14577 16827 14577 16825 14578 16827 14578 16828 14578 16828 14579 16827 14579 16814 14579 16828 14580 16814 14580 16829 14580 16829 14581 16814 14581 16830 14581 16866 14582 16831 14582 16867 14582 16832 14583 16848 14583 16850 14583 16886 14584 16833 14584 16834 14584 16834 14585 16833 14585 16835 14585 16834 14586 16835 14586 16836 14586 16836 14587 16835 14587 16837 14587 16836 14588 16837 14588 16839 14588 16839 14589 16837 14589 16838 14589 16839 14590 16838 14590 16841 14590 16841 14591 16838 14591 16840 14591 16841 14592 16840 14592 16842 14592 16842 14593 16840 14593 16843 14593 16842 14594 16843 14594 16844 14594 16844 14595 16843 14595 16846 14595 16844 14596 16846 14596 16845 14596 16845 14597 16846 14597 16832 14597 16845 14598 16832 14598 16847 14598 16847 14599 16832 14599 16850 14599 16848 14600 16849 14600 16850 14600 16850 14601 16849 14601 16851 14601 16850 14602 16851 14602 16852 14602 16852 14603 16851 14603 16853 14603 16852 14604 16853 14604 16855 14604 16855 14605 16853 14605 16854 14605 16855 14606 16854 14606 16856 14606 16856 14607 16854 14607 16857 14607 16856 14608 16857 14608 16859 14608 16859 14609 16857 14609 16858 14609 16859 14610 16858 14610 16860 14610 16860 14611 16858 14611 16861 14611 16860 14612 16861 14612 16862 14612 16862 14613 16861 14613 16863 14613 16862 14614 16863 14614 16864 14614 16864 14615 16863 14615 16866 14615 16864 14616 16866 14616 16865 14616 16865 14617 16866 14617 16867 14617 16865 14618 16867 14618 16869 14618 16869 14619 16867 14619 16868 14619 16869 14620 16868 14620 16815 14620 16810 14621 16812 14621 16830 14621 16830 14622 16812 14622 16870 14622 16830 14622 16870 14622 16872 14622 16872 14623 16870 14623 16871 14623 16872 14623 16871 14623 16873 14623 16873 14624 16871 14624 16874 14624 16873 14625 16874 14625 16876 14625 16876 14626 16874 14626 16875 14626 16876 14627 16875 14627 16877 14627 16877 14628 16875 14628 16878 14628 16877 14629 16878 14629 16879 14629 16879 14630 16878 14630 16880 14630 16879 14631 16880 14631 16882 14631 16882 14632 16880 14632 16881 14632 16882 14633 16881 14633 16883 14633 16883 14634 16881 14634 16884 14634 16883 14635 16884 14635 16885 14635 16885 14636 16884 14636 16887 14636 16885 14637 16887 14637 16886 14637 16886 14638 16887 14638 16888 14638 16886 14639 16888 14639 16833 14639 16891 14640 16916 14640 17009 14640 17009 960 16916 960 17008 960 17010 960 17012 960 16889 960 17010 14641 16889 14641 17009 14641 17009 14642 16889 14642 16890 14642 17009 14643 16890 14643 16891 14643 16931 14644 16897 14644 16914 14644 16914 14645 16897 14645 16915 14645 16893 14646 16927 14646 16903 14646 16903 14647 17006 14647 16893 14647 16893 14648 17006 14648 16892 14648 16893 14649 16892 14649 16928 14649 16892 14650 17034 14650 16928 14650 16928 14651 17034 14651 17027 14651 16928 14652 17027 14652 16894 14652 16894 14653 17027 14653 17028 14653 16894 14654 17028 14654 16921 14654 17028 14655 16895 14655 16921 14655 16921 14656 16895 14656 17030 14656 16921 14657 17030 14657 16932 14657 17030 14658 17014 14658 16932 14658 16932 14659 17014 14659 17044 14659 16932 14660 17044 14660 16931 14660 16931 14661 17044 14661 16896 14661 16931 14662 16896 14662 16897 14662 17005 960 16898 960 16899 960 16899 14663 16898 14663 16900 14663 16899 14664 16900 14664 16901 14664 16901 960 16999 960 16899 960 16899 14665 16999 14665 17001 14665 16899 14666 17001 14666 17003 14666 16902 14667 16996 14667 16898 14667 16902 14668 16898 14668 16927 14668 16927 14669 16898 14669 17005 14669 16927 14670 17005 14670 16903 14670 16996 14671 16902 14671 16997 14671 16997 14672 16902 14672 16913 14672 16918 14673 16917 14673 16919 14673 16919 14674 16917 14674 17043 14674 17043 14675 17042 14675 16919 14675 16919 14676 17042 14676 16904 14676 16919 14677 16904 14677 16906 14677 16904 14678 16905 14678 16906 14678 16906 14679 16905 14679 16907 14679 16906 14680 16907 14680 16908 14680 16908 14681 16907 14682 16909 14683 16908 14684 16909 14684 16922 14684 16909 14685 17040 14685 16922 14685 16922 14686 17040 14687 16910 14688 16922 14689 16910 14689 16912 14689 16910 14690 16911 14690 16912 14690 16912 14691 16911 14691 17038 14691 16912 14692 17038 14692 16913 14692 16913 14693 17038 14693 17036 14693 16913 14694 17036 14694 16997 14694 16914 14695 16915 14695 17008 14695 16914 14696 17008 14696 16918 14696 16918 14697 17008 14697 16916 14697 16918 14695 16916 14695 16917 14695 16955 960 16952 960 16918 960 16918 14698 16952 14698 16914 14698 16918 14699 16919 14699 16955 14699 16955 960 16919 960 16906 960 16955 14700 16906 14700 16920 14700 16920 960 16906 960 16908 960 16920 14701 16908 14701 16923 14701 16939 960 16929 960 16921 960 16908 960 16922 960 16923 960 16923 960 16922 960 16912 960 16923 960 16912 960 16924 960 16924 14702 16912 14702 16913 14702 16924 960 16913 960 16925 960 16925 14703 16913 14703 16902 14703 16925 14704 16902 14704 16926 14704 16926 960 16902 960 16927 960 16926 960 16927 960 16938 960 16938 960 16927 960 16893 960 16938 14705 16893 14705 16933 14705 16933 960 16893 960 16928 960 16933 960 16928 960 16929 960 16929 960 16928 960 16894 960 16929 14706 16894 14706 16921 14706 16952 960 16942 960 16914 960 16914 14707 16942 14707 16930 14707 16914 960 16930 960 16931 960 16931 14708 16930 14708 16939 14708 16931 14709 16939 14709 16932 14709 16932 960 16939 960 16921 960 16965 14710 16945 14710 16950 14710 16980 14711 16978 14711 16933 14711 16994 14712 16935 14712 16934 14712 16934 14713 16935 14713 16936 14713 16934 14714 16936 14714 16937 14714 16985 14715 16984 14715 16938 14715 16938 14716 16984 14716 16990 14716 16938 14717 16990 14717 16926 14717 16926 14718 16990 14718 16988 14718 16926 14719 16988 14720 16987 14721 16933 14722 16978 14722 16938 14722 16938 14723 16978 14723 16986 14723 16938 14724 16986 14725 16985 14726 16941 14727 16976 14727 16939 14727 16939 14728 16976 14728 16940 14728 16939 14729 16940 14729 16929 14729 16929 14730 16940 14730 16983 14730 16929 14731 16983 14731 16933 14731 16933 14732 16983 14732 16981 14732 16933 14733 16981 14733 16980 14733 16941 14734 16939 14734 16975 14734 16975 14735 16939 14735 16930 14735 16975 14736 16930 14736 16973 14736 16951 14737 16969 14737 16942 14737 16942 14738 16969 14738 16974 14738 16942 14739 16974 14739 16930 14739 16930 14740 16974 14740 16943 14740 16930 14741 16943 14741 16973 14741 16944 14742 16971 14742 16946 14742 16946 14743 16971 14743 16951 14743 16946 14744 16951 14744 16953 14744 16950 14745 16945 14745 16946 14745 16946 14746 16945 14746 16947 14746 16946 14747 16947 14747 16944 14747 16994 14748 16993 14748 16935 14748 16935 14749 16993 14749 16949 14749 16935 14750 16949 14750 16948 14750 16948 14751 16949 14751 16992 14751 16948 14752 16992 14752 16950 14752 16950 14753 16992 14753 16966 14753 16950 14754 16966 14754 16965 14754 16951 14755 16942 14755 16953 14755 16953 14756 16942 14756 16952 14756 16953 14756 16952 14756 16954 14756 16954 14757 16952 14757 16955 14757 16954 14757 16955 14757 16956 14757 16956 14758 16955 14758 16920 14758 16956 14759 16920 14759 16957 14759 16957 14760 16920 14760 16958 14760 16958 14761 16920 14761 16923 14761 16958 14762 16923 14762 16959 14762 16959 14763 16923 14763 16924 14763 16959 14764 16924 14764 16960 14764 16960 14765 16924 14765 16925 14765 16960 14766 16925 14766 16961 14766 16961 14767 16925 14767 16926 14767 16961 14768 16926 14768 16962 14768 16962 14769 16926 14769 16987 14769 16962 14770 16987 14770 16936 14770 16936 14771 16987 14771 16991 14771 16936 14772 16991 14772 16937 14772 16963 14773 16995 14773 16937 14773 16975 14774 16973 14774 16964 14774 16964 14775 16973 14775 16972 14775 16968 14776 16945 14776 17016 14776 17016 14777 16945 14777 16965 14777 17016 14778 16965 14778 17019 14778 17019 14779 16965 14779 16966 14779 17019 14780 16966 14780 16967 14780 16967 14781 16966 14781 16992 14781 16967 14782 16992 14782 17021 14782 16970 14783 16971 14783 17015 14783 17015 14784 16971 14784 16944 14784 17015 14785 16944 14785 16968 14785 16968 14786 16944 14786 16947 14786 16968 14787 16947 14787 16945 14787 16974 14788 16969 14788 16970 14788 16970 14789 16969 14789 16951 14789 16970 14790 16951 14790 16971 14790 16972 14791 16973 14791 16970 14791 16970 14792 16973 14792 16943 14792 16970 14793 16943 14793 16974 14793 16975 14794 16964 14794 16941 14794 16941 14795 16964 14795 16977 14795 16941 14796 16977 14796 16976 14796 16976 14797 16977 14797 17032 14797 16976 14798 17032 14798 16940 14798 16940 14799 17032 14799 17031 14799 16940 14800 17031 14800 16983 14800 17025 14801 16978 14801 17026 14801 17026 14802 16978 14802 16980 14802 17026 14803 16980 14803 16979 14803 16979 14804 16980 14804 16981 14804 16979 14805 16981 14805 16982 14805 16982 14806 16981 14806 16983 14806 16982 14807 16983 14807 17029 14807 17029 14808 16983 14808 17031 14808 16989 14809 16984 14809 17024 14809 17024 14810 16984 14810 16985 14810 17024 14811 16985 14811 17025 14811 17025 14812 16985 14812 16986 14812 17025 14813 16986 14813 16978 14813 16987 14814 16988 14814 16989 14814 16989 14815 16988 14815 16990 14815 16989 14816 16990 14816 16984 14816 16963 14817 16937 14817 16989 14817 16989 14818 16937 14818 16991 14818 16989 14819 16991 14819 16987 14819 17021 14820 16992 14820 17022 14820 17022 14821 16992 14821 16949 14821 17022 14822 16949 14822 17023 14822 17023 14823 16949 14823 16993 14823 17023 14824 16993 14824 17017 14824 17017 14825 16993 14825 16994 14825 17017 14826 16994 14826 16995 14826 16995 14827 16994 14827 16934 14827 16995 14828 16934 14828 16937 14828 16898 14829 16996 14829 16997 14829 16900 14830 16898 14830 17729 14830 17729 14831 16998 14831 16900 14831 16900 14832 16998 14832 17672 14832 16900 14833 17672 14833 16901 14833 17006 14834 16903 14834 17005 14834 17672 14835 17674 14835 16901 14835 16901 14836 17674 14836 17000 14836 16901 14837 17000 14837 16999 14837 16999 14838 17000 14838 17673 14838 16999 14839 17673 14839 17001 14839 17001 14840 17673 14840 17002 14840 17001 14841 17002 14841 17003 14841 17003 14842 17002 14842 17004 14842 17003 14843 17004 14843 16899 14843 16899 14844 17004 14844 17837 14844 16899 14845 17837 14845 17005 14845 17005 14846 17837 14846 17033 14846 17005 14847 17033 14847 17006 14847 17006 14848 17033 14848 16892 14848 17009 14849 17008 14849 17007 14849 17007 14850 17008 14850 16915 14850 17007 14851 16915 14851 16897 14851 17007 14852 17665 14852 17009 14852 17009 14853 17665 14853 17660 14853 17009 14854 17660 14854 17010 14854 17660 14855 17011 14855 17010 14855 17010 14856 17011 14856 17669 14856 17010 14857 17669 14857 17012 14857 17012 14858 17669 14858 17668 14858 17012 14859 17668 14859 16889 14859 16889 14860 17668 14860 17013 14860 16889 14861 17013 14861 16890 14861 16890 14862 17013 14862 17667 14862 16890 14863 17667 14863 16891 14863 16891 14864 17667 14864 17827 14864 16891 14865 17827 14865 16916 14865 16916 14866 17827 14866 17670 14866 16916 14867 17670 14867 16917 14867 16977 14868 16964 14868 17014 14868 16964 14869 16972 14869 17014 14869 17014 14870 16972 14870 16970 14870 17014 14871 16970 14871 17020 14871 16970 14872 17015 14872 17020 14872 17020 14873 17015 14873 16968 14873 17020 14874 16968 14874 17016 14874 17017 14875 16995 14875 17018 14875 17017 14876 17018 14876 17023 14876 17016 14877 17019 14877 17020 14877 17020 14878 17019 14878 16967 14878 17020 14879 16967 14879 17662 14879 17662 14880 16967 14880 17021 14880 17662 14881 17021 14881 17018 14881 17018 14882 17021 14882 17022 14882 17018 14883 17022 14883 17023 14883 16995 14884 16963 14884 17018 14884 17018 14885 16963 14885 16989 14885 17018 14886 16989 14886 17027 14886 17027 14887 16989 14888 17024 14889 17027 14890 17024 14890 17025 14890 17025 14891 17026 14891 17027 14891 17027 14892 17026 14892 16979 14892 17027 14893 16979 14893 17028 14893 17028 14894 16979 14894 16982 14894 17028 14895 16982 14895 16895 14895 16895 14896 16982 14896 17029 14896 16895 14897 17029 14897 17030 14897 17030 14898 17029 14898 17031 14898 17030 14899 17031 14899 17014 14899 17014 14900 17031 14900 17032 14900 17014 14901 17032 14901 16977 14901 16892 14902 17033 14902 17034 14902 17034 14903 17033 14903 17677 14903 17034 14904 17677 14904 17027 14904 17027 14905 17677 14905 17675 14905 17027 14906 17675 14906 17018 14906 16898 14907 16997 14907 17729 14907 17729 14908 16997 14908 17036 14908 17729 14909 17036 14909 17035 14909 17035 14910 17036 14910 17038 14910 17035 14911 17038 14911 17037 14911 17037 14912 17038 14912 16911 14912 17037 14913 16911 14913 17039 14913 16911 14914 16910 14914 17039 14914 17039 14915 16910 14916 17040 14917 17039 14918 17040 14918 17041 14918 17040 14919 16909 14919 17041 14919 17041 14920 16909 14921 16907 14922 17041 14923 16907 14923 17742 14923 17742 14924 16907 14924 16905 14924 17742 14925 16905 14925 17671 14925 16905 14926 16904 14926 17671 14926 17671 14927 16904 14927 17042 14927 17671 14928 17042 14928 17670 14928 17670 14929 17042 14929 17043 14929 17670 14930 17043 14930 16917 14930 17020 14931 17661 14931 17014 14931 17014 14932 17661 14932 17045 14932 17014 14933 17045 14933 17044 14933 17044 14934 17045 14934 17007 14934 17044 14935 17007 14935 16896 14935 16896 14936 17007 14936 16897 14936 17569 14937 17046 14937 17047 14937 17047 14938 17046 14938 17048 14938 17047 14939 17048 14939 17782 14939 17782 14940 17048 14940 17049 14940 17782 14941 17049 14941 17783 14941 17783 14942 17049 14942 17576 14942 17783 14943 17576 14943 17050 14943 17050 14944 17576 14944 17575 14944 17050 14944 17575 14944 17052 14944 17052 14945 17575 14945 17051 14945 17052 14946 17051 14946 17054 14946 17054 14947 17051 14947 17053 14947 17054 14948 17053 14948 17789 14948 17789 14949 17053 14949 17055 14949 17789 14950 17055 14950 17056 14950 17056 14951 17055 14951 17571 14951 17056 14952 17571 14952 17780 14952 17780 14953 17571 14953 17570 14953 17780 14953 17570 14953 17785 14953 17785 14954 17570 14954 17574 14954 17785 14955 17574 14955 17786 14955 17786 14956 17574 14956 17057 14956 17786 14957 17057 14957 17058 14957 17058 14958 17057 14958 17573 14958 17058 14959 17573 14959 17059 14959 17059 14960 17573 14960 17568 14960 17059 14961 17568 14961 17788 14961 17788 14962 17568 14962 17060 14962 17788 14963 17060 14963 17781 14963 17781 14964 17060 14964 17569 14964 17781 14965 17569 14965 17047 14965 17467 14966 17061 14966 17686 14966 17686 14967 17061 14967 17076 14967 17467 14968 17686 14968 17468 14968 17468 14969 17686 14969 17683 14969 17468 14970 17683 14970 17463 14970 17683 14971 17682 14971 17463 14971 17463 14972 17682 14972 17062 14972 17463 14972 17062 14972 17063 14972 17063 14973 17062 14973 17064 14973 17063 14974 17064 14974 17461 14974 17461 14975 17064 14975 17681 14975 17461 14976 17681 14976 17065 14976 17065 14977 17681 14977 17066 14977 17065 14978 17066 14978 17067 14978 17066 14979 17689 14979 17067 14979 17067 14980 17689 14981 17688 14982 17067 14983 17688 14983 17462 14983 17462 14984 17688 14984 17069 14984 17462 14985 17069 14985 17068 14985 17068 14986 17069 14986 17070 14986 17070 14987 17069 14987 17071 14987 17070 14988 17071 14988 17072 14988 17072 14989 17071 14989 17693 14989 17072 14990 17693 14990 17073 14990 17073 14991 17693 14991 17074 14991 17073 14992 17074 14992 17075 14992 17074 14993 17691 14993 17075 14993 17075 14994 17691 14994 17680 14994 17075 14995 17680 14995 17460 14995 17460 14996 17680 14996 17679 14996 17460 14996 17679 14996 17472 14996 17472 14997 17679 14997 17080 14997 17061 14998 17077 14998 17076 14998 17076 14999 17077 14999 17078 14999 17076 14999 17078 14999 17678 14999 17678 15000 17078 15000 17079 15000 17678 15001 17079 15001 17080 15001 17080 15002 17079 15002 17471 15002 17080 15003 17471 15003 17472 15003 17087 15004 17081 15004 17477 15004 17095 15005 17703 15005 17478 15005 17478 15006 17703 15006 17082 15006 17082 14946 17703 14946 17083 14946 17082 15007 17083 15007 17476 15007 17476 15008 17083 15008 17698 15008 17476 15009 17698 15009 17085 15009 17085 15010 17698 15010 17084 15010 17085 15011 17084 15011 17086 15011 17086 15012 17084 15012 17697 15012 17086 15013 17697 15013 17477 15013 17477 15014 17697 15014 17704 15014 17477 15015 17704 15015 17087 15015 17081 15016 17087 15016 17088 15016 17088 15017 17087 15017 17090 15017 17088 15018 17090 15018 17089 15018 17089 15019 17090 15019 17091 15019 17091 15020 17090 15020 17092 15020 17091 15021 17092 15021 17487 15021 17092 15022 17708 15022 17487 15022 17487 15023 17708 15023 17707 15023 17487 15024 17707 15024 17489 15024 17707 15025 17710 15025 17489 15025 17489 15026 17710 15026 17709 15026 17489 15026 17709 15026 17093 15026 17093 15027 17709 15027 17094 15027 17093 15028 17094 15028 17486 15028 17486 14997 17094 14997 17713 14997 17478 15029 17482 15029 17095 15029 17095 15030 17482 15030 17483 15030 17095 15030 17483 15030 17701 15030 17701 15031 17483 15031 17484 15031 17701 15032 17484 15032 17711 15032 17711 15033 17484 15033 17485 15033 17711 15034 17485 15034 17097 15034 17097 15035 17485 15035 17096 15035 17097 15036 17096 15036 17713 15036 17713 15037 17096 15037 17098 15037 17713 15003 17098 15003 17486 15003 17490 15038 17715 15038 17100 15038 17100 15039 17715 15039 17099 15039 17100 15040 17099 15040 17101 15040 17101 15041 17099 15041 17102 15041 17101 14972 17102 14972 17103 14972 17103 15042 17102 15042 17105 15042 17103 15043 17105 15043 17104 15043 17104 15044 17105 15044 17106 15044 17104 15045 17106 15045 17107 15045 17107 15046 17106 15046 17714 15046 17107 15047 17714 15047 17493 15047 17493 15048 17714 15048 17109 15048 17543 15049 17542 15049 17725 15049 17725 15050 17542 15050 17108 15050 17725 15051 17108 15051 17109 15051 17109 15052 17108 15052 17494 15052 17109 15053 17494 15053 17493 15053 17725 15054 17724 15054 17543 15054 17543 15055 17724 15055 17110 15055 17543 15056 17110 15056 17111 15056 17111 15057 17110 15057 17112 15057 17111 15057 17112 15057 17113 15057 17113 15058 17112 15058 17720 15058 17113 15059 17720 15059 17114 15059 17114 15060 17720 15060 17719 15060 17114 15061 17719 15061 17496 15061 17496 15062 17719 15062 17718 15062 17496 15063 17718 15063 17116 15063 17116 15064 17718 15064 17115 15064 17116 15065 17115 15065 17497 15065 17497 15066 17115 15066 17117 15066 17117 15067 17115 15067 17716 15067 17117 15068 17716 15068 17490 15068 17490 15069 17716 15069 17118 15069 17490 15038 17118 15038 17715 15038 17123 14938 17512 14938 17122 14938 17128 15070 17129 15070 17727 15070 17128 15071 17727 15071 17502 15071 17502 15072 17727 15072 17119 15072 17502 15072 17119 15072 17120 15072 17120 15073 17119 15073 17726 15073 17120 15074 17726 15074 17499 15074 17499 15075 17726 15075 17731 15075 17499 15076 17731 15076 17122 15076 17122 15077 17731 15077 17121 15077 17122 14939 17121 14939 17123 14939 17512 14937 17123 14937 17513 14937 17513 15078 17123 15078 17124 15078 17513 15079 17124 15079 17514 15079 17514 15080 17124 15080 17515 15080 17515 15081 17124 15081 17125 15081 17515 15082 17125 15082 17126 15082 17125 15083 17127 15083 17126 15083 17126 15084 17127 15084 17734 15084 17126 15085 17734 15085 17517 15085 17734 15086 17735 15086 17517 15086 17517 15087 17735 15087 17736 15087 17517 15088 17736 15088 17511 15088 17511 15089 17736 15089 17741 15089 17128 15090 17504 15090 17129 15090 17129 15091 17504 15091 17505 15091 17129 15091 17505 15091 17728 15091 17728 15092 17505 15092 17130 15092 17728 15030 17130 15030 17730 15030 17730 15031 17130 15031 17131 15031 17730 15032 17131 15032 17737 15032 17737 15093 17131 15093 17509 15093 17737 15094 17509 15094 17738 15094 17738 15095 17509 15095 17132 15095 17738 15096 17132 15096 17740 15096 17740 15097 17132 15098 17133 15099 17740 15100 17133 15100 17741 15100 17741 15101 17133 15101 17134 15101 17741 15060 17134 15060 17511 15060 17615 15102 17147 15102 17135 15102 17615 15103 17135 15103 17613 15103 17613 15104 17135 15104 17136 15104 17613 15105 17136 15105 17137 15105 17137 15106 17136 15106 17751 15106 17137 15090 17751 15090 17138 15090 17138 15107 17751 15107 17749 15107 17138 15108 17749 15108 17526 15108 17526 15109 17749 15109 17748 15109 17526 15110 17748 15110 17527 15110 17527 15111 17748 15111 17747 15111 17527 15111 17747 15111 17528 15111 17528 15112 17747 15112 17659 15112 17528 15113 17659 15113 17522 15113 17659 15114 17658 15114 17522 15114 17522 6 17658 6 17755 6 17522 15115 17755 15115 17139 15115 17139 15116 17755 15116 17757 15116 17139 15117 17757 15117 17140 15117 17140 15118 17757 15118 17141 15118 17141 15119 17757 15119 17142 15119 17141 15120 17142 15120 17521 15120 17521 15121 17142 15121 17759 15121 17521 15122 17759 15122 17143 15122 17143 15123 17759 15123 17753 15123 17143 15124 17753 15124 17145 15124 17753 15125 17144 15125 17145 15125 17145 15126 17144 15126 17146 15126 17145 15127 17146 15127 17529 15127 17529 15128 17146 15128 17743 15128 17615 15129 17148 15129 17147 15129 17147 15130 17148 15130 17149 15130 17147 15131 17149 15131 17150 15131 17150 15132 17149 15132 17532 15132 17150 15133 17532 15133 17746 15133 17746 15134 17532 15135 17531 15136 17746 15137 17531 15137 17743 15137 17743 15138 17531 15138 17151 15138 17743 14996 17151 14996 17529 14996 17153 960 17152 960 17174 960 17153 960 17174 960 17155 960 17174 15139 17154 15139 17155 15139 17155 15140 17154 15140 17156 15140 17155 960 17156 960 17986 960 17986 960 17156 960 17157 960 17986 960 17157 960 17189 960 17929 15141 17310 15141 17158 15141 17158 15142 17310 15142 17309 15142 17158 15143 17309 15143 17159 15143 17159 15144 17309 15144 17160 15144 17159 15145 17160 15145 17926 15145 17926 15146 17160 15146 17173 15146 17172 15147 17161 15147 17162 15147 17172 15148 17162 15148 17163 15148 17163 15149 17162 15149 17816 15149 17163 15150 17816 15150 17164 15150 17164 15151 17816 15151 17165 15151 17165 15152 17816 15152 17821 15152 17165 15153 17821 15153 17166 15153 17166 15154 17821 15154 17168 15154 17166 15155 17168 15155 17167 15155 17167 15156 17168 15156 17169 15156 17167 15157 17169 15157 17539 15157 17539 15158 17169 15158 17820 15158 17539 15159 17820 15159 17537 15159 17537 15160 17820 15160 17818 15160 17537 15161 17818 15161 17535 15161 17535 15162 17818 15162 17762 15162 17535 15163 17762 15163 17170 15163 17170 15164 17762 15164 17760 15164 17170 15165 17760 15165 17534 15165 17926 15166 17173 15166 17925 15166 17925 15167 17173 15167 17171 15167 17925 15168 17171 15168 17172 15168 17172 15169 17171 15169 17161 15169 17171 15170 17173 15170 17723 15170 17723 15171 17173 15171 17308 15171 17723 15172 17308 15172 17722 15172 17308 15173 17307 15173 17722 15173 17722 15174 17307 15174 17305 15174 17722 15175 17305 15175 17721 15175 17174 15176 17176 15176 17175 15176 17175 15177 17176 15177 17177 15177 17175 15178 17177 15178 17179 15178 17179 15179 17177 15179 17178 15179 17179 15180 17178 15180 17302 15180 17302 15181 17178 15181 17721 15181 17302 15182 17721 15182 17303 15182 17303 15183 17721 15183 17305 15183 17547 15184 17180 15184 17181 15184 17181 15185 17180 15185 17176 15185 17181 15186 17176 15186 17152 15186 17152 15187 17176 15187 17174 15187 17182 15188 17554 15188 17184 15188 17183 15189 17807 15189 17805 15189 17183 15190 17805 15190 17556 15190 17556 15191 17805 15191 17804 15191 17556 15192 17804 15192 17184 15192 17184 15193 17804 15193 17185 15193 17184 15194 17185 15194 17182 15194 17554 15195 17182 15195 17186 15195 17186 15196 17182 15196 17810 15196 17186 15197 17810 15197 17553 15197 17553 15198 17810 15198 17812 15198 17553 15199 17812 15199 17551 15199 17551 15200 17812 15200 17814 15200 17551 15201 17814 15201 17187 15201 17814 15202 17815 15203 17187 15204 17187 15205 17815 15205 17188 15205 17187 15206 17188 15206 17546 15206 17546 15207 17188 15207 17180 15207 17546 15208 17180 15208 17547 15208 17190 15209 17189 15209 17157 15209 17807 15210 17183 15210 17806 15210 17806 15211 17183 15211 17190 15211 17806 15212 17190 15212 17191 15212 17191 15213 17190 15213 17157 15213 17191 15214 17157 15214 17192 15214 17192 15215 17157 15215 17301 15215 17192 15216 17301 15216 17198 15216 17193 15217 17194 15217 17340 15217 17340 15218 17194 15218 17695 15218 17340 15219 17695 15219 17298 15219 17298 15220 17695 15220 17700 15220 17298 15221 17700 15221 17195 15221 17195 15222 17700 15222 17712 15222 17195 15223 17712 15223 17299 15223 17299 15224 17712 15224 17803 15224 17299 15225 17803 15225 17196 15225 17196 15226 17803 15226 17198 15226 17196 15227 17198 15227 17197 15227 17197 15228 17198 15228 17301 15228 17224 960 17199 960 17898 960 17898 15229 17199 15229 17331 15229 17898 960 17331 960 17200 960 17200 15230 17331 15230 17202 15230 17200 960 17202 960 17201 960 17201 15231 17202 15231 17233 15231 17201 15232 17233 15232 17203 15232 17915 15233 17193 15233 17914 15233 17914 960 17193 960 17339 960 17914 15234 17339 15234 17906 15234 17906 960 17339 960 17204 960 17906 960 17204 960 17909 960 17909 960 17204 960 17206 960 17909 960 17206 960 17205 960 17205 960 17206 960 17216 960 17696 15235 17481 15235 17480 15235 17470 15236 17469 15236 17207 15236 17207 15236 17469 15236 17687 15236 17470 15237 17207 15237 17558 15237 17558 15238 17207 15238 17208 15238 17558 15239 17208 15239 17209 15239 17208 15240 17210 15240 17209 15240 17209 15241 17210 15241 17211 15241 17209 15242 17211 15242 17559 15242 17559 15243 17211 15243 17212 15243 17559 15244 17212 15244 17213 15244 17213 15245 17212 15245 17215 15245 17213 15245 17215 15245 17560 15245 17560 15246 17215 15246 17214 15246 17214 15247 17215 15247 17699 15247 17214 15248 17699 15248 17480 15248 17480 15249 17699 15249 17702 15249 17480 15250 17702 15250 17696 15250 17205 15251 17216 15251 17874 15251 17874 15252 17216 15252 17217 15252 17874 15253 17217 15253 17469 15253 17469 15254 17217 15254 17687 15254 17217 15255 17216 15255 17337 15255 17217 15256 17337 15256 17218 15256 17218 15257 17337 15257 17219 15257 17218 15258 17219 15258 17685 15258 17685 15259 17219 15259 17220 15259 17685 15260 17220 15260 17684 15260 17684 15261 17220 15261 17336 15261 17684 15262 17336 15262 17797 15262 17797 15263 17336 15263 17221 15263 17797 15264 17221 15264 17222 15264 17199 15265 17223 15265 17332 15265 17332 15266 17223 15266 17222 15266 17332 15267 17222 15267 17334 15267 17334 15268 17222 15268 17221 15268 17563 15269 17798 15269 17938 15269 17938 15270 17798 15270 17223 15270 17938 15271 17223 15271 17224 15271 17224 15272 17223 15272 17199 15272 17798 15273 17563 15273 17561 15273 17225 15274 17226 15274 17792 15274 17225 15275 17792 15275 17227 15275 17227 15276 17792 15276 17791 15276 17227 15277 17791 15277 17228 15277 17228 15278 17791 15278 17229 15278 17228 15279 17229 15279 17567 15279 17567 15280 17229 15280 17564 15280 17564 15281 17229 15281 17790 15281 17564 15282 17790 15282 17230 15282 17790 15283 17795 15283 17230 15283 17230 15284 17795 15284 17794 15284 17230 15284 17794 15284 17231 15284 17231 15285 17794 15285 17796 15285 17231 15286 17796 15286 17561 15286 17561 15287 17796 15287 17232 15287 17561 15273 17232 15273 17798 15273 17203 15288 17233 15288 17234 15288 17234 15289 17233 15289 17235 15289 17234 15290 17235 15290 17225 15290 17225 15291 17235 15291 17226 15291 17235 15292 17233 15292 17784 15292 17784 15293 17233 15293 17330 15293 17784 15294 17330 15294 17237 15294 17330 15295 17236 15295 17237 15295 17237 15296 17236 15296 17238 15296 17237 15297 17238 15297 17242 15297 17326 15298 17239 15298 17240 15298 17240 15299 17239 15299 17774 15299 17240 15300 17774 15300 17327 15300 17327 15301 17774 15301 17241 15301 17327 15302 17241 15302 17328 15302 17328 15303 17241 15303 17242 15303 17328 15304 17242 15304 17329 15304 17329 15305 17242 15305 17238 15305 17885 960 17357 960 17243 960 17315 15306 17245 15306 17244 15306 17244 15307 17245 15307 17882 15307 17244 15308 17882 15308 17316 15308 17316 960 17882 960 17885 960 17316 15309 17885 15309 17317 15309 17317 960 17885 960 17243 960 18000 590 17246 590 17247 590 17247 590 17246 590 17999 590 17247 590 17999 590 17248 590 17248 590 17999 590 18029 590 17248 15310 18029 15310 17249 15310 17249 590 18029 590 17251 590 17249 15311 17251 15311 17250 15311 17250 590 17251 590 18028 590 17250 15312 18028 15312 17252 15312 17252 590 18028 590 17323 590 17252 590 17323 590 17253 590 17253 590 17323 590 17255 590 17253 590 17255 590 17254 590 17254 590 17255 590 17256 590 17254 15313 17256 15313 17257 15313 17257 15314 17256 15314 17258 15314 17257 15315 17258 15315 17259 15315 17259 15316 17258 15316 18024 15316 17259 15317 18024 15317 17260 15317 17260 590 18024 590 17261 590 17260 590 17261 590 17262 590 17262 590 17261 590 18022 590 17262 15318 18022 15318 17263 15318 17263 15319 18022 15319 18021 15319 17263 590 18021 590 17264 590 17264 15320 18021 15320 17265 15320 17264 590 17265 590 17266 590 17266 15321 17265 15321 17333 15321 17266 590 17333 590 17267 590 17267 590 17333 590 17335 590 17267 590 17335 590 17268 590 17268 590 17335 590 17269 590 17268 590 17269 590 17270 590 17270 15322 17269 15322 18020 15322 17270 590 18020 590 17271 590 17271 15323 18020 15323 17272 15323 17271 590 17272 590 17273 590 17273 590 17272 590 17338 590 17273 15324 17338 15324 17274 15324 17274 15325 17338 15325 17275 15325 17274 15326 17275 15326 17276 15326 17276 15327 17275 15327 18016 15327 17276 590 18016 590 17277 590 17277 590 18016 590 17300 590 17277 15328 17300 15328 17279 15328 17279 590 17300 590 17278 590 17279 590 17278 590 17280 590 17280 15329 17278 15329 17281 15329 17280 590 17281 590 17282 590 17282 590 17281 590 18012 590 17282 590 18012 590 17283 590 17283 590 18012 590 17284 590 17283 590 17284 590 17285 590 17285 590 17284 590 18011 590 17285 15330 18011 15330 17286 15330 17286 590 18011 590 17304 590 17286 15331 17304 15331 17287 15331 17287 15332 17304 15332 18008 15332 17287 590 18008 590 17288 590 17288 590 18008 590 17306 590 17288 590 17306 590 17289 590 17289 15333 17306 15333 18006 15333 17289 590 18006 590 17290 590 17290 15334 18006 15334 18005 15334 17290 590 18005 590 17291 590 17291 590 18005 590 17292 590 17291 15335 17292 15335 17293 15335 17293 15336 17292 15336 17295 15336 17293 590 17295 590 17294 590 17294 15337 17295 15337 17312 15337 17294 590 17312 590 17296 590 17296 15338 17312 15338 17313 15338 17296 590 17313 590 17297 590 17297 15339 17313 15339 18000 15339 17297 590 18000 590 17247 590 17300 15340 18016 15340 17298 15340 17298 15341 17195 15341 17300 15341 17300 15342 17195 15342 17299 15342 17300 15343 17299 15343 17278 15343 17299 15344 17196 15344 17278 15344 17278 15345 17196 15345 17197 15345 17278 15346 17197 15346 17281 15346 17197 15347 17301 15347 17281 15347 17281 15348 17301 15348 17157 15348 17281 15349 17157 15349 18012 15349 17157 15350 17156 15350 18012 15350 18012 15351 17156 15351 17154 15351 18012 15352 17154 15352 17284 15352 17284 15353 17154 15353 17174 15353 17284 15354 17174 15354 18011 15354 18011 15355 17174 15355 17175 15355 18011 15356 17175 15356 17304 15356 17304 15357 17175 15357 17179 15357 17179 15358 17302 15358 17304 15358 17304 15359 17302 15359 17303 15359 17304 15360 17303 15360 18008 15360 17303 15361 17305 15361 18008 15361 18008 15362 17305 15362 17307 15362 18008 15363 17307 15363 17306 15363 17307 15364 17308 15364 17306 15364 17306 15365 17308 15365 17173 15365 17306 15366 17173 15366 18006 15366 17173 15367 17160 15367 18006 15367 18006 15368 17160 15368 17309 15368 18006 15369 17309 15369 18005 15369 18005 15370 17309 15370 17310 15370 18005 15371 17310 15371 17292 15371 17310 15372 17311 15372 17292 15372 17292 15373 17311 15373 17865 15373 17292 15374 17865 15374 17295 15374 17865 15375 17863 15375 17295 15375 17295 15376 17863 15376 17860 15376 17295 15377 17860 15377 17312 15377 17860 15378 17858 15378 17312 15378 17312 15379 17858 15379 17314 15379 17312 15380 17314 15380 17313 15380 17314 15381 17855 15381 17313 15381 17313 15382 17855 15382 17315 15382 17313 15383 17315 15383 18000 15383 17315 15384 17244 15384 18000 15384 18000 15385 17244 15385 17316 15385 18000 15385 17316 15385 17246 15385 17246 15386 17316 15386 17317 15386 17246 15387 17317 15387 17999 15387 17999 15388 17317 15388 17243 15388 17999 15389 17243 15389 18029 15389 17243 15390 17318 15390 18029 15390 18029 15391 17318 15391 17319 15391 18029 15392 17319 15392 17251 15392 17319 15393 17320 15393 17251 15393 17251 15394 17320 15394 17321 15394 17251 15395 17321 15395 18028 15395 17321 15396 17355 15396 18028 15396 18028 15397 17355 15397 17322 15397 18028 15398 17322 15398 17323 15398 17322 15399 17324 15399 17323 15399 17323 15400 17324 15400 17351 15400 17323 15401 17351 15401 17255 15401 17351 15402 17343 15402 17255 15402 17255 15403 17343 15403 17325 15403 17255 15403 17325 15403 17256 15403 17256 15404 17325 15404 17326 15404 17256 15405 17326 15405 17258 15405 17258 15406 17326 15406 17240 15406 17258 15407 17240 15407 18024 15407 18024 15408 17240 15408 17327 15408 17327 15409 17328 15409 18024 15409 18024 15410 17328 15410 17329 15410 18024 15411 17329 15411 17261 15411 17329 15412 17238 15412 17261 15412 17261 15413 17238 15413 17236 15413 17261 15414 17236 15414 18022 15414 17236 15415 17330 15415 18022 15415 18022 15416 17330 15416 17233 15416 18022 15417 17233 15417 18021 15417 17233 15418 17202 15418 18021 15418 18021 15419 17202 15419 17331 15419 18021 15420 17331 15420 17265 15420 17265 15421 17331 15421 17199 15421 17265 15422 17199 15422 17333 15422 17199 15423 17332 15423 17333 15423 17333 15424 17332 15424 17334 15424 17333 15425 17334 15425 17335 15425 17334 15426 17221 15426 17335 15426 17335 15427 17221 15427 17336 15427 17335 15428 17336 15428 17269 15428 17336 15429 17220 15429 17269 15429 17269 15430 17220 15430 17219 15430 17269 15431 17219 15431 18020 15431 17219 15432 17337 15432 18020 15432 18020 15433 17337 15433 17216 15433 18020 15434 17216 15434 17272 15434 17216 15435 17206 15435 17272 15435 17272 15436 17206 15436 17204 15436 17272 15437 17204 15437 17338 15437 17338 15438 17204 15438 17339 15438 17338 15439 17339 15439 17275 15439 17275 15440 17339 15440 17193 15440 17275 15441 17193 15441 18016 15441 18016 15442 17193 15442 17340 15442 18016 15443 17340 15443 17298 15443 17341 960 17326 960 17891 960 17891 960 17326 960 17325 960 17891 15444 17325 15444 17888 15444 17888 15445 17325 15445 17343 15445 17888 15446 17343 15446 17342 15446 17342 960 17343 960 17351 960 17348 15447 17584 15447 17346 15447 17594 15448 17596 15448 17344 15448 17344 15449 17596 15449 17766 15449 17594 15450 17344 15450 17583 15450 17583 15451 17344 15451 17769 15451 17583 15452 17769 15452 17345 15452 17345 15453 17769 15453 17347 15453 17345 15454 17347 15454 17346 15454 17346 15455 17347 15455 17779 15455 17346 15456 17779 15456 17348 15456 17584 15457 17348 15457 17585 15457 17585 15458 17348 15458 17777 15458 17585 15459 17777 15459 17588 15459 17588 15460 17777 15460 17771 15460 17588 15461 17771 15461 17589 15461 17589 15462 17771 15462 17349 15462 17589 15463 17349 15463 17350 15463 17342 15464 17351 15464 17593 15464 17593 15465 17351 15465 17352 15465 17593 15466 17352 15466 17596 15466 17596 15467 17352 15467 17766 15467 17352 15468 17351 15468 17767 15468 17767 15469 17351 15469 17324 15469 17767 15470 17324 15470 17353 15470 17243 15471 17354 15471 17318 15471 17318 15472 17354 15472 17758 15472 17318 15473 17758 15473 17319 15473 17319 15474 17758 15474 17756 15474 17319 15475 17756 15475 17320 15475 17320 15476 17756 15476 17754 15476 17320 15477 17754 15477 17321 15477 17321 15478 17754 15478 17656 15478 17321 15479 17656 15479 17355 15479 17355 15480 17656 15480 17353 15480 17355 15481 17353 15481 17322 15481 17322 15482 17353 15482 17324 15482 17356 15483 17358 15483 17518 15483 17518 15484 17358 15484 17354 15484 17518 15485 17354 15485 17357 15485 17357 15486 17354 15486 17243 15486 17358 15487 17356 15487 17519 15487 17500 15488 17503 15488 17732 15488 17732 15489 17503 15489 17359 15489 17500 15490 17732 15490 17501 15490 17501 15491 17732 15491 17733 15491 17501 15492 17733 15492 17361 15492 17733 15493 17765 15493 17361 15493 17361 15494 17765 15494 17360 15494 17361 15495 17360 15495 17363 15495 17363 15496 17360 15496 17362 15496 17363 15497 17362 15497 17598 15497 17598 15498 17362 15498 17764 15498 17598 15499 17764 15499 17364 15499 17364 15500 17764 15500 17365 15500 17365 15501 17764 15501 17366 15501 17365 15502 17366 15502 17519 15502 17519 15503 17366 15503 17367 15503 17519 15504 17367 15504 17358 15504 17368 15505 17799 15505 17639 15505 17639 15506 17799 15506 17800 15506 17639 15506 17800 15506 17638 15506 17638 15507 17800 15507 17369 15507 17638 15508 17369 15508 17370 15508 17370 15509 17369 15509 17801 15509 17370 15510 17801 15510 17371 15510 17371 15511 17801 15511 17373 15511 17371 15511 17373 15511 17372 15511 17372 15512 17373 15512 17374 15512 17372 15513 17374 15513 17376 15513 17376 15514 17374 15514 17375 15514 17376 15515 17375 15515 17377 15515 17377 15516 17375 15516 17378 15516 17377 15517 17378 15517 17635 15517 17635 15518 17378 15518 17379 15518 17635 15519 17379 15519 17636 15519 17636 15520 17379 15520 17380 15520 17636 15521 17380 15521 17637 15521 17637 15522 17380 15522 17802 15522 17637 15523 17802 15523 17640 15523 17640 15524 17802 15524 17381 15524 17640 15525 17381 15525 17368 15525 17368 15505 17381 15505 17799 15505 17606 15526 17605 15526 17382 15526 17382 15527 17605 15527 17400 15527 17382 15528 17383 15528 17606 15528 17606 15529 17383 15529 17384 15529 17606 15530 17384 15530 17607 15530 17607 15531 17384 15531 17386 15531 17607 15532 17386 15532 17385 15532 17385 15533 17386 15533 17387 15533 17385 15533 17387 15533 17608 15533 17608 15534 17387 15534 17823 15534 17608 15535 17823 15535 17610 15535 17610 15536 17823 15536 17388 15536 17388 15537 17823 15537 17389 15537 17388 15538 17389 15538 17391 15538 17389 15539 17390 15539 17391 15539 17391 15540 17390 15540 17392 15540 17391 15541 17392 15541 17566 15541 17566 15542 17392 15542 17393 15542 17566 15543 17393 15543 17395 15543 17395 15544 17393 15544 17394 15544 17395 15545 17394 15545 17396 15545 17396 15546 17394 15546 17397 15546 17396 15547 17397 15547 17565 15547 17565 15548 17397 15548 17398 15548 17565 15549 17398 15549 17399 15549 17399 15550 17398 15550 17400 15550 17399 15551 17400 15551 17401 15551 17401 15527 17400 15527 17605 15527 17414 15550 17844 15550 17597 15550 17597 15552 17844 15552 17402 15552 17597 15553 17402 15553 17403 15553 17403 15554 17402 15554 17404 15554 17403 15555 17404 15555 17405 15555 17405 15556 17404 15556 17406 15556 17405 15557 17406 15557 17602 15557 17602 15558 17406 15558 17407 15558 17602 15558 17407 15558 17604 15558 17604 15559 17407 15559 17849 15559 17604 15560 17849 15560 17408 15560 17408 15561 17849 15561 17409 15561 17408 15562 17409 15562 17633 15562 17633 15563 17409 15563 17410 15563 17633 15564 17410 15564 17411 15564 17411 15565 17410 15565 17847 15565 17411 15566 17847 15566 17601 15566 17601 15509 17847 15509 17412 15509 17601 15510 17412 15510 17600 15510 17600 15567 17412 15567 17413 15567 17600 15568 17413 15568 17599 15568 17599 15569 17413 15569 17846 15569 17599 15549 17846 15549 17414 15549 17414 15550 17846 15550 17844 15550 17415 15570 17417 15570 17416 15570 17416 15571 17417 15571 17541 15571 17541 15572 17417 15572 17419 15572 17541 15573 17419 15573 17418 15573 17418 15574 17419 15574 17822 15574 17418 15560 17822 15560 17420 15560 17420 15575 17822 15575 17421 15575 17420 15576 17421 15576 17643 15576 17643 15577 17421 15577 17642 15577 17642 15578 17421 15578 17422 15578 17642 15579 17422 15579 17424 15579 17422 15580 17423 15580 17424 15580 17424 15581 17423 15581 17833 15581 17424 15582 17833 15582 17624 15582 17624 15583 17833 15583 17425 15583 17624 15584 17425 15584 17426 15584 17426 15585 17425 15585 17508 15585 17508 15586 17425 15586 17427 15586 17508 15587 17427 15587 17428 15587 17428 15569 17427 15569 17835 15569 17428 15549 17835 15549 17429 15549 17429 15588 17835 15588 17430 15588 17430 15589 17835 15589 17834 15589 17430 15590 17834 15590 17538 15590 17834 15591 17431 15591 17538 15591 17538 15592 17431 15592 17819 15592 17538 15593 17819 15593 17536 15593 17536 15594 17819 15594 17415 15594 17536 15595 17415 15595 17540 15595 17540 15596 17415 15596 17416 15596 17432 15597 17548 15597 17491 15597 17433 15598 17434 15598 17578 15598 17350 590 17435 590 17946 590 17048 590 17046 590 17579 590 17465 590 17464 590 17562 590 17560 590 17214 590 17473 590 17557 590 17555 590 17479 590 17134 590 17133 590 17510 590 17088 590 17089 590 17474 590 17442 590 17436 590 17437 590 17475 15599 17628 15599 17438 15599 17438 590 17439 590 17634 590 17634 590 17439 590 17440 590 17634 15600 17440 15600 17441 15600 17442 15601 17437 15601 17443 15601 17444 590 17445 590 17623 590 17623 15602 17445 15602 17446 15602 17623 15603 17446 15603 17437 15603 17437 590 17446 590 17447 590 17437 590 17447 590 17443 590 17631 590 17618 590 17448 590 17630 590 17449 590 17632 590 17632 590 17449 590 17450 590 17632 15604 17450 15604 17506 15604 17609 590 17459 590 17453 590 17453 15605 17459 15605 17451 15605 17451 590 17452 590 17453 590 17453 15606 17452 15606 17454 15606 17453 15607 17454 15607 17619 15607 17619 590 17454 590 17455 590 17455 590 17456 590 17619 590 17619 15608 17456 15608 17457 15608 17619 15609 17457 15609 17458 15609 17072 590 17073 590 17634 590 17609 15610 17068 15610 17070 15610 17441 15611 17459 15611 17634 15611 17634 590 17459 590 17609 590 17634 15612 17609 15612 17072 15612 17072 15613 17609 15613 17070 15613 17472 15614 17641 15614 17460 15614 17460 590 17641 590 17634 590 17460 15615 17634 15615 17075 15615 17075 590 17634 590 17073 590 17463 590 17063 590 17464 590 17464 590 17063 590 17461 590 17464 590 17461 590 17611 590 17461 15616 17065 15616 17611 15616 17611 15617 17065 15617 17067 15617 17611 590 17067 590 17609 590 17609 15618 17067 15618 17462 15618 17609 590 17462 590 17068 590 17463 590 17464 590 17468 590 17468 15619 17464 15619 17465 15619 17468 15620 17465 15620 17939 15620 17874 590 17078 590 17466 590 17466 590 17078 590 17077 590 17466 590 17077 590 17934 590 17934 15621 17077 15621 17061 15621 17934 590 17061 590 17939 590 17939 590 17061 590 17467 590 17939 15622 17467 15622 17468 15622 17470 15623 17558 15623 17641 15623 17874 15624 17469 15624 17078 15624 17078 590 17469 590 17470 590 17078 15625 17470 15625 17079 15625 17079 590 17470 590 17641 590 17079 590 17641 590 17471 590 17471 590 17641 590 17472 590 17473 15626 17478 15626 17082 15626 17088 590 17474 590 17081 590 17081 590 17474 590 17475 590 17081 590 17475 590 17477 590 17082 590 17476 590 17473 590 17473 15627 17476 15627 17085 15627 17473 590 17085 590 17475 590 17475 590 17085 590 17086 590 17475 590 17086 590 17477 590 17473 590 17214 590 17478 590 17478 15628 17214 15628 17480 15628 17478 590 17480 590 17482 590 17479 590 17555 590 17990 590 17480 590 17481 590 17482 590 17482 15629 17481 15629 17916 15629 17482 590 17916 590 17483 590 17483 590 17916 590 17993 590 17483 590 17993 590 17484 590 17484 590 17993 590 17992 590 17484 15630 17992 15630 17485 15630 17485 590 17992 590 17990 590 17485 15631 17990 15631 17096 15631 17096 590 17990 590 17555 590 17096 590 17555 590 17098 590 17488 15632 17093 15632 17555 15632 17555 15633 17093 15633 17486 15633 17555 590 17486 590 17098 590 17091 590 17487 590 17488 590 17488 15634 17487 15634 17489 15634 17488 15635 17489 15635 17093 15635 17490 15636 17100 15636 17491 15636 17491 590 17100 590 17101 590 17101 590 17103 590 17491 590 17491 15637 17103 15637 17104 15637 17491 15638 17104 15638 17492 15638 17492 590 17104 590 17107 590 17107 590 17493 590 17492 590 17492 590 17493 590 17494 590 17492 590 17494 590 17544 590 17544 15639 17494 15639 17108 15639 17544 590 17108 590 17542 590 17117 590 17549 590 17497 590 17497 15640 17549 15640 17495 15640 17543 15641 17111 15641 17545 15641 17545 15642 17111 15642 17113 15642 17545 15643 17113 15643 17978 15643 17978 15644 17113 15644 17114 15644 17978 15645 17114 15645 17979 15645 17979 15646 17114 15646 17496 15646 17979 15647 17496 15647 17495 15647 17495 590 17496 590 17116 590 17495 15648 17116 15648 17497 15648 17498 15649 17879 15649 17512 15649 17122 15650 17500 15650 17499 15650 17499 590 17500 590 17501 590 17499 590 17501 590 17120 590 17120 590 17501 590 17603 590 17120 590 17603 590 17502 590 17502 590 17603 590 17128 590 17122 590 17512 590 17500 590 17500 15651 17512 15651 17879 15651 17500 590 17879 590 17503 590 17503 590 17879 590 17878 590 17507 590 17131 590 17130 590 17128 590 17603 590 17504 590 17504 15652 17603 15652 17632 15652 17504 590 17632 590 17505 590 17444 590 17623 590 17506 590 17506 15653 17623 15653 17507 15653 17506 590 17507 590 17632 590 17632 15654 17507 15654 17130 15654 17632 15655 17130 15655 17505 15655 17507 590 17508 590 17131 590 17131 15656 17508 15656 17428 15656 17131 15657 17428 15657 17509 15657 17509 15658 17428 15658 17429 15658 17509 15659 17429 15659 17132 15659 17132 590 17429 590 17430 590 17134 590 17510 590 17511 590 17511 15660 17510 15660 17516 15660 17511 590 17516 590 17517 590 17512 590 17513 590 17498 590 17498 15661 17513 15661 17514 15661 17498 590 17514 590 17969 590 17969 590 17514 590 17515 590 17969 590 17515 590 17516 590 17516 590 17515 590 17126 590 17516 15662 17126 15662 17517 15662 17356 590 17518 590 17520 590 17356 590 17520 590 17519 590 17530 590 17365 590 17529 590 17524 590 17141 590 17520 590 17520 15663 17141 15663 17521 15663 17520 590 17521 590 17519 590 17519 15664 17521 15664 17143 15664 17519 590 17143 590 17365 590 17365 15665 17143 15665 17145 15665 17365 15666 17145 15666 17529 15666 17961 590 17522 590 17523 590 17523 590 17522 590 17139 590 17523 590 17139 590 17524 590 17524 15667 17139 15667 17140 15667 17524 590 17140 590 17141 590 17138 590 17526 590 17525 590 17525 590 17526 590 17527 590 17525 590 17527 590 17961 590 17961 15668 17527 15668 17528 15668 17961 590 17528 590 17522 590 17529 590 17151 590 17530 590 17530 15669 17151 15669 17531 15669 17530 15670 17531 15670 17631 15670 17531 590 17532 590 17631 590 17631 590 17532 590 17149 590 17631 590 17149 590 17620 590 17620 15671 17149 15671 17148 15671 17620 15672 17148 15672 17615 15672 17534 15673 17867 15673 17966 15673 17966 590 17533 590 17534 590 17534 15674 17533 15674 17516 15674 17534 15675 17516 15675 17170 15675 17539 590 17537 590 17536 590 17170 590 17516 590 17535 590 17535 15676 17516 15676 17510 15676 17535 15677 17510 15678 17537 15679 17536 590 17537 590 17538 590 17538 15680 17537 15680 17510 15680 17538 590 17510 590 17430 590 17430 590 17510 590 17133 590 17430 15681 17133 15681 17132 15681 17539 590 17536 590 17167 590 17167 15682 17536 15682 17540 15682 17167 590 17540 590 17166 590 17166 15683 17540 15683 17416 15683 17166 15684 17416 15684 17165 15684 17643 590 17492 590 17420 590 17420 590 17492 590 17544 590 17420 590 17544 590 17418 590 17418 590 17544 590 17541 590 17172 590 17163 590 17544 590 17416 15685 17541 15685 17165 15685 17165 590 17541 590 17544 590 17165 590 17544 590 17164 590 17164 590 17544 590 17163 590 17542 15686 17543 15686 17544 15686 17544 15687 17543 15687 17545 15687 17544 15688 17545 15688 17172 15688 17172 15689 17545 15689 17981 15689 17172 590 17981 590 17925 590 17551 590 17187 590 17549 590 17549 590 17187 590 17546 590 17549 590 17546 590 17495 590 17495 590 17546 590 17547 590 17495 590 17547 590 17181 590 17655 15690 17625 15690 17488 15690 17548 15691 17648 15691 17491 15691 17491 15692 17648 15692 17549 15692 17491 15693 17549 15693 17490 15693 17490 590 17549 590 17117 590 17552 590 17653 590 17186 590 17648 15694 17550 15694 17549 15694 17549 15695 17550 15695 17650 15695 17549 15696 17650 15696 17551 15696 17551 15697 17650 15697 17552 15697 17551 590 17552 590 17553 590 17553 15698 17552 15698 17186 15698 17653 590 17655 590 17186 590 17186 15699 17655 15699 17488 15699 17186 15700 17488 15700 17554 15700 17554 15701 17488 15701 17184 15701 17987 15702 17190 15702 17183 15702 17184 590 17488 590 17556 590 17556 590 17488 590 17555 590 17556 590 17555 590 17183 590 17183 590 17555 590 17557 590 17183 15703 17557 15704 17987 15705 17558 590 17209 590 17641 590 17641 590 17209 590 17559 590 17641 590 17559 590 17473 590 17473 590 17559 590 17213 590 17473 15706 17213 15706 17560 15706 17611 15707 17231 15707 17464 15707 17464 590 17231 590 17561 590 17464 590 17561 590 17562 590 17562 15708 17561 15708 17563 15708 17562 590 17563 590 17942 590 17942 590 17563 590 17938 590 17399 15709 17401 15709 17572 15709 17391 15710 17564 15710 17611 15710 17611 15711 17564 15711 17230 15711 17611 15712 17230 15712 17231 15712 17396 590 17565 590 17227 590 17227 590 17565 590 17943 590 17227 15713 17943 15713 17225 15713 17225 15714 17943 15714 17234 15714 17391 590 17566 590 17564 590 17564 15715 17566 15715 17395 15715 17564 590 17395 590 17567 590 17567 15716 17395 15716 17396 15716 17567 590 17396 590 17228 590 17228 590 17396 590 17227 590 17060 15717 17568 15717 17578 15717 17060 590 17578 590 17569 590 17572 15718 17570 15718 17571 15718 17571 590 17055 590 17572 590 17572 15719 17055 15719 17943 15719 17572 590 17943 590 17399 590 17399 15720 17943 15720 17565 15720 17568 590 17573 590 17578 590 17578 15721 17573 15721 17057 15721 17578 15722 17057 15722 17572 15722 17572 590 17057 590 17574 590 17572 15723 17574 15723 17570 15723 17055 15724 17053 15724 17943 15724 17943 15725 17053 15725 17051 15725 17943 590 17051 590 17944 590 17944 15726 17051 15726 17575 15726 17944 590 17575 590 17577 590 17577 15727 17575 15727 17576 15727 17577 15728 17576 15728 17579 15728 17579 590 17576 590 17049 590 17579 15729 17049 15729 17048 15729 17434 15730 17582 15730 17578 15730 17578 15731 17582 15731 17579 15731 17578 590 17579 590 17569 590 17569 15732 17579 15732 17046 15732 17587 590 17946 590 17580 590 17580 15733 17946 15733 17579 15733 17580 590 17579 590 17581 590 17581 590 17579 590 17582 590 17586 590 17592 590 17346 590 17346 590 17592 590 17345 590 17525 15734 17583 15734 17345 15734 17346 590 17584 590 17586 590 17586 15735 17584 15735 17585 15735 17586 590 17585 590 17587 590 17587 590 17585 590 17588 590 17587 15736 17588 15736 17946 15736 17946 15737 17588 15737 17589 15737 17946 15738 17589 15738 17350 15738 17612 590 17525 590 17590 590 17590 590 17525 590 17345 590 17590 15739 17345 15739 17591 15739 17591 15740 17345 15740 17592 15740 17955 15741 17593 15741 17596 15741 17583 15742 17525 15742 17594 15742 17594 15743 17525 15743 17961 15743 17594 590 17961 590 17596 590 17596 590 17961 590 17595 590 17596 590 17595 590 17955 590 17414 15744 17597 15744 17363 15744 17633 15745 17411 15745 17530 15745 17363 15746 17597 15746 17361 15746 17363 15747 17598 15747 17414 15747 17414 590 17598 590 17364 590 17414 590 17364 590 17599 590 17599 590 17364 590 17365 590 17599 590 17365 590 17600 590 17600 590 17365 590 17530 590 17600 590 17530 590 17601 590 17601 590 17530 590 17411 590 17597 15748 17403 15748 17361 15748 17361 15749 17403 15749 17405 15749 17361 590 17405 590 17501 590 17501 15750 17405 15750 17602 15750 17501 15751 17602 15751 17603 15751 17603 590 17602 590 17604 590 17603 15752 17604 15752 17408 15752 17605 15753 17606 15753 17453 15753 17453 15754 17606 15754 17607 15754 17453 15755 17607 15755 17609 15755 17609 15756 17607 15756 17385 15756 17385 590 17608 590 17609 590 17609 15757 17608 15757 17610 15757 17609 15758 17610 15758 17611 15758 17611 590 17610 590 17388 590 17611 590 17388 590 17391 590 17138 590 17525 590 17137 590 17137 15759 17525 15759 17612 15759 17137 590 17612 590 17613 590 17613 15760 17612 15760 17614 15760 17613 15761 17614 15761 17615 15761 17615 15762 17614 15762 17616 15762 17615 590 17616 590 17620 590 17620 15763 17616 15763 17617 15763 17620 15764 17617 15764 17621 15764 17618 590 17631 590 17458 590 17458 590 17631 590 17620 590 17458 15765 17620 15765 17619 15765 17619 15766 17620 15766 17621 15766 17619 15767 17621 15767 17622 15767 17642 15768 17424 15768 17623 15768 17623 590 17424 590 17624 590 17623 15769 17624 15769 17507 15769 17507 15770 17624 15770 17426 15770 17507 15771 17426 15771 17508 15771 17625 590 17626 590 17488 590 17488 590 17626 590 17474 590 17488 15772 17474 15772 17091 15772 17091 15773 17474 15773 17089 15773 17626 590 17644 590 17474 590 17474 15774 17644 15774 17645 15774 17474 15775 17645 15775 17627 15775 17628 590 17475 590 17436 590 17436 15776 17475 15776 17474 15776 17436 590 17474 590 17437 590 17437 15777 17474 15777 17627 15777 17437 15778 17627 15778 17629 15778 17401 15779 17605 15779 17572 15779 17572 590 17605 590 17453 590 17572 15780 17453 15780 17578 15780 17578 590 17453 590 17619 590 17578 590 17619 590 17433 590 17433 15781 17619 15781 17622 15781 17448 590 17630 590 17631 590 17631 590 17630 590 17632 590 17631 590 17632 590 17530 590 17530 15782 17632 15782 17603 15782 17530 15783 17603 15783 17633 15783 17633 590 17603 590 17408 590 17634 15784 17376 15784 17377 15784 17438 590 17634 590 17475 590 17475 15785 17634 15785 17377 15785 17475 15786 17377 15786 17635 15786 17635 590 17636 590 17475 590 17475 15787 17636 15787 17637 15787 17475 590 17637 590 17473 590 17473 590 17637 590 17640 590 17638 590 17641 590 17639 590 17639 590 17641 590 17473 590 17639 15788 17473 15788 17368 15788 17368 590 17473 590 17640 590 17638 590 17370 590 17641 590 17641 15789 17370 15789 17371 15789 17641 15790 17371 15790 17634 15790 17634 15791 17371 15791 17372 15791 17634 590 17372 590 17376 590 17629 590 17432 590 17437 590 17437 590 17432 590 17491 590 17437 15792 17491 15792 17623 15792 17623 590 17491 590 17492 590 17623 15793 17492 15793 17642 15793 17642 590 17492 590 17643 590 17644 15794 17626 15794 17841 15794 17841 15795 17626 15795 17808 15795 17841 15796 17840 15796 17644 15796 17644 15507 17840 15507 17839 15507 17644 15508 17839 15508 17645 15508 17645 15797 17839 15797 17838 15797 17645 15798 17838 15798 17627 15798 17627 15799 17838 15799 17646 15799 17627 15800 17646 15800 17629 15800 17629 15548 17646 15548 17647 15548 17629 15801 17647 15801 17432 15801 17432 15802 17647 15802 17548 15802 17548 15803 17647 15803 17853 15803 17548 15804 17853 15804 17648 15804 17853 15805 17649 15806 17648 15807 17648 15808 17649 15808 17811 15808 17648 15809 17811 15809 17550 15809 17550 15810 17811 15810 17651 15810 17550 15811 17651 15811 17650 15811 17650 15520 17651 15520 17813 15520 17650 15521 17813 15521 17552 15521 17552 15812 17813 15812 17652 15812 17552 15813 17652 15813 17653 15813 17653 15814 17652 15814 17654 15814 17653 15815 17654 15815 17655 15815 17655 15505 17654 15505 17808 15505 17655 15505 17808 15505 17625 15505 17625 15816 17808 15816 17626 15816 17423 960 17422 960 17850 960 17383 960 17382 960 17843 960 17192 15817 17806 15817 17191 15817 17353 15818 17656 15818 17768 15818 17866 15819 17868 15819 17657 15819 17658 960 17659 960 17768 960 17827 960 17667 960 17826 960 17011 960 17660 960 17664 960 17661 15820 17020 15820 17692 15820 17692 15821 17020 15821 17662 15821 17692 960 17662 960 17663 960 17663 960 17662 960 17018 960 17663 960 17018 960 17705 960 17664 960 17660 960 17666 960 17045 960 17694 960 17007 960 17007 960 17694 960 17666 960 17007 960 17666 960 17665 960 17665 960 17666 960 17660 960 17667 15822 17013 15822 17826 15822 17826 960 17013 960 17668 960 17826 15823 17668 15823 17664 15823 17664 15824 17668 15824 17669 15824 17664 15825 17669 15825 17011 15825 17671 15826 17670 15826 17752 15826 17671 960 17752 960 17742 960 17035 960 17037 960 17848 960 17848 960 17037 960 17039 960 17848 960 17039 960 17745 960 17745 960 17039 960 17041 960 17745 15827 17041 15827 17742 15827 17672 15828 16998 15828 17739 15828 17739 960 16998 960 17729 960 17837 15829 17004 15829 17851 15829 17851 15830 17004 15830 17002 15830 17002 960 17673 960 17851 960 17851 960 17673 960 17000 960 17851 960 17000 960 17836 960 17836 15831 17000 15831 17674 15831 17018 15832 17675 15833 17705 15834 17705 960 17675 960 17677 960 17705 960 17677 960 17676 960 17676 15835 17677 15835 17033 15835 17687 15836 17217 15836 17218 15836 17678 960 17080 960 17208 960 17208 960 17080 960 17679 960 17208 960 17679 960 17692 960 17692 15837 17679 15837 17680 15837 17692 15838 17680 15838 17691 15838 17690 960 17681 960 17064 960 17690 15839 17064 15839 17797 15839 17064 15840 17062 15840 17797 15840 17797 15841 17062 15841 17682 15841 17797 15842 17682 15842 17684 15842 17684 960 17682 960 17683 960 17684 960 17683 960 17685 960 17685 960 17683 960 17686 960 17685 15843 17686 15843 17218 15843 17218 15844 17686 15844 17076 15844 17218 15845 17076 15845 17687 15845 17687 15846 17076 15846 17678 15846 17687 960 17678 960 17207 960 17207 960 17678 960 17208 960 17666 15847 17688 15847 17793 15847 17793 15848 17688 15848 17689 15848 17793 960 17689 960 17690 960 17690 15849 17689 15849 17066 15849 17690 960 17066 960 17681 960 17691 960 17074 960 17692 960 17692 15850 17074 15850 17694 15850 17692 15851 17694 15851 17661 15851 17661 15852 17694 15852 17045 15852 17074 960 17693 960 17694 960 17694 15853 17693 15853 17071 15853 17694 15854 17071 15854 17666 15854 17666 15855 17071 15855 17069 15855 17666 960 17069 960 17688 960 17695 15856 17194 15856 17696 15856 17697 960 17084 960 17663 960 17663 960 17084 960 17698 960 17663 15857 17698 15857 17699 15857 17700 15858 17695 15858 17701 15858 17701 15859 17695 15859 17696 15859 17701 960 17696 960 17095 960 17095 15860 17696 15860 17702 15860 17095 960 17702 960 17703 960 17703 15861 17702 15861 17699 15861 17703 960 17699 960 17083 960 17083 960 17699 960 17698 960 17697 960 17663 960 17704 960 17704 15862 17663 15862 17705 15862 17704 960 17705 960 17087 960 17087 15863 17705 15863 17676 15863 17087 15864 17676 15864 17090 15864 17706 960 17707 960 17809 960 17809 960 17707 960 17708 960 17809 15865 17708 15865 17676 15865 17676 15866 17708 15866 17092 15866 17676 15867 17092 15867 17090 15867 17803 15868 17709 15868 17706 15868 17706 15869 17709 15869 17710 15869 17706 960 17710 960 17707 960 17701 960 17711 960 17700 960 17700 15870 17711 15870 17097 15870 17700 15871 17097 15871 17712 15871 17712 960 17097 960 17713 960 17712 15872 17713 15872 17803 15872 17803 15873 17713 15873 17094 15873 17803 15874 17094 15874 17709 15874 17850 15875 17109 15875 17714 15875 17102 960 17852 960 17105 960 17105 15876 17852 15876 17850 15876 17105 15877 17850 15877 17106 15877 17106 960 17850 960 17714 960 17102 960 17099 960 17852 960 17852 960 17099 960 17715 960 17852 15878 17715 15878 17717 15878 17715 15879 17118 15879 17717 15879 17717 960 17118 960 17716 960 17717 15880 17716 15880 17177 15880 17716 960 17115 960 17177 960 17177 960 17115 960 17718 960 17177 15881 17718 15881 17178 15881 17178 15882 17718 15882 17719 15882 17178 960 17719 960 17721 960 17721 15883 17719 15883 17720 15883 17721 960 17720 960 17722 960 17722 15884 17720 15884 17112 15884 17722 960 17112 960 17723 960 17723 15885 17112 15885 17110 15885 17723 15886 17110 15886 17817 15886 17817 15887 17110 15887 17724 15887 17817 15888 17724 15888 17725 15888 17845 960 17731 960 17726 960 17119 960 17727 960 17848 960 17848 15889 17727 15889 17129 15889 17848 960 17129 960 17728 960 17729 15890 17035 15890 17739 15890 17739 15891 17035 15891 17848 15891 17739 15892 17848 15892 17730 15892 17730 960 17848 960 17728 960 17731 960 17845 960 17121 960 17359 960 17123 960 17732 960 17732 15893 17123 15893 17121 15893 17732 960 17121 960 17733 960 17733 960 17121 960 17845 960 17733 15894 17845 15894 17765 15894 17359 15895 17854 15895 17123 15895 17123 960 17854 960 17856 960 17123 15896 17856 15896 17124 15896 17124 15897 17856 15897 17857 15897 17124 960 17857 960 17125 960 17125 960 17857 960 17859 960 17125 960 17859 960 17127 960 17127 15898 17859 15898 17861 15898 17127 960 17861 960 17734 960 17734 15899 17861 15899 17761 15899 17734 960 17761 960 17735 960 17735 15900 17761 15900 17736 15900 17730 15901 17737 15901 17739 15901 17739 15902 17737 15902 17738 15902 17739 15903 17738 15903 17763 15903 17763 15904 17738 15904 17740 15904 17763 15905 17740 15905 17741 15905 17135 15906 17147 15906 17752 15906 17742 960 17752 960 17745 960 17745 15907 17752 15907 17147 15907 17745 15908 17147 15908 17150 15908 17146 960 17744 960 17743 960 17743 15909 17744 15909 17745 15909 17743 960 17745 960 17746 960 17746 960 17745 960 17150 960 17659 15910 17747 15910 17768 15910 17768 960 17747 960 17748 960 17768 960 17748 960 17750 960 17748 15911 17749 15911 17750 15911 17750 15912 17749 15912 17751 15912 17750 15913 17751 15913 17752 15913 17752 960 17751 960 17136 960 17752 15914 17136 15914 17135 15914 17146 960 17144 960 17744 960 17744 15915 17144 15915 17753 15915 17744 960 17753 960 17366 960 17366 15916 17753 15916 17759 15916 17768 15917 17656 15917 17658 15917 17658 960 17656 960 17754 960 17658 960 17754 960 17755 960 17755 960 17754 960 17756 960 17755 15918 17756 15918 17757 15918 17757 960 17756 960 17758 960 17757 15919 17758 15919 17142 15919 17758 960 17354 960 17142 960 17142 15920 17354 15920 17358 15920 17142 15921 17358 15921 17759 15921 17759 15922 17358 15922 17367 15922 17759 15923 17367 15923 17366 15923 17657 15924 17868 15924 17864 15924 17760 960 17762 960 17761 960 17761 15925 17762 15925 17763 15925 17761 15926 17763 15926 17736 15926 17736 15927 17763 15927 17741 15927 17868 960 17760 960 17864 960 17864 960 17760 960 17761 960 17864 15928 17761 15928 17862 15928 17862 15929 17761 15929 17861 15929 17366 960 17764 960 17744 960 17744 960 17764 960 17362 960 17744 960 17362 960 17845 960 17845 960 17362 960 17360 960 17845 960 17360 960 17765 960 17768 15930 17344 15930 17766 15930 17353 960 17768 960 17767 960 17767 960 17768 960 17766 960 17767 15931 17766 15931 17352 15931 17344 960 17768 960 17769 960 17769 15932 17768 15932 17750 15932 17769 960 17750 960 17347 960 17347 15933 17750 15933 17832 15933 17347 960 17832 960 17770 960 17771 960 17774 960 17349 960 17349 960 17774 960 17239 960 17772 15934 17787 15934 17773 15934 17773 960 17787 960 17774 960 17773 960 17774 960 17775 960 17775 960 17774 960 17771 960 17775 960 17771 960 17776 960 17776 960 17771 960 17777 960 17776 15935 17777 15935 17778 15935 17778 15936 17777 15936 17348 15936 17778 15937 17348 15937 17770 15937 17770 960 17348 960 17779 960 17770 15938 17779 15938 17347 15938 17056 960 17780 960 17843 960 17843 15939 17780 15939 17785 15939 17788 960 17781 960 17787 960 17787 15940 17781 15940 17047 15940 17787 960 17047 960 17774 960 17774 15941 17047 15941 17782 15941 17774 15942 17782 15942 17241 15942 17241 15943 17782 15943 17783 15943 17241 960 17783 960 17242 960 17242 15944 17783 15944 17050 15944 17242 15945 17050 15945 17237 15945 17237 15946 17050 15946 17052 15946 17237 960 17052 960 17784 960 17784 15947 17052 15947 17054 15947 17784 15948 17054 15948 17789 15948 17785 15949 17786 15949 17843 15949 17843 15950 17786 15950 17058 15950 17843 960 17058 960 17787 960 17787 15951 17058 15951 17059 15951 17787 15952 17059 15952 17788 15952 17382 960 17400 960 17843 960 17843 15953 17400 15953 17784 15953 17843 15954 17784 15954 17056 15954 17056 15955 17784 15955 17789 15955 17793 960 17790 960 17392 960 17400 960 17398 960 17784 960 17784 15956 17398 15956 17397 15956 17784 960 17397 960 17394 960 17229 960 17394 960 17790 960 17790 15957 17394 15957 17393 15957 17790 15958 17393 15958 17392 15958 17229 960 17791 960 17394 960 17394 15959 17791 15959 17792 15959 17394 15960 17792 15960 17784 15960 17784 15961 17792 15961 17226 15961 17784 15962 17226 15962 17235 15962 17690 15963 17796 15963 17794 15963 17690 960 17794 960 17793 960 17793 15964 17794 15964 17795 15964 17793 15965 17795 15965 17790 15965 17796 15966 17690 15966 17232 15966 17232 960 17690 960 17797 960 17232 960 17797 960 17798 960 17798 15967 17797 15967 17222 15967 17798 960 17222 960 17223 960 17800 15968 17799 15968 17212 15968 17212 15969 17799 15969 17215 15969 17212 960 17211 960 17800 960 17800 960 17211 960 17210 960 17800 15970 17210 15970 17369 15970 17369 15971 17210 15971 17208 15971 17369 960 17208 960 17801 960 17801 960 17208 960 17692 960 17801 960 17692 960 17373 960 17799 15972 17381 15972 17215 15972 17215 15973 17381 15973 17802 15973 17215 15974 17802 15974 17699 15974 17699 960 17802 960 17380 960 17699 15975 17380 15975 17663 15975 17663 15976 17380 15976 17379 15976 17379 15977 17378 15977 17663 15977 17663 960 17378 960 17375 960 17663 960 17375 960 17692 960 17692 15978 17375 15978 17374 15978 17692 15979 17374 15979 17373 15979 17706 960 17804 960 17803 960 17803 15980 17804 15980 17805 15980 17803 15981 17805 15981 17807 15981 17806 15982 17192 15982 17807 15982 17807 15983 17192 15983 17198 15983 17807 960 17198 960 17803 960 17808 960 17810 960 17809 960 17809 15984 17810 15984 17182 15984 17809 15985 17182 15985 17706 15985 17706 15986 17182 15986 17185 15986 17706 15987 17185 15987 17804 15987 17649 15988 17852 15988 17811 15988 17811 15989 17852 15989 17717 15989 17811 15990 17717 15990 17651 15990 17651 960 17717 960 17813 960 17808 960 17654 960 17810 960 17810 15991 17654 15991 17652 15991 17810 960 17652 960 17812 960 17812 960 17652 960 17813 960 17812 960 17813 960 17814 960 17814 960 17813 960 17717 960 17814 15992 17717 15992 17815 15992 17815 960 17717 960 17188 960 17188 960 17717 960 17180 960 17180 960 17717 960 17177 960 17180 960 17177 960 17176 960 17821 960 17816 960 17817 960 17817 15993 17816 15993 17162 15993 17817 960 17162 960 17723 960 17723 960 17162 960 17161 960 17723 960 17161 960 17171 960 17422 960 17421 960 17850 960 17850 960 17421 960 17817 960 17850 15994 17817 15994 17109 15994 17109 15995 17817 15995 17725 15995 17762 15996 17818 15996 17763 15996 17763 15997 17818 15997 17820 15997 17763 15998 17820 15998 17819 15998 17819 15999 17820 15999 17169 15999 17819 960 17169 960 17415 960 17415 16000 17169 16000 17168 16000 17415 960 17168 960 17417 960 17417 16001 17168 16001 17821 16001 17417 16002 17821 16002 17419 16002 17419 960 17821 960 17817 960 17419 960 17817 960 17822 960 17822 960 17817 960 17421 960 17392 16003 17390 16003 17793 16003 17793 960 17390 960 17389 960 17793 16004 17389 16004 17666 16004 17666 16005 17389 16005 17823 16005 17384 960 17664 960 17386 960 17386 960 17664 960 17666 960 17386 16006 17666 16006 17387 16006 17387 960 17666 960 17823 960 17842 960 17824 960 17826 960 17826 16007 17824 16007 17825 16007 17825 16008 17828 16008 17826 16008 17826 16009 17828 16009 17752 16009 17826 16010 17752 16010 17827 16010 17827 16011 17752 16011 17670 16011 17828 960 17829 960 17752 960 17752 16012 17829 16012 17830 16012 17752 16013 17830 16013 17750 16013 17750 16014 17830 16014 17831 16014 17750 16015 17831 16015 17832 16015 17425 960 17833 960 17836 960 17819 16016 17431 16016 17763 16016 17763 960 17431 960 17834 960 17763 960 17834 960 17739 960 17739 960 17834 960 17835 960 17739 16017 17835 16017 17427 16017 17674 960 17672 960 17836 960 17836 960 17672 960 17739 960 17836 960 17739 960 17425 960 17425 16018 17739 16018 17427 16018 17647 16019 17646 16019 17851 16019 17647 960 17851 960 17853 960 17033 960 17837 960 17676 960 17676 16020 17837 16020 17851 16020 17676 16021 17851 16021 17838 16021 17838 16022 17851 16022 17646 16022 17838 960 17839 960 17676 960 17676 16023 17839 16023 17840 16023 17676 16024 17840 16024 17809 16024 17809 16025 17840 16025 17841 16025 17809 960 17841 960 17808 960 17772 960 17842 960 17787 960 17787 16026 17842 16026 17826 16026 17787 960 17826 960 17843 960 17843 960 17826 960 17664 960 17843 16027 17664 16027 17383 16027 17383 16028 17664 16028 17384 16028 17406 960 17404 960 17845 960 17726 960 17119 960 17845 960 17845 16029 17119 16029 17848 16029 17845 16030 17848 16030 17406 16030 17406 960 17848 960 17407 960 17846 960 17744 960 17844 960 17844 16031 17744 16031 17845 16031 17844 16032 17845 16032 17402 16032 17402 960 17845 960 17404 960 17847 16033 17745 16033 17412 16033 17412 16034 17745 16034 17744 16034 17412 960 17744 960 17413 960 17413 960 17744 960 17846 960 17847 960 17410 960 17745 960 17745 16035 17410 16035 17409 16035 17745 16036 17409 16036 17848 16036 17848 960 17409 960 17849 960 17848 960 17849 960 17407 960 17833 960 17423 960 17836 960 17836 16037 17423 16037 17850 16037 17836 16038 17850 16038 17851 16038 17851 16039 17850 16039 17852 16039 17851 16040 17852 16040 17853 16040 17853 960 17852 960 17649 960 17854 16041 17315 16041 17855 16041 17854 16042 17855 16042 17856 16042 17856 16043 17855 16043 17314 16043 17856 16044 17314 16044 17857 16044 17857 16045 17314 16045 17858 16045 17857 16046 17858 16046 17859 16046 17859 16047 17858 16047 17860 16047 17859 16048 17860 16048 17861 16048 17861 16049 17860 16049 17863 16049 17861 16050 17863 16050 17862 16050 17862 16051 17863 16051 17865 16051 17862 16052 17865 16052 17864 16052 17864 16053 17865 16053 17311 16053 17864 16054 17311 16054 17657 16054 17657 16055 17311 16055 17310 16055 17657 16056 17310 16056 17866 16056 17310 16057 17929 16057 17866 16057 17866 16058 17929 16058 17867 16058 17866 16059 17867 16059 17868 16059 17868 16060 17867 16061 17534 16062 17868 16063 17534 16063 17760 16063 17948 16064 17869 16064 17870 16064 17922 16065 17871 16066 17923 16067 17189 16068 17190 16068 17987 16068 17872 16069 17995 16070 17873 16071 17205 16072 17874 16072 17466 16072 17937 16073 17875 16073 17936 16073 17342 16074 17593 16074 17955 16074 17958 16075 17876 16075 17877 16075 17245 16076 17878 16076 17879 16076 17963 16077 17880 16077 17881 16077 17520 16078 17518 16078 17357 16078 17881 16079 17883 16079 17882 16079 17882 16080 17883 16080 17884 16080 17882 16081 17884 16081 17885 16081 17885 16082 17884 16082 17357 16082 17886 16083 17891 16083 17887 16083 17887 16084 17891 16084 17888 16084 17887 16085 17888 16085 17954 16085 17889 16086 17890 16086 17892 16086 17947 16087 17341 16087 17892 16087 17892 16088 17341 16088 17891 16088 17892 16089 17891 16089 17889 16089 17889 16090 17891 16090 17886 16090 17889 16091 17886 16091 17893 16091 17901 16092 17200 16092 17894 16092 17894 16093 17200 16093 17201 16093 17894 16094 17201 16094 17895 16094 17895 16095 17201 16095 17203 16095 17895 16096 17203 16096 17234 16096 17900 16097 17896 16097 17899 16097 17937 16098 17224 16098 17897 16098 17897 16099 17224 16099 17898 16099 17897 16100 17898 16100 17899 16100 17899 16101 17898 16101 17200 16101 17899 16102 17200 16102 17900 16102 17900 16103 17200 16103 17901 16103 17900 16104 17901 16104 17902 16104 17205 16105 17903 16105 17909 16105 17909 16106 17903 16106 17910 16106 17908 16107 17904 16108 17907 16109 17872 16110 17914 16110 17905 16110 17905 16111 17914 16111 17906 16111 17905 16112 17906 16112 17907 16112 17907 16113 17906 16113 17909 16113 17907 16114 17909 16114 17908 16114 17908 16115 17909 16115 17910 16115 17908 16116 17910 16116 17911 16116 17873 16117 17912 16117 17913 16117 17872 16118 17873 16119 17914 16120 17914 16121 17873 16121 17913 16121 17914 16122 17913 16122 17915 16122 17915 16123 17913 16123 17991 16123 17915 16124 17991 16124 17916 16124 17917 16125 17918 16126 17988 16127 17922 16128 17155 16128 17919 16128 17919 16129 17155 16129 17986 16129 17919 16130 17986 16130 17988 16130 17923 16131 17920 16131 17921 16131 17495 16132 17181 16132 17152 16132 17922 16133 17923 16134 17155 16135 17155 16136 17923 16136 17921 16136 17155 16137 17921 16137 17153 16137 17153 16138 17921 16138 17924 16138 17153 16139 17924 16139 17152 16139 17152 16140 17924 16140 17977 16140 17152 16141 17977 16141 17495 16141 17926 16142 17925 16142 17981 16142 17931 16143 17159 16143 17980 16143 17980 16144 17159 16144 17926 16144 17932 16145 17927 16145 17928 16145 17967 16146 17929 16146 17930 16146 17930 16147 17929 16147 17158 16147 17930 16148 17158 16148 17928 16148 17928 16149 17158 16149 17159 16149 17928 16150 17159 16150 17932 16150 17932 16151 17159 16151 17931 16151 17932 16152 17931 16152 17933 16152 17205 16153 17466 16153 17903 16153 17903 16154 17466 16154 17934 16154 17903 16155 17934 16155 17940 16155 17935 16156 17941 16156 17936 16156 17936 16157 17941 16157 17942 16157 17936 16158 17942 16158 17937 16158 17937 16159 17942 16159 17938 16159 17937 16160 17938 16160 17224 16160 17934 16161 17939 16161 17940 16161 17940 16162 17939 16162 17465 16162 17940 16163 17465 16163 17941 16163 17941 16164 17465 16164 17562 16164 17941 16165 17562 16165 17942 16165 17234 16166 17943 16166 17895 16166 17895 16167 17943 16167 17944 16167 17895 16168 17944 16168 17945 16168 17945 16169 17944 16169 17577 16169 17435 16170 17341 16170 17946 16170 17946 16171 17341 16171 17947 16171 17946 16172 17947 16172 17579 16172 17579 16173 17947 16173 17948 16173 17579 16174 17948 16174 17577 16174 17577 16175 17948 16175 17870 16175 17577 16176 17870 16176 17945 16176 17945 16177 17870 16177 17949 16177 17950 16178 17951 16178 17952 16178 17953 16179 17595 16179 17961 16179 17953 16180 17961 16180 17960 16180 17888 16181 17342 16181 17954 16181 17954 16182 17342 16182 17955 16182 17954 16183 17955 16183 17952 16183 17952 16184 17955 16184 17595 16184 17952 16185 17595 16185 17950 16185 17950 16186 17595 16186 17953 16186 17950 16187 17953 16187 17956 16187 17877 16188 17957 16188 17959 16188 17884 16189 17958 16189 17357 16189 17357 16190 17958 16190 17877 16190 17357 16191 17877 16191 17520 16191 17520 16192 17877 16192 17959 16192 17520 16193 17959 16193 17524 16193 17524 16194 17959 16194 17960 16194 17524 16195 17960 16195 17523 16195 17523 16196 17960 16196 17961 16196 17879 16197 17498 16197 17962 16197 17962 16198 17498 16198 17970 16198 17882 16199 17245 16199 17881 16199 17881 16200 17245 16200 17879 16200 17881 16201 17879 16201 17963 16201 17963 16202 17879 16202 17962 16202 17963 16203 17962 16203 17964 16203 17972 16204 17965 16204 17971 16204 17867 16205 17929 16205 17966 16205 17966 16206 17929 16206 17967 16206 17966 16207 17967 16207 17533 16207 17533 16208 17967 16208 17968 16208 17498 16209 17969 16209 17970 16209 17970 16210 17969 16210 17516 16210 17970 16211 17516 16211 17971 16211 17971 16212 17516 16212 17533 16212 17971 16213 17533 16213 17972 16213 17972 16214 17533 16214 17968 16214 17972 16215 17968 16215 17973 16215 17974 16216 17975 16216 17982 16216 17976 16217 17978 16217 17977 16217 17977 16218 17978 16218 17979 16218 17977 16219 17979 16219 17495 16219 17926 16220 17981 16220 17980 16220 17980 16221 17981 16221 17545 16221 17980 16222 17545 16222 17982 16222 17982 16223 17545 16223 17978 16223 17982 16224 17978 16224 17974 16224 17974 16225 17978 16225 17976 16225 17974 16226 17976 16226 17983 16226 17987 16227 17557 16228 17984 16229 17984 16230 17557 16230 17479 16230 17984 16231 17479 16231 17985 16231 17986 16232 17189 16232 17988 16232 17988 16233 17189 16233 17987 16233 17988 16234 17987 16235 17917 16236 17917 16237 17987 16237 17984 16237 17917 16238 17984 16238 17989 16238 17479 16239 17990 16239 17985 16239 17985 16240 17990 16240 17992 16240 17985 16241 17992 16241 17991 16241 17991 16242 17992 16242 17993 16242 17991 16243 17993 16243 17916 16243 17994 16244 17995 16244 17996 16244 17996 16245 17995 16245 17872 16245 17996 16246 17872 16246 17997 16246 17997 16247 17872 16247 17998 16247 17999 16248 18101 16248 17246 16248 17246 16249 18101 16249 18100 16249 17246 16250 18100 16250 18000 16250 18000 16251 18100 16251 18001 16251 18000 16252 18001 16252 17313 16252 17313 16253 18001 16253 18002 16253 17313 16254 18002 16254 17312 16254 17312 16255 18002 16255 18003 16255 17312 16255 18003 16255 17295 16255 17295 16256 18003 16256 18004 16256 17295 16257 18004 16257 17292 16257 17292 16258 18004 16258 18098 16258 17292 16259 18098 16259 18005 16259 18005 16260 18098 16260 18007 16260 18005 16261 18007 16261 18006 16261 18006 16262 18007 16262 18097 16262 18006 16263 18097 16263 17306 16263 17306 16264 18097 16264 18095 16264 17306 16265 18095 16265 18008 16265 18008 16266 18095 16266 18094 16266 18008 16267 18094 16267 17304 16267 17304 16268 18094 16268 18009 16268 17304 16269 18009 16269 18011 16269 18011 16270 18009 16270 18010 16270 18011 16271 18010 16271 17284 16271 17284 16272 18010 16272 18093 16272 17284 16273 18093 16273 18012 16273 18012 16274 18093 16274 18091 16274 18012 16275 18091 16275 17281 16275 17281 16276 18091 16276 18013 16276 17281 16277 18013 16277 17278 16277 17278 16278 18013 16278 18014 16278 17278 16279 18014 16279 17300 16279 17300 16280 18014 16280 18015 16280 17300 16281 18015 16281 18016 16281 18016 16282 18015 16282 18017 16282 18016 16283 18017 16283 17275 16283 17275 16284 18017 16284 18124 16284 17275 16285 18124 16285 17338 16285 17338 16286 18124 16286 18018 16286 17338 16287 18018 16287 17272 16287 17272 16288 18018 16288 18123 16288 17272 16289 18123 16289 18020 16289 18020 16290 18123 16290 18019 16290 18020 16290 18019 16290 17269 16290 17269 16291 18019 16291 18122 16291 17269 16292 18122 16292 17335 16292 17335 16293 18122 16293 18120 16293 17335 16294 18120 16294 17333 16294 17333 16295 18120 16295 18118 16295 17333 16296 18118 16296 17265 16296 17265 16297 18118 16297 18116 16297 17265 16298 18116 16298 18021 16298 18021 16299 18116 16299 18115 16299 18021 16300 18115 16300 18022 16300 18022 16301 18115 16301 18023 16301 18022 16302 18023 16302 17261 16302 17261 16303 18023 16303 18112 16303 17261 16304 18112 16304 18024 16304 18024 16305 18112 16305 18025 16305 18024 16306 18025 16306 17258 16306 17258 16307 18025 16307 18109 16307 17258 16308 18109 16308 17256 16308 17256 16309 18109 16309 18107 16309 17256 16310 18107 16310 17255 16310 17255 16311 18107 16311 18026 16311 17255 16312 18026 16312 17323 16312 17323 16313 18026 16313 18027 16313 17323 16314 18027 16314 18028 16314 18028 16315 18027 16315 18105 16315 18028 16316 18105 16316 17251 16316 17251 16317 18105 16317 18104 16317 17251 16318 18104 16318 18029 16318 18029 16319 18104 16319 18102 16319 18029 16320 18102 16320 17999 16320 17999 16321 18102 16321 18101 16321 18087 16322 18030 16322 18032 16322 18032 16323 18030 16323 18031 16323 18032 16324 18031 16324 18033 16324 18033 16325 18031 16325 18103 16325 18033 16326 18103 16326 18034 16326 18034 16327 18103 16327 18035 16327 18034 16328 18035 16328 18036 16328 18036 16329 18035 16329 18037 16329 18036 16330 18037 16330 18038 16330 18038 16331 18037 16331 18106 16331 18038 16331 18106 16331 18039 16331 18039 16332 18106 16332 18040 16332 18039 16333 18040 16333 18041 16333 18041 16334 18040 16334 18108 16334 18041 16335 18108 16335 18042 16335 18042 16336 18108 16336 18110 16336 18042 16337 18110 16337 18043 16337 18043 16338 18110 16338 18111 16338 18043 16339 18111 16339 18044 16339 18044 16340 18111 16340 18113 16340 18044 16341 18113 16341 18045 16341 18045 16342 18113 16342 18114 16342 18045 16343 18114 16343 18047 16343 18047 16344 18114 16344 18046 16344 18047 16345 18046 16345 18048 16345 18048 16346 18046 16346 18117 16346 18048 16347 18117 16347 18049 16347 18049 16348 18117 16348 18119 16348 18049 16349 18119 16349 18050 16349 18050 16350 18119 16350 18121 16350 18050 16351 18121 16351 18051 16351 18051 16352 18121 16352 18052 16352 18051 16353 18052 16353 18054 16353 18054 16354 18052 16354 18053 16354 18054 16355 18053 16355 18055 16355 18055 16356 18053 16356 18056 16356 18055 16357 18056 16357 18057 16357 18057 16358 18056 16358 18059 16358 18057 16359 18059 16359 18058 16359 18058 16360 18059 16360 18061 16360 18058 16361 18061 16361 18060 16361 18060 16362 18061 16362 18089 16362 18060 16363 18089 16363 18062 16363 18062 16364 18089 16364 18063 16364 18062 16365 18063 16365 18064 16365 18064 16366 18063 16366 18065 16366 18064 16367 18065 16367 18066 16367 18066 16368 18065 16368 18090 16368 18066 16369 18090 16369 18067 16369 18067 16370 18090 16370 18092 16370 18067 16371 18092 16371 18068 16371 18068 16372 18092 16372 18070 16372 18068 16373 18070 16373 18069 16373 18069 16374 18070 16374 18071 16374 18069 16374 18071 16374 18072 16374 18072 16375 18071 16375 18073 16375 18072 16376 18073 16376 18074 16376 18074 16377 18073 16377 18096 16377 18074 16378 18096 16378 18076 16378 18076 16379 18096 16379 18075 16379 18076 16380 18075 16380 18077 16380 18077 16381 18075 16381 18078 16381 18077 16382 18078 16382 18079 16382 18079 16383 18078 16383 18080 16383 18079 16384 18080 16384 18081 16384 18081 16385 18080 16385 18082 16385 18081 16386 18082 16386 18083 16386 18083 16387 18082 16387 18099 16387 18083 16387 18099 16387 18084 16387 18084 16388 18099 16388 18085 16388 18084 16389 18085 16389 18086 16389 18086 16390 18085 16390 18088 16390 18086 16391 18088 16391 18087 16391 18087 16392 18088 16392 18030 16392 18059 16393 18017 16393 18061 16393 18061 16394 18017 16394 18015 16394 18061 590 18015 590 18089 590 18089 590 18015 590 18014 590 18089 16395 18014 16395 18063 16395 18063 16396 18014 16396 18013 16396 18063 16397 18013 16397 18065 16397 18065 590 18013 590 18091 590 18065 590 18091 590 18090 590 18090 590 18091 590 18093 590 18090 16398 18093 16398 18092 16398 18092 590 18093 590 18010 590 18092 16399 18010 16399 18070 16399 18070 590 18010 590 18009 590 18070 16400 18009 16400 18071 16400 18071 16401 18009 16401 18094 16401 18071 16402 18094 16402 18073 16402 18073 590 18094 590 18095 590 18073 590 18095 590 18096 590 18096 16403 18095 16403 18097 16403 18096 16404 18097 16404 18075 16404 18075 16405 18097 16405 18007 16405 18075 590 18007 590 18078 590 18078 590 18007 590 18098 590 18078 590 18098 590 18080 590 18080 16406 18098 16406 18004 16406 18080 590 18004 590 18082 590 18082 590 18004 590 18003 590 18082 590 18003 590 18099 590 18099 590 18003 590 18002 590 18099 590 18002 590 18085 590 18085 590 18002 590 18001 590 18085 590 18001 590 18088 590 18088 590 18001 590 18100 590 18088 590 18100 590 18030 590 18030 590 18100 590 18101 590 18030 590 18101 590 18031 590 18031 590 18101 590 18102 590 18031 590 18102 590 18103 590 18103 590 18102 590 18104 590 18103 590 18104 590 18035 590 18035 590 18104 590 18105 590 18035 590 18105 590 18037 590 18037 16407 18105 16407 18027 16407 18037 590 18027 590 18106 590 18106 590 18027 590 18026 590 18106 590 18026 590 18040 590 18040 16408 18026 16408 18107 16408 18040 590 18107 590 18108 590 18108 590 18107 590 18109 590 18108 16409 18109 16409 18110 16409 18110 590 18109 590 18025 590 18110 16410 18025 16410 18111 16410 18111 590 18025 590 18112 590 18111 16411 18112 16411 18113 16411 18113 590 18112 590 18023 590 18113 16412 18023 16412 18114 16412 18114 16413 18023 16413 18115 16413 18114 590 18115 590 18046 590 18046 16414 18115 16414 18116 16414 18046 590 18116 590 18117 590 18117 16415 18116 16415 18118 16415 18117 590 18118 590 18119 590 18119 16416 18118 16416 18120 16416 18119 590 18120 590 18121 590 18121 16417 18120 16417 18122 16417 18121 16418 18122 16418 18052 16418 18052 16419 18122 16419 18019 16419 18052 590 18019 590 18053 590 18053 16420 18019 16420 18123 16420 18053 590 18123 590 18056 590 18056 590 18123 590 18018 590 18056 16421 18018 16421 18059 16421 18059 590 18018 590 18124 590 18059 16422 18124 16422 18017 16422 18144 16423 18125 16423 18126 16423 18127 16424 18128 16424 18170 16424 18180 16425 18129 16425 18181 16425 18130 16426 18127 16426 18208 16426 18131 16427 18169 16427 18196 16427 18196 16428 18169 16428 18132 16428 18196 16429 18132 16429 18133 16429 18133 16430 18132 16430 18134 16430 18133 16431 18134 16431 18199 16431 18199 16432 18134 16432 18135 16432 18199 16432 18135 16432 18136 16432 18136 16433 18135 16433 18137 16433 18136 16434 18137 16434 18138 16434 18138 16435 18137 16435 18139 16435 18138 16436 18139 16436 18140 16436 18140 16437 18139 16437 18141 16437 18140 16438 18141 16438 18203 16438 18203 16439 18141 16439 18130 16439 18203 16440 18130 16440 18205 16440 18205 16441 18130 16441 18208 16441 18167 16442 18142 16442 18143 16442 18155 16443 18144 16443 18145 16443 18223 16444 18183 16444 18224 16444 18224 16445 18183 16445 18146 16445 18224 16446 18146 16446 18147 16446 18147 16447 18146 16447 18148 16447 18147 16448 18148 16448 18149 16448 18149 16449 18148 16449 18150 16449 18149 16449 18150 16449 18229 16449 18229 16450 18150 16450 18151 16450 18229 16451 18151 16451 18231 16451 18231 16452 18151 16452 18152 16452 18231 16453 18152 16453 18153 16453 18153 16454 18152 16454 18154 16454 18153 16455 18154 16455 18156 16455 18156 16456 18154 16456 18155 16456 18156 16457 18155 16457 18157 16457 18157 16458 18155 16458 18145 16458 18144 16459 18126 16459 18145 16459 18145 16460 18126 16460 18158 16460 18145 16461 18158 16461 18238 16461 18238 16462 18158 16462 18159 16462 18238 16463 18159 16463 18239 16463 18239 16464 18159 16464 18160 16464 18239 16465 18160 16465 18161 16465 18161 16466 18160 16466 18162 16466 18161 16467 18162 16467 18184 16467 18184 16468 18162 16468 18163 16468 18184 16468 18163 16468 18188 16468 18188 16469 18163 16469 18164 16469 18188 16470 18164 16470 18165 16470 18165 16471 18164 16471 18166 16471 18165 16472 18166 16472 18190 16472 18190 16473 18166 16473 18167 16473 18190 16474 18167 16474 18192 16474 18192 16475 18167 16475 18143 16475 18192 16476 18143 16476 18131 16476 18131 16477 18143 16477 18168 16477 18131 16478 18168 16478 18169 16478 18127 16479 18170 16479 18208 16479 18208 16480 18170 16480 18172 16480 18208 16481 18172 16481 18171 16481 18171 16482 18172 16482 18173 16482 18171 16483 18173 16483 18210 16483 18210 16484 18173 16484 18174 16484 18210 16485 18174 16485 18212 16485 18212 16486 18174 16486 18175 16486 18212 16487 18175 16487 18215 16487 18215 16488 18175 16488 18176 16488 18215 16489 18176 16489 18216 16489 18216 16490 18176 16490 18178 16490 18216 16491 18178 16491 18177 16491 18177 16492 18178 16492 18179 16492 18177 16492 18179 16492 18219 16492 18219 16493 18179 16493 18180 16493 18219 16494 18180 16494 18222 16494 18222 16495 18180 16495 18181 16495 18222 16496 18181 16496 18223 16496 18223 16497 18181 16497 18182 16497 18223 16498 18182 16498 18183 16498 18239 16499 18161 16499 18185 16499 18185 960 18161 960 18184 960 18185 960 18184 960 18186 960 18186 960 18184 960 18188 960 18186 16500 18188 16500 18187 16500 18187 960 18188 960 18165 960 18187 960 18165 960 18189 960 18189 16501 18165 16501 18190 16501 18189 16502 18190 16502 18191 16502 18191 960 18190 960 18192 960 18191 960 18192 960 18193 960 18193 16503 18192 16503 18131 16503 18193 16504 18131 16504 18194 16504 18194 960 18131 960 18196 960 18194 16505 18196 16505 18195 16505 18195 960 18196 960 18133 960 18195 16506 18133 16506 18197 16506 18197 960 18133 960 18199 960 18197 16507 18199 16507 18198 16507 18198 16508 18199 16508 18136 16508 18198 16509 18136 16509 18200 16509 18200 16510 18136 16510 18138 16510 18200 960 18138 960 18201 960 18201 16511 18138 16511 18140 16511 18201 960 18140 960 18202 960 18202 16512 18140 16512 18203 16512 18202 16513 18203 16513 18204 16513 18204 16514 18203 16514 18205 16514 18204 960 18205 960 18206 960 18206 960 18205 960 18208 960 18206 960 18208 960 18207 960 18207 16515 18208 16515 18171 16515 18207 16516 18171 16516 18209 16516 18209 960 18171 960 18210 960 18209 960 18210 960 18211 960 18211 16517 18210 16517 18212 16517 18211 960 18212 960 18213 960 18213 960 18212 960 18215 960 18213 16518 18215 16518 18214 16518 18214 960 18215 960 18216 960 18214 960 18216 960 18217 960 18217 960 18216 960 18177 960 18217 960 18177 960 18218 960 18218 16519 18177 16519 18219 16519 18218 960 18219 960 18220 960 18220 960 18219 960 18222 960 18220 960 18222 960 18221 960 18221 960 18222 960 18223 960 18221 16520 18223 16520 18225 16520 18225 960 18223 960 18224 960 18225 16521 18224 16521 18226 16521 18226 16522 18224 16522 18147 16522 18226 16523 18147 16523 18227 16523 18227 960 18147 960 18149 960 18227 960 18149 960 18228 960 18228 960 18149 960 18229 960 18228 960 18229 960 18230 960 18230 16524 18229 16524 18231 16524 18230 960 18231 960 18232 960 18232 16525 18231 16525 18153 16525 18232 960 18153 960 18233 960 18233 16526 18153 16526 18156 16526 18233 960 18156 960 18234 960 18234 960 18156 960 18157 960 18234 960 18157 960 18235 960 18235 16527 18157 16527 18145 16527 18235 960 18145 960 18236 960 18236 16528 18145 16528 18238 16528 18236 960 18238 960 18237 960 18237 16529 18238 16529 18239 16529 18237 960 18239 960 18185 960 18850 16530 18771 16530 18240 16530 18240 16531 18771 16531 18709 16531 18240 16532 18709 16532 18852 16532 18852 590 18709 590 18241 590 18852 590 18241 590 18846 590 18846 590 18241 590 18242 590 18846 16533 18242 16533 18243 16533 18243 590 18242 590 18244 590 18243 590 18244 590 18246 590 18246 590 18244 590 18245 590 18246 590 18245 590 18959 590 18751 590 18749 590 18884 590 18884 16534 18749 16534 18247 16534 18247 16535 18749 16535 18757 16535 18247 590 18757 590 18248 590 18884 16536 18249 16536 18751 16536 18751 590 18249 590 18885 590 18751 16537 18885 16537 18250 16537 18250 590 18885 590 18251 590 18250 16538 18251 16538 18252 16538 18252 590 18251 590 18253 590 18252 590 18253 590 18752 590 18336 16539 18256 16539 18254 16539 18254 16540 18256 16540 18447 16540 18254 16541 18447 16541 18338 16541 18338 16542 18447 16542 18258 16542 18338 16543 18258 16543 18260 16543 18257 16544 18255 16544 18337 16544 18337 16545 18255 16545 18450 16545 18337 16546 18450 16546 18336 16546 18336 16547 18450 16547 18449 16547 18336 16548 18449 16548 18256 16548 18266 16549 18438 16549 18342 16549 18342 16550 18438 16550 18441 16550 18342 16551 18441 16551 18333 16551 18333 16552 18441 16552 18440 16552 18333 16553 18440 16553 18257 16553 18257 16554 18440 16554 18451 16554 18257 16555 18451 16555 18255 16555 18258 16556 18259 16556 18260 16556 18260 16557 18259 16557 18261 16557 18260 16558 18261 16558 18262 16558 18262 16559 18261 16559 18444 16559 18262 16560 18444 16560 18263 16560 18263 16561 18444 16561 18442 16561 18263 16562 18442 16562 18265 16562 18265 16563 18442 16563 18264 16563 18265 16564 18264 16564 18266 16564 18266 16565 18264 16565 18267 16565 18266 16566 18267 16566 18438 16566 18322 16567 18268 16567 18323 16567 18269 590 18270 590 18422 590 18271 590 18316 590 18315 590 18271 590 18315 590 18277 590 18415 590 18272 590 18297 590 18291 16568 18273 16568 18292 16568 18274 16569 18275 16569 18276 16569 18276 590 18275 590 18300 590 18276 16570 18300 16570 18341 16570 18269 16571 18422 16571 18310 16571 18277 590 18315 590 18278 590 18278 16572 18315 16572 18279 16572 18278 16573 18279 16573 18280 16573 18280 590 18279 590 18281 590 18280 16574 18281 16574 18290 16574 18296 590 18297 590 18283 590 18283 16575 18297 16575 18282 16575 18283 590 18282 590 18284 590 18284 590 18282 590 18286 590 18284 590 18286 590 18285 590 18285 16576 18286 16576 18287 16576 18285 590 18287 590 18288 590 18288 590 18287 590 18289 590 18288 16577 18289 16577 18281 16577 18281 590 18289 590 18291 590 18281 16578 18291 16578 18290 16578 18290 590 18291 590 18292 590 18313 590 18314 590 18293 590 18293 16579 18314 16579 18294 16579 18420 590 18419 590 18305 590 18305 16580 18419 16580 18417 16580 18305 16581 18417 16581 18295 16581 18295 590 18417 590 18416 590 18295 590 18416 590 18296 590 18296 590 18416 590 18298 590 18296 590 18298 590 18297 590 18297 16582 18298 16582 18299 16582 18297 590 18299 590 18415 590 18300 16583 18301 16583 18341 16583 18341 590 18301 590 18425 590 18341 16584 18425 16584 18270 16584 18270 16585 18425 16585 18302 16585 18270 16586 18302 16586 18422 16586 18294 16587 18303 16587 18293 16587 18293 590 18303 590 18304 590 18293 16588 18304 16588 18305 16588 18305 16589 18304 16589 18306 16589 18305 16590 18306 16590 18420 16590 18306 16591 18307 16591 18420 16591 18420 590 18307 590 18308 590 18420 590 18308 590 18422 590 18422 16592 18308 16592 18309 16592 18422 16593 18309 16593 18310 16593 18318 590 18321 590 18311 590 18318 16594 18335 16594 18317 16594 18311 16595 18312 16595 18390 16595 18313 590 18315 590 18314 590 18314 590 18315 590 18316 590 18314 16596 18316 16596 18330 16596 18330 16597 18316 16597 18328 16597 18317 590 18319 590 18318 590 18318 16598 18319 16598 18320 16598 18318 590 18320 590 18321 590 18322 590 18323 590 18324 590 18324 16599 18323 16599 18390 16599 18324 590 18390 590 18325 590 18325 590 18390 590 18312 590 18325 16600 18312 16600 18326 16600 18326 16601 18312 16601 18327 16601 18326 590 18327 590 18328 590 18328 16602 18327 16602 18329 16602 18328 16603 18329 16603 18330 16603 18266 590 18331 590 18265 590 18265 590 18331 590 18332 590 18265 16604 18332 16604 18263 16604 18336 590 18254 590 18341 590 18341 590 18254 590 18338 590 18263 590 18332 590 18262 590 18262 590 18332 590 18339 590 18262 590 18339 590 18260 590 18333 590 18355 590 18342 590 18342 590 18355 590 18334 590 18342 16605 18334 16605 18344 16605 18270 16606 18335 16606 18341 16606 18341 590 18335 590 18318 590 18341 16607 18318 16607 18336 16607 18336 16608 18318 16608 18337 16608 18260 16609 18339 16609 18338 16609 18338 16610 18339 16610 18340 16610 18338 16611 18340 16611 18341 16611 18266 16612 18342 16612 18331 16612 18331 590 18342 590 18344 590 18331 16613 18344 16613 18343 16613 18343 16614 18344 16614 18345 16614 18343 16615 18345 16615 18346 16615 18349 590 18347 590 18359 590 18352 16616 18348 16616 18318 16616 18318 16617 18348 16617 18353 16617 18349 590 18359 590 18357 590 18358 590 18350 590 18318 590 18318 16618 18350 16618 18351 16618 18318 16619 18351 16619 18352 16619 18337 590 18318 590 18257 590 18257 16620 18318 16620 18353 16620 18257 16621 18353 16621 18333 16621 18333 16622 18353 16622 18354 16622 18333 16623 18354 16623 18355 16623 18356 16624 18360 16624 18318 16624 18318 590 18360 590 18357 590 18318 16625 18357 16625 18358 16625 18358 590 18357 590 18359 590 18360 590 18361 590 18357 590 18357 16626 18361 16626 18362 16626 18357 16627 18362 16627 18364 16627 18364 590 18362 590 18363 590 18364 590 18363 590 18365 590 18365 16628 18363 16628 18366 16628 18365 590 18366 590 18368 590 18368 16629 18366 16629 18367 16629 18368 590 18367 590 18370 590 18370 16630 18367 16630 18369 16630 18370 590 18369 590 18373 590 18373 16631 18369 16631 18371 16631 18371 16632 18372 16632 18373 16632 18373 16633 18372 16633 18374 16633 18373 16634 18374 16634 18318 16634 18318 16635 18374 16635 18375 16635 18318 590 18375 590 18356 590 18379 590 18404 590 18318 590 18376 590 18381 590 18377 590 18311 590 18390 590 18318 590 18318 590 18390 590 18378 590 18318 16636 18378 16636 18379 16636 18401 590 18402 590 18380 590 18380 590 18402 590 18403 590 18380 590 18403 590 18404 590 18377 590 18381 590 18388 590 18382 590 18384 590 18383 590 18383 16637 18384 16637 18400 16637 18383 16638 18400 16638 18385 16638 18381 16639 18386 16639 18388 16639 18388 590 18386 590 18387 590 18388 590 18387 590 18389 590 18389 590 18387 590 18391 590 18389 590 18391 590 18390 590 18390 590 18391 590 18392 590 18390 16640 18392 16640 18378 16640 18408 16641 18393 16641 18318 16641 18318 16642 18393 16642 18394 16642 18318 16643 18394 16643 18373 16643 18373 590 18394 590 18395 590 18373 590 18395 590 18397 590 18397 590 18395 590 18396 590 18397 590 18396 590 18398 590 18376 16644 18377 16644 18399 16644 18399 590 18377 590 18385 590 18399 590 18385 590 18401 590 18401 590 18385 590 18400 590 18401 590 18400 590 18402 590 18403 16645 18405 16645 18404 16645 18404 16646 18405 16646 18406 16646 18404 590 18406 590 18318 590 18318 16647 18406 16647 18407 16647 18318 16648 18407 16648 18408 16648 18410 16649 18409 16649 18272 16649 18410 16650 18272 16650 18601 16650 18599 16651 18411 16651 18410 16651 18410 16652 18411 16652 18412 16652 18410 16653 18412 16653 18409 16653 18610 16654 18430 16654 18611 16654 18611 16655 18430 16655 18413 16655 18611 16656 18413 16656 18599 16656 18599 16657 18413 16657 18414 16657 18599 16658 18414 16658 18411 16658 18272 16659 18415 16659 18601 16659 18601 16660 18415 16660 18299 16660 18601 16661 18299 16661 18604 16661 18604 16662 18299 16662 18298 16662 18604 16663 18298 16663 18605 16663 18605 16664 18298 16664 18416 16664 18605 16665 18416 16665 18600 16665 18600 16666 18416 16666 18417 16666 18600 16667 18417 16667 18418 16667 18418 16668 18417 16668 18419 16668 18418 16669 18419 16669 18607 16669 18607 16670 18419 16670 18420 16670 18607 16671 18420 16671 18421 16671 18421 16672 18420 16672 18422 16672 18421 16673 18422 16673 18609 16673 18609 16674 18422 16674 18302 16674 18609 16675 18302 16675 18423 16675 18423 16676 18302 16676 18425 16676 18423 16677 18425 16677 18424 16677 18424 16678 18425 16678 18301 16678 18424 16679 18301 16679 18426 16679 18426 16680 18301 16680 18300 16680 18426 16681 18300 16681 18427 16681 18427 16682 18300 16682 18275 16682 18427 16682 18275 16682 18428 16682 18428 16683 18275 16683 18274 16683 18428 16684 18274 16684 18610 16684 18610 16685 18274 16685 18429 16685 18610 16686 18429 16686 18430 16686 18431 960 18432 960 18556 960 18522 960 18623 960 18606 960 18433 960 18434 960 18511 960 18475 960 18480 960 18613 960 18435 16687 18476 16687 18606 16687 18461 960 18436 960 18511 960 18707 960 18437 960 18267 960 18707 960 18267 960 18743 960 18529 16688 18441 16688 18437 16688 18437 960 18441 960 18438 960 18437 960 18438 960 18267 960 18439 16689 18451 16689 18529 16689 18529 16690 18451 16690 18440 16690 18529 16691 18440 16691 18441 16691 18267 960 18264 960 18743 960 18743 960 18264 960 18442 960 18743 960 18442 960 18741 960 18741 16692 18442 16692 18444 16692 18741 960 18444 960 18443 960 18443 16693 18444 16693 18261 16693 18443 960 18261 960 18445 960 18445 16694 18261 16694 18259 16694 18445 960 18259 960 18446 960 18446 16695 18259 16695 18258 16695 18446 16696 18258 16696 18797 16696 18797 16697 18258 16697 18447 16697 18256 16698 18449 16698 18448 16698 18448 960 18449 960 18450 960 18448 960 18450 960 18439 960 18439 16699 18450 16699 18255 16699 18439 16700 18255 16700 18451 16700 18881 16701 18659 16701 18452 16701 18452 16702 18659 16702 18580 16702 18452 16703 18580 16703 18581 16703 18453 16704 18456 16704 18663 16704 18458 960 18454 960 18453 960 18453 960 18454 960 18455 960 18453 960 18455 960 18456 960 18511 960 18436 960 18457 960 18457 16705 18436 16705 18459 16705 18457 960 18459 960 18458 960 18458 16706 18459 16706 18460 16706 18458 16707 18460 16707 18454 16707 18461 960 18511 960 18462 960 18462 960 18511 960 18434 960 18462 960 18434 960 18464 960 18464 960 18434 960 18463 960 18464 16708 18463 16708 18465 16708 18580 16709 18466 16709 18502 16709 18467 960 18501 960 18503 960 18463 16710 18468 16710 18465 16710 18465 16711 18468 16711 18467 16711 18465 960 18467 960 18469 960 18469 16712 18467 16712 18503 16712 18470 960 18471 960 18633 960 18633 960 18471 960 18632 960 18472 960 18614 960 18473 960 18472 960 18473 960 18633 960 18633 960 18473 960 18474 960 18633 960 18474 960 18470 960 18475 960 18613 960 18615 960 18606 16713 18476 16713 18603 16713 18603 16714 18476 16714 18477 16714 18603 960 18477 960 18478 960 18478 16715 18477 16715 18481 16715 18478 960 18481 960 18479 960 18479 960 18481 960 18480 960 18480 16716 18481 16716 18482 16716 18480 16717 18482 16717 18613 16717 18542 960 18483 960 18552 960 18552 16718 18483 16718 18484 16718 18484 960 18485 960 18552 960 18552 960 18485 960 18486 960 18552 960 18486 960 18487 960 18486 960 18488 960 18487 960 18487 16719 18488 16719 18489 16719 18487 960 18489 960 18619 960 18620 960 18496 960 18495 960 18489 960 18490 960 18619 960 18619 16720 18490 16720 18491 16720 18619 16721 18491 16721 18492 16721 18541 16722 18493 16722 18542 16722 18542 16723 18493 16723 18494 16723 18542 960 18494 960 18483 960 18495 16724 18496 16724 18807 16724 18807 960 18496 960 18497 960 18807 960 18497 960 18498 960 18540 16725 18499 16725 18500 16725 18500 16726 18499 16726 18635 16726 18500 960 18635 960 18634 960 18507 16727 18580 16727 18501 16727 18501 16728 18580 16728 18502 16728 18501 16729 18502 16729 18503 16729 18504 960 18596 960 18505 960 18505 960 18596 960 18580 960 18505 16730 18580 16730 18506 16730 18506 16731 18580 16731 18507 16731 18569 16732 18533 16732 18508 16732 18508 960 18509 960 18569 960 18569 16733 18509 16733 18510 16733 18569 960 18510 960 18511 960 18511 960 18510 960 18512 960 18511 960 18512 960 18433 960 18552 16734 18518 16734 18513 16734 18487 960 18630 960 18514 960 18514 16735 18515 16735 18487 16735 18487 16736 18515 16736 18516 16736 18487 960 18516 960 18552 960 18552 16737 18516 16737 18517 16737 18552 960 18517 960 18518 960 18526 960 18519 960 18608 960 18608 16738 18519 16738 18520 16738 18608 960 18520 960 18606 960 18606 960 18520 960 18521 960 18606 960 18521 960 18522 960 18439 960 18523 960 18448 960 18448 16739 18523 16739 18524 16739 18448 16740 18524 16740 18608 16740 18608 16741 18524 16741 18525 16741 18608 16742 18525 16742 18526 16742 18504 16743 18527 16743 18596 16743 18596 960 18527 960 18528 960 18596 960 18528 960 18529 960 18529 960 18528 960 18530 960 18529 16744 18530 16744 18439 16744 18439 16745 18530 16745 18531 16745 18439 960 18531 960 18523 960 18513 960 18532 960 18534 960 18534 16746 18532 16746 18533 16746 18534 960 18533 960 18535 960 18535 960 18533 960 18569 960 18535 960 18569 960 18536 960 18536 960 18569 960 18539 960 18556 960 18640 960 18537 960 18537 960 18640 960 18538 960 18537 960 18538 960 18539 960 18544 16747 18649 16747 18834 16747 18834 960 18844 960 18711 960 18540 960 18541 960 18499 960 18499 960 18541 960 18542 960 18499 960 18542 960 18780 960 18780 16748 18542 16748 18543 16748 18780 16749 18543 16749 18547 16749 18544 960 18834 960 18545 960 18545 16750 18834 16750 18711 16750 18545 960 18711 960 18546 960 18546 16751 18711 16751 18548 16751 18546 960 18548 960 18547 960 18547 960 18548 960 18710 960 18547 960 18710 960 18780 960 18534 16752 18549 16752 18513 16752 18513 16753 18549 16753 18550 16753 18513 960 18550 960 18552 960 18552 16754 18550 16754 18551 16754 18552 960 18551 960 18542 960 18542 16755 18551 16755 18553 16755 18542 16756 18553 16756 18543 16756 18554 960 18562 960 18651 960 18654 16757 18556 16757 18555 16757 18555 960 18556 960 18561 960 18557 16758 18558 16758 18537 16758 18537 960 18558 960 18559 960 18537 960 18559 960 18556 960 18556 960 18559 960 18560 960 18556 16759 18560 16759 18561 16759 18651 16760 18562 16760 18785 16760 18785 960 18562 960 18655 960 18785 960 18655 960 18783 960 18656 960 18563 960 18457 960 18563 16761 18564 16761 18457 16761 18457 16762 18564 16762 18565 16762 18457 960 18565 960 18511 960 18511 16763 18565 16763 18566 16763 18539 960 18569 960 18537 960 18537 16764 18569 16764 18571 16764 18537 960 18571 960 18557 960 18566 16765 18567 16765 18511 16765 18511 16766 18567 16766 18568 16766 18511 16767 18568 16767 18569 16767 18569 16768 18568 16768 18570 16768 18569 960 18570 960 18571 960 18572 960 18574 960 18596 960 18580 16769 18573 16769 18578 16769 18574 960 18575 960 18596 960 18596 960 18575 960 18576 960 18596 960 18576 960 18580 960 18580 16770 18576 16770 18577 16770 18580 960 18577 960 18573 960 18578 960 18579 960 18580 960 18580 16771 18579 16771 18582 16771 18580 960 18582 960 18581 960 18581 16772 18582 16772 18584 16772 18581 16773 18584 16773 18583 16773 18583 960 18584 960 18585 960 18583 16774 18585 16774 18816 16774 18816 960 18585 960 18586 960 18816 16775 18586 16775 18587 16775 18586 16776 18588 16776 18587 16776 18587 960 18588 960 18589 960 18587 960 18589 960 18866 960 18866 16777 18589 16777 18590 16777 18866 16778 18590 16778 18591 16778 18591 16779 18590 16779 18592 16779 18591 16780 18592 16780 18597 16780 18593 16781 18594 16781 18437 16781 18437 16782 18594 16782 18595 16782 18437 16783 18595 16783 18529 16783 18529 960 18595 960 18591 960 18529 16784 18591 16784 18596 16784 18596 960 18591 960 18597 960 18596 16785 18597 16785 18572 16785 18447 960 18256 960 18797 960 18797 16786 18256 16786 18448 16786 18797 960 18448 960 18598 960 18598 16787 18448 16787 18608 16787 18598 960 18608 960 18802 960 18410 960 18601 960 18732 960 18410 16788 18732 16788 18599 16788 18606 960 18600 960 18418 960 18918 16789 18732 16789 18602 16789 18602 960 18732 960 18601 960 18602 16790 18601 16790 18603 16790 18603 16791 18601 16791 18604 16791 18603 16792 18604 16792 18606 16792 18606 16793 18604 16793 18605 16793 18606 16794 18605 16794 18600 16794 18418 960 18607 960 18606 960 18606 16795 18607 16795 18421 16795 18606 16796 18421 16796 18608 16796 18608 960 18421 960 18609 960 18608 960 18609 960 18423 960 18423 960 18424 960 18608 960 18608 16797 18424 16797 18426 16797 18608 16798 18426 16798 18802 16798 18802 960 18426 960 18427 960 18802 16799 18427 16799 18801 16799 18801 16800 18427 16800 18428 16800 18801 16801 18428 16801 18800 16801 18800 960 18428 960 18610 960 18800 960 18610 960 18732 960 18732 16802 18610 16802 18611 16802 18732 16803 18611 16803 18599 16803 18617 16804 18612 16804 18472 16804 18472 960 18612 960 18891 960 18472 16805 18891 16805 18902 16805 18613 16806 18614 16806 18615 16806 18615 16807 18614 16807 18472 16807 18615 16808 18472 16808 18616 16808 18616 16809 18472 16809 18902 16809 18617 960 18472 960 18720 960 18720 960 18472 960 18633 960 18720 16810 18633 16810 18804 16810 18618 960 18619 960 18495 960 18495 960 18619 960 18492 960 18495 16811 18492 16811 18620 16811 18435 960 18606 960 18621 960 18621 960 18606 960 18623 960 18621 960 18623 960 18622 960 18622 16812 18623 16812 18624 16812 18622 16813 18624 16813 18625 16813 18625 960 18624 960 18627 960 18625 960 18627 960 18626 960 18626 16814 18627 16814 18628 16814 18626 960 18628 960 18629 960 18629 16815 18628 16815 18630 16815 18629 16816 18630 16816 18631 16816 18631 16817 18630 16817 18487 16817 18631 960 18487 960 18632 960 18632 16818 18487 16818 18619 16818 18632 960 18619 960 18633 960 18633 960 18619 960 18618 960 18633 960 18618 960 18804 960 18498 960 18634 960 18807 960 18807 960 18634 960 18635 960 18807 16819 18635 16819 18637 16819 18637 960 18635 960 18636 960 18637 16820 18636 16820 18809 16820 18432 960 18638 960 18556 960 18556 16821 18638 16821 18639 16821 18556 960 18639 960 18640 960 18640 16822 18639 16822 18833 16822 18640 960 18833 960 18642 960 18642 16823 18833 16823 18641 16823 18642 960 18641 960 18644 960 18644 16824 18641 16824 18643 16824 18644 960 18643 960 18645 960 18645 16825 18643 16825 18646 16825 18645 960 18646 960 18648 960 18648 960 18646 960 18647 960 18648 960 18647 960 18649 960 18649 16826 18647 16826 18650 16826 18649 16827 18650 16827 18834 16827 18651 16828 18779 16828 18653 16828 18652 960 18431 960 18653 960 18653 960 18431 960 18556 960 18653 960 18556 960 18651 960 18651 16829 18556 16829 18654 16829 18651 16830 18654 16830 18554 16830 18655 960 18656 960 18783 960 18783 16831 18656 16831 18457 16831 18783 960 18457 960 18657 960 18657 16832 18457 16832 18458 16832 18657 960 18458 960 18658 960 18658 16833 18458 16833 18453 16833 18466 16834 18580 16834 18660 16834 18660 16835 18580 16835 18659 16835 18660 960 18659 960 18661 960 18661 960 18659 960 18764 960 18661 16836 18764 16836 18662 16836 18662 16837 18764 16837 18766 16837 18662 960 18766 960 18663 960 18663 960 18766 960 18664 960 18663 16838 18664 16838 18453 16838 18453 960 18664 960 18787 960 18453 960 18787 960 18788 960 18788 960 18790 960 18453 960 18453 16839 18790 16839 18792 16839 18453 960 18792 960 18658 960 18887 16840 18886 16840 18665 16840 18665 960 18886 960 18883 960 18665 960 18883 960 18750 960 18750 960 18883 960 18666 960 18750 16841 18666 16841 18756 16841 18756 960 18666 960 18873 960 18756 960 18873 960 18667 960 18667 960 18873 960 18926 960 18667 960 18926 960 18760 960 18760 16842 18926 16842 18668 16842 18760 960 18668 960 18789 960 18789 960 18668 960 18669 960 18789 16843 18669 16843 18791 16843 18791 960 18669 960 18671 960 18791 960 18671 960 18670 960 18670 960 18671 960 18672 960 18670 16844 18672 16844 18784 16844 18784 960 18672 960 18673 960 18784 16845 18673 16845 18770 16845 18770 960 18673 960 18823 960 18770 960 18823 960 18708 960 18708 960 18823 960 18829 960 18708 16846 18829 16846 18674 16846 18674 16847 18829 16847 18851 16847 18674 960 18851 960 18675 960 18675 960 18851 960 18676 960 18675 960 18676 960 18677 960 18677 960 18676 960 18678 960 18677 960 18678 960 18679 960 18679 960 18678 960 18847 960 18679 960 18847 960 18715 960 18715 16848 18847 16848 18848 16848 18715 16849 18848 16849 18712 16849 18712 960 18848 960 18680 960 18712 960 18680 960 18681 960 18681 960 18680 960 18947 960 18681 960 18947 960 18781 960 18781 960 18947 960 18949 960 18781 16850 18949 16850 18808 16850 18808 960 18949 960 18682 960 18808 960 18682 960 18683 960 18683 960 18682 960 18952 960 18683 960 18952 960 18684 960 18684 960 18952 960 18954 960 18684 960 18954 960 18685 960 18685 16851 18954 16851 18955 16851 18685 16852 18955 16852 18727 16852 18727 960 18955 960 18686 960 18727 16853 18686 16853 18687 16853 18687 960 18686 960 18688 960 18687 16854 18688 16854 18689 16854 18689 960 18688 960 18690 960 18689 16855 18690 16855 18724 16855 18724 960 18690 960 18691 960 18724 960 18691 960 18692 960 18692 960 18691 960 18694 960 18692 960 18694 960 18693 960 18693 960 18694 960 18696 960 18693 16856 18696 16856 18695 16856 18695 960 18696 960 18697 960 18695 960 18697 960 18698 960 18698 16857 18697 16857 18937 16857 18698 16858 18937 16858 18803 16858 18803 16859 18937 16859 18939 16859 18803 960 18939 960 18796 960 18796 960 18939 960 18699 960 18796 16860 18699 16860 18700 16860 18700 16861 18699 16861 18701 16861 18700 960 18701 960 18795 960 18795 960 18701 960 18941 960 18795 960 18941 960 18702 960 18702 16862 18941 16862 18861 16862 18702 960 18861 960 18703 960 18703 16863 18861 16863 18888 16863 18703 960 18888 960 18704 960 18704 16864 18888 16864 18705 16864 18704 16865 18705 16865 18665 16865 18665 16866 18705 16866 18887 16866 18706 16867 18437 16867 18707 16867 18723 16868 18612 16868 18617 16868 18708 16869 18674 16869 18709 16869 18709 16870 18674 16870 18675 16870 18709 16871 18675 16871 18241 16871 18241 16872 18675 16872 18677 16872 18241 16873 18677 16873 18242 16873 18242 16874 18677 16874 18679 16874 18242 16875 18679 16875 18244 16875 18244 16876 18679 16876 18715 16876 18244 16877 18715 16877 18245 16877 18969 16878 18968 16878 18710 16878 18969 16879 18710 16879 18971 16879 18971 16880 18710 16880 18972 16880 18972 16881 18710 16881 18548 16881 18972 16882 18548 16882 18711 16882 18966 16883 18965 16883 18712 16883 18965 16884 18713 16884 18712 16884 18712 16885 18713 16885 18963 16885 18712 16886 18963 16886 18714 16886 18714 16887 18961 16887 18712 16887 18712 16888 18961 16888 18960 16888 18712 16889 18960 16889 18715 16889 18715 16890 18960 16890 18959 16890 18715 16891 18959 16891 18245 16891 18806 16892 18716 16892 18720 16892 18730 16893 18717 16893 18685 16893 18685 16894 18717 16894 18718 16894 18685 16895 18718 16895 18805 16895 18716 16896 18719 16896 18720 16896 18720 16897 18719 16897 18721 16897 18720 16898 18721 16898 18617 16898 18617 16899 18721 16899 18722 16899 18617 16900 18722 16900 18723 16900 18692 16901 18812 16901 18724 16901 18724 16902 18812 16902 18815 16902 18724 16903 18815 16903 18689 16903 18689 16904 18815 16904 18725 16904 18689 16905 18725 16905 18687 16905 18687 16906 18725 16906 18726 16906 18687 16907 18726 16907 18727 16907 18727 16908 18726 16908 18728 16908 18727 16909 18728 16909 18685 16909 18685 16910 18728 16910 18729 16910 18685 16911 18729 16911 18730 16911 18693 16912 18731 16912 18692 16912 18692 16913 18731 16913 18811 16913 18692 16914 18811 16914 18812 16914 18800 16915 18732 16915 18733 16915 18733 16916 18734 16916 18800 16916 18800 16917 18734 16917 18735 16917 18800 16918 18735 16918 18798 16918 18799 16919 18736 16919 18695 16919 18695 16920 18736 16920 18737 16920 18737 16921 18738 16921 18695 16921 18695 16922 18738 16922 18739 16922 18695 16923 18739 16923 18693 16923 18693 16924 18739 16924 18740 16924 18693 16925 18740 16925 18731 16925 18794 16926 18742 16926 18741 16926 18741 16927 18742 16927 18744 16927 18741 16928 18744 16928 18743 16928 18743 16929 18744 16929 18745 16929 18743 16930 18745 16930 18707 16930 18707 16931 18745 16931 18746 16931 18707 16932 18746 16932 18706 16932 18793 16933 18795 16933 18747 16933 18747 16934 18795 16934 18702 16934 18747 16935 18702 16935 18748 16935 18748 16936 18702 16936 18754 16936 18756 16937 18749 16937 18750 16937 18750 16938 18749 16938 18751 16938 18750 16939 18751 16939 18665 16939 18665 16940 18751 16940 18250 16940 18665 16941 18250 16941 18704 16941 18704 16942 18250 16942 18252 16942 18704 16943 18252 16943 18703 16943 18703 16944 18252 16944 18752 16944 18703 16945 18752 16945 18702 16945 18702 16946 18752 16946 18753 16946 18702 16947 18753 16947 18754 16947 18762 16948 18755 16948 18667 16948 18667 16949 18755 16949 18248 16949 18667 16950 18248 16950 18756 16950 18756 16951 18248 16951 18757 16951 18756 16952 18757 16952 18749 16952 18786 16953 18758 16953 18760 16953 18760 16954 18758 16954 18759 16954 18760 16955 18759 16955 18667 16955 18667 16956 18759 16956 18761 16956 18667 16957 18761 16957 18762 16957 18659 16958 18763 16958 18764 16958 18764 16959 18763 16959 18765 16959 18764 16960 18765 16960 18766 16960 18766 16961 18765 16961 18767 16961 18766 16962 18767 16962 18664 16962 18664 16963 18767 16963 18768 16963 18664 16964 18768 16965 18787 16966 18775 16967 18776 16967 18779 16967 18769 16968 18782 16968 18770 16968 18769 16969 18770 16969 18774 16969 18709 16970 18771 16970 18708 16970 18708 16971 18771 16971 18772 16971 18708 16972 18772 16972 18770 16972 18770 16973 18772 16973 18773 16973 18770 16974 18773 16974 18774 16974 18775 16975 18779 16975 18782 16975 18776 16976 18777 16976 18779 16976 18779 16977 18777 16977 18778 16977 18779 16978 18778 16978 18653 16978 18968 16979 18966 16979 18710 16979 18710 16980 18966 16980 18712 16980 18710 16981 18712 16981 18780 16981 18780 16982 18712 16982 18681 16982 18780 16983 18681 16983 18499 16983 18499 16984 18681 16984 18781 16984 18499 16985 18781 16985 18635 16985 18782 16986 18779 16986 18770 16986 18770 16987 18779 16987 18651 16987 18770 16988 18651 16988 18784 16988 18657 16989 18670 16989 18783 16989 18783 16990 18670 16990 18784 16990 18783 16991 18784 16991 18785 16991 18785 16992 18784 16992 18651 16992 18768 16993 18786 16993 18787 16993 18787 16994 18786 16994 18760 16994 18787 16995 18760 16995 18788 16995 18788 16996 18760 16996 18789 16996 18788 16997 18789 16997 18790 16997 18790 16998 18789 16998 18791 16998 18790 16999 18791 16999 18792 16999 18792 17000 18791 17000 18670 17000 18792 17001 18670 17001 18658 17001 18658 17002 18670 17002 18657 17002 18793 17003 18794 17003 18795 17003 18795 17004 18794 17004 18741 17004 18795 17005 18741 17005 18700 17005 18700 17006 18741 17006 18443 17006 18700 17007 18443 17007 18796 17007 18797 17008 18803 17008 18446 17008 18446 17009 18803 17009 18796 17009 18446 17010 18796 17010 18445 17010 18445 17011 18796 17011 18443 17011 18798 17012 18799 17012 18800 17012 18800 17013 18799 17013 18695 17013 18800 17014 18695 17014 18801 17014 18801 17015 18695 17015 18698 17015 18801 17016 18698 17016 18802 17016 18802 17017 18698 17017 18803 17017 18802 17018 18803 17018 18598 17018 18598 17019 18803 17019 18797 17019 18618 17020 18684 17020 18804 17020 18804 17021 18684 17021 18685 17021 18804 17022 18685 17022 18720 17022 18720 17023 18685 17023 18805 17023 18720 17024 18805 17024 18806 17024 18618 17025 18495 17025 18684 17025 18684 17026 18495 17026 18807 17026 18684 17027 18807 17027 18683 17027 18683 17028 18807 17028 18637 17028 18683 17029 18637 17029 18808 17029 18808 17030 18637 17030 18809 17030 18808 17031 18809 17031 18781 17031 18781 17032 18809 17032 18636 17032 18781 17033 18636 17033 18635 17033 18731 590 18810 590 18811 590 18811 590 18810 590 18921 590 18811 590 18921 590 18812 590 18812 17034 18921 17034 18813 17034 18812 590 18813 590 18815 590 18815 590 18813 590 18814 590 18815 17035 18814 17035 18725 17035 18725 17036 18814 17036 18924 17036 18725 17037 18924 17037 18726 17037 18726 590 18924 590 18923 590 18726 590 18923 590 18728 590 18479 17038 18906 17038 18908 17038 18816 17039 18869 17039 18817 17039 18819 17040 18934 17040 18818 17040 18818 17041 18934 17041 18830 17041 18818 17042 18830 17042 18652 17042 18819 17043 18820 17043 18934 17043 18934 17044 18820 17044 18821 17044 18934 17045 18821 17045 18822 17045 18933 17046 18824 17046 18823 17046 18823 17047 18824 17047 18825 17047 18823 17048 18825 17048 18826 17048 18826 17049 18827 17049 18823 17049 18823 17050 18827 17050 18828 17050 18823 17051 18828 17051 18829 17051 18832 17052 18432 17052 18830 17052 18830 17053 18432 17053 18431 17053 18830 17054 18431 17054 18652 17054 18831 17055 18639 17055 18832 17055 18832 17056 18639 17056 18638 17056 18832 17057 18638 17057 18432 17057 18836 17058 18641 17058 18831 17058 18831 17059 18641 17059 18833 17059 18831 17060 18833 17060 18639 17060 18834 17061 18650 17061 18845 17061 18845 17062 18650 17062 18647 17062 18845 17063 18647 17063 18835 17063 18835 17064 18647 17064 18646 17064 18835 17065 18646 17065 18836 17065 18836 17066 18646 17066 18643 17066 18836 17067 18643 17067 18641 17067 18848 17068 18837 17068 18680 17068 18680 17069 18837 17069 18838 17069 18680 17070 18838 17070 18962 17070 18962 17071 18839 17071 18680 17071 18680 17072 18839 17072 18840 17072 18680 17073 18840 17073 18964 17073 18946 17074 18841 17074 18842 17074 18842 17075 18841 17075 18967 17075 18967 17076 18970 17076 18842 17076 18842 17077 18970 17077 18843 17077 18842 17078 18843 17078 18845 17078 18845 17079 18843 17079 18844 17079 18845 17080 18844 17080 18834 17080 18243 17081 18246 17081 18848 17081 18848 17082 18246 17082 18958 17082 18848 17083 18958 17083 18837 17083 18851 17084 18852 17084 18676 17084 18676 17085 18852 17085 18846 17085 18676 17086 18846 17086 18678 17086 18678 17087 18846 17087 18243 17087 18678 17088 18243 17088 18847 17088 18847 17089 18243 17089 18848 17089 18828 17090 18849 17090 18829 17090 18829 17091 18849 17091 18850 17091 18829 17092 18850 17092 18851 17092 18851 17093 18850 17093 18240 17093 18851 17094 18240 17094 18852 17094 18855 17095 18945 17095 18853 17095 18853 17096 18945 17096 18854 17096 18853 17097 18854 17097 18593 17097 18593 17098 18854 17098 18594 17098 18855 17099 18856 17099 18945 17099 18945 17100 18856 17100 18857 17100 18945 17101 18857 17101 18858 17101 18944 17102 18859 17102 18861 17102 18861 17103 18859 17103 18860 17103 18861 17104 18860 17104 18862 17104 18862 17105 18863 17105 18861 17105 18861 17106 18863 17106 18864 17106 18861 17107 18864 17107 18888 17107 18594 17108 18854 17108 18595 17108 18595 17109 18854 17109 18865 17109 18595 17110 18865 17110 18591 17110 18591 17111 18865 17111 18866 17111 18866 17112 18865 17112 18867 17112 18866 17113 18867 17113 18587 17113 18587 17114 18867 17114 18816 17114 18816 17115 18867 17115 18868 17115 18816 17116 18868 17116 18869 17116 18881 17117 18452 17117 18870 17117 18870 17118 18452 17118 18581 17118 18870 17119 18581 17119 18817 17119 18817 17120 18581 17120 18583 17120 18817 17121 18583 17121 18816 17121 18871 17122 18877 17122 18927 17122 18872 17123 18925 17123 18926 17123 18872 17124 18926 17124 18876 17124 18873 17125 18874 17125 18926 17125 18926 17126 18874 17126 18875 17126 18926 17127 18875 17127 18876 17127 18877 17128 18878 17128 18927 17128 18927 17129 18878 17129 18879 17129 18927 17130 18879 17130 18870 17130 18870 17131 18879 17131 18880 17131 18870 17132 18880 17132 18881 17132 18884 17133 18247 17133 18873 17133 18873 17134 18247 17134 18882 17134 18873 17135 18882 17135 18874 17135 18873 17136 18666 17136 18884 17136 18884 17137 18666 17137 18883 17137 18884 17138 18883 17138 18249 17138 18249 17139 18883 17139 18886 17139 18249 17140 18886 17140 18885 17140 18885 17141 18886 17141 18887 17141 18885 17142 18887 17142 18705 17142 18864 17143 18889 17143 18888 17143 18888 17144 18889 17144 18253 17144 18888 17145 18253 17145 18705 17145 18705 17146 18253 17146 18251 17146 18705 17147 18251 17147 18885 17147 18892 17148 18957 17148 18890 17148 18890 17149 18957 17149 18903 17149 18890 17150 18903 17150 18891 17150 18892 17151 18893 17151 18957 17151 18957 17152 18893 17152 18894 17152 18957 17153 18894 17153 18895 17153 18896 17154 18897 17155 18955 17156 18955 17157 18897 17157 18898 17157 18955 17158 18898 17158 18899 17158 18899 17159 18900 17159 18955 17159 18955 17160 18900 17160 18901 17160 18955 17161 18901 17161 18686 17161 18891 17162 18903 17162 18902 17162 18902 17163 18903 17163 18904 17163 18902 17164 18904 17164 18616 17164 18616 17165 18904 17165 18615 17165 18615 17166 18904 17166 18905 17166 18615 17167 18905 17167 18475 17167 18906 17168 18479 17168 18905 17168 18905 17169 18479 17169 18480 17169 18905 17170 18480 17170 18475 17170 18918 17171 18602 17171 18907 17171 18907 17172 18602 17172 18603 17172 18907 17173 18603 17173 18908 17173 18908 17174 18603 17174 18478 17174 18908 17175 18478 17175 18479 17175 18909 17176 18910 17176 18914 17176 18911 17177 18935 17177 18697 17177 18911 17178 18697 17178 18912 17178 18696 17179 18920 17179 18697 17179 18697 17180 18920 17181 18913 17182 18697 17183 18913 17183 18912 17183 18910 17184 18915 17184 18914 17184 18914 17185 18915 17185 18916 17185 18914 17186 18916 17186 18907 17186 18907 17187 18916 17187 18917 17187 18907 17188 18917 17188 18918 17188 18921 17189 18810 17189 18696 17189 18696 17190 18810 17190 18919 17190 18696 17191 18919 17191 18920 17191 18688 17192 18814 17192 18690 17192 18690 17193 18814 17193 18813 17193 18690 17194 18813 17194 18691 17194 18691 17195 18813 17195 18921 17195 18691 17196 18921 17196 18694 17196 18694 17197 18921 17197 18696 17197 18901 17198 18922 17198 18686 17198 18686 17199 18922 17199 18923 17199 18686 17200 18923 17200 18688 17200 18688 17201 18923 17201 18924 17201 18688 17202 18924 17202 18814 17202 18925 17203 18871 17203 18926 17203 18926 17204 18871 17204 18927 17204 18926 17205 18927 17205 18668 17205 18668 17206 18927 17206 18928 17206 18668 17207 18928 17207 18669 17207 18669 17208 18928 17208 18929 17208 18669 17209 18929 17209 18671 17209 18671 17210 18929 17210 18930 17210 18671 17211 18930 17211 18672 17211 18672 17212 18930 17212 18931 17212 18672 17213 18931 17213 18673 17213 18673 17214 18931 17214 18932 17214 18673 17215 18932 17215 18823 17215 18823 17216 18932 17216 18934 17216 18823 17217 18934 17217 18933 17217 18933 17218 18934 17218 18822 17218 18935 17219 18909 17219 18697 17219 18697 17220 18909 17220 18914 17220 18697 17221 18914 17221 18937 17221 18937 17222 18914 17222 18936 17222 18937 17223 18936 17223 18939 17223 18939 17224 18936 17224 18938 17224 18939 17225 18938 17225 18699 17225 18699 17226 18938 17226 18940 17226 18699 17227 18940 17227 18701 17227 18701 17228 18940 17228 18942 17228 18701 17229 18942 17229 18941 17229 18941 17230 18942 17230 18943 17230 18941 17231 18943 17231 18861 17231 18861 17232 18943 17232 18945 17232 18861 17233 18945 17233 18944 17233 18944 17234 18945 17234 18858 17234 18964 17235 18946 17235 18680 17235 18680 17236 18946 17236 18842 17236 18680 17237 18842 17237 18947 17237 18947 17238 18842 17238 18948 17238 18947 17239 18948 17239 18949 17239 18949 17240 18948 17240 18950 17240 18949 17241 18950 17241 18682 17241 18682 17242 18950 17242 18951 17242 18682 17243 18951 17243 18952 17243 18952 17244 18951 17244 18953 17244 18952 17245 18953 17245 18954 17245 18954 17246 18953 17246 18956 17246 18954 17247 18956 17247 18955 17247 18955 17248 18956 17248 18957 17248 18955 17249 18957 17249 18896 17249 18896 17250 18957 17250 18895 17250 18970 17251 18972 17251 18843 17251 18843 17252 18972 17252 18711 17252 18843 17253 18711 17253 18844 17253 18958 17254 18246 17254 18959 17254 18958 17255 18959 17255 18837 17255 18837 17256 18959 17256 18960 17256 18837 17257 18960 17257 18838 17257 18838 17258 18960 17258 18961 17258 18838 17259 18961 17259 18962 17259 18962 17260 18961 17260 18714 17260 18962 17261 18714 17261 18839 17261 18839 17262 18714 17262 18963 17262 18839 17263 18963 17263 18840 17263 18840 17264 18963 17264 18713 17264 18840 17265 18713 17265 18964 17265 18964 17266 18713 17266 18965 17266 18964 17267 18965 17267 18946 17267 18946 17268 18965 17268 18966 17268 18946 17269 18966 17269 18841 17269 18841 17270 18966 17270 18968 17270 18841 17271 18968 17271 18967 17271 18967 17272 18968 17272 18969 17272 18967 17273 18969 17273 18970 17273 18970 17274 18969 17274 18971 17274 18970 17275 18971 17275 18972 17275 18973 17276 18975 17276 18974 17276 18973 17277 18974 17277 19058 17277 18975 17278 18973 17278 18976 17278 18976 17279 18973 17279 18978 17279 18976 17280 18978 17280 18977 17280 18977 17281 18978 17281 19062 17281 19062 17282 18978 17282 18979 17282 19062 17283 18979 17283 19064 17283 18980 17284 18981 17284 18979 17284 18979 17285 18981 17285 18982 17285 18979 17286 18982 17286 19064 17286 19068 17287 18983 17287 18985 17287 18985 17288 18983 17288 18984 17288 18985 17289 18984 17289 18980 17289 18980 17290 18984 17290 19066 17290 18980 17291 19066 17291 18981 17291 19068 17292 18985 17292 19069 17292 19069 17293 18985 17293 18986 17293 19069 17294 18986 17294 19070 17294 19070 17295 18986 17295 19071 17295 19071 17296 18986 17296 18987 17296 19071 17297 18987 17297 18988 17297 18988 17298 18987 17298 18989 17298 18989 17299 18987 17299 18991 17299 18989 17300 18991 17300 18990 17300 18994 17301 19074 17301 18991 17301 18991 17302 19074 17302 19073 17302 18991 17303 19073 17303 18990 17303 19077 17304 19075 17304 18992 17304 18992 17305 19075 17305 18993 17305 18992 17306 18993 17306 18994 17306 18994 17307 18993 17307 18995 17307 18994 17308 18995 17308 19074 17308 19077 17309 18992 17309 18996 17309 18996 17310 18992 17310 18997 17310 18996 17311 18997 17311 18998 17311 18998 17312 18997 17312 19078 17312 19078 17313 18997 17313 18999 17313 19078 17314 18999 17314 19000 17314 19000 17315 18999 17315 19001 17315 19001 17316 18999 17316 19002 17316 19001 17317 19002 17317 19003 17317 19006 17318 19007 17318 19002 17318 19002 17319 19007 17319 19081 17319 19002 17320 19081 17320 19003 17320 19008 17321 19004 17321 19009 17321 19009 17322 19004 17322 19005 17322 19009 17323 19005 17323 19006 17323 19006 17324 19005 17324 19082 17324 19006 17325 19082 17325 19007 17325 19008 17326 19009 17326 19010 17326 19010 17327 19009 17327 19012 17327 19010 17328 19012 17328 19085 17328 19085 17329 19012 17329 19011 17329 19011 17330 19012 17330 19014 17330 19011 17331 19014 17331 19013 17331 19013 17332 19014 17332 19015 17332 19015 17333 19014 17333 19016 17333 19015 17334 19016 17334 19086 17334 19020 17335 19088 17335 19016 17335 19016 17336 19088 17336 19087 17336 19016 17337 19087 17337 19086 17337 19092 17338 19017 17338 19018 17338 19018 17339 19017 17339 19090 17339 19018 17340 19090 17340 19020 17340 19020 17341 19090 17341 19019 17341 19020 17342 19019 17342 19088 17342 19092 17343 19018 17343 19021 17343 19021 17344 19018 17344 19022 17344 19021 17345 19022 17345 19023 17345 19023 17346 19022 17346 19094 17346 19094 17347 19022 17347 19025 17347 19094 17348 19025 17348 19024 17348 19029 17349 19096 17349 19025 17349 19025 17350 19096 17350 19026 17350 19025 17351 19026 17351 19024 17351 19027 17352 19028 17352 19029 17352 19029 17353 19028 17353 19098 17353 19029 17354 19098 17354 19096 17354 19032 17355 19030 17355 19033 17355 19033 17356 19030 17356 19031 17356 19033 17357 19031 17357 19027 17357 19027 17358 19031 17358 19100 17358 19027 17359 19100 17359 19028 17359 19032 17360 19033 17360 19035 17360 19035 17361 19033 17361 19034 17361 19035 17362 19034 17362 19036 17362 19037 17363 19104 17363 19034 17363 19034 17364 19104 17364 19101 17364 19034 17365 19101 17365 19036 17365 19038 17366 19039 17366 19037 17366 19037 17367 19039 17367 19105 17367 19037 17368 19105 17368 19104 17368 19042 17369 19107 17369 19038 17369 19038 17370 19107 17370 19106 17370 19038 17371 19106 17371 19039 17371 19112 17372 19110 17372 19040 17372 19040 17373 19110 17373 19041 17373 19040 17374 19041 17374 19042 17374 19042 17375 19041 17375 19108 17375 19042 17376 19108 17376 19107 17376 19112 17377 19040 17377 19114 17377 19114 17378 19040 17378 19043 17378 19114 17379 19043 17379 19044 17379 19044 17380 19043 17380 19115 17380 19115 17381 19043 17381 19045 17381 19115 17382 19045 17382 19116 17382 19047 17383 19118 17383 19045 17383 19045 17384 19118 17384 19046 17384 19045 17385 19046 17385 19116 17385 19051 17386 19121 17386 19047 17386 19047 17387 19121 17387 19120 17387 19047 17388 19120 17388 19118 17388 19048 17389 19049 17389 19050 17389 19050 17390 19049 17390 19123 17390 19050 17391 19123 17391 19051 17391 19051 17392 19123 17393 19122 17394 19051 17395 19122 17395 19121 17395 19048 17396 19050 17396 19125 17396 19125 17397 19050 17397 19052 17397 19125 17398 19052 17398 19055 17398 19057 17399 19053 17399 19052 17399 19052 17400 19053 17400 19054 17400 19052 17401 19054 17401 19055 17401 19056 17402 19131 17402 19057 17402 19057 17403 19131 17403 19128 17403 19057 17404 19128 17404 19053 17404 18974 17405 19133 17405 19058 17405 19058 17406 19133 17406 19059 17406 19058 17407 19059 17407 19056 17407 19056 17408 19059 17408 19060 17408 19056 17409 19060 17409 19131 17409 19061 17410 18975 17410 19190 17410 19190 17411 18975 17411 18976 17411 19190 17412 18976 17412 19189 17412 18976 17413 18977 17413 19189 17413 19189 17414 18977 17414 19062 17414 19189 17415 19062 17415 19063 17415 19062 17416 19064 17416 19063 17416 19063 17417 19064 17417 18982 17417 19063 17418 18982 17418 19065 17418 19065 17419 18982 17419 18981 17419 19065 17420 18981 17420 19184 17420 18981 17421 19066 17421 19184 17421 19184 17422 19066 17422 18984 17422 19184 17423 18984 17423 19067 17423 18984 17424 18983 17424 19067 17424 19067 17425 18983 17426 19068 17427 19067 17428 19068 17428 19182 17428 19068 17429 19069 17429 19182 17429 19182 17430 19069 17430 19070 17430 19182 17431 19070 17431 19072 17431 19070 17432 19071 17432 19072 17432 19072 17433 19071 17433 18988 17433 19072 17434 18988 17434 19180 17434 19180 17435 18988 17435 18989 17435 19180 17436 18989 17436 19178 17436 18989 17437 18990 17437 19178 17437 19178 17438 18990 17438 19073 17438 19178 17439 19073 17439 19177 17439 19177 17440 19073 17440 19074 17440 19177 17441 19074 17441 19176 17441 19074 17442 18995 17442 19176 17442 19176 17443 18995 17443 18993 17443 19176 17444 18993 17444 19174 17444 18993 17445 19075 17445 19174 17445 19174 17446 19075 17446 19077 17446 19174 17447 19077 17448 19076 17449 19076 17450 19077 17451 18996 17452 19076 17453 18996 17453 19171 17453 19171 17454 18996 17454 18998 17454 18998 17455 19078 17456 19171 17457 19171 17458 19078 17459 19000 17460 19171 17461 19000 17461 19170 17461 19170 17462 19000 17462 19001 17462 19170 17463 19001 17463 19079 17463 19001 17464 19003 17464 19079 17464 19079 17465 19003 17466 19081 17466 19079 17467 19081 17467 19080 17467 19080 17468 19081 17468 19007 17468 19080 17469 19007 17469 19168 17469 19007 17470 19082 17470 19168 17470 19168 17471 19082 17471 19005 17471 19168 17472 19005 17472 19083 17472 19005 17473 19004 17473 19083 17473 19083 17474 19004 17474 19008 17474 19083 17475 19008 17475 19084 17475 19084 17476 19008 17476 19010 17476 19084 17477 19010 17477 19163 17477 19163 17478 19010 17478 19085 17478 19085 17479 19011 17479 19163 17479 19163 17480 19011 17480 19013 17480 19163 17481 19013 17481 19162 17481 19162 17482 19013 17482 19015 17482 19162 17483 19015 17483 19160 17483 19015 17484 19086 17484 19160 17484 19160 17485 19086 17485 19087 17485 19160 17486 19087 17486 19159 17486 19159 17487 19087 17487 19088 17487 19159 17488 19088 17488 19089 17488 19088 17489 19019 17489 19089 17489 19089 17490 19019 17490 19090 17490 19089 17491 19090 17491 19158 17491 19090 17492 19017 17492 19158 17492 19158 17493 19017 17493 19092 17493 19158 17494 19092 17494 19091 17494 19091 17495 19092 17495 19021 17495 19091 17496 19021 17496 19093 17496 19021 17497 19023 17497 19093 17497 19093 17498 19023 17498 19094 17498 19093 17499 19094 17499 19095 17499 19094 17500 19024 17500 19095 17500 19095 17501 19024 17502 19026 17502 19095 17503 19026 17503 19097 17503 19026 17504 19096 17504 19097 17504 19097 17505 19096 17505 19098 17505 19097 17506 19098 17506 19099 17506 19098 17507 19028 17507 19099 17507 19099 17508 19028 17508 19100 17508 19099 17509 19100 17509 19155 17509 19155 17510 19100 17510 19031 17510 19155 17511 19031 17511 19153 17511 19031 17512 19030 17512 19153 17512 19153 17513 19030 17513 19032 17513 19153 17514 19032 17514 19151 17514 19151 17515 19032 17516 19035 17517 19151 17518 19035 17518 19102 17518 19035 17519 19036 17519 19102 17519 19102 17520 19036 17520 19101 17520 19102 17521 19101 17521 19103 17521 19101 17522 19104 17522 19103 17522 19103 17523 19104 17523 19105 17523 19103 17524 19105 17524 19148 17524 19105 17525 19039 17525 19148 17525 19148 17526 19039 17526 19106 17526 19148 17527 19106 17527 19147 17527 19106 17528 19107 17528 19147 17528 19147 17529 19107 17529 19108 17529 19147 17530 19108 17531 19109 17532 19109 17533 19108 17533 19041 17533 19109 17534 19041 17534 19111 17534 19041 17535 19110 17536 19111 17537 19111 17538 19110 17539 19112 17540 19111 17541 19112 17541 19113 17541 19113 17542 19112 17542 19114 17542 19113 17543 19114 17543 19144 17543 19114 17544 19044 17544 19144 17544 19144 17545 19044 17545 19115 17545 19144 17546 19115 17546 19117 17546 19115 17547 19116 17547 19117 17547 19117 17548 19116 17548 19046 17548 19117 17549 19046 17549 19140 17549 19140 17550 19046 17550 19118 17550 19140 17551 19118 17551 19119 17551 19119 17552 19118 17552 19120 17552 19120 17553 19121 17553 19119 17553 19119 17554 19121 17554 19122 17554 19119 17555 19122 17555 19139 17555 19139 17556 19122 17556 19123 17556 19139 17557 19123 17557 19137 17557 19123 17558 19049 17558 19137 17558 19137 17559 19049 17559 19048 17559 19137 17560 19048 17560 19124 17560 19124 17561 19048 17561 19125 17561 19124 17562 19125 17562 19126 17562 19125 17563 19055 17563 19126 17563 19126 17564 19055 17565 19054 17566 19126 17567 19054 17567 19127 17567 19054 17568 19053 17568 19127 17568 19127 17569 19053 17569 19128 17569 19127 17570 19128 17570 19129 17570 19129 17571 19128 17571 19131 17571 19129 17572 19131 17572 19130 17572 19131 17573 19060 17573 19130 17573 19130 17574 19060 17574 19059 17574 19130 17575 19059 17575 19132 17575 19132 17576 19059 17576 19133 17576 19132 17577 19133 17577 19061 17577 19061 17578 19133 17578 18974 17578 19061 17579 18974 17579 18975 17579 19130 17580 19193 17580 19129 17580 19129 17581 19193 17581 19195 17581 19129 17582 19195 17582 19127 17582 19127 17583 19195 17583 19134 17583 19127 17584 19134 17584 19126 17584 19126 17585 19134 17585 19196 17585 19126 17586 19196 17586 19124 17586 19124 17587 19196 17587 19135 17587 19124 17588 19135 17588 19137 17588 19137 17589 19135 17589 19136 17589 19137 17590 19136 17590 19139 17590 19139 17591 19136 17591 19138 17591 19139 17592 19138 17592 19119 17592 19119 17593 19138 17593 19141 17593 19119 17594 19141 17594 19140 17594 19140 17595 19141 17595 19142 17595 19140 17596 19142 17596 19117 17596 19117 17597 19142 17597 19143 17597 19117 17598 19143 17598 19144 17598 19144 17599 19143 17599 19199 17599 19144 17600 19199 17600 19113 17600 19113 17601 19199 17601 19201 17601 19113 17602 19201 17603 19111 17604 19111 17605 19201 17605 19145 17605 19111 17606 19145 17606 19109 17606 19109 17607 19145 17607 19146 17607 19109 17608 19146 17608 19147 17608 19147 17609 19146 17609 19149 17609 19147 17610 19149 17610 19148 17610 19148 17611 19149 17611 19203 17611 19148 17612 19203 17612 19103 17612 19103 17613 19203 17613 19205 17613 19103 17614 19205 17614 19102 17614 19102 17615 19205 17615 19150 17615 19102 17616 19150 17616 19151 17616 19151 17617 19150 17617 19152 17617 19151 17618 19152 17618 19153 17618 19153 17619 19152 17619 19154 17619 19153 17620 19154 17620 19155 17620 19155 17621 19154 17621 19208 17621 19155 17622 19208 17622 19099 17622 19099 17623 19208 17623 19211 17623 19099 17624 19211 17624 19097 17624 19097 17625 19211 17625 19213 17625 19097 17626 19213 17626 19095 17626 19095 17627 19213 17627 19215 17627 19095 17628 19215 17628 19093 17628 19093 17629 19215 17629 19156 17629 19093 17630 19156 17630 19091 17630 19091 17631 19156 17631 19157 17631 19091 17632 19157 17632 19158 17632 19158 17633 19157 17633 19218 17633 19158 17634 19218 17634 19089 17634 19089 17635 19218 17635 19219 17635 19089 17636 19219 17636 19159 17636 19159 17637 19219 17637 19221 17637 19159 17638 19221 17638 19160 17638 19160 17639 19221 17639 19161 17639 19160 17640 19161 17640 19162 17640 19162 17641 19161 17641 19164 17641 19162 17642 19164 17642 19163 17642 19163 17643 19164 17643 19165 17643 19163 17644 19165 17644 19084 17644 19084 17645 19165 17645 19166 17645 19084 17646 19166 17646 19083 17646 19083 17647 19166 17647 19167 17647 19083 17648 19167 17648 19168 17648 19168 17649 19167 17649 19225 17649 19168 17650 19225 17650 19080 17650 19080 17651 19225 17651 19227 17651 19080 17652 19227 17652 19079 17652 19079 17653 19227 17653 19169 17653 19079 17654 19169 17654 19170 17654 19170 17655 19169 17655 19228 17655 19170 17656 19228 17656 19171 17656 19171 17657 19228 17657 19172 17657 19171 17658 19172 17658 19076 17658 19076 17659 19172 17659 19173 17659 19076 17660 19173 17660 19174 17660 19174 17661 19173 17661 19229 17661 19174 17662 19229 17662 19176 17662 19176 17663 19229 17664 19175 17664 19176 17665 19175 17665 19177 17665 19177 17666 19175 17666 19179 17666 19177 17667 19179 17667 19178 17667 19178 17668 19179 17668 19231 17668 19178 17669 19231 17669 19180 17669 19180 17670 19231 17670 19232 17670 19180 17671 19232 17671 19072 17671 19072 17672 19232 17672 19181 17672 19072 17673 19181 17673 19182 17673 19182 17674 19181 17674 19234 17674 19182 17675 19234 17675 19067 17675 19067 17676 19234 17676 19183 17676 19067 17677 19183 17677 19184 17677 19184 17678 19183 17678 19185 17678 19184 17679 19185 17679 19065 17679 19065 17680 19185 17680 19186 17680 19065 17681 19186 17681 19063 17681 19063 17682 19186 17682 19187 17682 19063 17683 19187 17683 19189 17683 19189 17684 19187 17684 19188 17684 19189 17685 19188 17685 19190 17685 19190 17686 19188 17686 19238 17686 19190 17687 19238 17687 19061 17687 19061 17688 19238 17688 19191 17688 19061 17689 19191 17689 19132 17689 19132 17690 19191 17690 19192 17690 19132 17691 19192 17691 19130 17691 19130 17692 19192 17692 19193 17692 19193 17693 19241 17693 19195 17693 19195 17694 19241 17694 19194 17694 19195 17695 19194 17695 19134 17695 19134 17696 19194 17696 19244 17696 19134 17697 19244 17697 19196 17697 19196 17698 19244 17698 19246 17698 19196 17699 19246 17699 19135 17699 19135 17700 19246 17700 19248 17700 19135 17701 19248 17701 19136 17701 19136 17702 19248 17702 19249 17702 19136 17703 19249 17703 19138 17703 19138 17704 19249 17704 19251 17704 19138 17705 19251 17705 19141 17705 19141 17706 19251 17706 19197 17706 19141 17707 19197 17707 19142 17707 19142 17708 19197 17708 19254 17708 19142 17709 19254 17709 19143 17709 19143 17710 19254 17710 19198 17710 19143 17711 19198 17711 19199 17711 19199 17712 19198 17712 19200 17712 19199 17713 19200 17713 19201 17713 19201 17714 19200 17714 19202 17714 19201 17715 19202 17715 19145 17715 19145 17716 19202 17716 19260 17716 19145 17717 19260 17717 19146 17717 19146 17718 19260 17718 19261 17718 19146 17719 19261 17719 19149 17719 19149 17720 19261 17720 19204 17720 19149 17721 19204 17721 19203 17721 19203 17722 19204 17722 19264 17722 19203 17723 19264 17723 19205 17723 19205 17724 19264 17724 19267 17724 19205 17725 19267 17725 19150 17725 19150 17726 19267 17726 19206 17726 19150 17727 19206 17727 19152 17727 19152 17728 19206 17728 19207 17728 19152 17729 19207 17729 19154 17729 19154 17730 19207 17730 19209 17730 19154 17731 19209 17731 19208 17731 19208 17732 19209 17732 19210 17732 19208 17733 19210 17733 19211 17733 19211 17734 19210 17734 19212 17734 19211 17735 19212 17735 19213 17735 19213 17736 19212 17736 19273 17736 19213 17737 19273 17737 19215 17737 19215 17738 19273 17738 19214 17738 19215 17739 19214 17739 19156 17739 19156 17740 19214 17740 19216 17740 19156 17741 19216 17741 19157 17741 19157 17742 19216 17742 19217 17742 19157 17743 19217 17743 19218 17743 19218 17744 19217 17744 19279 17744 19218 17745 19279 17745 19219 17745 19219 17746 19279 17746 19220 17746 19219 17747 19220 17747 19221 17747 19221 17748 19220 17748 19282 17748 19221 17749 19282 17749 19161 17749 19161 17750 19282 17750 19284 17750 19161 17751 19284 17751 19164 17751 19164 17752 19284 17752 19222 17752 19164 17753 19222 17753 19165 17753 19165 17754 19222 17754 19223 17754 19165 17755 19223 17755 19166 17755 19166 17756 19223 17756 19224 17756 19166 17757 19224 17757 19167 17757 19167 17758 19224 17758 19226 17758 19167 17759 19226 17759 19225 17759 19225 17760 19226 17760 19289 17760 19225 17761 19289 17761 19227 17761 19227 17762 19289 17762 19293 17762 19227 17763 19293 17763 19169 17763 19169 17764 19293 17764 19295 17764 19169 17765 19295 17765 19228 17765 19228 17766 19295 17766 19296 17766 19228 17767 19296 17767 19172 17767 19172 17768 19296 17768 19297 17768 19172 17769 19297 17769 19173 17769 19173 17770 19297 17770 19299 17770 19173 17771 19299 17771 19229 17771 19229 17772 19299 17772 19301 17772 19229 17773 19301 17773 19175 17773 19175 17774 19301 17774 19304 17774 19175 17775 19304 17775 19179 17775 19179 17776 19304 17776 19230 17776 19179 17777 19230 17777 19231 17777 19231 17778 19230 17778 19307 17778 19231 17779 19307 17780 19232 17781 19232 17782 19307 17782 19309 17782 19232 17783 19309 17783 19181 17783 19181 17784 19309 17784 19233 17784 19181 17785 19233 17785 19234 17785 19234 17786 19233 17786 19313 17786 19234 17787 19313 17787 19183 17787 19183 17788 19313 17788 19235 17788 19183 17789 19235 17789 19185 17789 19185 17790 19235 17790 19315 17790 19185 17791 19315 17791 19186 17791 19186 17792 19315 17792 19236 17792 19186 17793 19236 17793 19187 17793 19187 17794 19236 17794 19237 17794 19187 17795 19237 17795 19188 17795 19188 17796 19237 17796 19239 17796 19188 17797 19239 17797 19238 17797 19238 17798 19239 17798 19240 17798 19238 17799 19240 17799 19191 17799 19191 17800 19240 17800 19322 17800 19191 17801 19322 17801 19192 17801 19192 17802 19322 17802 19323 17802 19192 17803 19323 17803 19193 17803 19193 17804 19323 17804 19241 17804 19241 17805 19242 17805 19194 17805 19194 17806 19242 17806 19243 17806 19194 17807 19243 17807 19244 17807 19244 17808 19243 17808 19245 17808 19244 17809 19245 17809 19246 17809 19246 17810 19245 17810 19247 17810 19246 17811 19247 17811 19248 17811 19248 17812 19247 17812 19250 17812 19248 17813 19250 17813 19249 17813 19249 17814 19250 17814 19252 17814 19249 17815 19252 17815 19251 17815 19251 17816 19252 17816 19253 17816 19251 17817 19253 17817 19197 17817 19197 17818 19253 17818 19255 17818 19197 17819 19255 17819 19254 17819 19254 17820 19255 17820 19256 17820 19254 17821 19256 17821 19198 17821 19198 17822 19256 17822 19257 17822 19198 17823 19257 17823 19200 17823 19200 17824 19257 17824 19258 17824 19200 17825 19258 17825 19202 17825 19202 17826 19258 17826 19259 17826 19202 17827 19259 17827 19260 17827 19260 17828 19259 17828 19262 17828 19260 17829 19262 17829 19261 17829 19261 17830 19262 17830 19263 17830 19261 17831 19263 17831 19204 17831 19204 17832 19263 17832 19265 17832 19204 17833 19265 17833 19264 17833 19264 17834 19265 17834 19266 17834 19264 17835 19266 17835 19267 17835 19267 17836 19266 17836 19268 17836 19267 17837 19268 17837 19206 17837 19206 17838 19268 17838 19269 17838 19206 17839 19269 17839 19207 17839 19207 17840 19269 17840 19270 17840 19207 17841 19270 17841 19209 17841 19209 17842 19270 17842 19271 17842 19209 17843 19271 17843 19210 17843 19210 17844 19271 17844 19272 17844 19210 17845 19272 17845 19212 17845 19212 17846 19272 17846 19274 17846 19212 17847 19274 17847 19273 17847 19273 17848 19274 17848 19275 17848 19273 17849 19275 17849 19214 17849 19214 17850 19275 17850 19276 17850 19214 17851 19276 17851 19216 17851 19216 17852 19276 17852 19277 17852 19216 17853 19277 17853 19217 17853 19217 17854 19277 17854 19278 17854 19217 17855 19278 17855 19279 17855 19279 17856 19278 17856 19280 17856 19279 17857 19280 17857 19220 17857 19220 17858 19280 17858 19281 17858 19220 17859 19281 17859 19282 17859 19282 17860 19281 17860 19283 17860 19282 17861 19283 17861 19284 17861 19284 17862 19283 17862 19285 17862 19284 17863 19285 17863 19222 17863 19222 17864 19285 17864 19286 17864 19222 17865 19286 17865 19223 17865 19223 17866 19286 17866 19287 17866 19223 17867 19287 17867 19224 17867 19224 17868 19287 17868 19288 17868 19224 17869 19288 17869 19226 17869 19226 17870 19288 17870 19290 17870 19226 17871 19290 17871 19289 17871 19289 17872 19290 17872 19291 17872 19289 17873 19291 17873 19293 17873 19293 17874 19291 17874 19292 17874 19293 17875 19292 17875 19295 17875 19295 17876 19292 17876 19294 17876 19295 17877 19294 17877 19296 17877 19296 17878 19294 17878 19298 17878 19296 17879 19298 17879 19297 17879 19297 17880 19298 17880 19300 17880 19297 17881 19300 17881 19299 17881 19299 17882 19300 17882 19302 17882 19299 17883 19302 17883 19301 17883 19301 17884 19302 17884 19303 17884 19301 17885 19303 17885 19304 17885 19304 17886 19303 17886 19305 17886 19304 17887 19305 17887 19230 17887 19230 17888 19305 17888 19306 17888 19230 17889 19306 17889 19307 17889 19307 17890 19306 17890 19308 17890 19307 17891 19308 17891 19309 17891 19309 17892 19308 17892 19310 17892 19309 17893 19310 17893 19233 17893 19233 17894 19310 17894 19311 17894 19233 17895 19311 17895 19313 17895 19313 17896 19311 17896 19312 17896 19313 17897 19312 17897 19235 17897 19235 17898 19312 17898 19314 17898 19235 17899 19314 17899 19315 17899 19315 17900 19314 17900 19316 17900 19315 17901 19316 17901 19236 17901 19236 17902 19316 17902 19317 17902 19236 17903 19317 17903 19237 17903 19237 17904 19317 17904 19318 17904 19237 17905 19318 17905 19239 17905 19239 17906 19318 17906 19319 17906 19239 17907 19319 17907 19240 17907 19240 17908 19319 17908 19320 17908 19240 17909 19320 17909 19322 17909 19322 17910 19320 17910 19321 17910 19322 17911 19321 17911 19323 17911 19323 17912 19321 17912 19324 17912 19323 17913 19324 17913 19241 17913 19241 17914 19324 17914 19242 17914 19447 960 19325 960 19441 960 19441 17915 19325 17915 19353 17915 19441 960 19442 960 19447 960 19447 17916 19442 17916 19444 17916 19447 17917 19444 17917 19446 17917 19446 17918 19444 17918 19445 17918 19366 17919 19336 17919 19364 17919 19364 17920 19336 17920 19440 17920 19327 17921 19361 17921 19326 17921 19326 17922 19430 17922 19327 17922 19327 17923 19430 17923 19439 17923 19327 17924 19439 17924 19328 17924 19439 17925 19469 17925 19328 17925 19328 17926 19469 17926 19470 17926 19328 17927 19470 17927 19329 17927 19329 17928 19470 17928 19465 17928 19329 17929 19465 17929 19330 17929 19465 17930 19331 17930 19330 17930 19330 17931 19331 17931 19332 17931 19330 17932 19332 17932 19333 17932 19332 17933 19468 17933 19333 17933 19333 17934 19468 17934 19334 17934 19333 17935 19334 17935 19366 17935 19366 17936 19334 17936 19335 17936 19366 17937 19335 17937 19336 17937 19437 960 19340 960 19337 960 19337 17938 19338 17938 19437 17938 19437 960 19338 960 19432 960 19437 960 19432 960 19436 960 19436 17939 19432 17939 19433 17939 19436 960 19433 960 19434 960 19339 17940 19337 17940 19341 17940 19341 17941 19337 17941 19340 17941 19341 17942 19340 17942 19361 17942 19361 17940 19340 17940 19326 17940 19339 17943 19341 17943 19352 17943 19352 17944 19341 17944 19351 17944 19357 17945 19482 17945 19342 17945 19342 17946 19482 17946 19343 17946 19343 17947 19481 17947 19342 17947 19342 17948 19481 17948 19479 17948 19342 17949 19479 17949 19355 17949 19479 17950 19478 17950 19355 17950 19355 17951 19478 17951 19344 17951 19355 17952 19344 17952 19345 17952 19345 17953 19344 17953 19347 17953 19345 17954 19347 17954 19346 17954 19347 17955 19348 17955 19346 17955 19346 17956 19348 17956 19471 17956 19346 17957 19471 17957 19350 17957 19471 17958 19349 17958 19350 17958 19350 17959 19349 17959 19472 17959 19350 17960 19472 17960 19351 17960 19351 17961 19472 17961 19474 17961 19351 17962 19474 17962 19352 17962 19440 17963 19353 17963 19364 17963 19364 17964 19353 17964 19325 17964 19364 17965 19325 17965 19357 17965 19357 17963 19325 17963 19482 17963 19394 960 19354 960 19345 960 19345 960 19354 960 19355 960 19355 960 19354 960 19356 960 19355 17966 19356 17966 19342 17966 19342 17967 19356 17967 19357 17967 19357 17968 19356 17968 19358 17968 19357 17969 19358 17969 19364 17969 19365 960 19363 960 19330 960 19345 960 19346 960 19394 960 19394 17970 19346 17970 19350 17970 19394 960 19350 960 19359 960 19359 17971 19350 17971 19351 17971 19359 960 19351 960 19360 960 19360 17972 19351 17972 19341 17972 19360 960 19341 960 19399 960 19399 960 19341 960 19361 960 19399 17973 19361 17973 19372 17973 19372 960 19361 960 19327 960 19372 17974 19327 17974 19362 17974 19362 17975 19327 17975 19328 17975 19362 960 19328 960 19363 960 19363 960 19328 960 19329 960 19363 17976 19329 17976 19330 17976 19358 17977 19390 17977 19364 17977 19364 17978 19390 17978 19377 17978 19364 17979 19377 17979 19366 17979 19366 960 19377 960 19365 960 19366 17980 19365 17980 19333 17980 19333 17981 19365 17981 19330 17981 19403 17982 19382 17982 19388 17982 19367 17983 19422 17983 19362 17983 19427 17984 19386 17984 19368 17984 19368 17985 19386 17985 19369 17985 19368 17986 19369 17986 19370 17986 19420 17987 19371 17987 19372 17987 19372 17988 19371 17988 19373 17988 19372 17989 19373 17989 19399 17989 19399 17990 19373 17990 19423 17990 19399 17991 19423 17991 19400 17991 19362 17992 19422 17992 19372 17992 19372 17993 19422 17993 19421 17993 19372 17994 19421 17994 19420 17994 19375 17995 19374 17995 19365 17995 19365 17996 19374 17996 19415 17996 19365 17997 19415 17997 19363 17997 19363 17998 19415 17998 19418 17998 19363 17999 19418 17999 19362 17999 19362 18000 19418 18000 19417 18000 19362 18001 19417 18001 19367 18001 19375 18002 19365 18002 19413 18002 19413 18003 19365 18003 19377 18003 19413 18004 19377 18004 19379 18004 19380 18005 19376 18005 19390 18005 19390 18006 19376 18006 19412 18006 19390 18007 19412 18007 19377 18007 19377 18008 19412 18008 19378 18008 19377 18009 19378 18009 19379 18009 19408 18010 19406 18010 19383 18010 19383 18011 19406 18011 19380 18011 19383 18012 19380 18012 19381 18012 19388 18013 19382 18013 19383 18013 19383 18014 19382 18014 19384 18014 19383 18015 19384 18015 19408 18015 19427 18016 19385 18016 19386 18016 19386 18017 19385 18017 19425 18017 19386 18018 19425 18018 19387 18018 19387 18019 19425 18019 19405 18019 19387 18020 19405 18020 19388 18020 19388 18021 19405 18021 19389 18021 19388 18022 19389 18022 19403 18022 19380 18023 19390 18023 19381 18023 19381 18024 19390 18024 19358 18024 19381 18024 19358 18024 19391 18024 19391 18025 19358 18025 19356 18025 19391 18026 19356 18026 19392 18026 19392 18027 19356 18027 19354 18027 19392 18028 19354 18028 19393 18028 19393 18029 19354 18029 19395 18029 19395 18030 19354 18030 19394 18030 19395 18031 19394 18031 19396 18031 19396 18032 19394 18032 19359 18032 19396 18033 19359 18033 19397 18033 19397 18034 19359 18034 19360 18034 19397 18035 19360 18035 19398 18035 19398 18036 19360 18036 19399 18036 19398 18037 19399 18037 19401 18037 19401 18038 19399 18038 19400 18038 19401 18039 19400 18039 19369 18039 19369 18040 19400 18040 19402 18040 19369 18041 19402 18041 19370 18041 19461 18042 19460 18042 19370 18042 19413 18043 19379 18043 19451 18043 19451 18044 19379 18044 19411 18044 19409 18045 19382 18045 19453 18045 19453 18046 19382 18046 19403 18046 19453 18047 19403 18047 19404 18047 19404 18048 19403 18048 19389 18048 19404 18049 19389 18049 19455 18049 19455 18050 19389 18050 19405 18050 19455 18051 19405 18051 19456 18051 19410 18052 19406 18052 19407 18052 19407 18053 19406 18053 19408 18053 19407 18054 19408 18054 19409 18054 19409 18055 19408 18055 19384 18055 19409 18056 19384 18056 19382 18056 19412 18057 19376 18057 19410 18057 19410 18058 19376 18058 19380 18058 19410 18059 19380 18059 19406 18059 19411 18060 19379 18060 19410 18060 19410 18061 19379 18061 19378 18061 19410 18062 19378 18062 19412 18062 19413 18063 19451 18063 19375 18063 19375 18064 19451 18064 19450 18064 19375 18065 19450 18065 19374 18065 19374 18066 19450 18066 19414 18066 19374 18067 19414 18067 19415 18067 19415 18068 19414 18068 19419 18068 19415 18069 19419 18069 19418 18069 19463 18070 19422 18070 19464 18070 19464 18071 19422 18071 19367 18071 19464 18072 19367 18072 19416 18072 19416 18073 19367 18073 19417 18073 19416 18074 19417 18074 19466 18074 19466 18075 19417 18075 19418 18075 19466 18076 19418 18076 19467 18076 19467 18077 19418 18077 19419 18077 19424 18078 19371 18078 19462 18078 19462 18079 19371 18079 19420 18079 19462 18080 19420 18080 19463 18080 19463 18081 19420 18081 19421 18081 19463 18082 19421 18082 19422 18082 19400 18083 19423 18083 19424 18083 19424 18084 19423 18084 19373 18084 19424 18085 19373 18085 19371 18085 19461 18086 19370 18086 19424 18086 19424 18087 19370 18087 19402 18087 19424 18088 19402 18088 19400 18088 19456 18089 19405 18089 19458 18089 19458 18090 19405 18090 19425 18090 19458 18091 19425 18091 19459 18091 19459 18092 19425 18092 19385 18092 19459 18093 19385 18093 19426 18093 19426 18094 19385 18094 19427 18094 19426 18095 19427 18095 19460 18095 19460 18096 19427 18096 19368 18096 19460 18097 19368 18097 19370 18097 19338 18098 19337 18098 19473 18098 19473 18099 19428 18099 19338 18099 19338 18100 19428 18100 19429 18100 19338 18101 19429 18101 19432 18101 19430 18102 19326 18102 19340 18102 19429 18103 19431 18103 19432 18103 19432 18104 19431 18104 20069 18104 19432 18105 20069 18105 19433 18105 19433 18106 20069 18106 20068 18106 19433 18107 20068 18107 19434 18107 19434 18108 20068 18108 19435 18108 19434 18109 19435 18109 19436 18109 19436 18110 19435 18110 20067 18110 19436 18111 20067 18111 19437 18111 19437 18112 20067 18112 19438 18112 19437 18113 19438 18113 19340 18113 19340 18114 19438 18114 20239 18114 19340 18115 20239 18115 19430 18115 19430 18116 20239 18116 19439 18116 19441 18117 19353 18117 20059 18117 20059 18118 19353 18118 19440 18118 20059 18119 20058 18119 19441 18119 19441 18120 20058 18120 20057 18120 19441 18121 20057 18121 19442 18121 20057 18122 19443 18122 19442 18122 19442 18123 19443 18123 20063 18123 19442 18124 20063 18124 19444 18124 19444 18125 20063 18125 20062 18125 19444 18126 20062 18126 19445 18126 19445 18127 20062 18127 20061 18127 19445 18128 20061 18128 19446 18128 19446 18129 20061 18129 20060 18129 19446 18130 20060 18130 19447 18130 19447 18131 20060 18131 19448 18131 19447 18132 19448 18132 19325 18132 19325 18133 19448 18133 19449 18133 19325 18134 19449 18134 19482 18134 19450 18135 19451 18135 19468 18135 19468 18136 19451 18136 19411 18136 19468 18137 19411 18137 19410 18137 19407 18138 19409 18138 19452 18138 19452 18139 19409 18139 19453 18139 19426 18140 19460 18140 19457 18140 19426 18141 19457 18141 19459 18141 19453 18142 19404 18142 19452 18142 19452 18143 19404 18143 19455 18143 19452 18144 19455 18144 19454 18144 19454 18145 19455 18145 19456 18145 19454 18146 19456 18146 19457 18146 19457 18147 19456 18147 19458 18147 19457 18148 19458 18148 19459 18148 19460 18149 19461 18149 19457 18149 19457 18150 19461 18150 19424 18150 19457 18151 19424 18151 19470 18151 19470 18152 19424 18152 19462 18152 19470 18153 19462 18153 19463 18153 19463 18154 19464 18154 19470 18154 19470 18155 19464 18155 19416 18155 19470 18156 19416 18156 19465 18156 19465 18157 19416 18157 19466 18157 19465 18158 19466 18158 19331 18158 19331 18159 19466 18159 19467 18159 19331 18160 19467 18160 19332 18160 19332 18161 19467 18161 19419 18161 19332 18162 19419 18162 19468 18162 19468 18163 19419 18163 19414 18163 19468 18164 19414 18164 19450 18164 19439 18165 20239 18165 19469 18165 19469 18166 20239 18166 20071 18166 19469 18167 20071 18167 19470 18167 19470 18168 20071 18168 20070 18168 19470 18169 20070 18169 19457 18169 19471 18170 19475 18170 19349 18170 19349 18171 19475 18171 20065 18171 19349 18172 20065 18172 19472 18172 19472 18173 20065 18173 20113 18173 19472 18174 20113 18174 19474 18174 19474 18175 20113 18175 19473 18175 19474 18176 19473 18176 19352 18176 19352 18177 19473 18177 19337 18177 19352 18178 19337 18178 19339 18178 19471 18179 19348 18179 19475 18179 19475 18180 19348 18180 19347 18180 19475 18181 19347 18181 19476 18181 19476 18182 19347 18182 19344 18182 19476 18183 19344 18183 19477 18183 19477 18184 19344 18184 19478 18184 19477 18185 19478 18185 19480 18185 19478 18186 19479 18186 19480 18186 19480 18187 19479 18187 19481 18187 19480 18188 19481 18188 19449 18188 19449 18189 19481 18189 19343 18189 19449 18190 19343 18190 19482 18190 19440 18191 19336 18191 20059 18191 20059 18192 19336 18192 19335 18192 20059 18193 19335 18193 19483 18193 19483 18194 19335 18194 19334 18194 19483 18195 19334 18195 19484 18195 19484 18196 19334 18196 19468 18196 19484 18197 19468 18197 19452 18197 19452 18198 19468 18198 19410 18198 19452 18199 19410 18199 19407 18199 19500 18200 19485 18200 20159 18200 20159 18201 19485 18201 19972 18201 20159 18202 19972 18202 19486 18202 19486 18203 19972 18203 19488 18203 19486 18204 19488 18204 19487 18204 19487 18205 19488 18205 19968 18205 19487 18206 19968 18206 20161 18206 20161 18207 19968 18207 19489 18207 20161 18208 19489 18208 20162 18208 20162 18209 19489 18209 19490 18209 20162 18210 19490 18210 20163 18210 20163 18211 19490 18211 19967 18211 20163 18212 19967 18212 19491 18212 19491 18213 19967 18213 19964 18213 19491 18214 19964 18214 19492 18214 19492 18215 19964 18215 19963 18215 19492 18216 19963 18216 19493 18216 19493 18217 19963 18217 19494 18217 19493 18218 19494 18218 19495 18218 19495 18219 19494 18219 19496 18219 19495 18220 19496 18220 20154 18220 20154 18221 19496 18221 19497 18221 20154 18222 19497 18222 20155 18222 20155 18223 19497 18223 19971 18223 20155 18224 19971 18224 19498 18224 19498 18225 19971 18225 19970 18225 19498 18226 19970 18226 20157 18226 20157 18227 19970 18227 19499 18227 20157 18228 19499 18228 20158 18228 20158 18229 19499 18229 19500 18229 20158 18230 19500 18230 20159 18230 19501 18231 19868 18231 20078 18231 20078 18232 19868 18232 19517 18232 19501 18233 20078 18233 19867 18233 19867 18234 20078 18234 19502 18234 19867 18235 19502 18235 19504 18235 19502 18236 19503 18236 19504 18236 19504 18237 19503 18237 19506 18237 19504 18238 19506 18238 19505 18238 19505 18239 19506 18239 20080 18239 19505 18240 20080 18240 19861 18240 19861 18241 20080 18241 20084 18241 19861 18242 20084 18242 19863 18242 19863 18243 20084 18243 19507 18243 19863 18244 19507 18244 19864 18244 19507 18245 20083 18245 19864 18245 19864 18246 20083 18246 20082 18246 19864 18247 20082 18247 19508 18247 19508 18248 20082 18248 19509 18248 19508 18249 19509 18249 19859 18249 19859 18250 19509 18250 19510 18250 19510 18251 19509 18251 19511 18251 19510 18252 19511 18252 19860 18252 19860 18253 19511 18253 20088 18253 19860 18253 20088 18253 19512 18253 19512 18254 20088 18254 20087 18254 19512 18255 20087 18255 19514 18255 20087 18256 19513 18256 19514 18256 19514 18257 19513 18257 20073 18257 19514 18258 20073 18258 19515 18258 19515 18259 20073 18259 20072 18259 19515 18260 20072 18260 19858 18260 19858 18261 20072 18261 19518 18261 19868 18262 19516 18262 19517 18262 19517 18263 19516 18263 19869 18263 19517 18264 19869 18264 20075 18264 20075 18265 19869 18265 19870 18265 20075 18266 19870 18266 19518 18266 19518 18267 19870 18267 19871 18267 19518 18268 19871 18268 19858 18268 19525 18269 19874 18269 19524 18269 19534 18270 20091 18270 19872 18270 19872 18271 20091 18271 19519 18271 19519 18237 20091 18237 19520 18237 19519 18238 19520 18238 19521 18238 19521 18240 19520 18240 19522 18240 19521 18240 19522 18240 19873 18240 19873 18272 19522 18272 20089 18272 19873 18273 20089 18273 19875 18273 19875 18274 20089 18274 19523 18274 19875 18275 19523 18275 19524 18275 19524 18276 19523 18276 20093 18276 19524 18277 20093 18277 19525 18277 19874 18278 19525 18278 19526 18278 19526 18279 19525 18279 19527 18279 19526 18280 19527 18280 19882 18280 19882 18281 19527 18281 19883 18281 19883 18282 19527 18282 20099 18282 19883 18283 20099 18283 19529 18283 20099 18284 20098 18284 19529 18284 19529 18285 20098 18285 19528 18285 19529 18286 19528 18286 19881 18286 19528 18287 19530 18287 19881 18287 19881 18288 19530 18288 19531 18288 19881 18289 19531 18289 19879 18289 19879 18290 19531 18290 19532 18290 19879 18290 19532 18290 19541 18290 19541 18219 19532 18219 20104 18219 19872 18291 19533 18291 19534 18291 19534 18292 19533 18292 19535 18292 19534 18293 19535 18293 19536 18293 19536 18294 19535 18294 19537 18294 19536 18295 19537 18295 20101 18295 20101 18296 19537 18296 19538 18296 20101 18297 19538 18297 20102 18297 20102 18298 19538 18298 19539 18298 20102 18299 19539 18299 20104 18299 20104 18300 19539 18300 19540 18300 20104 18219 19540 18219 19541 18219 19885 18301 20109 18301 19884 18301 19884 18302 20109 18302 19542 18302 19884 18303 19542 18303 19886 18303 19886 18304 19542 18304 19544 18304 19886 18305 19544 18305 19543 18305 19543 18240 19544 18240 20107 18240 19543 18240 20107 18240 19545 18240 19545 18306 20107 18306 20106 18306 19545 18307 20106 18307 19546 18307 19546 18308 20106 18308 19547 18308 19546 18309 19547 18309 19887 18309 19887 18310 19547 18310 20105 18310 19945 18311 19549 18311 19548 18311 19548 18312 19549 18312 19889 18312 19548 18313 19889 18313 20105 18313 20105 18314 19889 18314 19550 18314 20105 18315 19550 18315 19887 18315 19548 18316 19551 18317 19945 18318 19945 18319 19551 18319 19552 18319 19945 18320 19552 18320 19894 18320 19894 18321 19552 18321 20112 18321 19894 18322 20112 18322 19895 18322 19895 18323 20112 18323 19553 18323 19895 18324 19553 18324 19896 18324 19896 18325 19553 18325 20110 18325 19896 18325 20110 18325 19554 18325 19554 18326 20110 18326 19555 18326 19554 18327 19555 18327 19899 18327 19899 18328 19555 18328 19556 18328 19899 18329 19556 18329 19892 18329 19892 18330 19556 18330 19890 18330 19890 18330 19556 18330 19557 18330 19890 18331 19557 18331 19885 18331 19885 18332 19557 18332 19558 18332 19885 18333 19558 18333 20109 18333 19559 18334 19902 18334 19903 18334 19912 18335 19572 18335 19560 18335 19912 18336 19560 18336 19901 18336 19901 18240 19560 18240 19561 18240 19901 18337 19561 18337 19562 18337 19562 18338 19561 18338 20116 18338 19562 18339 20116 18339 19900 18339 19900 18340 20116 18340 19563 18340 19900 18341 19563 18341 19903 18341 19903 18342 19563 18342 20117 18342 19903 18269 20117 18269 19559 18269 19902 18314 19559 18314 19564 18314 19564 18343 19559 18343 19565 18343 19564 18280 19565 18280 19566 18280 19566 18281 19565 18281 19917 18281 19917 18344 19565 18344 19567 18344 19917 18345 19567 18345 19918 18345 19567 18346 19568 18346 19918 18346 19918 18347 19568 18347 19569 18347 19918 18348 19569 18348 19570 18348 19569 18349 20124 18349 19570 18349 19570 18350 20124 18350 19571 18350 19570 18351 19571 18351 19578 18351 19578 18352 19571 18352 19576 18352 19912 18353 19910 18353 19572 18353 19572 18354 19910 18354 19573 18354 19572 18355 19573 18355 20115 18355 20115 18356 19573 18356 19908 18356 20115 18357 19908 18357 20118 18357 20118 18294 19908 18294 19913 18294 20118 18358 19913 18358 20119 18358 20119 18359 19913 18359 19914 18359 20119 18360 19914 18360 19574 18360 19574 18361 19914 18361 19936 18361 19574 18362 19936 18362 20120 18362 20120 18363 19936 18363 19575 18363 20120 18364 19575 18364 19576 18364 19576 18365 19575 18365 19577 18365 19576 18366 19577 18366 19578 18366 20007 18367 20125 18367 19580 18367 20007 18231 19580 18231 19579 18231 19579 18368 19580 18368 19581 18368 19579 18369 19581 18369 19582 18369 19582 18370 19581 18370 19583 18370 19582 18371 19583 18371 20004 18371 20004 18372 19583 18372 19584 18372 20004 18373 19584 18373 19585 18373 19585 18374 19584 18374 19586 18374 19585 18240 19586 18240 19587 18240 19587 18375 19586 18375 20140 18375 19587 18376 20140 18376 19924 18376 19924 18377 20140 18377 19588 18377 19924 18378 19588 18378 19925 18378 19588 18342 19589 18342 19925 18342 19925 18379 19589 18379 19590 18379 19925 18380 19590 18380 19591 18380 19591 18381 19590 18381 20136 18381 19591 18382 20136 18382 19592 18382 19592 18250 20136 18250 19927 18250 19927 18383 20136 18383 19593 18383 19927 18384 19593 18384 19594 18384 19594 18253 19593 18253 19595 18253 19594 18320 19595 18320 19596 18320 19596 18385 19595 18385 20128 18385 19596 18386 20128 18386 19922 18386 20128 18387 19597 18387 19922 18387 19922 18388 19597 18388 19598 18388 19922 18257 19598 18257 19599 18257 19599 18389 19598 18389 20127 18389 20007 18390 19600 18390 20125 18390 20125 18391 19600 18391 19601 18391 20125 18392 19601 18392 20126 18392 20126 18393 19601 18393 19602 18393 20126 18394 19602 18394 19603 18394 19603 18395 19602 18395 19930 18395 19603 18396 19930 18396 20127 18396 20127 18365 19930 18365 19929 18365 20127 18397 19929 18397 19599 18397 20147 18398 19607 18398 19604 18398 19989 18399 19988 18399 19605 18399 19605 18400 19988 18400 20141 18400 19989 18401 19605 18401 19979 18401 19979 18402 19605 18402 20138 18402 19979 18403 20138 18403 19606 18403 19606 18404 20138 18404 20151 18404 19606 18405 20151 18405 19604 18405 19604 18406 20151 18406 20149 18406 19604 18407 20149 18407 20147 18407 19607 18408 20147 18408 19980 18408 19980 18409 20147 18409 19608 18409 19980 18410 19608 18410 19609 18410 19609 18411 19608 18411 19610 18411 19609 18411 19610 18411 19983 18411 19983 18412 19610 18412 19611 18412 19983 18413 19611 18413 19831 18413 20198 18414 19834 18414 19615 18414 19613 18415 20197 18415 19612 18415 19613 18416 19612 18416 19614 18416 19614 18417 19612 18417 20201 18417 19614 18418 20201 18418 19615 18418 19615 18419 20201 18419 20200 18419 19615 18420 20200 18420 20198 18420 19834 18421 20198 18421 19835 18421 19835 18422 20198 18422 20204 18422 19835 18423 20204 18423 19955 18423 19955 18424 20204 18424 20205 18424 19955 18425 20205 18425 19953 18425 19953 18426 20205 18426 19616 18426 19953 18427 19616 18427 19617 18427 19616 18428 20207 18428 19617 18428 19617 18429 20207 18429 19618 18429 19617 18430 19618 18430 19619 18430 19619 18431 19618 18431 20210 18431 19619 18432 20210 18432 19948 18432 20261 18433 19620 18433 19622 18433 19622 960 19620 960 19621 960 19622 960 19621 960 20321 960 20321 960 19621 960 19725 960 20321 960 19725 960 20267 960 20267 960 19725 960 19724 960 19626 18434 19942 18434 20211 18434 20211 18435 19942 18435 19623 18435 20211 18436 19623 18436 20212 18436 19624 18437 19625 18437 20217 18437 20217 18438 19625 18438 19944 18438 20217 18439 19944 18439 19626 18439 19626 18440 19944 18440 19627 18440 19626 18434 19627 18434 19942 18434 20217 18441 20218 18441 19624 18441 19624 18442 20218 18442 20221 18442 19624 18443 20221 18443 19629 18443 19629 18444 20221 18444 19628 18444 19629 18445 19628 18445 19934 18445 19934 18446 19628 18446 19630 18446 19934 18447 19630 18447 19933 18447 19933 18448 19630 18448 19631 18448 19933 18449 19631 18449 19632 18449 19632 18450 19631 18450 20130 18450 19632 18451 20130 18451 20263 18451 20267 18452 19724 18452 19947 18452 19947 18453 19724 18453 19633 18453 19947 18454 19633 18454 19623 18454 19623 18455 19633 18455 20212 18455 19633 18456 19724 18456 19634 18456 19634 18457 19724 18457 19635 18457 19634 18458 19635 18458 19636 18458 19635 18459 19637 18459 19636 18459 19636 18460 19637 18460 19638 18460 19636 18461 19638 18461 20111 18461 19644 18462 19639 18462 19640 18462 19640 18463 19639 18463 20209 18463 19640 18464 20209 18464 19720 18464 19720 18465 20209 18465 19641 18465 19720 18466 19641 18466 19721 18466 19721 18467 19641 18467 20111 18467 19721 18468 20111 18468 19642 18468 19642 18469 20111 18469 19638 18469 19948 18470 20210 18470 19643 18470 19643 18471 20210 18471 19639 18471 19643 18472 19639 18472 20315 18472 20315 18473 19639 18473 19644 18473 20312 960 20315 960 19644 960 20312 960 19644 960 20307 960 19644 960 19645 960 20307 960 20307 960 19645 960 19717 960 20307 18474 19717 18474 20308 18474 20308 18475 19717 18475 19662 18475 20308 18476 19662 18476 20386 18476 19646 960 19647 960 19649 960 19649 960 19647 960 19648 960 19649 960 19648 960 19650 960 19650 18477 19648 18477 19759 18477 19650 960 19759 960 19651 960 19651 18478 19759 18478 19652 18478 19651 18479 19652 18479 20325 18479 20325 18480 19652 18480 19757 18480 19647 18481 19653 18481 19654 18481 19654 18482 19653 18482 20090 18482 19654 18483 20090 18483 19655 18483 19655 18484 20090 18484 20100 18484 19655 18485 20100 18485 19656 18485 19656 18486 20100 18486 20103 18486 19656 18487 20103 18487 19714 18487 19714 18488 20103 18488 20196 18488 19714 18489 20196 18489 19657 18489 19657 18490 20196 18490 19658 18490 19657 18491 19658 18491 19659 18491 19659 18492 19658 18492 19660 18492 19659 18493 19660 18493 19661 18493 19661 18494 19660 18494 20055 18494 19661 18495 20055 18495 19662 18495 19663 18496 19675 18496 19876 18496 19876 18497 19675 18497 19653 18497 19876 18498 19653 18498 19646 18498 19646 18499 19653 18499 19647 18499 19675 18500 19663 18500 19674 18500 19664 18501 19677 18501 19665 18501 19665 18502 19677 18502 20076 18502 19664 18503 19665 18503 19666 18503 19666 18503 19665 18503 20074 18503 19666 18504 20074 18504 19667 18504 20074 18505 20188 18505 19667 18505 19667 18506 20188 18506 20190 18506 19667 18507 20190 18507 19668 18507 19668 18508 20190 18508 19669 18508 19668 18509 19669 18509 19956 18509 19956 18510 19669 18510 19671 18510 19956 18511 19671 18511 19670 18511 19670 18512 19671 18512 19672 18512 19672 18513 19671 18513 19673 18513 19672 18514 19673 18514 19674 18514 19674 18515 19673 18515 20092 18515 19674 18516 20092 18516 19675 18516 20325 18517 19757 18517 20293 18517 20293 18518 19757 18518 19676 18518 20293 18519 19676 18519 19677 18519 19677 18520 19676 18520 20076 18520 19676 18521 19757 18521 19678 18521 19676 18522 19678 18522 20077 18522 20077 18523 19678 18523 19756 18523 20077 18524 19756 18524 19679 18524 19679 18525 19756 18525 19680 18525 19679 18526 19680 18526 19681 18526 19681 18527 19680 18527 19682 18527 19681 18528 19682 18528 20079 18528 20079 18529 19682 18529 19753 18529 20079 18530 19753 18530 19684 18530 19751 18531 20182 18531 19683 18531 19683 18532 20182 18532 19684 18532 19683 18533 19684 18533 19752 18533 19752 18534 19684 18534 19753 18534 20333 960 19751 960 20335 960 20335 18535 19751 18535 19685 18535 20335 960 19685 960 20286 960 20286 960 19685 960 19686 960 20286 960 19686 960 19687 960 19687 18536 19686 18536 19695 18536 19687 960 19695 960 20288 960 20181 18537 19688 18537 19689 18537 19697 18538 19690 18538 20175 18538 19697 18539 20175 18539 19961 18539 19961 18540 20175 18540 20173 18540 19961 18540 20173 18540 19691 18540 19691 18541 20173 18541 20172 18541 19691 18542 20172 18542 19692 18542 19692 18543 20172 18543 19959 18543 19959 18544 20172 18544 20170 18544 19959 18545 20170 18545 19693 18545 20170 18546 20179 18546 19693 18546 19693 18547 20179 18547 20177 18547 19693 18548 20177 18548 19957 18548 19957 18549 20177 18549 20180 18549 19957 18550 20180 18550 19689 18550 19689 18551 20180 18551 19694 18551 19689 18537 19694 18537 20181 18537 20288 18552 19695 18552 19696 18552 19696 18553 19695 18553 19698 18553 19696 18554 19698 18554 19697 18554 19697 18555 19698 18555 19690 18555 19698 18556 19695 18556 20168 18556 20168 18557 19695 18557 19699 18557 20168 18558 19699 18558 19700 18558 19699 18559 19748 18559 19700 18559 19700 18560 19748 18560 19746 18560 19700 18561 19746 18561 19701 18561 19746 18562 19745 18562 19701 18562 19701 18563 19745 18563 19702 18563 19701 18564 19702 18564 20160 18564 20160 18565 19702 18565 19703 18565 20160 18566 19703 18566 20144 18566 20144 18567 19703 18567 19704 18567 20144 18568 19704 18568 19705 18568 19705 18569 19704 18569 19706 18569 20281 960 19706 960 19707 960 19707 960 19706 960 19741 960 19707 18570 19741 18570 20278 18570 20278 960 19741 960 19708 960 20278 960 19708 960 19775 960 19775 18571 19708 18571 19762 18571 19732 18572 20364 18572 19709 18572 19709 18573 20364 18573 19713 18573 19710 960 19735 960 19711 960 19711 18574 19735 18574 19712 18574 19711 960 19712 960 19713 960 19713 18575 19712 18575 19734 18575 19713 18576 19734 18576 19709 18576 20412 18577 20413 18577 19655 18577 19655 18578 19656 18578 20412 18578 20412 18579 19656 18579 19714 18579 20412 18580 19714 18580 19715 18580 19714 18581 19657 18581 19715 18581 19715 18582 19657 18582 19659 18582 19715 18583 19659 18583 19716 18583 19659 18584 19661 18584 19716 18584 19716 18585 19661 18585 19662 18585 19716 18586 19662 18586 20409 18586 19662 18587 19717 18587 20409 18587 20409 18588 19717 18588 19645 18588 20409 18589 19645 18589 19718 18589 19718 18590 19645 18590 19644 18590 19718 18591 19644 18591 20406 18591 20406 18592 19644 18592 19640 18592 20406 18593 19640 18593 19719 18593 19640 18594 19720 18594 19719 18594 19719 18595 19720 18595 19721 18595 19719 18596 19721 18596 19722 18596 19722 18597 19721 18597 19642 18597 19642 18598 19638 18598 19722 18598 19722 18599 19638 18599 19637 18599 19722 18600 19637 18600 19723 18600 19637 18601 19635 18601 19723 18601 19723 18602 19635 18602 19724 18602 19723 18603 19724 18603 19726 18603 19724 18604 19725 18604 19726 18604 19726 18605 19725 18605 19621 18605 19726 18605 19621 18605 20402 18605 20402 18606 19621 18606 19620 18606 20402 18607 19620 18607 20400 18607 19620 18608 19727 18608 20400 18608 20400 18609 19727 18609 19728 18609 20400 18610 19728 18610 20399 18610 19728 18611 19729 18611 20399 18611 20399 18612 19729 18612 19730 18612 20399 18613 19730 18613 20398 18613 19730 18614 19731 18614 20398 18614 20398 18615 19731 18615 20258 18615 20398 18616 20258 18616 20396 18616 20258 18617 20260 18617 20396 18617 20396 18618 20260 18618 19732 18618 20396 18619 19732 18619 19733 18619 19732 18620 19709 18620 19733 18620 19733 18621 19709 18621 19734 18621 19733 18621 19734 18621 20395 18621 20395 18622 19734 18622 19712 18622 20395 18623 19712 18623 20429 18623 20429 18624 19712 18624 19735 18624 20429 18625 19735 18625 20427 18625 19735 18626 19771 18626 20427 18626 20427 18627 19771 18627 19736 18627 20427 18628 19736 18628 20426 18628 19736 18629 19774 18629 20426 18629 20426 18630 19774 18630 19769 18630 20426 18631 19769 18631 19737 18631 19769 18632 19766 18632 19737 18632 19737 18633 19766 18633 19738 18633 19737 18634 19738 18634 19739 18634 19738 18635 19764 18635 19739 18635 19739 18636 19764 18636 19762 18636 19739 18637 19762 18637 19740 18637 19762 18638 19708 18638 19740 18638 19740 18639 19708 18639 19741 18639 19740 18640 19741 18640 19742 18640 19742 18641 19741 18641 19706 18641 19742 18642 19706 18642 19743 18642 19743 18643 19706 18643 19704 18643 19743 18644 19704 18644 19744 18644 19744 18645 19704 18645 19703 18645 19703 18646 19702 18646 19744 18646 19744 18647 19702 18647 19745 18647 19744 18648 19745 18648 19747 18648 19745 18649 19746 18649 19747 18649 19747 18650 19746 18650 19748 18650 19747 18651 19748 18651 19749 18651 19748 18652 19699 18652 19749 18652 19749 18653 19699 18653 19695 18653 19749 18654 19695 18654 19750 18654 19695 18655 19686 18655 19750 18655 19750 18656 19686 18656 19685 18656 19750 18657 19685 18657 20420 18657 20420 18658 19685 18658 19751 18658 20420 18659 19751 18659 20419 18659 19751 18660 19683 18660 20419 18660 20419 18661 19683 18661 19752 18661 20419 18662 19752 18662 19754 18662 19752 18663 19753 18663 19754 18663 19754 18664 19753 18664 19682 18664 19754 18665 19682 18665 19755 18665 19682 18666 19680 18666 19755 18666 19755 18667 19680 18667 19756 18667 19755 18668 19756 18668 20417 18668 19756 18669 19678 18669 20417 18669 20417 18670 19678 18670 19757 18670 20417 18671 19757 18671 19758 18671 19757 18672 19652 18672 19758 18672 19758 18673 19652 18673 19759 18673 19758 18673 19759 18673 19760 18673 19760 18674 19759 18674 19648 18674 19760 18675 19648 18675 19761 18675 19761 18676 19648 18676 19647 18676 19761 18677 19647 18677 20413 18677 20413 18678 19647 18678 19654 18678 20413 18679 19654 18679 19655 18679 19777 18680 19762 18680 19763 18680 19763 18681 19762 18681 19764 18681 19763 18682 19764 18682 19765 18682 19764 18683 19738 18683 19765 18683 19765 18684 19738 18684 19766 18684 19765 18685 19766 18685 19767 18685 19767 18686 19766 18686 19769 18686 19767 18687 19769 18687 19768 18687 19768 18688 19769 18688 19770 18688 19770 18689 19769 18689 19774 18689 19770 18690 19774 18690 19773 18690 19735 18691 19772 18691 19771 18691 19771 18692 19772 18692 19773 18692 19771 18693 19773 18693 19736 18693 19736 18694 19773 18694 19774 18694 19775 18695 19762 18695 19776 18695 19776 18696 19762 18696 19777 18696 19776 18697 19777 18697 19988 18697 19988 18698 19777 18698 20141 18698 20137 18699 19778 18699 19921 18699 19904 18700 19779 18700 19780 18700 19780 18701 19779 18701 19781 18701 19904 18702 19780 18702 19998 18702 19998 18703 19780 18703 19782 18703 19998 18704 19782 18704 19997 18704 19782 18704 19783 18704 19997 18704 19997 18705 19783 18705 20135 18705 19997 18706 20135 18706 19992 18706 19992 18707 20135 18707 20249 18707 19992 18708 20249 18708 19784 18708 19784 18709 20249 18709 19785 18709 19784 18710 19785 18710 19995 18710 19995 18711 19785 18711 19994 18711 19994 18712 19785 18712 20134 18712 19994 18713 20134 18713 19921 18713 19921 18714 20134 18714 19786 18714 19921 18715 19786 18715 20137 18715 19792 18716 19787 18716 20030 18716 20030 18717 19787 18717 20189 18717 20030 18718 20189 18718 20031 18718 20031 18719 20189 18719 20187 18719 20031 18720 20187 18720 20032 18720 20032 18721 20187 18721 20186 18721 20032 18722 20186 18722 19788 18722 19788 18723 20186 18723 20185 18723 19788 18724 20185 18724 20027 18724 20027 18725 20185 18725 20184 18725 20027 18726 20184 18726 19789 18726 19789 18727 20184 18727 20183 18727 19789 18727 20183 18727 20029 18727 20029 18728 20183 18728 20195 18728 20029 18729 20195 18729 20033 18729 20033 18730 20195 18730 20194 18730 20033 18731 20194 18731 19790 18731 19790 18732 20194 18732 20193 18732 19790 18733 20193 18733 20034 18733 20034 18734 20193 18734 20192 18734 20034 18735 20192 18735 19791 18735 19791 18736 20192 18736 20191 18736 19791 18737 20191 18737 19792 18737 19792 18738 20191 18738 19787 18738 19803 18739 20166 18739 20021 18739 20021 18740 20166 18740 20002 18740 20166 18741 20165 18741 20002 18741 20002 18742 20165 18742 20225 18742 20002 18743 20225 18743 19793 18743 19793 18732 20225 18732 19794 18732 19793 18733 19794 18733 19795 18733 19795 18744 19794 18744 19796 18744 19795 18745 19796 18745 20003 18745 20003 18746 19796 18746 20227 18746 20003 18747 20227 18747 19797 18747 19797 18748 20227 18748 19798 18748 19798 18749 20227 18749 20224 18749 19798 18750 20224 18750 19962 18750 20224 18751 20223 18751 19962 18751 19962 18752 20223 18752 20169 18752 19962 18752 20169 18752 19799 18752 19799 18753 20169 18753 20171 18753 19799 18754 20171 18754 19800 18754 19800 18755 20171 18755 20174 18755 19800 18756 20174 18756 19801 18756 19801 18757 20174 18757 20164 18757 19801 18758 20164 18758 19966 18758 19966 18759 20164 18759 19802 18759 19966 18760 19802 18760 19960 18760 19960 18761 19802 18761 19803 18761 19960 18761 19803 18761 19804 18761 19804 18762 19803 18762 20021 18762 19991 18763 20251 18763 19805 18763 19805 18764 20251 18764 20248 18764 19805 18765 20248 18765 19806 18765 19806 18766 20248 18766 20253 18766 19806 18767 20253 18767 19996 18767 19996 18768 20253 18768 20252 18768 19996 18769 20252 18769 19999 18769 19999 18770 20252 18770 19807 18770 19999 18771 19807 18771 20000 18771 20000 18772 19807 18772 19808 18772 20000 18773 19808 18773 20025 18773 20025 18774 19808 18774 20246 18774 20025 18774 20246 18774 19809 18774 19809 18775 20246 18775 19810 18775 19809 18776 19810 18776 19811 18776 19811 18777 19810 18777 19812 18777 19811 18778 19812 18778 19814 18778 19814 18779 19812 18779 19813 18779 19814 18779 19813 18779 19815 18779 19815 18780 19813 18780 19816 18780 19815 18781 19816 18781 19993 18781 19993 18782 19816 18782 20254 18782 19993 18783 20254 18783 19991 18783 19991 18784 20254 18784 20251 18784 20220 18785 20219 18785 19939 18785 19939 18786 20219 18786 19943 18786 19943 18787 20219 18787 20216 18787 19943 18788 20216 18788 19940 18788 19940 18789 20216 18789 20214 18789 19940 18790 20214 18790 19817 18790 19817 18791 20214 18791 20213 18791 19817 18791 20213 18791 20038 18791 20038 18792 20213 18792 20014 18792 20014 18793 20213 18793 20052 18793 20014 18794 20052 18794 19819 18794 20052 18795 19818 18795 19819 18795 19819 18796 19818 18796 19820 18796 19819 18797 19820 18797 20015 18797 20015 18798 19820 18798 19823 18798 20015 18799 19823 18799 19821 18799 19821 18800 19823 18800 19822 18800 19822 18801 19823 18801 20236 18801 19822 18802 20236 18802 19824 18802 19824 18803 20236 18803 19827 18803 19824 18804 19827 18804 19825 18804 19825 18805 19827 18805 19826 18805 19826 18806 19827 18806 19828 18806 19826 18807 19828 18807 19829 18807 19828 18808 20235 18808 19829 18808 19829 18809 20235 18809 20234 18809 19829 18809 20234 18809 19937 18809 19937 18810 20234 18810 20220 18810 19937 18811 20220 18811 19938 18811 19938 18812 20220 18812 19939 18812 19830 590 20042 590 19949 590 20023 590 19973 590 20022 590 19831 18813 20344 18813 19982 18813 19832 18814 19866 18814 19833 18814 19670 590 19672 590 20035 590 20385 590 19880 590 20389 590 19834 590 19835 590 19951 590 19577 18815 19575 18815 19935 18815 20028 18816 19836 18816 19837 18816 19836 18817 20028 18817 19838 18817 19838 18818 20028 18818 19839 18818 19838 590 19839 590 20018 590 19907 590 19841 590 20037 590 20019 18819 19842 18819 19840 18819 19840 590 19842 590 19844 590 20037 590 19841 590 19842 590 19842 590 19841 590 19843 590 19842 590 19843 590 19844 590 19931 18820 20009 18820 20024 18820 19845 590 19846 590 19909 590 19909 590 19846 590 19847 590 19909 590 19847 590 19848 590 20001 18821 19856 18821 19853 18821 19849 590 19850 590 19851 590 19851 590 19850 590 20001 590 19851 18822 20001 18822 19852 18822 19852 590 20001 590 19853 590 19849 18823 19854 18823 19850 18823 19850 590 19854 590 19855 590 19850 18824 19855 18824 20010 18824 20001 590 19865 590 19856 590 19856 18825 19865 18825 20028 18825 19856 590 20028 590 19857 590 19857 18826 20028 18826 19837 18826 19515 590 19858 590 20026 590 19859 590 19510 590 19865 590 19865 18827 19510 18827 19860 18827 19865 590 19860 590 20028 590 20028 18828 19860 18828 19512 18828 20028 590 19512 590 19514 590 19504 590 19505 590 19866 590 19866 590 19505 590 19861 590 19866 590 19861 590 19862 590 19861 590 19863 590 19862 590 19862 590 19863 590 19864 590 19862 590 19864 590 19865 590 19865 18829 19864 18829 19508 18829 19865 18830 19508 18830 19859 18830 19504 18831 19866 18831 19867 18831 19867 18832 19866 18832 19832 18832 19867 18833 19832 18833 20339 18833 20293 18834 19869 18834 20327 18834 20327 590 19869 590 19516 590 20327 590 19516 590 20328 590 20328 18835 19516 18835 19868 18835 20328 18836 19868 18836 20339 18836 20339 18837 19868 18837 19501 18837 20339 18838 19501 18838 19867 18838 19664 18839 19666 18839 20026 18839 20293 590 19677 590 19869 590 19869 18840 19677 18840 19664 18840 19869 590 19664 590 19870 590 19870 590 19664 590 20026 590 19870 18841 20026 18841 19871 18841 19871 590 20026 590 19858 590 20035 590 19872 590 19519 590 19519 18842 19521 18842 20035 18842 20035 590 19521 590 19873 590 20035 18843 19873 18843 19839 18843 19839 18844 19873 18844 19875 18844 19526 18845 20017 18845 19874 18845 19874 18846 20017 18846 19839 18846 19874 18847 19839 18847 19524 18847 19524 590 19839 590 19875 590 20035 590 19672 590 19872 590 19872 18848 19672 18848 19674 18848 19872 18849 19674 18849 19533 18849 20389 590 19880 590 19878 590 19674 18850 19663 18850 19533 18850 19533 18851 19663 18851 19876 18851 19533 590 19876 590 19535 590 19535 18852 19876 18852 20391 18852 19535 18853 20391 18853 19537 18853 19537 18854 20391 18854 19877 18854 19537 18855 19877 18855 19538 18855 19538 590 19877 590 19878 590 19538 590 19878 590 19539 590 19539 18856 19878 18856 19880 18856 19539 590 19880 590 19540 590 19540 590 19880 590 19541 590 19541 590 19880 590 19879 590 19879 18857 19880 18857 19951 18857 19879 590 19951 590 19881 590 19526 590 19882 590 20017 590 20017 18858 19882 18858 19883 18858 20017 590 19883 590 19951 590 19951 18859 19883 18859 19529 18859 19951 18860 19529 18860 19881 18860 19884 18861 19886 18861 19949 18861 19884 590 19949 590 19885 590 19886 18862 19543 18862 19949 18862 19949 18863 19543 18863 19545 18863 19949 590 19545 590 19941 590 19941 590 19545 590 19546 590 19546 590 19887 590 19941 590 19941 590 19887 590 19550 590 19941 590 19550 590 19888 590 19888 18864 19550 18864 19889 18864 19888 18865 19889 18865 19549 18865 19890 18866 19891 18866 19892 18866 19892 590 19891 590 19898 590 19945 590 19894 590 19893 590 19893 590 19894 590 19895 590 19893 18867 19895 18867 20380 18867 20380 590 19895 590 19896 590 20380 18868 19896 18868 19897 18868 19897 590 19896 590 19554 590 19897 18869 19554 18869 19898 18869 19898 18870 19554 18870 19899 18870 19898 590 19899 590 19892 590 19903 590 19904 590 19900 590 19900 590 19904 590 19998 590 19900 590 19998 590 19562 590 19562 18871 19998 18871 19911 18871 19562 590 19911 590 19901 590 20370 590 20366 590 19902 590 19903 18872 19902 18872 19904 18872 19904 18873 19902 18873 20366 18873 19904 18874 20366 18874 19779 18874 19779 590 20366 590 19905 590 20016 18875 19913 18875 19908 18875 19908 590 19909 590 20016 590 20016 590 19909 590 19848 590 20016 590 19848 590 20037 590 20037 18876 19848 18876 19906 18876 20037 590 19906 590 19907 590 19908 590 19573 590 19909 590 19909 18877 19573 18877 19910 18877 19909 18878 19910 18878 19911 18878 19911 18879 19910 18879 19912 18879 19911 590 19912 590 19901 590 20016 18880 19822 18880 19913 18880 19913 18881 19822 18881 19824 18881 19913 590 19824 590 19914 590 19914 590 19824 590 19825 590 19914 590 19825 590 19936 590 19936 18882 19825 18882 19826 18882 19577 590 19935 590 19578 590 19578 18883 19935 18883 19915 18883 19578 18884 19915 18884 19570 18884 19902 590 19564 590 20370 590 20370 18885 19564 18885 19566 18885 20370 590 19566 590 19916 590 19916 18886 19566 18886 19917 18886 19916 590 19917 590 19915 590 19915 18887 19917 18887 19918 18887 19915 18888 19918 18888 19570 18888 19778 18889 20276 18889 19920 18889 19928 590 19994 590 19599 590 19778 590 19920 590 19921 590 19919 590 19927 590 19920 590 19920 18890 19927 18890 19594 18890 19920 18891 19594 18891 19921 18891 19921 18892 19594 18892 19596 18892 19921 590 19596 590 19994 590 19994 590 19596 590 19922 590 19994 18893 19922 18893 19599 18893 20004 18894 19585 18894 19923 18894 19923 18895 19585 18895 19587 18895 19923 590 19587 590 19926 590 19587 18896 19924 18896 19926 18896 19926 590 19924 590 19925 590 19926 590 19925 590 20358 590 20358 590 19925 590 19591 590 20358 18897 19591 18897 19919 18897 19919 18898 19591 18898 19592 18898 19919 18899 19592 18899 19927 18899 19599 18900 19929 18900 19928 18900 19928 590 19929 590 19930 590 19928 590 19930 590 19931 590 19930 590 19602 590 19931 590 19931 18901 19602 18901 19601 18901 19931 590 19601 590 20011 590 20011 18902 19601 18902 19600 18902 20011 18903 19600 18903 20007 18903 20263 18904 19932 18904 20369 18904 20369 590 20373 590 20263 590 20263 18905 20373 18905 19915 18905 20263 590 19915 590 19632 590 19632 18906 19915 18906 19933 18906 19933 590 19915 590 19935 590 19933 18907 19935 18907 19934 18907 19629 590 19934 590 19937 590 19937 590 19934 590 19829 590 19829 18908 19934 18908 19935 18908 19829 590 19935 590 19826 590 19826 18909 19935 18909 19575 18909 19826 18910 19575 18911 19936 18912 19629 18913 19937 18913 19624 18913 19624 590 19937 590 19938 590 19624 18914 19938 18914 19625 18914 19625 590 19938 590 19939 590 19625 590 19939 590 19944 590 19943 18915 19940 18915 19888 18915 19888 18916 19940 18916 19817 18916 19888 590 19817 590 19941 590 19941 590 19817 590 20038 590 19623 590 19942 590 19888 590 19939 590 19943 590 19944 590 19944 590 19943 590 19888 590 19944 590 19888 590 19627 590 19627 590 19888 590 19942 590 19549 590 19945 590 19888 590 19888 18917 19945 18917 19893 18917 19888 590 19893 590 19623 590 19623 18918 19893 18918 19946 18918 19623 590 19946 590 19947 590 19953 18919 19617 18919 19891 18919 19891 18920 19617 18920 19619 18920 19891 590 19619 590 19898 590 19898 18921 19619 18921 19948 18921 19898 18922 19948 18922 19643 18922 20042 18923 20044 18923 19949 18923 19949 18924 20044 18924 19891 18924 19949 590 19891 590 19885 590 19885 590 19891 590 19890 590 19954 590 20048 590 19835 590 19835 18925 20048 18925 19950 18925 19835 590 19950 590 19951 590 20044 590 20046 590 19891 590 19891 18926 20046 18926 19952 18926 19891 18927 19952 18927 19953 18927 19953 590 19952 590 19954 590 19953 18928 19954 18928 19955 18928 19955 590 19954 590 19835 590 20271 590 19613 590 20387 590 20387 590 19613 590 20385 590 20385 590 19613 590 19880 590 19880 18929 19613 18929 19614 18929 19880 590 19614 590 19951 590 19951 18930 19614 18930 19615 18930 19951 18931 19615 18931 19834 18931 19666 18932 19667 18932 20026 18932 20026 18933 19667 18933 19668 18933 20026 590 19668 590 20035 590 20035 590 19668 590 19956 590 20035 18934 19956 18934 19670 18934 19862 590 19957 590 19866 590 19866 18935 19957 18935 19689 18935 19866 590 19689 590 19833 590 19833 590 19689 590 19688 590 19833 18936 19688 18937 20292 18938 20292 18939 19688 18939 19958 18939 19962 18940 19959 18940 19862 18940 19862 18941 19959 18941 19693 18941 19862 18942 19693 18942 19957 18942 19960 590 19804 590 19969 590 19801 590 19966 590 19961 590 19961 18943 19966 18943 19965 18943 19961 590 19965 590 19697 590 19697 18944 19965 18944 19696 18944 19962 18945 19799 18945 19959 18945 19959 18946 19799 18946 19800 18946 19959 18947 19800 18947 19692 18947 19692 18948 19800 18948 19801 18948 19692 18949 19801 18949 19691 18949 19691 18950 19801 18950 19961 18950 19494 590 19963 590 19969 590 19494 18951 19969 18951 19496 18951 19963 18952 19964 18952 19969 18952 19969 18953 19964 18953 19965 18953 19969 18954 19965 18954 19960 18954 19960 590 19965 590 19966 590 19964 18955 19967 18955 19965 18955 19965 18956 19967 18956 19490 18956 19965 18957 19490 18957 20342 18957 20342 18958 19490 18958 19489 18958 20342 18959 19489 18959 20343 18959 20343 18960 19489 18960 19968 18960 20343 590 19968 590 20346 590 19496 590 19969 590 19497 590 19497 590 19969 590 20022 590 19497 590 20022 590 19971 590 19500 590 19499 590 20022 590 20022 18961 19499 18961 19970 18961 20022 18962 19970 18962 19971 18962 19968 18963 19488 18963 20346 18963 20346 590 19488 590 19972 590 20346 590 19972 590 19485 590 19973 590 19974 590 20022 590 20022 590 19974 590 20346 590 20022 18964 20346 18964 19500 18964 19500 590 20346 590 19485 590 19981 18965 19982 18965 19975 18965 19975 18966 19982 18966 20346 18966 19975 590 20346 590 19976 590 19976 18967 20346 18967 19974 18967 19977 590 19978 590 19604 590 19604 18968 19978 18968 19606 18968 19923 18969 19979 18969 19606 18969 19604 590 19607 590 19977 590 19977 590 19607 590 19980 590 19977 590 19980 590 19981 590 19981 590 19980 590 19609 590 19981 590 19609 590 19982 590 19982 18970 19609 18970 19983 18970 19982 18971 19983 18971 19831 18971 19984 590 19923 590 19985 590 19985 18972 19923 18972 19606 18972 19985 590 19606 590 19986 590 19986 590 19606 590 19978 590 19987 590 19776 590 19988 590 19979 1897 19923 1897 19989 1897 19989 590 19923 590 19926 590 19989 590 19926 590 19988 590 19988 18973 19926 18973 19990 18973 19988 590 19990 590 19987 590 19928 18974 19809 18974 19811 18974 19991 590 19805 590 19992 590 19992 590 19805 590 19997 590 19811 590 19814 590 19928 590 19928 18975 19814 18975 19815 18975 19928 590 19815 590 19994 590 19994 18976 19815 18976 19993 18976 19994 18977 19993 18977 19995 18977 19995 18978 19993 18978 19991 18978 19995 590 19991 590 19784 590 19784 590 19991 590 19992 590 19805 590 19806 590 19997 590 19997 18979 19806 18979 19996 18979 19997 590 19996 590 19998 590 19998 18980 19996 18980 19999 18980 19998 18981 19999 18981 19911 18981 19911 18982 19999 18982 20000 18982 19911 590 20000 590 20025 590 20021 18983 20002 18983 20001 18983 20001 18984 20002 18984 19793 18984 20001 18985 19793 18985 19865 18985 19865 18986 19793 18986 19795 18986 19795 590 20003 590 19865 590 19865 590 20003 590 19797 590 19865 590 19797 590 19862 590 19862 18987 19797 18987 19798 18987 19862 18988 19798 18988 19962 18988 20004 590 19923 590 19582 590 19582 590 19923 590 19984 590 19582 18989 19984 18989 19579 18989 19579 18990 19984 18990 20005 18990 19579 18991 20005 18991 20007 18991 20007 18992 20005 18992 20006 18992 20007 18993 20006 18993 20011 18993 20011 590 20006 590 20008 590 20011 18994 20008 18994 20012 18994 20009 590 19931 590 20010 590 20010 590 19931 590 20011 590 20010 590 20011 590 19850 590 19850 18995 20011 18995 20012 18995 19850 18996 20012 18996 20013 18996 20014 590 19819 590 20037 590 20037 18997 19819 18997 20015 18997 20037 18998 20015 18998 20016 18998 20016 18999 20015 18999 19821 18999 20016 19000 19821 19000 19822 19000 20041 590 20020 590 20017 590 20018 590 19839 590 20019 590 20019 590 19839 590 20017 590 20019 590 20017 590 19842 590 19842 19001 20017 19001 20020 19001 19842 19002 20020 19002 20036 19002 19950 19003 20050 19003 19951 19003 19951 19004 20050 19004 20051 19004 19951 590 20051 590 20017 590 20017 19005 20051 19005 20039 19005 20017 19006 20039 19006 20041 19006 19804 590 20021 590 19969 590 19969 19007 20021 19007 20001 19007 19969 590 20001 590 20022 590 20022 590 20001 590 19850 590 20022 590 19850 590 20023 590 20023 590 19850 590 20013 590 20024 19008 19845 19008 19931 19008 19931 19009 19845 19009 19909 19009 19931 19010 19909 19010 19928 19010 19928 590 19909 590 19911 590 19928 590 19911 590 19809 590 19809 590 19911 590 20025 590 20032 19011 19788 19011 20026 19011 20026 590 19788 590 20028 590 20026 19012 20028 19012 19515 19012 19515 19013 20028 19013 19514 19013 19788 590 20027 590 20028 590 20028 19014 20027 19014 19789 19014 20028 590 19789 590 19839 590 19839 19015 19789 19015 20029 19015 19839 19016 20029 19016 20033 19016 20035 590 19792 590 20030 590 20035 590 20030 590 20026 590 20026 19017 20030 19017 20031 19017 20026 19018 20031 19018 20032 19018 20033 19019 19790 19019 19839 19019 19839 19020 19790 19020 20034 19020 19839 19021 20034 19021 20035 19021 20035 19022 20034 19022 19791 19022 20035 19023 19791 19023 19792 19023 20036 19024 19830 19024 19842 19024 19842 590 19830 590 19949 590 19842 590 19949 590 20037 590 20037 590 19949 590 19941 590 20037 590 19941 590 20014 590 20014 590 19941 590 20038 590 20203 18793 20243 18793 20051 18793 20051 19025 20243 19025 20039 19025 20243 19026 20242 19026 20039 19026 20039 18796 20242 18796 20040 18796 20039 18797 20040 18797 20041 18797 20041 18755 20040 18755 20241 18755 20041 19027 20241 19027 20020 19027 20020 19028 20241 19028 20238 19028 20020 19028 20238 19028 20036 19028 20036 19029 20238 19029 20237 19029 20036 19029 20237 19029 19830 19029 19830 19030 20237 19030 20042 19030 20042 19031 20237 19031 20256 19031 20042 18807 20256 18807 20044 18807 20256 18808 20043 18808 20044 18808 20044 19032 20043 19032 20045 19032 20044 19033 20045 19033 20046 19033 20046 19034 20045 19034 20202 19034 20046 18811 20202 18811 19952 18811 19952 19035 20202 19035 20047 19035 19952 19036 20047 19036 19954 19036 19954 19037 20047 19037 20206 19037 19954 19038 20206 19038 20048 19038 20048 19039 20206 19039 20049 19039 20048 18790 20049 18790 19950 18790 19950 18791 20049 18791 20203 18791 19950 18791 20203 18791 20050 18791 20050 18792 20203 18792 20051 18792 19818 19040 20052 19040 20053 19040 19660 19041 20054 19041 20055 19041 20262 960 20264 960 20129 960 19583 960 19581 960 20064 960 19597 19042 20128 19042 20250 19042 19476 960 19477 960 20056 960 19443 960 20057 960 20226 960 19452 960 19454 960 20085 960 19452 960 20085 960 19484 960 19454 960 19457 960 20094 960 20094 19043 19457 19043 20095 19043 19483 960 20086 960 20059 960 20059 19044 20086 19044 20081 19044 20226 960 20057 960 20081 960 20081 19045 20057 19045 20058 19045 20081 960 20058 960 20059 960 20060 19046 20061 19046 20245 19046 20245 19047 20061 19047 20062 19047 20245 19048 20062 19048 20226 19048 20226 19049 20062 19049 20063 19049 20226 960 20063 960 19443 960 20060 960 20245 960 19448 960 19448 960 20245 960 20064 960 19448 960 20064 960 19449 960 20056 19050 19477 19050 20064 19050 20064 1221 19477 1221 19480 1221 20064 960 19480 960 19449 960 20113 960 20065 960 20114 960 20114 960 20065 960 19475 960 20114 19051 19475 19051 19476 19051 20255 960 19429 960 20066 960 20066 19052 19429 19052 19428 19052 20066 19053 19428 19053 19473 19053 19438 960 20067 960 20240 960 20240 19054 20067 19054 19435 19054 19435 960 20068 960 20240 960 20240 19055 20068 19055 20069 19055 20240 960 20069 960 20255 960 20255 960 20069 960 19431 960 20255 960 19431 960 19429 960 19457 19056 20070 19056 20095 19056 20095 960 20070 960 20071 960 20095 960 20071 960 20097 960 20097 960 20071 960 20239 960 20076 19057 19676 19057 20077 19057 20075 960 19518 960 20074 960 20074 19058 19518 19058 20072 19058 20074 960 20072 960 20085 960 20085 19059 20072 19059 20073 19059 20085 960 20073 960 19513 960 20074 19060 19665 19060 20075 19060 20075 960 19665 960 20076 960 20075 960 20076 960 19517 960 19517 19061 20076 19061 20077 19061 19517 960 20077 960 20078 960 20078 19062 20077 19062 19679 19062 20078 960 19679 960 19502 960 19502 19063 19679 19063 19681 19063 19502 960 19681 960 19503 960 19503 19064 19681 19064 20079 19064 19503 19065 20079 19065 19506 19065 19506 960 20079 960 20080 960 20080 960 20079 960 20176 960 20080 19066 20176 19066 20084 19066 20081 960 20082 960 20178 960 20178 19067 20082 19067 20083 19067 20178 19068 20083 19068 20176 19068 20176 19069 20083 19069 19507 19069 20176 960 19507 960 20084 960 19513 960 20087 960 20085 960 20085 19070 20087 19070 20086 19070 20085 19071 20086 19071 19484 19071 19484 960 20086 960 19483 960 20087 19072 20088 19072 20086 19072 20086 19073 20088 19073 19511 19073 20086 960 19511 960 20081 960 20081 19074 19511 19074 19509 19074 20081 19075 19509 19075 20082 19075 19523 19076 20089 19076 20094 19076 20094 960 20089 960 19522 960 20094 960 19522 960 19673 960 20090 960 19653 960 19675 960 20100 19077 20090 19077 19536 19077 19536 19078 20090 19078 19675 19078 19536 960 19675 960 19534 960 19534 19079 19675 19079 20092 19079 19534 960 20092 960 20091 960 20091 19080 20092 19080 19673 19080 20091 960 19673 960 19520 960 19520 960 19673 960 19522 960 19523 960 20094 960 20093 960 20093 960 20094 960 20095 960 20093 960 20095 960 19525 960 19525 19081 20095 19081 20097 19081 19525 960 20097 960 19527 960 20199 960 19528 960 20096 960 20096 19082 19528 19082 20098 19082 20096 19083 20098 19083 20097 19083 20097 19084 20098 19084 20099 19084 20097 19085 20099 19085 19527 19085 20196 19086 19531 19086 20199 19086 20199 19087 19531 19087 19530 19087 20199 19088 19530 19088 19528 19088 19536 960 20101 960 20100 960 20100 960 20101 960 20102 960 20100 960 20102 960 20103 960 20103 19089 20102 19089 20104 19089 20103 960 20104 960 20196 960 20196 19090 20104 19090 19532 19090 20196 19091 19532 19091 19531 19091 20108 19092 19542 19092 20109 19092 20108 960 20109 960 20208 960 20053 19093 20105 19093 19547 19093 19547 960 20106 960 20053 960 20053 19094 20106 19094 20107 19094 20053 19095 20107 19095 20108 19095 20108 19096 20107 19096 19544 19096 20108 19097 19544 19097 19542 19097 20109 960 19558 960 20208 960 20208 960 19558 960 19557 960 20208 19098 19557 19098 20209 19098 19557 960 19556 960 20209 960 20209 960 19556 960 19555 960 20209 19099 19555 19099 19641 19099 19641 19100 19555 19100 20110 19100 19641 960 20110 960 20111 960 20111 960 20110 960 19553 960 20111 19101 19553 19101 19636 19101 19636 960 19553 960 20112 960 19636 960 20112 960 19634 960 19634 19102 20112 19102 19552 19102 19634 960 19552 960 20215 960 20215 19103 19552 19103 19551 19103 20215 960 19551 960 19548 960 20114 19104 19572 19104 20115 19104 19473 960 20113 960 20066 960 20066 960 20113 960 20114 960 20066 960 20114 960 20118 960 20118 960 20114 960 20115 960 19563 960 20116 960 20247 960 20247 19105 20116 19105 19561 19105 20247 960 19561 960 20114 960 20114 19106 19561 19106 19560 19106 20114 960 19560 960 19572 960 20117 19107 19780 19107 19559 19107 19559 19108 19780 19108 19781 19108 19563 960 20247 960 20117 960 20117 960 20247 960 19782 960 20117 19109 19782 19109 19780 19109 20118 960 20119 960 20066 960 20066 960 20119 960 19574 960 20066 960 19574 960 20222 960 20222 19110 19574 19110 20120 19110 20222 19111 20120 19111 19576 19111 19781 19112 20121 19112 19559 19112 19559 19113 20121 19113 20259 19113 19559 960 20259 960 19565 960 19565 19114 20259 19114 20257 19114 19565 960 20257 960 19567 960 19567 19115 20257 19115 20122 19115 19567 960 20122 960 19568 960 19568 19116 20122 19116 20123 19116 19568 960 20123 960 19569 960 19569 960 20123 960 20132 960 19569 960 20132 960 20124 960 20124 960 20132 960 19571 960 20126 960 20056 960 20125 960 20125 960 20056 960 20064 960 20125 19117 20064 19117 19580 19117 19580 960 20064 960 19581 960 20126 960 19603 960 20056 960 20056 19118 19603 19118 20127 19118 20056 960 20127 960 20250 960 20250 19119 20127 19119 19598 19119 20250 960 19598 960 19597 960 19584 960 19583 960 20228 960 19584 960 20228 960 19586 960 19589 19120 19588 19120 20139 19120 20139 960 19588 960 20140 960 20128 960 19595 960 20134 960 19593 960 20137 960 19595 960 19595 960 20137 960 19786 960 19595 19121 19786 19121 20134 19121 20129 960 20264 960 20131 960 20130 960 19631 960 20132 960 20132 960 19631 960 20222 960 20132 960 20222 960 19571 960 19571 19122 20222 19122 19576 19122 20264 19123 20130 19123 20131 19123 20131 19124 20130 19124 20132 19124 20131 960 20132 960 20133 960 20133 960 20132 960 20123 960 20128 960 20134 960 20250 960 20250 19125 20134 19125 19785 19125 20250 19126 19785 19126 20249 19126 20249 19127 20135 19127 20247 19127 20247 960 20135 960 19783 960 20247 19128 19783 19128 19782 19128 19763 960 19765 960 20139 960 20139 960 19765 960 19767 960 20139 19129 19767 19129 19589 19129 19589 19130 19767 19130 19768 19130 19589 960 19768 960 19590 960 19590 19131 19768 19131 19770 19131 19590 960 19770 960 20136 960 20136 19132 19770 19132 19773 19132 20136 960 19773 960 19593 960 19593 19133 19773 19133 19772 19133 19593 19134 19772 19134 20137 19134 20151 960 20138 960 20228 960 20228 19135 20138 19135 20139 19135 20228 960 20139 960 19586 960 19586 960 20139 960 20140 960 19777 960 19763 960 20141 960 20141 19136 19763 19136 20139 19136 20141 960 20139 960 19605 960 19605 19137 20139 19137 20138 19137 19610 960 20144 960 19611 960 19611 960 20144 960 19705 960 20142 960 20156 960 20143 960 20143 960 20156 960 20144 960 20143 960 20144 960 20145 960 20145 960 20144 960 19610 960 20145 960 19610 960 20146 960 19610 960 19608 960 20146 960 20146 960 19608 960 20147 960 20146 19138 20147 19138 20148 19138 20148 19139 20147 19139 20149 19139 20148 19140 20149 19140 20150 19140 20150 960 20149 960 20151 960 20150 19141 20151 19141 20152 19141 20152 19142 20151 19142 20228 19142 20152 960 20228 960 20153 960 19495 960 20154 960 20167 960 20167 19143 20154 19143 20155 19143 20167 19144 20155 19144 20156 19144 20156 960 20155 960 19498 960 20156 19145 19498 19145 20157 19145 20157 19146 20158 19146 20156 19146 20156 19147 20158 19147 20159 19147 20156 960 20159 960 20144 960 20144 960 20159 960 19486 960 20144 19148 19486 19148 20160 19148 20160 19149 19486 19149 19487 19149 20160 19150 19487 19150 19701 19150 19701 19151 19487 19151 20161 19151 19701 960 20161 960 19700 960 19700 19152 20161 19152 20162 19152 19700 960 20162 960 20168 960 20168 19153 20162 19153 20163 19153 20163 960 19491 960 20168 960 20168 19154 19491 19154 19492 19154 20168 960 19492 960 20167 960 20167 960 19492 960 19493 960 20167 19155 19493 19155 19495 19155 20168 960 20164 960 20174 960 20165 19156 20166 19156 20167 19156 20167 19157 20166 19157 19803 19157 20167 960 19803 960 20168 960 20168 960 19803 960 19802 960 20168 960 19802 960 20164 960 20178 960 20170 960 20169 960 20172 19158 20174 19158 20170 19158 20170 19159 20174 19159 20171 19159 20170 19160 20171 19160 20169 19160 20172 19161 20173 19161 20174 19161 20174 960 20173 960 20175 960 20174 960 20175 960 20168 960 20168 19162 20175 19162 19690 19162 20168 19163 19690 19163 19698 19163 20176 19164 20180 19164 20177 19164 20176 960 20177 960 20178 960 20178 960 20177 960 20179 960 20178 960 20179 960 20170 960 20180 960 20176 960 19694 960 19694 960 20176 960 20079 960 19694 960 20079 960 20181 960 20181 19165 20079 19165 19684 19165 20181 960 19684 960 20182 960 20195 960 20183 960 20094 960 19454 19166 20094 19166 20085 19166 20085 960 20094 960 20183 960 20085 19167 20183 19167 20184 19167 20184 960 20185 960 20085 960 20085 19168 20185 19168 20186 19168 20085 960 20186 960 20074 960 20074 19169 20186 19169 20187 19169 20074 19170 20187 19170 20188 19170 20188 19171 20187 19171 20189 19171 20188 960 20189 960 20190 960 20190 19172 20189 19172 19787 19172 20190 4600 19787 4600 19669 4600 19669 960 19787 960 20191 960 19669 19173 20191 19173 19671 19173 19671 19174 20191 19174 20192 19174 19671 19175 20192 19175 19673 19175 19673 19176 20192 19176 20193 19176 19673 19177 20193 19177 20094 19177 20094 5905 20193 5905 20194 5905 20094 19178 20194 19178 20195 19178 20199 960 20201 960 20196 960 20196 19179 20201 19179 19612 19179 20196 19180 19612 19180 20197 19180 20054 19181 19660 19181 20197 19181 20197 960 19660 960 19658 960 20197 19182 19658 19182 20196 19182 20203 19183 20204 19183 20096 19183 20096 960 20204 960 20198 960 20096 960 20198 960 20199 960 20199 960 20198 960 20200 960 20199 19184 20200 19184 20201 19184 20043 960 20108 960 20045 960 20045 960 20108 960 20208 960 20045 19185 20208 19185 20202 19185 20202 19186 20208 19186 20047 19186 20203 960 20049 960 20204 960 20204 19187 20049 19187 20206 19187 20204 19188 20206 19188 20205 19188 20205 19189 20206 19189 20047 19189 20205 19190 20047 19190 19616 19190 19616 960 20047 960 20208 960 19616 960 20208 960 20207 960 20207 19191 20208 19191 19618 19191 19618 19192 20208 19192 20210 19192 20210 960 20208 960 20209 960 20210 960 20209 960 19639 960 20217 960 19626 960 20215 960 20215 19193 19626 19193 20211 19193 20215 19194 20211 19194 19634 19194 19634 19195 20211 19195 20212 19195 19634 19196 20212 19196 19633 19196 20052 960 20213 960 20053 960 20053 19197 20213 19197 20215 19197 20053 19198 20215 19198 20105 19198 20105 19199 20215 19199 19548 19199 20213 19200 20214 19200 20215 19200 20215 960 20214 960 20216 960 20215 19201 20216 19201 20217 19201 20217 960 20216 960 20219 960 20217 960 20219 960 20218 960 20218 19202 20219 19202 20220 19202 20218 960 20220 960 20221 960 20221 19203 20220 19203 20234 19203 20221 960 20234 960 19628 960 19628 960 20234 960 20222 960 19628 960 20222 960 19630 960 19630 960 20222 960 19631 960 20169 960 20223 960 20178 960 20178 19204 20223 19204 20224 19204 20178 19205 20224 19205 20081 19205 20081 19206 20224 19206 20227 19206 20225 19207 20226 19207 19794 19207 19794 960 20226 960 20081 960 19794 19208 20081 19208 19796 19208 19796 19209 20081 19209 20227 19209 20244 960 20229 960 20245 960 19583 19210 20064 19210 20228 19210 20228 19211 20064 19211 20233 19211 20228 19212 20233 19212 20153 19212 20229 960 20230 960 20245 960 20245 19213 20230 19213 20231 19213 20245 19214 20231 19214 20064 19214 20064 19215 20231 19215 20232 19215 20064 19216 20232 19216 20233 19216 20234 960 20235 960 20222 960 20222 19217 20235 19217 19828 19217 20222 960 19828 960 20066 960 20066 19218 19828 19218 19827 19218 19827 19219 20236 19219 20066 19219 20066 19220 20236 19220 19823 19220 20066 19221 19823 19221 20255 19221 20255 19222 19823 19222 19820 19222 20256 960 20237 960 20240 960 20240 960 20237 960 20238 960 20239 960 19438 960 20097 960 20097 960 19438 960 20240 960 20097 19223 20240 19223 20241 19223 20241 960 20240 960 20238 960 20241 960 20040 960 20097 960 20097 960 20040 960 20242 960 20097 960 20242 960 20096 960 20096 19224 20242 19224 20243 19224 20096 19225 20243 19225 20203 19225 20142 19226 20244 19226 20156 19226 20156 19227 20244 19227 20245 19227 20156 19228 20245 19228 20167 19228 20167 960 20245 960 20226 960 20167 960 20226 960 20165 960 20165 960 20226 960 20225 960 19810 960 20246 960 20056 960 20247 19229 20248 19229 20251 19229 20249 19230 20247 19230 20250 19230 20250 960 20247 960 20251 960 20250 960 20251 960 20254 960 19476 19231 20056 19231 20114 19231 20114 19232 20056 19232 20246 19232 20114 19233 20246 19233 19808 19233 19808 960 19807 960 20114 960 20114 19234 19807 19234 20252 19234 20114 960 20252 960 20247 960 20247 19235 20252 19235 20253 19235 20247 19236 20253 19236 20248 19236 20254 960 19816 960 20250 960 20250 19237 19816 19237 19813 19237 20250 19238 19813 19238 20056 19238 20056 19239 19813 19239 19812 19239 20056 19240 19812 19240 19810 19240 19820 960 19818 960 20255 960 20255 960 19818 960 20053 960 20255 19241 20053 19241 20240 19241 20240 960 20053 960 20108 960 20240 960 20108 960 20256 960 20256 19242 20108 19242 20043 19242 19727 19243 19620 19243 20262 19243 20262 19244 20129 19244 19727 19244 19727 19245 20129 19245 20131 19245 19727 19246 20131 19246 19728 19246 19728 19247 20131 19247 20133 19247 19728 19248 20133 19248 19729 19248 19729 19249 20133 19249 20123 19249 19729 19250 20123 19250 19730 19250 19730 19251 20123 19251 20122 19251 19730 19252 20122 19252 19731 19252 19731 19253 20122 19253 20257 19253 19731 19254 20257 19254 20258 19254 20258 19255 20257 19255 20259 19255 20258 19256 20259 19256 20260 19256 20260 19257 20259 19257 20121 19257 20260 19258 20121 19258 19732 19258 19620 19259 20261 19259 20262 19259 20262 19260 20261 19260 19932 19260 20262 19261 19932 19261 20264 19261 20264 19262 19932 19262 20263 19262 20264 19263 20263 19263 20130 19263 20347 19264 20265 19264 20266 19264 20267 19265 19947 19265 19946 19265 20268 19266 20269 19266 20270 19266 20386 19267 20271 19267 20387 19267 20302 19268 20272 19268 20303 19268 19775 19269 19776 19269 19987 19269 20364 19270 19905 19270 20366 19270 20365 19271 20273 19271 20274 19271 20274 19272 20275 19272 19713 19272 19713 19273 20275 19273 20277 19273 19713 19274 20277 19274 19711 19274 19920 19275 20276 19275 19710 19275 19711 19276 20277 19276 19710 19276 19710 19277 20277 19277 20361 19277 19710 19278 20361 19278 19920 19278 20284 19279 19707 19279 20279 19279 20279 19280 19707 19280 20278 19280 20279 19281 20278 19281 20351 19281 20283 19282 20280 19282 20282 19282 20345 19283 20281 19283 20282 19283 20282 19284 20281 19284 19707 19284 20282 19285 19707 19285 20283 19285 20283 19286 19707 19286 20284 19286 20283 19287 20284 19287 20285 19287 20336 19288 20286 19288 20287 19288 20287 19289 20286 19289 19687 19289 20287 19290 19687 19290 20341 19290 20341 19291 19687 19291 20288 19291 20341 19292 20288 19292 19696 19292 20337 19293 20289 19293 20334 19293 20331 19294 20290 19294 20291 19294 20292 19295 19958 19295 20333 19295 20325 19296 20293 19296 20327 19296 20298 19297 19651 19297 20326 19297 20326 19298 19651 19298 20325 19298 20297 19299 20294 19299 20296 19299 20302 19300 19649 19300 20295 19300 20295 19301 19649 19301 19650 19301 20295 19302 19650 19302 20296 19302 20296 19303 19650 19303 19651 19303 20296 19304 19651 19304 20297 19304 20297 19305 19651 19305 20298 19305 20297 19306 20298 19306 20299 19306 20303 19307 20300 19307 20301 19307 20302 19308 20303 19308 19649 19308 19649 19309 20303 19309 20301 19309 19649 19310 20301 19310 19646 19310 19646 19311 20301 19311 20304 19311 19646 19312 20304 19312 19876 19312 20305 19313 20306 19313 20310 19313 20268 19314 20307 19314 20309 19314 20309 19315 20307 19315 20308 19315 20309 19316 20308 19316 20310 19316 20270 19317 20311 19317 20313 19317 19898 19318 19643 19318 20315 19318 20268 19319 20270 19319 20307 19319 20307 19320 20270 19320 20313 19320 20307 19321 20313 19321 20312 19321 20312 19322 20313 19322 20314 19322 20312 19323 20314 19323 20315 19323 20315 19324 20314 19324 20378 19324 20315 19325 20378 19325 19898 19325 20267 19326 20316 19326 20321 19326 20321 19327 20316 19327 20322 19327 20323 19328 20317 19328 20320 19328 20318 19329 20261 19329 20319 19329 20319 19330 20261 19330 19622 19330 20319 19331 19622 19331 20320 19331 20320 19332 19622 19332 20321 19332 20320 19333 20321 19333 20323 19333 20323 19334 20321 19334 20322 19334 20323 19335 20322 19335 20324 19335 20325 19336 20327 19336 20326 19336 20326 19337 20327 19337 20328 19337 20326 19338 20328 19338 20329 19338 20330 19339 20340 19339 20291 19339 20291 19340 20340 19340 20292 19340 20291 19341 20292 19341 20331 19341 20331 19342 20292 19342 20333 19342 20331 19343 20333 19343 20332 19343 20332 19344 20333 19344 20335 19344 20332 19345 20335 19345 20334 19345 20334 19346 20335 19346 20286 19346 20334 19347 20286 19347 20337 19347 20337 19348 20286 19348 20336 19348 20337 19349 20336 19349 20338 19349 20328 19350 20339 19350 20329 19350 20329 19351 20339 19351 19832 19351 20329 19352 19832 19352 20340 19352 20340 19353 19832 19353 19833 19353 20340 19354 19833 19354 20292 19354 19696 19355 19965 19355 20341 19355 20341 19356 19965 19356 20342 19356 20341 19357 20342 19357 20348 19357 20348 19358 20342 19358 20343 19358 20344 19359 20281 19359 19982 19359 19982 19360 20281 19360 20345 19360 19982 19361 20345 19361 20346 19361 20346 19362 20345 19362 20347 19362 20346 19363 20347 19363 20343 19363 20343 19364 20347 19364 20266 19364 20343 19365 20266 19365 20348 19365 20348 19366 20266 19366 20349 19366 20353 19367 20350 19367 20352 19367 20354 19368 19990 19368 19926 19368 20354 19369 19926 19369 20359 19369 20278 19370 19775 19370 20351 19370 20351 19371 19775 19371 19987 19371 20351 19372 19987 19372 20352 19372 20352 19373 19987 19373 19990 19373 20352 19374 19990 19374 20353 19374 20353 19375 19990 19375 20354 19375 20353 19376 20354 19376 20355 19376 20356 19377 20357 19377 20360 19377 19926 19378 20358 19378 20359 19378 20359 19379 20358 19379 19919 19379 20359 19380 19919 19380 20360 19380 20360 19381 19919 19381 19920 19381 20360 19382 19920 19382 20356 19382 20356 19383 19920 19383 20361 19383 20356 19384 20361 19384 20362 19384 20366 19385 20370 19385 20363 19385 20363 19386 20370 19386 20371 19386 19713 19387 20364 19387 20274 19387 20274 19388 20364 19388 20366 19388 20274 19389 20366 19389 20365 19389 20365 19390 20366 19390 20363 19390 20365 19391 20363 19391 20367 19391 20374 19392 20368 19392 20372 19392 19932 19393 20261 19393 20369 19393 20369 19394 20261 19394 20318 19394 20369 19395 20318 19395 20373 19395 20373 19396 20318 19396 20375 19396 20370 19397 19916 19397 20371 19397 20371 19398 19916 19398 19915 19398 20371 19399 19915 19399 20372 19399 20372 19400 19915 19400 20373 19400 20372 19401 20373 19401 20374 19401 20374 19402 20373 19402 20375 19402 20374 19403 20375 19403 20376 19403 20381 19404 20377 19404 20379 19404 20382 19405 20380 19405 20378 19405 20378 19406 20380 19406 19897 19406 20378 19407 19897 19407 19898 19407 20267 19408 19946 19408 20316 19408 20316 19409 19946 19409 19893 19409 20316 19410 19893 19410 20379 19410 20379 19411 19893 19411 20380 19411 20379 19412 20380 19412 20381 19412 20381 19413 20380 19413 20382 19413 20381 19414 20382 19414 20383 19414 20387 19415 20385 19415 20384 19415 20384 19416 20385 19416 20389 19416 20384 19417 20389 19417 20390 19417 20308 19418 20386 19418 20310 19418 20310 19419 20386 19419 20387 19419 20310 19420 20387 19420 20305 19420 20305 19421 20387 19421 20384 19421 20305 19422 20384 19422 20388 19422 20389 19423 19878 19423 20390 19423 20390 19424 19878 19424 19877 19424 20390 19425 19877 19425 20304 19425 20304 19426 19877 19426 20391 19426 20304 19427 20391 19427 19876 19427 20392 19428 20360 19428 20393 19428 20393 19429 20360 19429 20357 19429 20393 19430 20357 19430 20394 19430 20429 19431 20505 19431 20395 19431 20395 19432 20505 19432 20504 19432 20395 19432 20504 19432 19733 19432 19733 19433 20504 19433 20501 19433 19733 19434 20501 19434 20396 19434 20396 19435 20501 19435 20500 19435 20396 19436 20500 19436 20398 19436 20398 19437 20500 19437 20397 19437 20398 19438 20397 19438 20399 19438 20399 19439 20397 19439 20401 19439 20399 19440 20401 19440 20400 19440 20400 19441 20401 19441 20498 19441 20400 19442 20498 19442 20402 19442 20402 19443 20498 19443 20497 19443 20402 19444 20497 19444 19726 19444 19726 19445 20497 19445 20495 19445 19726 19446 20495 19446 19723 19446 19723 19447 20495 19447 20403 19447 19723 19448 20403 19448 19722 19448 19722 19449 20403 19449 20404 19449 19722 19450 20404 19450 19719 19450 19719 19451 20404 19451 20405 19451 19719 19452 20405 19452 20406 19452 20406 19453 20405 19453 20407 19453 20406 19454 20407 19454 19718 19454 19718 19455 20407 19455 20408 19455 19718 19456 20408 19456 20409 19456 20409 19457 20408 19457 20490 19457 20409 19458 20490 19458 19716 19458 19716 19459 20490 19459 20410 19459 19716 19460 20410 19460 19715 19460 19715 19461 20410 19461 20489 19461 19715 19462 20489 19462 20412 19462 20412 19463 20489 19463 20411 19463 20412 19464 20411 19464 20413 19464 20413 19465 20411 19465 20414 19465 20413 19466 20414 19466 19761 19466 19761 19467 20414 19467 20415 19467 19761 19468 20415 19468 19760 19468 19760 19469 20415 19469 20416 19469 19760 19469 20416 19469 19758 19469 19758 19470 20416 19470 20484 19470 19758 19471 20484 19471 20417 19471 20417 19472 20484 19472 20520 19472 20417 19473 20520 19473 19755 19473 19755 19474 20520 19474 20519 19474 19755 19475 20519 19475 19754 19475 19754 19476 20519 19476 20418 19476 19754 19477 20418 19477 20419 19477 20419 19478 20418 19478 20517 19478 20419 19479 20517 19479 20420 19479 20420 19480 20517 19480 20516 19480 20420 19481 20516 19481 19750 19481 19750 19482 20516 19482 20515 19482 19750 19483 20515 19483 19749 19483 19749 19484 20515 19484 20421 19484 19749 19485 20421 19485 19747 19485 19747 19486 20421 19486 20512 19486 19747 19487 20512 19487 19744 19487 19744 19488 20512 19488 20422 19488 19744 19489 20422 19489 19743 19489 19743 19490 20422 19490 20423 19490 19743 19491 20423 19491 19742 19491 19742 19492 20423 19492 20510 19492 19742 19493 20510 19493 19740 19493 19740 19494 20510 19494 20509 19494 19740 19495 20509 19495 19739 19495 19739 19496 20509 19496 20424 19496 19739 19497 20424 19497 19737 19497 19737 19498 20424 19498 20425 19498 19737 19499 20425 19499 20426 19499 20426 19500 20425 19500 20428 19500 20426 19501 20428 19501 20427 19501 20427 19502 20428 19502 20430 19502 20427 19503 20430 19503 20429 19503 20429 19504 20430 19504 20505 19504 20431 19505 20503 19505 20432 19505 20432 19506 20503 19506 20506 19506 20432 19507 20506 19507 20433 19507 20433 19508 20506 19508 20435 19508 20433 19509 20435 19509 20434 19509 20434 19510 20435 19510 20507 19510 20434 19511 20507 19511 20437 19511 20437 19512 20507 19512 20436 19512 20437 19513 20436 19513 20439 19513 20439 19514 20436 19514 20438 19514 20439 19515 20438 19515 20440 19515 20440 19516 20438 19516 20508 19516 20440 19517 20508 19517 20442 19517 20442 19518 20508 19518 20441 19518 20442 19519 20441 19519 20443 19519 20443 19520 20441 19520 20511 19520 20443 19521 20511 19521 20444 19521 20444 19522 20511 19522 20446 19522 20444 19523 20446 19523 20445 19523 20445 19524 20446 19524 20513 19524 20445 19525 20513 19525 20447 19525 20447 19526 20513 19526 20514 19526 20447 19527 20514 19527 20448 19527 20448 19528 20514 19528 20449 19528 20448 19529 20449 19529 20450 19529 20450 19530 20449 19530 20518 19530 20450 19531 20518 19531 20451 19531 20451 19532 20518 19532 20452 19532 20451 19533 20452 19533 20453 19533 20453 19534 20452 19534 20454 19534 20453 19535 20454 19535 20455 19535 20455 19536 20454 19536 20521 19536 20455 19537 20521 19537 20456 19537 20456 19538 20521 19538 20522 19538 20456 19539 20522 19539 20457 19539 20457 19540 20522 19540 20485 19540 20457 19541 20485 19541 20458 19541 20458 19542 20485 19542 20486 19542 20458 19543 20486 19543 20459 19543 20459 19544 20486 19544 20487 19544 20459 19545 20487 19545 20460 19545 20460 19546 20487 19546 20461 19546 20460 19547 20461 19547 20462 19547 20462 19548 20461 19548 20488 19548 20462 19549 20488 19549 20463 19549 20463 19550 20488 19550 20464 19550 20463 19551 20464 19551 20465 19551 20465 19552 20464 19552 20491 19552 20465 19552 20491 19552 20466 19552 20466 19553 20491 19553 20467 19553 20466 19554 20467 19554 20468 19554 20468 19555 20467 19555 20469 19555 20468 19556 20469 19556 20470 19556 20470 19557 20469 19557 20492 19557 20470 19558 20492 19558 20471 19558 20471 19559 20492 19559 20493 19559 20471 19560 20493 19560 20472 19560 20472 19561 20493 19561 20494 19561 20472 19562 20494 19562 20473 19562 20473 19563 20494 19563 20496 19563 20473 19564 20496 19564 20474 19564 20474 19565 20496 19565 20475 19565 20474 19566 20475 19566 20476 19566 20476 19567 20475 19567 20499 19567 20476 19567 20499 19567 20477 19567 20477 19568 20499 19568 20478 19568 20477 19569 20478 19569 20479 19569 20479 19570 20478 19570 20480 19570 20479 19571 20480 19571 20481 19571 20481 19572 20480 19572 20483 19572 20481 19573 20483 19573 20482 19573 20482 19574 20483 19574 20502 19574 20482 19575 20502 19575 20431 19575 20431 19505 20502 19505 20503 19505 20484 590 20416 590 20485 590 20485 19576 20416 19576 20415 19576 20485 590 20415 590 20486 590 20486 19577 20415 19577 20414 19577 20486 590 20414 590 20487 590 20487 590 20414 590 20411 590 20487 590 20411 590 20461 590 20461 590 20411 590 20489 590 20461 590 20489 590 20488 590 20488 590 20489 590 20410 590 20488 590 20410 590 20464 590 20464 590 20410 590 20490 590 20464 590 20490 590 20491 590 20491 590 20490 590 20408 590 20491 590 20408 590 20467 590 20467 19578 20408 19578 20407 19578 20467 590 20407 590 20469 590 20469 590 20407 590 20405 590 20469 19579 20405 19579 20492 19579 20492 19580 20405 19580 20404 19580 20492 19581 20404 19581 20493 19581 20493 19582 20404 19582 20403 19582 20493 590 20403 590 20494 590 20494 590 20403 590 20495 590 20494 590 20495 590 20496 590 20496 19583 20495 19583 20497 19583 20496 19584 20497 19584 20475 19584 20475 590 20497 590 20498 590 20475 590 20498 590 20499 590 20499 590 20498 590 20401 590 20499 19585 20401 19585 20478 19585 20478 590 20401 590 20397 590 20478 590 20397 590 20480 590 20480 590 20397 590 20500 590 20480 19586 20500 19586 20483 19586 20483 19587 20500 19587 20501 19587 20483 590 20501 590 20502 590 20502 19588 20501 19588 20504 19588 20502 590 20504 590 20503 590 20503 19589 20504 19589 20505 19589 20503 590 20505 590 20506 590 20506 19590 20505 19590 20430 19590 20506 590 20430 590 20435 590 20435 19591 20430 19591 20428 19591 20435 590 20428 590 20507 590 20507 590 20428 590 20425 590 20507 19592 20425 19592 20436 19592 20436 590 20425 590 20424 590 20436 590 20424 590 20438 590 20438 590 20424 590 20509 590 20438 590 20509 590 20508 590 20508 590 20509 590 20510 590 20508 590 20510 590 20441 590 20441 590 20510 590 20423 590 20441 590 20423 590 20511 590 20511 19593 20423 19593 20422 19593 20511 590 20422 590 20446 590 20446 590 20422 590 20512 590 20446 590 20512 590 20513 590 20513 590 20512 590 20421 590 20513 590 20421 590 20514 590 20514 590 20421 590 20515 590 20514 590 20515 590 20449 590 20449 590 20515 590 20516 590 20449 590 20516 590 20518 590 20518 590 20516 590 20517 590 20518 590 20517 590 20452 590 20452 590 20517 590 20418 590 20452 590 20418 590 20454 590 20454 19594 20418 19594 20519 19594 20454 590 20519 590 20521 590 20521 19595 20519 19595 20520 19595 20521 590 20520 590 20522 590 20522 590 20520 590 20484 590 20522 590 20484 590 20485 590 20609 19596 20797 19596 20523 19596 20523 19597 20797 19598 20524 19599 20523 19600 20524 19600 20525 19600 20524 19601 20526 19601 20525 19601 20525 19602 20526 19602 20527 19602 20525 19603 20527 19603 20530 19603 20527 19604 20528 19604 20530 19604 20530 19605 20528 19605 20529 19605 20530 19606 20529 19606 20531 19606 20531 19607 20529 19607 20801 19607 20531 19608 20801 19608 20532 19608 20801 19609 20804 19609 20532 19609 20532 19610 20804 19610 20533 19610 20532 19611 20533 19611 20534 19611 20533 19612 20535 19612 20534 19612 20534 19613 20535 19614 20536 19615 20534 19616 20536 19616 20649 19616 20536 19617 20537 19617 20649 19617 20649 19618 20537 19618 20538 19618 20649 19619 20538 19619 20539 19619 20538 19620 20806 19620 20539 19620 20539 19621 20806 19621 20540 19621 20539 19622 20540 19622 20541 19622 20541 19623 20540 19623 20542 19623 20541 19624 20542 19624 20543 19624 20542 19625 20808 19625 20543 19625 20543 19626 20808 19626 20810 19626 20543 19627 20810 19627 20646 19627 20646 19628 20810 19628 20545 19628 20646 19629 20545 19629 20544 19629 20545 19630 20546 19630 20544 19630 20544 19631 20546 19631 20811 19631 20544 19632 20811 19632 20548 19632 20811 19633 20547 19633 20548 19633 20548 19634 20547 19634 20813 19634 20548 19635 20813 19635 20644 19635 20644 19636 20813 19636 20814 19636 20644 19637 20814 19637 20641 19637 20641 19638 20814 19638 20549 19638 20549 19639 20815 19639 20641 19639 20641 19640 20815 19640 20550 19640 20641 19641 20550 19641 20551 19641 20551 19642 20550 19642 20553 19642 20551 19643 20553 19643 20552 19643 20553 19644 20818 19644 20552 19644 20552 19645 20818 19645 20554 19645 20552 19646 20554 19646 20639 19646 20639 19647 20554 19647 20817 19647 20639 19648 20817 19648 20555 19648 20817 19649 20556 19649 20555 19649 20555 19650 20556 19650 20821 19650 20555 19651 20821 19651 20638 19651 20821 19652 20819 19652 20638 19652 20638 19653 20819 19653 20557 19653 20638 19654 20557 19654 20558 19654 20558 19655 20557 19655 20559 19655 20558 19656 20559 19656 20560 19656 20560 19657 20559 19657 20561 19657 20561 19658 20562 19658 20560 19658 20560 19659 20562 19659 20822 19659 20560 19660 20822 19660 20563 19660 20563 19661 20822 19662 20824 19663 20563 19664 20824 19664 20634 19664 20824 19665 20826 19665 20634 19665 20634 19666 20826 19666 20564 19666 20634 19667 20564 19667 20633 19667 20633 19668 20564 19668 20565 19668 20633 19669 20565 19669 20632 19669 20565 19670 20566 19670 20632 19670 20632 19671 20566 19671 20827 19671 20632 19672 20827 19672 20567 19672 20827 19673 20568 19673 20567 19673 20567 19674 20568 19674 20569 19674 20567 19675 20569 19675 20631 19675 20631 19676 20569 19676 20829 19676 20631 19677 20829 19677 20630 19677 20829 19678 20830 19678 20630 19678 20630 19679 20830 19679 20570 19679 20630 19680 20570 19680 20571 19680 20570 19681 20831 19681 20571 19681 20571 19682 20831 19682 20833 19682 20571 19683 20833 19683 20572 19683 20833 19684 20573 19684 20572 19684 20572 19685 20573 19685 20574 19685 20572 19686 20574 19686 20627 19686 20574 19687 20835 19687 20627 19687 20627 19688 20835 19688 20575 19688 20627 19689 20575 19689 20577 19689 20577 19690 20575 19690 20576 19690 20577 19691 20576 19691 20580 19691 20576 19692 20578 19692 20580 19692 20580 19693 20578 19693 20579 19693 20580 19694 20579 19694 20625 19694 20625 19695 20579 19695 20581 19695 20625 19696 20581 19696 20624 19696 20581 19697 20836 19697 20624 19697 20624 19698 20836 19698 20582 19698 20624 19699 20582 19699 20623 19699 20582 19700 20837 19700 20623 19700 20623 19701 20837 19702 20583 19703 20623 19704 20583 19704 20584 19704 20583 19705 20841 19705 20584 19705 20584 19706 20841 19706 20586 19706 20584 19707 20586 19707 20585 19707 20586 19708 20840 19708 20585 19708 20585 19709 20840 19709 20838 19709 20585 19710 20838 19710 20587 19710 20587 19711 20838 19711 20842 19711 20587 19712 20842 19712 20588 19712 20842 19713 20589 19713 20588 19713 20588 19714 20589 19714 20843 19714 20588 19715 20843 19715 20620 19715 20620 19716 20843 19716 20844 19716 20620 19717 20844 19717 20619 19717 20844 19718 20590 19718 20619 19718 20619 19719 20590 19719 20591 19719 20619 19720 20591 19720 20618 19720 20591 19721 20592 19721 20618 19721 20618 19722 20592 19722 20846 19722 20618 19723 20846 19723 20593 19723 20593 19724 20846 19724 20594 19724 20593 19725 20594 19725 20617 19725 20617 19726 20594 19726 20595 19726 20595 19727 20596 19727 20617 19727 20617 19728 20596 19728 20597 19728 20617 19729 20597 19729 20615 19729 20615 19730 20597 19730 20598 19730 20615 19731 20598 19731 20614 19731 20598 19732 20847 19732 20614 19732 20614 19733 20847 19733 20848 19733 20614 19734 20848 19734 20599 19734 20599 19735 20848 19735 20849 19735 20599 19736 20849 19736 20600 19736 20849 19737 20850 19737 20600 19737 20600 19738 20850 19738 20851 19738 20600 19739 20851 19739 20601 19739 20851 19740 20853 19740 20601 19740 20601 19741 20853 19741 20602 19741 20601 19742 20602 19742 20603 19742 20603 19743 20602 19743 20604 19743 20603 19744 20604 19744 20606 19744 20604 19745 20605 19745 20606 19745 20606 19746 20605 19746 20607 19746 20606 19747 20607 19747 20608 19747 20608 19748 20607 19748 20854 19748 20608 19749 20854 19749 20609 19749 20609 19750 20854 19750 20610 19750 20609 19751 20610 19751 20797 19751 20606 19752 20611 19752 20603 19752 20603 19753 20611 19753 20657 19753 20603 19754 20657 19754 20601 19754 20601 19755 20657 19755 20612 19755 20601 19756 20612 19756 20600 19756 20600 19757 20612 19757 20613 19757 20600 19758 20613 19758 20599 19758 20599 19759 20613 19759 20659 19759 20599 19760 20659 19760 20614 19760 20614 19761 20659 19761 20616 19761 20614 19762 20616 19762 20615 19762 20615 19763 20616 19763 20660 19763 20615 19764 20660 19764 20617 19764 20617 19765 20660 19765 20661 19765 20617 19766 20661 19766 20593 19766 20593 19767 20661 19767 20662 19767 20593 19768 20662 19768 20618 19768 20618 19769 20662 19769 20663 19769 20618 19770 20663 19770 20619 19770 20619 19771 20663 19771 20665 19771 20619 19772 20665 19772 20620 19772 20620 19773 20665 19773 20667 19773 20620 19774 20667 19774 20588 19774 20588 19775 20667 19775 20621 19775 20588 19776 20621 19776 20587 19776 20587 19777 20621 19777 20622 19777 20587 19778 20622 19778 20585 19778 20585 19779 20622 19779 20670 19779 20585 19780 20670 19780 20584 19780 20584 19781 20670 19781 20673 19781 20584 19782 20673 19782 20623 19782 20623 19783 20673 19783 20675 19783 20623 19784 20675 19784 20624 19784 20624 19785 20675 19785 20626 19785 20624 19786 20626 19786 20625 19786 20625 19787 20626 19787 20677 19787 20625 19788 20677 19788 20580 19788 20580 19789 20677 19789 20680 19789 20580 19790 20680 19790 20577 19790 20577 19791 20680 19791 20681 19791 20577 19792 20681 19792 20627 19792 20627 19793 20681 19793 20628 19793 20627 19794 20628 19794 20572 19794 20572 19795 20628 19795 20629 19795 20572 19796 20629 19796 20571 19796 20571 19797 20629 19797 20683 19797 20571 19798 20683 19798 20630 19798 20630 19799 20683 19799 20685 19799 20630 19800 20685 19800 20631 19800 20631 19801 20685 19801 20686 19801 20631 19802 20686 19802 20567 19802 20567 19803 20686 19803 20689 19803 20567 19804 20689 19804 20632 19804 20632 19805 20689 19805 20690 19805 20632 19806 20690 19806 20633 19806 20633 19807 20690 19807 20692 19807 20633 19808 20692 19808 20634 19808 20634 19809 20692 19809 20635 19809 20634 19810 20635 19810 20563 19810 20563 19811 20635 19811 20694 19811 20563 19812 20694 19812 20560 19812 20560 19813 20694 19813 20636 19813 20560 19814 20636 19814 20558 19814 20558 19815 20636 19815 20637 19815 20558 19816 20637 19816 20638 19816 20638 19817 20637 19817 20695 19817 20638 19818 20695 19818 20555 19818 20555 19819 20695 19819 20640 19819 20555 19820 20640 19820 20639 19820 20639 19821 20640 19821 20697 19821 20639 19822 20697 19822 20552 19822 20552 19823 20697 19823 20698 19823 20552 19824 20698 19824 20551 19824 20551 19825 20698 19825 20642 19825 20551 19826 20642 19826 20641 19826 20641 19827 20642 19827 20643 19827 20641 19828 20643 19828 20644 19828 20644 19829 20643 19829 20699 19829 20644 19830 20699 19830 20548 19830 20548 19831 20699 19831 20700 19831 20548 19832 20700 19832 20544 19832 20544 19833 20700 19833 20645 19833 20544 19834 20645 19834 20646 19834 20646 19835 20645 19835 20647 19835 20646 19836 20647 19836 20543 19836 20543 19837 20647 19837 20704 19837 20543 19838 20704 19838 20541 19838 20541 19839 20704 19839 20705 19839 20541 19840 20705 19840 20539 19840 20539 19841 20705 19841 20648 19841 20539 19842 20648 19842 20649 19842 20649 19843 20648 19843 20706 19843 20649 19844 20706 19844 20534 19844 20534 19845 20706 19845 20650 19845 20534 19846 20650 19846 20532 19846 20532 19847 20650 19847 20651 19847 20532 19848 20651 19848 20531 19848 20531 19849 20651 19849 20652 19849 20531 19850 20652 19850 20530 19850 20530 19851 20652 19851 20653 19851 20530 19852 20653 19852 20525 19852 20525 19853 20653 19853 20654 19853 20525 19854 20654 19854 20523 19854 20523 19855 20654 19855 20655 19855 20523 19856 20655 19856 20609 19856 20609 19857 20655 19857 20708 19857 20609 19858 20708 19858 20608 19858 20608 19859 20708 19859 20709 19859 20608 19860 20709 19860 20606 19860 20606 19861 20709 19861 20611 19861 20611 19862 20656 19862 20657 19862 20657 19863 20656 19863 20711 19863 20657 19864 20711 19864 20612 19864 20612 19865 20711 19865 20713 19865 20612 19866 20713 19866 20613 19866 20613 19867 20713 19867 20658 19867 20613 19868 20658 19868 20659 19868 20659 19869 20658 19869 20716 19869 20659 19870 20716 19870 20616 19870 20616 19871 20716 19871 20718 19871 20616 19872 20718 19872 20660 19872 20660 19873 20718 19873 20721 19873 20660 19874 20721 19874 20661 19874 20661 19875 20721 19875 20722 19875 20661 19876 20722 19876 20662 19876 20662 19877 20722 19877 20725 19877 20662 19878 20725 19878 20663 19878 20663 19879 20725 19879 20664 19879 20663 19880 20664 19880 20665 19880 20665 19881 20664 19881 20666 19881 20665 19882 20666 19882 20667 19882 20667 19883 20666 19883 20668 19883 20667 19884 20668 19884 20621 19884 20621 19885 20668 19885 20669 19885 20621 19886 20669 19886 20622 19886 20622 19887 20669 19887 20671 19887 20622 19888 20671 19888 20670 19888 20670 19889 20671 19889 20672 19889 20670 19890 20672 19890 20673 19890 20673 19891 20672 19891 20674 19891 20673 19892 20674 19892 20675 19892 20675 19893 20674 19893 20676 19893 20675 19894 20676 19894 20626 19894 20626 19895 20676 19895 20678 19895 20626 19896 20678 19896 20677 19896 20677 19897 20678 19897 20679 19897 20677 19898 20679 19898 20680 19898 20680 19899 20679 19899 20682 19899 20680 19900 20682 19900 20681 19900 20681 19901 20682 19901 20737 19901 20681 19902 20737 19902 20628 19902 20628 19903 20737 19903 20739 19903 20628 19904 20739 19904 20629 19904 20629 19905 20739 19905 20741 19905 20629 19906 20741 19906 20683 19906 20683 19907 20741 19907 20684 19907 20683 19908 20684 19908 20685 19908 20685 19909 20684 19909 20687 19909 20685 19910 20687 19910 20686 19910 20686 19911 20687 19911 20688 19911 20686 19912 20688 19912 20689 19912 20689 19913 20688 19913 20746 19913 20689 19914 20746 19914 20690 19914 20690 19915 20746 19915 20691 19915 20690 19916 20691 19916 20692 19916 20692 19917 20691 19917 20693 19917 20692 19918 20693 19918 20635 19918 20635 19919 20693 19919 20750 19919 20635 19920 20750 19920 20694 19920 20694 19921 20750 19921 20752 19921 20694 19922 20752 19922 20636 19922 20636 19923 20752 19923 20754 19923 20636 19924 20754 19924 20637 19924 20637 19925 20754 19925 20757 19925 20637 19926 20757 19926 20695 19926 20695 19927 20757 19927 20696 19927 20695 19928 20696 19928 20640 19928 20640 19929 20696 19929 20758 19929 20640 19930 20758 19930 20697 19930 20697 19931 20758 19931 20761 19931 20697 19932 20761 19932 20698 19932 20698 19933 20761 19933 20763 19933 20698 19934 20763 19934 20642 19934 20642 19935 20763 19935 20766 19935 20642 19936 20766 19936 20643 19936 20643 19937 20766 19937 20768 19937 20643 19938 20768 19938 20699 19938 20699 19939 20768 19939 20770 19939 20699 19940 20770 19940 20700 19940 20700 19941 20770 19941 20701 19941 20700 19942 20701 19942 20645 19942 20645 19943 20701 19943 20702 19943 20645 19944 20702 19944 20647 19944 20647 19945 20702 19945 20703 19945 20647 19946 20703 19946 20704 19946 20704 19947 20703 19947 20774 19947 20704 19948 20774 19948 20705 19948 20705 19949 20774 19949 20775 19949 20705 19950 20775 19950 20648 19950 20648 19951 20775 19951 20778 19951 20648 19952 20778 19952 20706 19952 20706 19953 20778 19953 20780 19953 20706 19954 20780 19954 20650 19954 20650 19955 20780 19955 20782 19955 20650 19956 20782 19956 20651 19956 20651 19957 20782 19957 20784 19957 20651 19958 20784 19958 20652 19958 20652 19959 20784 19959 20786 19959 20652 19960 20786 19960 20653 19960 20653 19961 20786 19961 20787 19961 20653 19962 20787 19962 20654 19962 20654 19963 20787 19963 20789 19963 20654 19964 20789 19964 20655 19964 20655 19965 20789 19965 20791 19965 20655 19966 20791 19966 20708 19966 20708 19967 20791 19967 20707 19967 20708 19968 20707 19968 20709 19968 20709 19969 20707 19969 20796 19969 20709 19970 20796 19970 20611 19970 20611 19971 20796 19971 20656 19971 20656 19972 20710 19972 20711 19972 20711 19973 20710 19973 20712 19973 20711 19974 20712 19974 20713 19974 20713 19975 20712 19975 20714 19975 20713 19976 20714 19976 20658 19976 20658 19977 20714 19977 20715 19977 20658 19978 20715 19978 20716 19978 20716 19979 20715 19979 20717 19979 20716 19980 20717 19980 20718 19980 20718 19981 20717 19981 20719 19981 20718 19982 20719 19982 20721 19982 20721 19983 20719 19983 20720 19983 20721 19984 20720 19984 20722 19984 20722 19985 20720 19985 20723 19985 20722 19986 20723 19986 20725 19986 20725 19987 20723 19987 20724 19987 20725 19988 20724 19988 20664 19988 20664 19989 20724 19989 20726 19989 20664 19990 20726 19990 20666 19990 20666 19991 20726 19991 20727 19991 20666 19992 20727 19992 20668 19992 20668 19993 20727 19993 20728 19993 20668 19994 20728 19994 20669 19994 20669 19995 20728 19995 20729 19995 20669 19996 20729 19996 20671 19996 20671 19997 20729 19997 20730 19997 20671 19998 20730 19998 20672 19998 20672 19999 20730 19999 20731 19999 20672 20000 20731 20000 20674 20000 20674 20001 20731 20001 20732 20001 20674 20002 20732 20002 20676 20002 20676 20003 20732 20003 20733 20003 20676 20004 20733 20004 20678 20004 20678 20005 20733 20005 20734 20005 20678 20006 20734 20006 20679 20006 20679 20007 20734 20007 20735 20007 20679 20008 20735 20008 20682 20008 20682 20009 20735 20009 20736 20009 20682 20010 20736 20010 20737 20010 20737 20011 20736 20011 20738 20011 20737 20012 20738 20012 20739 20012 20739 20013 20738 20013 20740 20013 20739 20014 20740 20014 20741 20014 20741 20015 20740 20015 20742 20015 20741 20016 20742 20016 20684 20016 20684 20017 20742 20017 20743 20017 20684 20018 20743 20018 20687 20018 20687 20019 20743 20019 20744 20019 20687 20020 20744 20020 20688 20020 20688 20021 20744 20021 20745 20021 20688 20022 20745 20022 20746 20022 20746 20023 20745 20023 20747 20023 20746 20024 20747 20024 20691 20024 20691 20025 20747 20025 20748 20025 20691 20026 20748 20026 20693 20026 20693 20027 20748 20027 20749 20027 20693 20028 20749 20028 20750 20028 20750 20029 20749 20029 20751 20029 20750 20030 20751 20030 20752 20030 20752 20031 20751 20031 20753 20031 20752 20032 20753 20032 20754 20032 20754 20033 20753 20033 20755 20033 20754 20034 20755 20034 20757 20034 20757 20035 20755 20035 20756 20035 20757 20036 20756 20036 20696 20036 20696 20037 20756 20037 20759 20037 20696 20038 20759 20038 20758 20038 20758 20039 20759 20039 20760 20039 20758 20040 20760 20040 20761 20040 20761 20041 20760 20041 20762 20041 20761 20042 20762 20042 20763 20042 20763 20043 20762 20043 20764 20043 20763 20044 20764 20044 20766 20044 20766 20045 20764 20045 20765 20045 20766 20046 20765 20046 20768 20046 20768 20047 20765 20047 20767 20047 20768 20048 20767 20048 20770 20048 20770 20049 20767 20049 20769 20049 20770 20050 20769 20050 20701 20050 20701 20051 20769 20051 20771 20051 20701 20052 20771 20052 20702 20052 20702 20053 20771 20053 20772 20053 20702 20054 20772 20054 20703 20054 20703 20055 20772 20055 20773 20055 20703 20056 20773 20056 20774 20056 20774 20057 20773 20057 20776 20057 20774 20058 20776 20058 20775 20058 20775 20059 20776 20059 20777 20059 20775 20060 20777 20060 20778 20060 20778 20061 20777 20061 20779 20061 20778 20062 20779 20062 20780 20062 20780 20063 20779 20063 20781 20063 20780 20064 20781 20064 20782 20064 20782 20065 20781 20065 20783 20065 20782 20066 20783 20066 20784 20066 20784 20067 20783 20067 20785 20067 20784 20068 20785 20068 20786 20068 20786 20069 20785 20069 20788 20069 20786 20070 20788 20070 20787 20070 20787 20071 20788 20071 20790 20071 20787 20072 20790 20072 20789 20072 20789 20073 20790 20073 20792 20073 20789 20074 20792 20074 20791 20074 20791 20075 20792 20075 20793 20075 20791 20076 20793 20076 20707 20076 20707 20077 20793 20077 20794 20077 20707 20078 20794 20078 20796 20078 20796 20079 20794 20079 20795 20079 20796 20080 20795 20080 20656 20080 20656 20081 20795 20081 20710 20081 20798 20082 20797 20082 20610 20082 20798 20083 20610 20083 20855 20083 20797 20084 20798 20084 20524 20084 20524 20085 20798 20085 20799 20085 20524 20086 20799 20086 20526 20086 20526 20087 20799 20087 20527 20087 20527 20088 20799 20088 20800 20088 20527 20089 20800 20089 20528 20089 20803 20090 20801 20090 20800 20090 20800 20091 20801 20091 20529 20091 20800 20092 20529 20092 20528 20092 20536 20093 20535 20093 20802 20093 20802 20094 20535 20094 20533 20094 20802 20095 20533 20095 20803 20095 20803 20096 20533 20096 20804 20096 20803 20097 20804 20097 20801 20097 20536 20098 20802 20098 20537 20098 20537 20099 20802 20099 20805 20099 20537 20100 20805 20100 20538 20100 20538 20101 20805 20101 20806 20101 20806 20102 20805 20102 20807 20102 20806 20103 20807 20103 20540 20103 20540 20104 20807 20104 20542 20104 20542 20105 20807 20105 20858 20105 20542 20106 20858 20106 20808 20106 20809 20107 20545 20107 20858 20107 20858 20108 20545 20108 20810 20108 20858 20109 20810 20109 20808 20109 20813 20110 20547 20111 20812 20112 20812 20113 20547 20113 20811 20113 20812 20114 20811 20114 20809 20114 20809 20115 20811 20116 20546 20117 20809 20118 20546 20118 20545 20118 20813 20119 20812 20119 20814 20119 20814 20120 20812 20120 20910 20120 20814 20121 20910 20121 20549 20121 20549 20122 20910 20122 20815 20122 20815 20123 20910 20123 20816 20123 20815 20124 20816 20124 20550 20124 20550 20125 20816 20126 20553 20127 20553 20128 20816 20128 20907 20128 20553 20129 20907 20129 20818 20129 20905 20130 20817 20130 20907 20130 20907 20131 20817 20131 20554 20131 20907 20132 20554 20132 20818 20132 20557 20133 20819 20133 20820 20133 20820 20134 20819 20134 20821 20134 20820 20135 20821 20135 20905 20135 20905 20136 20821 20136 20556 20136 20905 20137 20556 20137 20817 20137 20557 20138 20820 20138 20559 20138 20559 20139 20820 20139 20902 20139 20559 20140 20902 20140 20561 20140 20561 20141 20902 20141 20562 20141 20562 20142 20902 20142 20823 20142 20562 20143 20823 20143 20822 20143 20822 20144 20823 20145 20824 20146 20824 20147 20823 20147 20825 20147 20824 20148 20825 20148 20826 20148 20898 20149 20565 20149 20825 20149 20825 20150 20565 20150 20564 20150 20825 20151 20564 20151 20826 20151 20569 20152 20568 20152 20828 20152 20828 20153 20568 20153 20827 20153 20828 20154 20827 20154 20898 20154 20898 20155 20827 20155 20566 20155 20898 20156 20566 20156 20565 20156 20569 20157 20828 20157 20829 20157 20829 20158 20828 20158 20895 20158 20829 20159 20895 20159 20830 20159 20830 20160 20895 20160 20570 20160 20570 20161 20895 20161 20832 20161 20570 20162 20832 20162 20831 20162 20892 20163 20573 20163 20832 20163 20832 20164 20573 20164 20833 20164 20832 20165 20833 20165 20831 20165 20576 20166 20575 20166 20834 20166 20834 20167 20575 20167 20835 20167 20834 20168 20835 20168 20892 20168 20892 20169 20835 20169 20574 20169 20892 20170 20574 20170 20573 20170 20576 20171 20834 20171 20578 20171 20578 20172 20834 20172 20889 20172 20578 20173 20889 20173 20579 20173 20579 20174 20889 20174 20581 20174 20581 20175 20889 20175 20887 20175 20581 20176 20887 20176 20836 20176 20886 20177 20837 20177 20887 20177 20887 20178 20837 20178 20582 20178 20887 20179 20582 20179 20836 20179 20883 20180 20841 20180 20886 20180 20886 20181 20841 20181 20583 20181 20886 20182 20583 20182 20837 20182 20842 20183 20838 20183 20839 20183 20839 20184 20838 20184 20840 20184 20839 20185 20840 20185 20883 20185 20883 20186 20840 20186 20586 20186 20883 20187 20586 20187 20841 20187 20842 20188 20839 20188 20589 20188 20589 20189 20839 20189 20880 20189 20589 20190 20880 20190 20843 20190 20843 20191 20880 20191 20844 20191 20844 20192 20880 20192 20879 20192 20844 20193 20879 20193 20590 20193 20590 20194 20879 20194 20591 20194 20591 20195 20879 20195 20845 20195 20591 20196 20845 20196 20592 20196 20877 20197 20594 20197 20845 20197 20845 20198 20594 20198 20846 20198 20845 20199 20846 20199 20592 20199 20875 20200 20596 20200 20877 20200 20877 20201 20596 20201 20595 20201 20877 20202 20595 20202 20594 20202 20848 20203 20847 20203 20872 20203 20872 20204 20847 20204 20598 20204 20872 20205 20598 20205 20875 20205 20875 20206 20598 20207 20597 20208 20875 20209 20597 20209 20596 20209 20848 20210 20872 20210 20849 20210 20849 20211 20872 20211 20871 20211 20849 20212 20871 20212 20850 20212 20850 20213 20871 20213 20851 20213 20851 20214 20871 20214 20852 20214 20851 20215 20852 20215 20853 20215 20856 20216 20604 20216 20852 20216 20852 20217 20604 20217 20602 20217 20852 20218 20602 20218 20853 20218 20610 20219 20854 20219 20855 20219 20855 20220 20854 20220 20607 20220 20855 20221 20607 20221 20856 20221 20856 20222 20607 20222 20605 20222 20856 20223 20605 20223 20604 20223 20911 15676 20809 15676 20857 15676 20857 590 20809 590 20858 590 20857 20224 20858 20224 20859 20224 20859 590 20858 590 20807 590 20859 590 20807 590 20860 590 20860 590 20807 590 20805 590 20860 20225 20805 20225 20861 20225 20861 20226 20805 20226 20802 20226 20861 590 20802 590 20862 590 20862 20227 20802 20227 20803 20227 20862 590 20803 590 20863 590 20863 20228 20803 20228 20800 20228 20863 590 20800 590 20864 590 20864 20229 20800 20229 20799 20229 20864 590 20799 590 20865 590 20865 590 20799 590 20798 590 20865 590 20798 590 20866 590 20866 590 20798 590 20855 590 20866 590 20855 590 20867 590 20867 590 20855 590 20856 590 20867 20230 20856 20230 20868 20230 20868 590 20856 590 20852 590 20868 590 20852 590 20869 590 20869 20231 20852 20231 20871 20231 20869 20232 20871 20232 20870 20232 20870 590 20871 590 20872 590 20870 590 20872 590 20873 590 20873 590 20872 590 20875 590 20873 590 20875 590 20874 590 20874 590 20875 590 20877 590 20874 590 20877 590 20876 590 20876 590 20877 590 20845 590 20876 20233 20845 20233 20878 20233 20878 590 20845 590 20879 590 20878 590 20879 590 20881 590 20879 20234 20880 20234 20881 20234 20881 20235 20880 20235 20839 20235 20881 20236 20839 20236 20882 20236 20882 590 20839 590 20883 590 20882 20237 20883 20237 20884 20237 20884 590 20883 590 20886 590 20884 20238 20886 20238 20885 20238 20885 590 20886 590 20887 590 20885 590 20887 590 20888 590 20888 20239 20887 20239 20889 20239 20888 590 20889 590 20890 590 20890 590 20889 590 20834 590 20890 590 20834 590 20891 590 20891 20240 20834 20240 20892 20240 20891 590 20892 590 20893 590 20893 20241 20892 20241 20832 20241 20893 590 20832 590 20894 590 20894 20242 20832 20242 20895 20242 20894 20243 20895 20243 20896 20243 20896 20244 20895 20244 20828 20244 20896 20245 20828 20245 20897 20245 20897 20246 20828 20246 20898 20246 20897 590 20898 590 20899 590 20899 590 20898 590 20825 590 20899 590 20825 590 20900 590 20900 590 20825 590 20823 590 20900 590 20823 590 20901 590 20901 590 20823 590 20902 590 20901 590 20902 590 20903 590 20903 590 20902 590 20820 590 20903 590 20820 590 20904 590 20904 20247 20820 20247 20905 20247 20904 590 20905 590 20906 590 20906 590 20905 590 20907 590 20906 590 20907 590 20908 590 20908 590 20907 590 20816 590 20908 590 20816 590 20909 590 20909 20248 20816 20248 20910 20248 20909 20249 20910 20249 20911 20249 20911 20250 20910 20250 20812 20250 20911 590 20812 590 20809 590 20912 20251 20989 20251 20913 20251 20913 20252 20989 20252 20914 20252 20913 20253 20914 20253 20915 20253 20915 20254 20914 20254 20916 20254 20915 20255 20916 20255 20917 20255 20917 20256 20916 20256 20918 20256 20917 20257 20918 20257 20919 20257 20919 20258 20918 20258 20920 20258 20919 20259 20920 20259 20921 20259 20921 20260 20920 20260 20922 20260 20921 20261 20922 20261 20923 20261 20923 20262 20922 20262 20925 20262 20923 20262 20925 20262 20924 20262 20924 20263 20925 20263 20927 20263 20924 20264 20927 20264 20926 20264 20926 20265 20927 20265 20928 20265 20926 20266 20928 20266 20930 20266 20930 20267 20928 20267 20929 20267 20930 20268 20929 20268 20931 20268 20931 20269 20929 20269 20932 20269 20931 20270 20932 20270 20933 20270 20933 20271 20932 20271 20935 20271 20933 20272 20935 20272 20934 20272 20934 20273 20935 20273 20937 20273 20934 20274 20937 20274 20936 20274 20936 20275 20937 20275 20938 20275 20936 20276 20938 20276 20939 20276 20939 20277 20938 20277 20940 20277 20939 20278 20940 20278 20941 20278 20941 20279 20940 20279 20943 20279 20941 20280 20943 20280 20942 20280 20942 20281 20943 20281 20944 20281 20942 20282 20944 20282 20945 20282 20945 20283 20944 20283 20946 20283 20945 20284 20946 20284 20947 20284 20947 20285 20946 20285 20949 20285 20947 20286 20949 20286 20948 20286 20948 20287 20949 20287 20951 20287 20948 20288 20951 20288 20950 20288 20950 20289 20951 20289 20952 20289 20950 20290 20952 20290 20954 20290 20954 20291 20952 20291 20953 20291 20954 20292 20953 20292 20955 20292 20955 20293 20953 20293 20956 20293 20955 20294 20956 20294 20957 20294 20957 20295 20956 20295 20958 20295 20957 20296 20958 20296 20959 20296 20959 20297 20958 20297 20960 20297 20959 20298 20960 20298 20961 20298 20961 20299 20960 20299 20962 20299 20961 20300 20962 20300 20963 20300 20963 20301 20962 20301 20964 20301 20963 20302 20964 20302 20965 20302 20965 20303 20964 20303 20967 20303 20965 20304 20967 20304 20966 20304 20966 20305 20967 20305 20968 20305 20966 20306 20968 20306 20969 20306 20969 20307 20968 20307 20970 20307 20969 20308 20970 20308 20971 20308 20971 20309 20970 20309 20972 20309 20971 20310 20972 20310 20973 20310 20973 20311 20972 20311 20974 20311 20973 20312 20974 20312 20975 20312 20975 20313 20974 20313 20976 20313 20975 20314 20976 20314 20977 20314 20977 20315 20976 20315 20978 20315 20977 20316 20978 20316 20979 20316 20979 20317 20978 20317 20980 20317 20979 20318 20980 20318 20981 20318 20981 20319 20980 20319 20982 20319 20981 20320 20982 20320 20983 20320 20983 20321 20982 20321 20984 20321 20983 20322 20984 20322 20985 20322 20985 20323 20984 20323 20986 20323 20985 20324 20986 20324 20988 20324 20988 20325 20986 20325 20987 20325 20988 20326 20987 20326 20912 20326 20912 20327 20987 20327 20989 20327 20990 20328 20994 20328 20991 20328 20991 20329 20994 20329 21002 20329 20991 20330 21002 20330 21003 20330 21706 20331 21444 20331 21688 20331 21688 20332 21444 20332 20992 20332 21688 20333 20992 20333 20990 20333 20990 20334 20992 20334 20993 20334 20990 20335 20993 20335 20994 20335 20998 20336 20995 20336 21706 20336 21706 20337 20995 20337 21445 20337 21706 20338 21445 20338 21444 20338 21000 20339 21001 20339 20996 20339 20996 20340 21001 20340 20997 20340 20996 20341 20997 20341 20998 20341 20998 20342 20997 20342 21442 20342 20998 20343 21442 20343 20995 20343 20999 20344 21437 20344 21000 20344 21000 20345 21437 20345 21436 20345 21000 20346 21436 20346 21001 20346 21686 20347 21536 20347 20999 20347 20999 20348 21536 20349 21539 20350 20999 20351 21539 20351 21437 20351 21701 20352 21004 20352 21686 20352 21686 20353 21004 20353 21535 20353 21686 20354 21535 20354 21536 20354 21002 20355 21432 20356 21003 20357 21003 20358 21432 20358 21434 20358 21003 20358 21434 20358 21702 20358 21702 20359 21434 20359 21435 20359 21702 20360 21435 20360 21701 20360 21701 20361 21435 20361 21534 20361 21701 20362 21534 20362 21004 20362 21105 20363 21104 20363 21005 20363 21081 20364 21083 20364 21198 20364 21468 20365 21056 20365 21063 20365 21006 20366 21142 20366 21007 20366 21007 20367 21142 20367 21016 20367 21007 20368 21016 20368 21543 20368 21006 20369 21008 20369 21142 20369 21142 20370 21008 20370 21009 20370 21142 20371 21009 20371 21144 20371 21143 20372 21010 20372 21014 20372 21014 20373 21010 20373 21011 20373 21014 20374 21011 20374 21012 20374 21012 20375 21013 20375 21014 20375 21014 20376 21013 20376 21015 20376 21014 20377 21015 20377 21175 20377 21017 20378 21330 20378 21016 20378 21016 20379 21330 20379 21544 20379 21016 20380 21544 20380 21543 20380 21020 20381 21532 20381 21017 20381 21017 20382 21532 20382 21531 20382 21017 20383 21531 20383 21330 20383 21018 20384 21019 20384 21020 20384 21020 20385 21019 20385 21533 20385 21020 20386 21533 20386 21532 20386 21032 20387 21540 20387 21021 20387 21021 20388 21540 20388 21538 20388 21021 20389 21538 20389 21018 20389 21018 20390 21538 20390 21537 20390 21018 20391 21537 20391 21019 20391 21157 20392 21027 20392 21158 20392 21022 20393 21156 20393 21024 20393 21022 20394 21024 20394 21023 20394 21181 20395 21025 20395 21024 20395 21024 20396 21025 20396 21026 20396 21024 20397 21026 20397 21023 20397 21027 20398 21028 20398 21158 20398 21158 20399 21028 20399 21029 20399 21158 20400 21029 20400 21032 20400 21032 20401 21029 20401 21030 20401 21032 20402 21030 20402 21031 20402 21031 20403 21438 20403 21032 20403 21032 20404 21438 20404 21541 20404 21032 20405 21541 20405 21540 20405 21038 20406 21033 20406 21181 20406 21181 20407 21033 20407 21034 20407 21181 20408 21034 20408 21025 20408 21035 13441 21036 13441 21177 13441 21177 13442 21036 13442 21037 13442 21177 20409 21037 20409 21178 20409 21178 20410 21037 20410 21038 20410 21178 20411 21038 20411 21180 20411 21180 20412 21038 20412 21181 20412 21015 20413 21039 20413 21175 20413 21175 20414 21039 20414 21040 20414 21175 20415 21040 20415 21035 20415 21035 20416 21040 20416 21041 20416 21035 20417 21041 20417 21036 20417 21045 20418 21042 20418 21043 20418 21043 20419 21042 20419 21044 20419 21043 20420 21044 20420 21478 20420 21045 20421 21046 20421 21042 20421 21042 20422 21046 20422 21047 20422 21042 20423 21047 20423 21048 20423 21049 20424 21050 20424 21053 20424 21053 20425 21050 20425 21051 20425 21053 20426 21051 20426 21052 20426 21052 20427 21054 20427 21053 20427 21053 20428 21054 20428 21055 20428 21053 20429 21055 20429 21084 20429 21060 20430 21480 20430 21044 20430 21044 20431 21480 20431 21479 20431 21044 20432 21479 20432 21478 20432 21056 20433 21468 20433 21057 20433 21057 20434 21468 20434 21058 20434 21057 20435 21058 20435 21059 20435 21059 20436 21058 20436 21471 20436 21059 20437 21471 20437 21060 20437 21060 20438 21471 20438 21473 20438 21060 20439 21473 20439 21480 20439 21074 20440 21354 20440 21062 20440 21062 20441 21354 20441 21061 20441 21062 20442 21061 20442 21063 20442 21063 20443 21061 20443 21467 20443 21063 20444 21467 20444 21468 20444 21132 20445 21069 20445 21071 20445 21064 20446 21065 20446 21133 20446 21064 20447 21133 20447 21066 20447 21076 20448 21067 20448 21133 20448 21133 20449 21067 20449 21068 20449 21133 20450 21068 20450 21066 20450 21069 20451 21070 20451 21071 20451 21071 20452 21070 20452 21072 20452 21071 20453 21072 20453 21062 20453 21062 20454 21072 20454 21073 20454 21062 20455 21073 20455 21074 20455 21078 20456 21075 20456 21076 20456 21076 20457 21075 20457 21077 20457 21076 20458 21077 20458 21067 20458 21076 20459 21169 20459 21078 20459 21078 20460 21169 20460 21080 20460 21078 20461 21080 20461 21079 20461 21079 20462 21080 20462 21081 20462 21081 20463 21080 20463 21082 20463 21081 20464 21082 20464 21083 20464 21055 20465 21085 20465 21084 20465 21084 20466 21085 20466 21086 20466 21084 13337 21086 13337 21198 13337 21198 13338 21086 13338 21087 13338 21198 20467 21087 20467 21081 20467 21088 20468 21093 20468 21089 20468 21089 20469 21093 20469 21090 20469 21089 20470 21090 20470 21100 20470 21088 20471 21091 20471 21093 20471 21093 20472 21091 20472 21092 20472 21093 20473 21092 20473 21167 20473 21166 20474 21094 20474 21095 20474 21095 20475 21094 20475 21096 20475 21095 20476 21096 20476 21097 20476 21097 20477 21098 20477 21095 20477 21095 20478 21098 20478 21128 20478 21095 20479 21128 20479 21099 20479 21100 20480 21090 20480 21511 20480 21511 20481 21090 20481 21101 20481 21511 20482 21101 20482 21102 20482 21102 20483 21101 20483 21103 20483 21103 20484 21101 20484 21106 20484 21103 20485 21106 20485 21334 20485 21104 20486 21105 20486 21106 20486 21106 20487 21105 20487 21378 20487 21106 20488 21378 20488 21334 20488 21107 20489 21489 20489 21118 20489 21118 20490 21489 20490 21490 20490 21118 20491 21490 20491 21005 20491 21005 20492 21490 20492 21108 20492 21005 20493 21108 20493 21105 20493 21146 20494 21109 20494 21110 20494 21111 20495 21145 20495 21114 20495 21111 20496 21114 20496 21112 20496 21191 20497 21113 20497 21114 20497 21114 20498 21113 20498 21115 20498 21114 20499 21115 20499 21112 20499 21109 20500 21116 20500 21110 20500 21110 20501 21116 20501 21117 20501 21110 20502 21117 20502 21118 20502 21118 20503 21117 20503 21119 20503 21118 20504 21119 20504 21107 20504 21127 20505 21120 20505 21191 20505 21191 20506 21120 20507 21121 20508 21191 20509 21121 20509 21113 20509 21187 20510 21123 20510 21122 20510 21122 20511 21123 20511 21124 20511 21122 20512 21124 20512 21125 20512 21125 20513 21124 20513 21127 20513 21125 20514 21127 20514 21126 20514 21126 20515 21127 20515 21191 20515 21128 20516 21129 20516 21099 20516 21099 20517 21129 20517 21130 20517 21099 20518 21130 20518 21187 20518 21187 20519 21130 20519 21131 20519 21187 20520 21131 20520 21123 20520 21065 20521 21132 20521 21133 20521 21133 20522 21132 20522 21071 20522 21133 20523 21071 20523 21171 20523 21171 13487 21071 13487 21135 13487 21171 20524 21135 20524 21134 20524 21134 20525 21135 20525 21137 20525 21134 20526 21137 20526 21136 20526 21136 20527 21137 20527 21138 20527 21136 20528 21138 20528 21173 20528 21173 20529 21138 20529 21140 20529 21173 20530 21140 20530 21139 20530 21139 20531 21140 20531 21141 20531 21139 20532 21141 20532 21014 20532 21014 13497 21141 13497 21142 13497 21014 20533 21142 20533 21143 20533 21143 20534 21142 20534 21144 20534 21145 20535 21146 20535 21114 20535 21114 20536 21146 20536 21110 20536 21114 20537 21110 20537 21147 20537 21147 20538 21110 20538 21148 20538 21147 20539 21148 20539 21149 20539 21149 20540 21148 20540 21150 20540 21149 20541 21150 20541 21151 20541 21151 20542 21150 20542 21153 20542 21151 20543 21153 20543 21152 20543 21152 13461 21153 13461 21154 13461 21152 20544 21154 20544 21194 20544 21194 20545 21154 20545 21155 20545 21194 20546 21155 20546 21053 20546 21053 20547 21155 20547 21042 20547 21053 20548 21042 20548 21049 20548 21049 20549 21042 20549 21048 20549 21156 20550 21157 20550 21024 20550 21024 20551 21157 20551 21158 20551 21024 20552 21158 20552 21183 20552 21183 20553 21158 20553 21160 20553 21183 20554 21160 20554 21159 20554 21159 20555 21160 20555 21161 20555 21159 20556 21161 20556 21185 20556 21185 20557 21161 20557 21162 20557 21185 20558 21162 20558 21186 20558 21186 20559 21162 20559 21163 20559 21186 20560 21163 20560 21164 20560 21164 20561 21163 20561 21165 20561 21164 20562 21165 20562 21095 20562 21095 13481 21165 13481 21093 13481 21095 20563 21093 20563 21166 20563 21166 20564 21093 20564 21167 20564 21083 960 21082 960 21199 960 21199 20565 21082 20565 21080 20565 21199 20566 21080 20566 21168 20566 21168 960 21080 960 21169 960 21168 20567 21169 20567 21265 20567 21265 960 21169 960 21076 960 21265 960 21076 960 21170 960 21170 960 21076 960 21133 960 21170 960 21133 960 21276 960 21276 20568 21133 20568 21171 20568 21276 960 21171 960 21307 960 21307 960 21171 960 21134 960 21307 960 21134 960 21310 960 21310 960 21134 960 21136 960 21310 960 21136 960 21172 960 21172 960 21136 960 21173 960 21172 960 21173 960 21303 960 21303 960 21173 960 21139 960 21303 20569 21139 20569 21174 20569 21174 960 21139 960 21014 960 21174 960 21014 960 21201 960 21201 960 21014 960 21175 960 21201 960 21175 960 21176 960 21176 960 21175 960 21035 960 21176 960 21035 960 21202 960 21202 960 21035 960 21177 960 21202 960 21177 960 21179 960 21179 20570 21177 20570 21178 20570 21179 20571 21178 20571 21205 20571 21205 960 21178 960 21180 960 21205 20572 21180 20572 21219 20572 21219 960 21180 960 21181 960 21219 960 21181 960 21212 960 21212 960 21181 960 21024 960 21212 960 21024 960 21182 960 21182 960 21024 960 21183 960 21182 20573 21183 20573 21184 20573 21184 960 21183 960 21159 960 21184 960 21159 960 21326 960 21326 960 21159 960 21185 960 21326 960 21185 960 21324 960 21324 960 21185 960 21186 960 21324 20574 21186 20574 21321 20574 21321 960 21186 960 21164 960 21321 20575 21164 20575 21225 20575 21225 960 21164 960 21095 960 21225 960 21095 960 21237 960 21237 960 21095 960 21099 960 21237 960 21099 960 21236 960 21236 20576 21099 20576 21187 20576 21236 960 21187 960 21188 960 21188 960 21187 960 21122 960 21188 960 21122 960 21189 960 21189 960 21122 960 21125 960 21189 960 21125 960 21240 960 21240 20577 21125 20577 21126 20577 21240 20578 21126 20578 21190 20578 21190 20579 21126 20579 21191 20579 21190 960 21191 960 21248 960 21248 960 21191 960 21114 960 21248 20580 21114 20580 21318 20580 21318 20581 21114 20581 21147 20581 21318 960 21147 960 21319 960 21319 960 21147 960 21149 960 21319 960 21149 960 21192 960 21192 20582 21149 20582 21151 20582 21192 960 21151 960 21193 960 21193 20583 21151 20583 21152 20583 21193 960 21152 960 21261 960 21261 960 21152 960 21194 960 21261 960 21194 960 21195 960 21195 960 21194 960 21053 960 21195 960 21053 960 21196 960 21196 20584 21053 20584 21084 20584 21196 960 21084 960 21197 960 21197 20585 21084 20585 21198 20585 21197 20586 21198 20586 21199 20586 21199 960 21198 960 21083 960 21260 20587 21200 20587 21258 20587 21232 20588 21510 20588 21508 20588 21201 20589 21176 20589 21290 20589 21290 20590 21176 20590 21202 20590 21290 20591 21202 20591 21203 20591 21203 20592 21202 20592 21179 20592 21203 20593 21179 20593 21204 20593 21204 20594 21179 20594 21205 20594 21204 20595 21205 20595 21206 20595 21206 20596 21205 20596 21219 20596 21206 20597 21219 20597 21221 20597 21211 20598 21207 20598 21212 20598 21213 20599 21300 20599 21208 20599 21208 20600 21300 20600 21210 20600 21208 20601 21210 20601 21209 20601 21209 20602 21210 20602 21441 20602 21211 20603 21212 20603 21299 20603 21213 20604 21214 20604 21300 20604 21300 20605 21214 20605 21215 20605 21300 20606 21215 20606 21216 20606 21207 20607 21217 20607 21212 20607 21212 20608 21217 20608 21218 20608 21212 20609 21218 20609 21219 20609 21219 20610 21218 20610 21220 20610 21219 20611 21220 20611 21221 20611 21222 20612 21228 20612 21513 20612 21222 20613 21513 20613 21227 20613 21223 20614 21224 20614 21225 20614 21225 20615 21224 20615 21226 20615 21225 20616 21226 20616 21227 20616 21228 20617 21229 20617 21513 20617 21513 20618 21229 20618 21230 20618 21513 20619 21230 20619 21508 20619 21508 20620 21230 20620 21231 20620 21508 20621 21231 20621 21232 20621 21240 20622 21242 20622 21189 20622 21189 20623 21242 20623 21233 20623 21189 20624 21233 20624 21188 20624 21188 20625 21233 20625 21234 20625 21188 20626 21234 20626 21236 20626 21236 20627 21234 20627 21235 20627 21236 20628 21235 20628 21237 20628 21237 20629 21235 20629 21238 20629 21237 20630 21238 20630 21225 20630 21225 20631 21238 20631 21239 20631 21225 20632 21239 20632 21223 20632 21190 20633 21253 20633 21240 20633 21240 20634 21253 20634 21241 20634 21240 20635 21241 20635 21242 20635 21498 20636 21500 20636 21243 20636 21243 20637 21244 20637 21498 20637 21498 20638 21244 20638 21245 20638 21498 20639 21245 20639 21246 20639 21316 20640 21247 20640 21248 20640 21248 20641 21247 20641 21249 20641 21249 20642 21250 20642 21248 20642 21248 20643 21250 20643 21251 20643 21248 20644 21251 20644 21190 20644 21190 20645 21251 20645 21252 20645 21190 20646 21252 20646 21253 20646 21312 20647 21254 20647 21313 20647 21313 20648 21254 20648 21256 20648 21313 20649 21256 20649 21255 20649 21255 20650 21256 20650 21257 20650 21255 20651 21257 20651 21258 20651 21258 20652 21257 20653 21259 20654 21258 20655 21259 20656 21260 20657 21311 20658 21261 20658 21262 20658 21262 20659 21261 20659 21195 20659 21262 20660 21195 20660 21263 20660 21263 20661 21195 20661 21264 20661 21265 20662 21266 20662 21168 20662 21168 20663 21266 20663 21267 20663 21168 20664 21267 20664 21199 20664 21199 20665 21267 20665 21268 20665 21199 20666 21268 20666 21197 20666 21197 20667 21268 20667 21269 20667 21197 20668 21269 20668 21196 20668 21196 20669 21269 20669 21270 20669 21196 20670 21270 20670 21195 20670 21195 20671 21270 20671 21271 20671 21195 20672 21271 20672 21264 20672 21280 20673 21272 20673 21170 20673 21170 20674 21272 20674 21273 20674 21170 20675 21273 20675 21265 20675 21265 20676 21273 20676 21274 20676 21265 20677 21274 20677 21266 20677 21275 20678 21277 20678 21276 20678 21276 20679 21277 20679 21278 20679 21276 20680 21278 20680 21170 20680 21170 20681 21278 20681 21279 20681 21170 20682 21279 20682 21280 20682 21555 20683 21281 20684 21283 20685 21283 20686 21281 20686 21282 20686 21283 20687 21282 20687 21284 20687 21284 20688 21282 20688 21285 20688 21284 20689 21285 20689 21558 20689 21558 20690 21285 20690 21286 20690 21558 20691 21286 20691 21287 20691 21295 20692 21296 20692 21302 20692 21289 20693 21288 20693 21174 20693 21289 20694 21174 20694 21294 20694 21290 20695 21291 20695 21201 20695 21201 20696 21291 20696 21292 20696 21201 20697 21292 20697 21174 20697 21174 20698 21292 20698 21293 20698 21174 20699 21293 20699 21294 20699 21295 20700 21302 20700 21288 20700 21296 20701 21297 20701 21302 20701 21302 20702 21297 20702 21298 20702 21302 20703 21298 20703 21542 20703 21216 20704 21299 20704 21300 20704 21300 20705 21299 20705 21212 20705 21300 20706 21212 20706 21301 20706 21301 20707 21212 20707 21182 20707 21301 20708 21182 20708 21391 20708 21391 20709 21182 20709 21184 20709 21391 20710 21184 20710 21327 20710 21288 20711 21302 20711 21174 20711 21174 20712 21302 20712 21305 20712 21174 20713 21305 20713 21303 20713 21546 20714 21172 20714 21304 20714 21304 20715 21172 20715 21303 20715 21304 20716 21303 20716 21453 20716 21453 20717 21303 20717 21305 20717 21286 20718 21275 20718 21287 20718 21287 20719 21275 20719 21276 20719 21287 20720 21276 20720 21306 20720 21306 20721 21276 20721 21307 20721 21306 20722 21307 20722 21308 20722 21308 20723 21307 20723 21310 20723 21308 20724 21310 20724 21309 20724 21309 20725 21310 20725 21172 20725 21309 20726 21172 20726 21328 20726 21328 20727 21172 20728 21546 20729 21311 20730 21312 20730 21261 20730 21261 20731 21312 20731 21313 20731 21261 20732 21313 20732 21193 20732 21193 20733 21313 20733 21315 20733 21193 20734 21315 20734 21192 20734 21348 20735 21319 20735 21314 20735 21314 20736 21319 20736 21192 20736 21314 20737 21192 20737 21345 20737 21345 20738 21192 20738 21315 20738 21246 20739 21316 20739 21498 20739 21498 20740 21316 20740 21248 20740 21498 20741 21248 20741 21317 20741 21317 20742 21248 20742 21318 20742 21317 20743 21318 20743 21504 20743 21504 20744 21318 20744 21319 20744 21504 20745 21319 20745 21320 20745 21320 20746 21319 20746 21348 20746 21227 20747 21513 20747 21225 20747 21225 20748 21513 20748 21514 20748 21225 20749 21514 20749 21321 20749 21514 20750 21322 20750 21321 20750 21321 20751 21322 20751 21323 20751 21321 20752 21323 20752 21324 20752 21323 20753 21331 20753 21324 20753 21324 20754 21331 20754 21325 20754 21324 20755 21325 20755 21326 20755 21326 20756 21325 20756 21529 20756 21326 20757 21529 20757 21184 20757 21184 20758 21529 20758 21528 20758 21184 20759 21528 20759 21327 20759 21328 20760 21329 20760 21358 20760 21546 20761 21304 20761 21548 20761 21544 20762 21330 20762 21530 20762 21529 20763 21325 20763 21331 20763 21573 20764 21332 20764 21400 20764 21333 960 21517 960 21418 960 21334 960 21378 960 21512 960 21335 20765 21336 20765 21418 20765 21547 20766 21355 20766 21329 20766 21200 960 21481 960 21340 960 21340 20767 21337 20767 21200 20767 21200 20768 21337 20768 21341 20768 21200 960 21341 960 21258 960 21258 960 21341 960 21255 960 21429 20769 21338 20769 21481 20769 21481 960 21338 960 21339 960 21481 960 21339 960 21340 960 21341 960 21342 960 21255 960 21255 20770 21342 20770 21343 20770 21255 20771 21343 20771 21313 20771 21313 960 21343 960 21344 960 21313 20772 21344 20772 21315 20772 21315 960 21344 960 21346 960 21315 20773 21346 20773 21345 20773 21345 20774 21346 20774 21347 20774 21345 20775 21347 20775 21314 20775 21314 960 21347 960 21349 960 21314 20776 21349 20776 21348 20776 21348 20777 21349 20777 21483 20777 21484 960 21350 960 21352 960 21352 960 21350 960 21351 960 21352 960 21351 960 21429 960 21429 960 21351 960 21353 960 21429 960 21353 960 21338 960 21074 960 21555 960 21354 960 21354 960 21555 960 21400 960 21354 960 21400 960 21061 960 21358 20778 21360 20778 21557 20778 21355 20779 21356 20779 21329 20779 21329 960 21356 960 21357 960 21329 960 21357 960 21358 960 21358 20780 21357 20780 21359 20780 21358 20781 21359 20781 21360 20781 21361 20782 21362 20782 21550 20782 21550 960 21362 960 21551 960 21551 960 21362 960 21363 960 21363 960 21362 960 21365 960 21363 960 21365 960 21366 960 21400 960 21552 960 21364 960 21368 960 21401 960 21370 960 21365 20783 21367 20783 21366 20783 21366 960 21367 960 21368 960 21366 20784 21368 20784 21369 20784 21369 960 21368 960 21370 960 21371 960 21372 960 21527 960 21527 20785 21372 20785 21373 20785 21527 20786 21373 20786 21374 20786 21371 960 21527 960 21375 960 21375 960 21527 960 21509 960 21375 960 21509 960 21376 960 21334 960 21512 960 21103 960 21490 960 21485 960 21108 960 21108 960 21485 960 21377 960 21108 960 21377 960 21105 960 21105 960 21377 960 21378 960 21378 20787 21377 20787 21379 20787 21378 20788 21379 20788 21512 20788 21387 20789 21380 20789 21414 20789 21414 20790 21380 20790 21381 20790 21382 960 21383 960 21440 960 21383 960 21384 960 21440 960 21440 20791 21384 20791 21385 20791 21440 960 21385 960 21414 960 21414 20792 21385 20792 21386 20792 21414 20793 21386 20793 21387 20793 21388 20794 21515 20794 21389 20794 21323 20795 21390 20795 21397 20795 21439 960 21391 960 21392 960 21392 960 21391 960 21327 960 21392 960 21327 960 21393 960 21380 20796 21394 20796 21381 20796 21381 20797 21394 20797 21395 20797 21381 960 21395 960 21389 960 21389 20798 21395 20798 21396 20798 21389 20799 21396 20799 21388 20799 21323 960 21397 960 21331 960 21397 20800 21398 20800 21331 20800 21331 20801 21398 20801 21399 20801 21331 20802 21399 20802 21393 20802 21405 960 21400 960 21401 960 21401 20803 21400 20803 21364 20803 21401 20804 21364 20804 21370 20804 21402 960 21477 960 21403 960 21403 960 21477 960 21400 960 21403 20805 21400 20805 21404 20805 21404 960 21400 960 21405 960 21433 20806 21431 20806 21406 20806 21406 960 21407 960 21433 960 21433 960 21407 960 21408 960 21433 20807 21408 20807 21550 20807 21550 960 21408 960 21409 960 21550 20808 21409 20808 21361 20808 21415 960 21410 960 21414 960 21414 20809 21410 20809 21443 20809 21526 960 21411 960 21381 960 21381 20810 21411 20810 21412 20810 21381 20811 21412 20811 21414 20811 21414 960 21412 960 21413 960 21414 960 21413 960 21415 960 21416 20812 21417 20812 21423 20812 21423 20813 21417 20813 21419 20813 21423 20814 21419 20814 21418 20814 21418 20815 21419 20815 21420 20815 21418 20816 21420 20816 21333 20816 21429 960 21421 960 21352 960 21352 960 21421 960 21422 960 21352 960 21422 960 21423 960 21423 960 21422 960 21424 960 21423 960 21424 960 21416 960 21402 20817 21425 20817 21477 20817 21477 20818 21425 20818 21426 20818 21477 20819 21426 20819 21481 20819 21481 20820 21426 20820 21427 20820 21481 20821 21427 20821 21429 20821 21429 20822 21427 20822 21428 20822 21429 20823 21428 20823 21421 20823 21443 20824 21430 20824 20994 20824 20994 960 21430 960 21431 960 20994 960 21431 960 21002 960 21002 960 21431 960 21433 960 21002 960 21433 960 21432 960 21432 960 21433 960 21434 960 21530 960 21534 960 21458 960 21458 20825 21534 20825 21435 20825 21458 20826 21435 20826 21434 20826 21436 20827 21437 20827 21438 20827 21438 20828 21031 20828 21441 20828 21439 960 21382 960 21391 960 21391 960 21382 960 21440 960 21391 960 21440 960 21301 960 21301 20829 21440 20829 20995 20829 21301 20830 20995 20830 21442 20830 21436 20831 21438 20831 21001 20831 21001 20832 21438 20832 21441 20832 21001 960 21441 960 20997 960 20997 20833 21441 20833 21210 20833 20997 960 21210 960 21442 960 21442 20834 21210 20834 21300 20834 21442 960 21300 960 21301 960 20994 960 20993 960 21443 960 21443 960 20993 960 20992 960 21443 20835 20992 20835 21414 20835 21414 20836 20992 20836 21444 20836 21414 20837 21444 20837 21440 20837 21440 20838 21444 20838 21445 20838 21440 20839 21445 20839 20995 20839 21446 960 21530 960 21447 960 21447 960 21530 960 21458 960 21447 960 21458 960 21448 960 21448 960 21458 960 21449 960 21450 960 21548 960 21451 960 21451 960 21548 960 21304 960 21451 960 21304 960 21452 960 21452 20840 21304 20840 21453 20840 21452 960 21453 960 21454 960 21454 20841 21453 20841 21305 20841 21454 960 21305 960 21455 960 21446 20842 21456 20842 21530 20842 21530 960 21456 960 21457 960 21530 960 21457 960 21545 960 21434 960 21433 960 21458 960 21458 20843 21433 20843 21459 20843 21458 20844 21459 20844 21449 20844 21450 20845 21460 20845 21548 20845 21548 960 21460 960 21461 960 21548 20846 21461 20846 21550 20846 21550 20847 21461 20847 21462 20847 21462 20848 21463 20848 21550 20848 21550 20849 21463 20849 21464 20849 21550 20850 21464 20850 21433 20850 21433 20851 21464 20851 21465 20851 21433 20852 21465 20852 21459 20852 21477 20853 21482 20853 21474 20853 21332 20854 21575 20854 21400 20854 21400 960 21575 960 21466 960 21400 960 21466 960 21061 960 21061 20855 21466 20855 21576 20855 21061 20856 21576 20856 21467 20856 21467 20857 21576 20857 21578 20857 21467 20858 21578 20858 21468 20858 21578 960 21469 960 21468 960 21468 20859 21469 20859 21470 20859 21468 20860 21470 20860 21058 20860 21058 960 21470 960 21563 960 21058 20861 21563 20861 21471 20861 21471 960 21563 960 21560 960 21471 960 21560 960 21473 960 21473 20862 21560 20862 21472 20862 21473 960 21472 960 21568 960 21474 960 21475 960 21477 960 21477 20863 21475 20863 21476 20863 21477 20864 21476 20864 21400 20864 21400 20865 21476 20865 21571 20865 21400 20866 21571 20866 21573 20866 21478 13848 21479 13848 21200 13848 21200 20867 21479 20867 21480 20867 21200 960 21480 960 21481 960 21481 20868 21480 20868 21473 20868 21481 960 21473 960 21477 960 21477 960 21473 960 21568 960 21477 20869 21568 20869 21482 20869 21483 20870 21484 20870 21348 20870 21348 20871 21484 20871 21352 20871 21348 960 21352 960 21320 960 21320 20872 21352 20872 21423 20872 21320 960 21423 960 21504 960 21486 20873 21418 20873 21490 20873 21490 20874 21418 20874 21336 20874 21490 20875 21336 20875 21485 20875 21486 20876 21487 20876 21418 20876 21418 960 21487 960 21488 960 21418 960 21488 960 21493 960 21107 960 21500 960 21489 960 21489 20877 21500 20877 21491 20877 21489 960 21491 960 21490 960 21490 20878 21491 20878 21492 20878 21490 20879 21492 20879 21486 20879 21493 20880 21494 20880 21418 20880 21418 20881 21494 20881 21495 20881 21418 20882 21495 20882 21423 20882 21423 20883 21495 20883 21496 20883 21423 20884 21496 20884 21497 20884 21498 20885 21507 20885 21500 20885 21500 20886 21507 20886 21499 20886 21500 960 21499 960 21491 960 21497 960 21501 960 21423 960 21423 20887 21501 20887 21502 20887 21423 20888 21502 20888 21504 20888 21504 20889 21502 20889 21503 20889 21504 960 21503 960 21317 960 21317 960 21503 960 21505 960 21317 20890 21505 20890 21498 20890 21498 960 21505 960 21506 960 21498 960 21506 960 21507 960 21508 960 21510 960 21509 960 21509 20891 21510 20891 21100 20891 21509 20892 21100 20892 21511 20892 21512 20893 21376 20893 21103 20893 21103 960 21376 960 21509 960 21103 20894 21509 20894 21102 20894 21102 960 21509 960 21511 960 21508 960 21509 960 21513 960 21513 20895 21509 20895 21527 20895 21513 960 21527 960 21514 960 21322 960 21389 960 21323 960 21323 20896 21389 20896 21515 20896 21323 20897 21515 20897 21390 20897 21335 20898 21418 20898 21516 20898 21516 20899 21418 20899 21517 20899 21516 20900 21517 20900 21518 20900 21518 960 21517 960 21519 960 21518 960 21519 960 21521 960 21521 20901 21519 20901 21520 20901 21521 960 21520 960 21523 960 21523 960 21520 960 21522 960 21523 20902 21522 20902 21524 20902 21524 20903 21522 20903 21526 20903 21524 960 21526 960 21525 960 21525 20904 21526 20904 21381 20904 21525 960 21381 960 21374 960 21374 960 21381 960 21389 960 21374 960 21389 960 21527 960 21527 960 21389 960 21322 960 21527 20905 21322 20905 21514 20905 21393 20906 21327 20906 21331 20906 21331 20907 21327 20907 21528 20907 21331 960 21528 960 21529 960 21330 20908 21531 20908 21530 20908 21530 960 21531 960 21532 960 21530 960 21532 960 21534 960 21534 20909 21532 20909 21533 20909 21534 960 21533 960 21004 960 21004 20910 21533 20910 21019 20910 21004 960 21019 960 21535 960 21535 960 21019 960 21537 960 21535 20911 21537 20911 21536 20911 21536 20912 21537 20912 21538 20912 21536 20913 21538 20913 21539 20913 21539 960 21538 960 21540 960 21539 960 21540 960 21437 960 21437 960 21540 960 21541 960 21437 20914 21541 20914 21438 20914 21305 20915 21302 20915 21542 20915 21543 960 21544 960 21542 960 21542 960 21544 960 21530 960 21542 20916 21530 20916 21305 20916 21305 20917 21530 20917 21545 20917 21305 20918 21545 20918 21455 20918 21328 960 21546 960 21329 960 21329 960 21546 960 21548 960 21329 960 21548 960 21547 960 21547 20919 21548 20919 21550 20919 21547 20920 21550 20920 21549 20920 21549 20921 21550 20921 21551 20921 21306 960 21308 960 21358 960 21358 20922 21308 20922 21309 20922 21358 960 21309 960 21328 960 21552 960 21400 960 21553 960 21553 20923 21400 20923 21555 20923 21553 960 21555 960 21554 960 21554 20924 21555 20924 21283 20924 21554 960 21283 960 21556 960 21556 20925 21283 20925 21284 20925 21556 960 21284 960 21557 960 21557 20926 21284 20926 21558 20926 21557 960 21558 960 21358 960 21358 20927 21558 20927 21287 20927 21358 20928 21287 20928 21306 20928 21563 20929 21559 20929 21560 20929 21560 20930 21559 20930 21561 20930 21560 20931 21561 20931 21643 20931 21469 20932 21562 20932 21470 20932 21470 20933 21562 20933 21564 20933 21470 20934 21564 20934 21563 20934 21563 20935 21564 20935 21565 20935 21563 20936 21565 20936 21559 20936 21578 20937 21579 20937 21469 20937 21469 20938 21579 20938 21566 20938 21469 20939 21566 20939 21562 20939 21643 20940 21642 20941 21560 20942 21560 20943 21642 20943 21567 20943 21560 20944 21567 20944 21472 20944 21472 20945 21567 20945 21664 20945 21472 20946 21664 20946 21568 20946 21568 20947 21664 20947 21651 20947 21568 20947 21651 20947 21482 20947 21482 20948 21651 20948 21569 20948 21482 20949 21569 20949 21474 20949 21474 20950 21569 20950 21570 20950 21474 20951 21570 20951 21475 20951 21475 20952 21570 20952 21660 20952 21475 20953 21660 20953 21476 20953 21476 20954 21660 20954 21652 20954 21476 20954 21652 20954 21571 20954 21571 20955 21652 20955 21572 20955 21571 20956 21572 20956 21573 20956 21573 20957 21572 20957 21574 20957 21573 20958 21574 20958 21332 20958 21332 20959 21574 20959 21657 20959 21332 20960 21657 20960 21575 20960 21575 20961 21657 20961 21656 20961 21575 20962 21656 20962 21466 20962 21466 20963 21656 20963 21654 20963 21466 20964 21654 20964 21576 20964 21576 20965 21654 20965 21653 20965 21576 20966 21653 20966 21578 20966 21578 20967 21653 20967 21577 20967 21578 20968 21577 20968 21579 20968 21580 590 21581 590 21582 590 21620 590 21631 590 21630 590 21597 590 21584 590 21583 590 21583 20969 21584 20969 21585 20969 21583 20970 21585 20970 21586 20970 21587 590 21588 590 21589 590 21590 20971 21626 20971 21718 20971 21633 590 21591 590 21635 590 21623 590 21592 590 21593 590 21593 20972 21592 20972 21595 20972 21593 590 21595 590 21594 590 21594 20973 21595 20973 21596 20973 21594 590 21596 590 21598 590 21596 20974 21597 20974 21598 20974 21598 20975 21597 20975 21583 20975 21598 590 21583 590 21599 590 21599 590 21583 590 21601 590 21599 20976 21601 20976 21600 20976 21600 20977 21601 20977 21602 20977 21600 590 21602 590 21603 590 21603 20978 21602 20978 21604 20978 21603 590 21604 590 21605 590 21605 20979 21604 20979 21606 20979 21605 590 21606 590 21615 590 21615 20980 21606 20980 21607 20980 21587 590 21589 590 21608 590 21608 20981 21589 20981 21609 20981 21608 20982 21609 20982 21610 20982 21611 590 21629 590 21622 590 21622 20983 21629 20983 21727 20983 21612 590 21613 590 21607 590 21607 590 21613 590 21614 590 21607 20984 21614 20984 21615 20984 21615 590 21614 590 21616 590 21615 590 21616 590 21617 590 21617 590 21616 590 21618 590 21617 590 21618 590 21630 590 21630 20985 21618 20985 21619 20985 21630 20986 21619 20986 21620 20986 21727 590 21621 590 21622 590 21622 20987 21621 20987 21724 20987 21622 590 21724 590 21593 590 21593 20988 21724 20988 21723 20988 21593 20989 21723 20989 21623 20989 21723 20990 21624 20990 21623 20990 21623 590 21624 590 21625 590 21623 590 21625 590 21626 590 21626 20991 21625 20991 21627 20991 21626 20992 21627 20992 21718 20992 21641 590 21739 590 21687 590 21687 20993 21739 20993 21738 20993 21687 590 21738 590 21735 590 21735 590 21628 590 21636 590 21611 20994 21630 20994 21629 20994 21629 20995 21630 20995 21631 20995 21629 590 21631 590 21632 590 21632 590 21631 590 21639 590 21715 20996 21608 20996 21718 20996 21718 20997 21608 20997 21610 20997 21718 590 21610 590 21590 590 21633 20998 21635 20998 21634 20998 21634 590 21635 590 21636 590 21634 590 21636 590 21637 590 21637 590 21636 590 21628 590 21637 590 21628 590 21638 590 21638 20999 21628 20999 21732 20999 21638 590 21732 590 21639 590 21639 21000 21732 21000 21640 21000 21639 21001 21640 21001 21632 21001 21715 590 21714 590 21608 590 21608 21002 21714 21002 21711 21002 21608 21003 21711 21003 21687 21003 21687 21004 21711 21004 21742 21004 21687 21005 21742 21005 21641 21005 21642 590 21643 590 21666 590 21582 21006 21581 21006 21644 21006 21687 590 21658 590 21645 590 21687 21007 21645 21007 21608 21007 21608 21008 21645 21008 21646 21008 21608 21009 21646 21009 21647 21009 21581 21010 21648 21010 21644 21010 21644 590 21648 590 21649 590 21644 590 21649 590 21665 590 21665 21011 21649 21011 21663 21011 21661 590 21569 590 21650 590 21650 21012 21569 21012 21651 21012 21650 21013 21651 21013 21664 21013 21574 590 21572 590 21687 590 21687 21014 21572 21014 21652 21014 21687 590 21652 590 21660 590 21577 590 21653 590 21655 590 21655 590 21653 590 21654 590 21655 590 21654 590 21682 590 21682 590 21654 590 21656 590 21682 21015 21656 21015 21687 21015 21687 21016 21656 21016 21657 21016 21687 590 21657 590 21574 590 21658 590 21687 590 21659 590 21659 21017 21687 21017 21660 21017 21659 21018 21660 21018 21661 21018 21661 21019 21660 21019 21570 21019 21661 21020 21570 21020 21569 21020 21580 590 21582 590 21647 590 21647 21021 21582 21021 21662 21021 21647 590 21662 590 21608 590 21663 590 21650 590 21665 590 21665 590 21650 590 21664 590 21665 590 21664 590 21666 590 21666 590 21664 590 21567 590 21666 590 21567 590 21642 590 21667 21022 21678 21022 21668 21022 21668 590 21678 590 21670 590 21668 21023 21670 21023 21669 21023 21669 590 21670 590 21672 590 21669 590 21672 590 21671 590 21671 21024 21672 21024 21673 21024 21671 590 21673 590 21674 590 21674 21025 21673 21025 21676 21025 21674 590 21676 590 21675 590 21675 21026 21676 21026 21682 21026 21667 590 21677 590 21678 590 21678 590 21677 590 21679 590 21678 21027 21679 21027 21687 21027 21687 590 21679 590 21680 590 21680 21028 21681 21028 21687 21028 21687 21029 21681 21029 21683 21029 21687 21030 21683 21030 21682 21030 21682 21031 21683 21031 21684 21031 21682 21032 21684 21032 21675 21032 21687 590 20990 590 20991 590 21685 590 21686 590 20999 590 21685 21033 20999 21033 21704 21033 21735 21034 21636 21034 21687 21034 21687 21035 21636 21035 21688 21035 21687 21036 21688 21036 20990 21036 21702 590 21689 590 21003 590 21003 590 21689 590 21707 590 21003 590 21707 590 20991 590 21690 21037 21691 21037 21692 21037 21692 21038 21691 21038 21693 21038 21692 21039 21693 21039 21703 21039 21694 590 21695 590 21687 590 21687 590 21695 590 21696 590 21687 590 21696 590 21678 590 21678 21040 21696 21040 21697 21040 21678 590 21697 590 21698 590 21698 21041 21697 21041 21699 21041 21698 21042 21699 21042 21700 21042 21686 590 21685 590 21701 590 21701 590 21685 590 21703 590 21701 590 21703 590 21702 590 21702 21043 21703 21043 21693 21043 21702 21044 21693 21044 21689 21044 20999 590 21000 590 21704 590 21704 21045 21000 21045 20996 21045 21704 590 20996 590 21705 590 21705 21046 20996 21046 20998 21046 21705 21047 20998 21047 21636 21047 21636 21048 20998 21048 21706 21048 21636 21049 21706 21049 21688 21049 21707 21050 21708 21050 20991 21050 20991 21051 21708 21051 21709 21051 20991 590 21709 590 21687 590 21687 590 21709 590 21710 590 21687 590 21710 590 21694 590 21743 21052 21711 21052 21712 21052 21712 21053 21711 21053 21714 21053 21712 21054 21714 21054 21713 21054 21713 21055 21714 21055 21715 21055 21713 21056 21715 21056 21716 21056 21716 21057 21715 21057 21718 21057 21716 21058 21718 21058 21717 21058 21717 21059 21718 21059 21627 21059 21717 21060 21627 21060 21719 21060 21719 21061 21627 21061 21625 21061 21719 21062 21625 21062 21720 21062 21720 21063 21625 21063 21624 21063 21720 21064 21624 21064 21721 21064 21721 21065 21624 21065 21723 21065 21721 21066 21723 21066 21722 21066 21722 21067 21723 21067 21724 21067 21722 21067 21724 21067 21725 21067 21725 21068 21724 21068 21621 21068 21725 21069 21621 21069 21726 21069 21726 21070 21621 21070 21727 21070 21726 21071 21727 21071 21728 21071 21728 21072 21727 21072 21629 21072 21728 21073 21629 21073 21729 21073 21729 21074 21629 21074 21632 21074 21729 21075 21632 21075 21730 21075 21730 21076 21632 21076 21640 21076 21730 21076 21640 21076 21731 21076 21731 21077 21640 21077 21732 21077 21731 21078 21732 21078 21733 21078 21733 21079 21732 21079 21628 21079 21733 21080 21628 21080 21734 21080 21734 21081 21628 21081 21735 21081 21734 21081 21735 21081 21736 21081 21736 21082 21735 21082 21738 21082 21736 21083 21738 21083 21737 21083 21737 21084 21738 21084 21739 21084 21737 21085 21739 21085 21740 21085 21740 21086 21739 21086 21641 21086 21740 21087 21641 21087 21741 21087 21741 21088 21641 21088 21742 21088 21741 21089 21742 21089 21743 21089 21743 21090 21742 21090 21711 21090 21785 21091 21744 21091 21745 21091 21746 21092 21747 21092 21748 21092 21749 21093 21750 21093 21821 21093 21766 21094 21746 21094 21767 21094 21751 21095 21805 21095 21752 21095 21752 21096 21805 21096 21754 21096 21752 21097 21754 21097 21753 21097 21753 21098 21754 21098 21756 21098 21753 21099 21756 21099 21755 21099 21755 21100 21756 21100 21757 21100 21755 21101 21757 21101 21758 21101 21758 21102 21757 21102 21759 21102 21758 21103 21759 21103 21761 21103 21761 21104 21759 21104 21760 21104 21761 21105 21760 21105 21762 21105 21762 14584 21760 14584 21763 14584 21762 21106 21763 21106 21764 21106 21764 21107 21763 21107 21766 21107 21764 21107 21766 21107 21765 21107 21765 21108 21766 21108 21767 21108 21801 21109 21768 21109 21803 21109 21783 21110 21785 21110 21786 21110 21822 21111 21769 21111 21770 21111 21770 21112 21769 21112 21771 21112 21770 21113 21771 21113 21772 21113 21772 21114 21771 21114 21773 21114 21772 21115 21773 21115 21774 21115 21774 21116 21773 21116 21775 21116 21774 21117 21775 21117 21777 21117 21777 21118 21775 21118 21776 21118 21777 21119 21776 21119 21778 21119 21778 21120 21776 21120 21780 21120 21778 21121 21780 21121 21779 21121 21779 21122 21780 21122 21782 21122 21779 21123 21782 21123 21781 21123 21781 21124 21782 21124 21783 21124 21781 21125 21783 21125 21784 21125 21784 14570 21783 14570 21786 14570 21785 21126 21745 21126 21786 21126 21786 21127 21745 21127 21788 21127 21786 21127 21788 21127 21787 21127 21787 21128 21788 21128 21789 21128 21787 21129 21789 21129 21790 21129 21790 21130 21789 21130 21792 21130 21790 21131 21792 21131 21791 21131 21791 21132 21792 21132 21793 21132 21791 21133 21793 21133 21794 21133 21794 21134 21793 21134 21796 21134 21794 21135 21796 21135 21795 21135 21795 21136 21796 21136 21797 21136 21795 21137 21797 21137 21798 21137 21798 21138 21797 21138 21800 21138 21798 21138 21800 21138 21799 21138 21799 21139 21800 21139 21801 21139 21799 21140 21801 21140 21802 21140 21802 21141 21801 21141 21803 21141 21802 21142 21803 21142 21751 21142 21751 21143 21803 21143 21804 21143 21751 21144 21804 21144 21805 21144 21746 21145 21748 21145 21767 21145 21767 21146 21748 21146 21806 21146 21767 21147 21806 21147 21807 21147 21807 21148 21806 21148 21808 21148 21807 21149 21808 21149 21810 21149 21810 21150 21808 21150 21809 21150 21810 21151 21809 21151 21811 21151 21811 21152 21809 21152 21812 21152 21811 21153 21812 21153 21813 21153 21813 21154 21812 21154 21815 21154 21813 21155 21815 21155 21814 21155 21814 21156 21815 21156 21816 21156 21814 21157 21816 21157 21817 21157 21817 21158 21816 21158 21818 21158 21817 21159 21818 21159 21819 21159 21819 21160 21818 21160 21749 21160 21819 21161 21749 21161 21820 21161 21820 21162 21749 21162 21821 21162 21820 21163 21821 21163 21822 21163 21822 21164 21821 21164 21823 21164 21822 21165 21823 21165 21769 21165 21852 21166 21850 21166 21950 21166 21953 960 21950 960 21952 960 21952 21167 21950 21167 21824 21167 21953 960 21956 960 21950 960 21950 960 21956 960 21958 960 21950 21168 21958 21168 21852 21168 21865 21169 21948 21169 21849 21169 21849 21170 21948 21170 21825 21170 21860 21171 21837 21171 21838 21171 21838 21172 21826 21172 21860 21172 21860 21173 21826 21173 21827 21173 21860 21174 21827 21174 21828 21174 21827 21175 21972 21175 21828 21175 21828 21176 21972 21176 21829 21176 21828 21177 21829 21177 21830 21177 21830 21178 21829 21178 21831 21178 21830 21179 21831 21179 21861 21179 21831 21180 21832 21180 21861 21180 21861 21181 21832 21181 21833 21181 21861 21182 21833 21182 21834 21182 21833 21183 21960 21183 21834 21183 21834 21184 21960 21184 21986 21184 21834 21185 21986 21185 21865 21185 21865 21186 21986 21186 21987 21186 21865 21187 21987 21187 21948 21187 21941 21188 21943 21188 21944 21188 21947 960 21974 960 21946 960 21946 21189 21974 21189 21936 21189 21946 960 21936 960 21944 960 21944 960 21936 960 21835 960 21944 21190 21835 21190 21941 21190 21859 21191 21836 21191 21974 21191 21859 21192 21974 21192 21837 21192 21837 21193 21974 21193 21947 21193 21837 21191 21947 21191 21838 21191 21836 21194 21859 21194 21839 21194 21839 21195 21859 21195 21840 21195 21851 21196 21959 21196 21862 21196 21862 21197 21959 21197 21985 21197 21985 21198 21841 21198 21862 21198 21862 21199 21841 21199 21842 21199 21862 21200 21842 21200 21854 21200 21842 21201 21843 21201 21854 21201 21854 21202 21843 21202 21844 21202 21854 21203 21844 21203 21853 21203 21853 21204 21844 21204 21845 21204 21853 21205 21845 21205 21846 21205 21845 21206 21980 21206 21846 21206 21846 21207 21980 21207 21978 21207 21846 21208 21978 21208 21857 21208 21978 21209 21847 21209 21857 21209 21857 21210 21847 21210 21975 21210 21857 21211 21975 21211 21840 21211 21840 21212 21975 21212 21848 21212 21840 21213 21848 21213 21839 21213 21849 21214 21825 21214 21850 21214 21849 21215 21850 21215 21851 21215 21851 21216 21850 21216 21852 21216 21851 21214 21852 21214 21959 21214 21855 21217 21889 21217 21853 21217 21853 21218 21889 21218 21854 21218 21854 21219 21889 21219 21863 21219 21854 960 21863 960 21862 960 21866 21220 21874 21220 21861 21220 21853 960 21846 960 21855 960 21855 960 21846 960 21857 960 21855 960 21857 960 21856 960 21856 21221 21857 21221 21840 21221 21856 960 21840 960 21858 960 21858 960 21840 960 21859 960 21858 21222 21859 21222 21896 21222 21896 21223 21859 21223 21837 21223 21896 960 21837 960 21870 960 21870 21224 21837 21224 21860 21224 21870 960 21860 960 21873 960 21873 21225 21860 21225 21828 21225 21873 960 21828 960 21874 960 21874 21226 21828 21226 21830 21226 21874 21227 21830 21227 21861 21227 21862 960 21863 960 21851 960 21851 21228 21863 21228 21886 21228 21851 21229 21886 21229 21849 21229 21886 21230 21864 21230 21849 21230 21849 960 21864 960 21876 960 21849 21231 21876 21231 21865 21231 21865 960 21876 960 21866 960 21865 21232 21866 21232 21834 21232 21834 960 21866 960 21861 960 21902 21233 21900 21233 21867 21233 21919 21234 21917 21234 21873 21234 21868 21235 21869 21235 21933 21235 21933 21236 21869 21236 21898 21236 21933 21237 21898 21237 21934 21237 21924 21238 21922 21238 21870 21238 21870 49 21922 49 21871 49 21870 21239 21871 21239 21896 21239 21896 21240 21871 21240 21872 21240 21896 21241 21872 21242 21897 21243 21873 21244 21917 21244 21870 21244 21870 21245 21917 21245 21926 21245 21870 21246 21926 21246 21924 21246 21913 21247 21915 21248 21866 21249 21866 21250 21915 21250 21916 21250 21866 21251 21916 21251 21874 21251 21874 21252 21916 21252 21875 21252 21874 21253 21875 21253 21873 21253 21873 21254 21875 21254 21920 21254 21873 21255 21920 21255 21919 21255 21913 21256 21866 21256 21911 21256 21911 21257 21866 21257 21876 21257 21911 21258 21876 21258 21909 21258 21884 21259 21877 21260 21864 21261 21864 21262 21877 21262 21878 21262 21864 21263 21878 21263 21876 21263 21876 21264 21878 21264 21910 21264 21876 21265 21910 21265 21909 21265 21879 21266 21908 21266 21880 21266 21880 21267 21908 21267 21884 21267 21880 21268 21884 21268 21885 21268 21867 21269 21900 21269 21880 21269 21880 21270 21900 21270 21881 21270 21880 21271 21881 21271 21879 21271 21868 21272 21882 21272 21869 21272 21869 21273 21882 21273 21930 21273 21869 21274 21930 21274 21883 21274 21883 21275 21930 21275 21929 21275 21883 21276 21929 21276 21867 21276 21867 21277 21929 21277 21904 21277 21867 21278 21904 21278 21902 21278 21884 21279 21864 21279 21885 21279 21885 21280 21864 21280 21886 21280 21885 21281 21886 21281 21887 21281 21887 21282 21886 21282 21863 21282 21887 21282 21863 21282 21888 21282 21888 21283 21863 21283 21889 21283 21888 21284 21889 21284 21890 21284 21890 21285 21889 21285 21891 21285 21891 21286 21889 21286 21855 21286 21891 21287 21855 21287 21892 21287 21892 21288 21855 21288 21856 21288 21892 21289 21856 21289 21893 21289 21893 21290 21856 21290 21858 21290 21893 21291 21858 21291 21894 21291 21894 21292 21858 21292 21896 21292 21894 21293 21896 21293 21895 21293 21895 21294 21896 21294 21897 21294 21895 21295 21897 21295 21898 21295 21898 49 21897 49 21928 49 21898 21296 21928 21296 21934 21296 21967 21297 21964 21297 21934 21297 21911 21298 21909 21298 21912 21298 21912 21299 21909 21299 21899 21299 21906 21300 21900 21300 21901 21300 21901 21301 21900 21301 21902 21301 21901 21302 21902 21302 21903 21302 21903 21303 21902 21303 21904 21303 21903 21304 21904 21304 21966 21304 21966 21305 21904 21305 21929 21305 21966 21306 21929 21306 21905 21306 21907 21307 21908 21307 21961 21307 21961 21308 21908 21308 21879 21308 21961 21309 21879 21309 21906 21309 21906 21310 21879 21310 21881 21310 21906 21311 21881 21311 21900 21311 21878 21312 21877 21312 21907 21312 21907 21313 21877 21313 21884 21313 21907 21314 21884 21314 21908 21314 21899 21315 21909 21315 21907 21315 21907 21316 21909 21316 21910 21316 21907 21317 21910 21317 21878 21317 21911 21318 21912 21318 21913 21318 21913 21319 21912 21319 21914 21319 21913 21320 21914 21320 21915 21320 21915 21321 21914 21321 21971 21321 21915 21322 21971 21322 21916 21322 21916 21323 21971 21323 21970 21323 21916 21324 21970 21324 21875 21324 21925 21325 21917 21325 21918 21325 21918 21326 21917 21326 21919 21326 21918 21327 21919 21327 21968 21327 21968 21328 21919 21328 21920 21328 21968 21329 21920 21329 21921 21329 21921 21330 21920 21330 21875 21330 21921 21331 21875 21331 21969 21331 21969 21332 21875 21332 21970 21332 21927 21333 21922 21333 21923 21333 21923 21334 21922 21334 21924 21334 21923 21335 21924 21335 21925 21335 21925 21336 21924 21336 21926 21336 21925 21337 21926 21337 21917 21337 21897 21338 21872 21338 21927 21338 21927 21339 21872 21339 21871 21339 21927 21340 21871 21340 21922 21340 21967 21341 21934 21341 21927 21341 21927 21342 21934 21342 21928 21342 21927 21343 21928 21343 21897 21343 21905 21344 21929 21344 21931 21344 21931 21345 21929 21345 21930 21345 21931 21346 21930 21346 21932 21346 21932 21347 21930 21347 21882 21347 21932 21348 21882 21348 21963 21348 21963 21349 21882 21349 21868 21349 21963 21350 21868 21350 21964 21350 21964 21351 21868 21351 21933 21351 21964 21352 21933 21352 21934 21352 21974 21353 21836 21353 21839 21353 21936 21354 21974 21354 21935 21354 21935 21355 21937 21355 21936 21355 21936 21356 21937 21356 21938 21356 21936 21357 21938 21357 21835 21357 21826 21358 21838 21358 21947 21358 21938 21359 21939 21359 21835 21359 21835 21360 21939 21360 21940 21360 21835 21361 21940 21361 21941 21361 21941 21362 21940 21362 22563 21362 21941 21363 22563 21363 21943 21363 21943 21364 22563 21364 21942 21364 21943 21365 21942 21365 21944 21365 21944 21366 21942 21366 21945 21366 21944 21367 21945 21367 21946 21367 21946 21368 21945 21368 22566 21368 21946 21369 22566 21369 21947 21369 21947 21370 22566 21370 22565 21370 21947 21371 22565 21371 21826 21371 21826 21372 22565 21372 21827 21372 21950 21373 21850 21373 22559 21373 22559 21374 21850 21374 21825 21374 22559 21375 21825 21375 21948 21375 22559 21376 22558 21376 21950 21376 21950 21377 22558 21377 21949 21377 21950 21378 21949 21378 21824 21378 21949 21379 22556 21379 21824 21379 21824 21380 22556 21380 21951 21380 21824 21381 21951 21381 21952 21381 21952 21382 21951 21382 21954 21382 21952 21383 21954 21383 21953 21383 21953 21384 21954 21384 21955 21384 21953 21385 21955 21385 21956 21385 21956 21386 21955 21386 21957 21386 21956 21387 21957 21387 21958 21387 21958 21388 21957 21388 22561 21388 21958 21389 22561 21389 21852 21389 21852 21390 22561 21390 21984 21390 21852 21391 21984 21391 21959 21391 21914 21392 21912 21392 21960 21392 21912 21393 21899 21393 21960 21393 21960 21394 21899 21394 21907 21394 21960 21395 21907 21395 21962 21395 21907 21396 21961 21396 21962 21396 21962 21397 21961 21397 21906 21397 21962 21398 21906 21398 21901 21398 21963 21399 21964 21399 21965 21399 21963 21400 21965 21400 21932 21400 21901 21401 21903 21401 21962 21401 21962 21402 21903 21402 21966 21402 21962 21403 21966 21403 22680 21403 22680 21404 21966 21404 21905 21404 22680 21405 21905 21405 21965 21405 21965 21406 21905 21406 21931 21406 21965 21407 21931 21407 21932 21407 21964 21408 21967 21408 21965 21408 21965 21409 21967 21409 21927 21409 21965 21410 21927 21410 21829 21410 21829 21411 21927 21412 21923 21413 21829 21414 21923 21414 21925 21414 21925 21415 21918 21415 21829 21415 21829 21416 21918 21416 21968 21416 21829 21417 21968 21417 21831 21417 21831 21418 21968 21418 21921 21418 21831 21419 21921 21419 21832 21419 21832 21420 21921 21420 21969 21420 21832 21421 21969 21421 21833 21421 21833 21422 21969 21422 21970 21422 21833 21423 21970 21423 21960 21423 21960 21424 21970 21424 21971 21424 21960 21425 21971 21425 21914 21425 21827 21426 22565 21426 21972 21426 21972 21427 22565 21427 22564 21427 21972 21428 22564 21428 21829 21428 21829 21429 22564 21429 21973 21429 21829 21430 21973 21431 21965 21432 21974 21433 21839 21433 21935 21433 21935 21434 21839 21434 21848 21434 21935 21435 21848 21435 21976 21435 21848 21436 21975 21436 21976 21436 21976 21437 21975 21437 21847 21437 21976 21438 21847 21438 21977 21438 21977 21439 21847 21439 21978 21439 21977 21440 21978 21440 21979 21440 21978 21441 21980 21441 21979 21441 21979 21442 21980 21442 21845 21442 21979 21443 21845 21443 21981 21443 21981 21444 21845 21445 21844 21446 21981 21447 21844 21447 21982 21447 21982 21448 21844 21448 21843 21448 21982 21449 21843 21449 21983 21449 21843 21450 21842 21450 21983 21450 21983 21451 21842 21451 21841 21451 21983 21452 21841 21452 21984 21452 21984 21453 21841 21453 21985 21453 21984 21454 21985 21454 21959 21454 21962 21455 22554 21455 21960 21455 21960 21456 22554 21456 22555 21456 21960 21457 22555 21457 21986 21457 21986 21458 22555 21458 22559 21458 21986 21459 22559 21459 21987 21459 21987 21460 22559 21460 21948 21460 22006 21461 21988 21461 21989 21461 21989 15061 21988 15061 22463 15061 21989 15061 22463 15061 21990 15061 21990 15088 22463 15088 21991 15088 21990 21462 21991 21462 21992 21462 21992 21463 21991 21463 22462 21463 21992 21464 22462 21464 21993 21464 21993 21465 22462 21465 22457 21465 21993 21466 22457 21466 22661 21466 22661 21467 22457 21467 22455 21467 22661 21468 22455 21468 21995 21468 21995 21469 22455 21469 21994 21469 21995 21470 21994 21470 22663 21470 22663 21471 21994 21471 22459 21471 22663 21471 22459 21471 21996 21471 21996 21472 22459 21472 21997 21472 21996 21473 21997 21473 21998 21473 21998 15042 21997 15042 21999 15042 21998 15043 21999 15043 22000 15043 22000 14972 21999 14972 22454 14972 22000 14972 22454 14972 22001 14972 22001 15091 22454 15091 22002 15091 22001 15091 22002 15091 22003 15091 22003 21474 22002 21474 22461 21474 22003 21475 22461 21475 22660 21475 22660 14999 22461 14999 22460 14999 22660 14999 22460 14999 22004 14999 22004 21476 22460 21476 22005 21476 22004 21477 22005 21477 22007 21477 22007 21478 22005 21478 22006 21478 22007 21479 22006 21479 21989 21479 22357 21480 22008 21480 22575 21480 22357 21481 22575 21481 22009 21481 22009 21482 22575 21482 22573 21482 22009 21483 22573 21483 22354 21483 22354 21484 22573 21484 22572 21484 22354 21485 22572 21485 22350 21485 22350 21486 22572 21486 22010 21486 22350 21487 22010 21487 22011 21487 22011 15122 22010 15122 22012 15122 22011 15122 22012 15122 22013 15122 22013 21488 22012 21488 22579 21488 22013 21489 22579 21489 22352 21489 22352 21490 22579 21490 22014 21490 22352 21491 22014 21491 22353 21491 22014 21492 22578 21492 22353 21492 22353 21493 22578 21493 22015 21493 22353 21494 22015 21494 22016 21494 22016 21495 22015 21495 22017 21495 22016 21496 22017 21496 22018 21496 22018 21497 22017 21497 22584 21497 22018 21498 22584 21498 22347 21498 22347 21499 22584 21499 22348 21499 22348 21476 22584 21476 22020 21476 22348 21477 22020 21477 22019 21477 22019 21500 22020 21500 22581 21500 22019 21501 22581 21501 22349 21501 22581 21502 22580 21502 22349 21502 22349 15030 22580 15030 22570 15030 22349 15030 22570 15030 22346 15030 22346 21503 22570 21503 22021 21503 22346 21504 22021 21504 22358 21504 22358 15041 22021 15041 22569 15041 22357 21505 22022 21505 22008 21505 22008 21506 22022 21506 22356 21506 22008 21507 22356 21507 22024 21507 22024 21508 22356 21508 22023 21508 22024 21509 22023 21509 22569 21509 22569 21510 22023 21510 22025 21510 22569 14972 22025 14972 22358 14972 22033 21511 22362 21511 22361 21511 22026 21512 22586 21512 22027 21512 22027 21513 22586 21513 22359 21513 22359 21514 22586 21514 22028 21514 22359 21515 22028 21515 22030 21515 22030 14962 22028 14962 22029 14962 22030 14962 22029 14962 22360 14962 22360 21516 22029 21516 22589 21516 22360 21517 22589 21517 22031 21517 22031 21490 22589 21490 22032 21490 22031 21518 22032 21518 22361 21518 22361 21519 22032 21519 22588 21519 22361 21520 22588 21520 22033 21520 22362 21521 22033 21521 22363 21521 22363 21522 22033 21522 22034 21522 22363 21523 22034 21524 22513 21525 22513 21526 22034 21526 22512 21526 22512 21527 22034 21527 22035 21527 22512 21528 22035 21528 22036 21528 22035 21529 22037 21529 22036 21529 22036 21530 22037 21530 22591 21530 22036 21531 22591 21531 22038 21531 22591 21502 22039 21502 22038 21502 22038 21532 22039 21532 22040 21532 22038 21533 22040 21533 22372 21533 22372 14948 22040 14948 22594 14948 22372 14947 22594 14947 22044 14947 22044 21534 22594 21534 22043 21534 22027 21535 22364 21535 22026 21535 22026 21536 22364 21536 22366 21536 22026 14940 22366 14940 22041 14940 22041 21537 22366 21537 22367 21537 22041 21538 22367 21538 22042 21538 22042 21539 22367 21539 22368 21539 22042 21540 22368 21540 22593 21540 22593 21541 22368 21541 22370 21541 22593 21542 22370 21542 22043 21542 22043 21543 22370 21543 22371 21543 22043 21544 22371 21544 22044 21544 22709 15128 22045 15128 22595 15128 22595 14995 22045 14995 22046 14995 22595 21545 22046 21545 22597 21545 22597 14960 22046 14960 22047 14960 22597 14961 22047 14961 22596 14961 22596 15121 22047 15121 22376 15121 22596 15122 22376 15122 22048 15122 22048 21514 22376 21514 22049 21514 22048 21546 22049 21546 22598 21546 22598 21547 22049 21547 22375 21547 22598 21548 22375 21548 22050 21548 22050 21549 22375 21549 22051 21549 22050 21550 22051 21550 22600 21550 22052 21551 22428 21552 22710 21553 22710 21554 22428 21554 22379 21554 22710 21555 22379 21555 22709 21555 22709 21556 22379 21556 22378 21556 22709 15128 22378 15128 22045 15128 22710 21557 22604 21557 22052 21557 22052 15132 22604 15132 22053 15132 22052 15133 22053 15133 22380 15133 22380 15130 22053 15130 22054 15130 22380 15131 22054 15131 22055 15131 22055 21558 22054 21558 22056 21558 22055 21559 22056 21559 22057 21559 22057 14948 22056 14948 22058 14948 22057 14947 22058 14947 22383 14947 22383 14972 22058 14972 22601 14972 22383 21560 22601 21560 22063 21560 22063 21561 22601 21561 22061 21561 22600 21562 22051 21562 22059 21562 22059 21563 22051 21563 22060 21563 22059 21564 22060 21564 22061 21564 22061 21565 22060 21565 22062 21565 22061 15110 22062 15110 22063 15110 22613 21566 22390 21566 22070 21566 22064 21567 22605 21567 22065 21567 22064 21568 22065 21568 22066 21568 22066 14989 22065 14989 22608 14989 22066 14990 22608 14990 22386 14990 22386 21569 22608 21569 22068 21569 22386 21570 22068 21570 22067 21570 22067 21571 22068 21571 22069 21571 22067 21572 22069 21572 22070 21572 22070 21573 22069 21573 22071 21573 22070 21574 22071 21574 22613 21574 22390 21556 22613 21556 22072 21556 22072 21575 22613 21575 22614 21575 22072 21576 22614 21576 22398 21576 22398 21526 22614 21526 22073 21526 22073 21577 22614 21577 22617 21577 22073 21578 22617 21578 22400 21578 22617 21529 22074 21529 22400 21529 22400 21579 22074 21579 22618 21579 22400 21580 22618 21580 22077 21580 22618 21581 22075 21581 22077 21581 22077 15092 22075 15092 22076 15092 22077 15030 22076 15030 22078 15030 22078 15091 22076 15091 22623 15091 22064 21582 22392 21583 22605 21584 22605 21585 22392 21585 22397 21585 22605 15015 22397 15015 22079 15015 22079 21586 22397 21586 22080 21586 22079 21586 22080 21586 22620 21586 22620 21537 22080 21537 22509 21537 22620 21587 22509 21587 22621 21587 22621 21588 22509 21588 22508 21588 22621 21589 22508 21589 22081 21589 22081 21590 22508 21590 22506 21590 22081 21591 22506 21591 22082 21591 22082 21592 22506 21593 22503 21594 22082 21595 22503 21595 22623 21595 22623 15071 22503 15071 22083 15071 22623 15091 22083 15091 22078 15091 22416 21596 22625 21596 22624 21596 22416 21597 22624 21597 22084 21597 22084 21598 22624 21598 22553 21598 22084 21599 22553 21599 22495 21599 22495 21600 22553 21600 22629 21600 22495 21601 22629 21602 22085 21603 22085 21604 22629 21604 22628 21604 22085 21605 22628 21605 22086 21605 22086 15055 22628 15055 22647 15055 22086 21606 22647 21606 22087 21606 22087 21607 22647 21607 22088 21607 22087 15057 22088 15057 22089 15057 22089 21608 22088 21608 22627 21608 22089 21609 22627 21609 22409 21609 22627 21610 22090 21610 22409 21610 22409 21611 22090 21611 22641 21611 22409 21612 22641 21612 22407 21612 22407 21613 22641 21613 22643 21613 22407 21614 22643 21614 22408 21614 22408 21615 22643 21615 22644 21615 22408 21616 22644 21616 22091 21616 22091 21617 22644 21617 22404 21617 22404 15064 22644 15064 22092 15064 22404 15065 22092 15065 22406 15065 22406 21618 22092 21618 22632 21618 22406 21619 22632 21619 22093 21619 22632 21620 22631 21620 22093 21620 22093 15038 22631 15038 22094 15038 22093 21621 22094 21621 22095 21621 22095 15091 22094 15091 22096 15091 22416 21622 22415 21622 22625 21622 22625 21623 22415 21623 22413 21623 22625 21624 22413 21624 22626 21624 22626 15043 22413 15043 22412 15043 22626 15043 22412 15043 22097 15043 22097 15090 22412 15090 22098 15090 22097 21625 22098 21625 22096 21625 22096 21626 22098 21626 22410 21626 22096 15091 22410 15091 22095 15091 22430 21627 22708 21627 22707 21627 22430 21628 22707 21628 22425 21628 22425 21629 22707 21629 22706 21629 22425 21630 22706 21630 22427 21630 22427 21631 22706 21631 22423 21631 22423 21632 22706 21632 22099 21632 22423 21633 22099 21633 22422 21633 22422 21634 22099 21634 22100 21634 22422 21635 22100 21635 22101 21635 22101 21636 22100 21636 22103 21636 22101 15244 22103 15244 22102 15244 22102 21637 22103 21637 22716 21637 22102 21638 22716 21638 22104 21638 22104 21639 22716 21639 22105 21639 22104 21640 22105 21640 22419 21640 22419 21641 22105 21641 22106 21641 22419 21642 22106 21642 22107 21642 22107 21643 22106 21643 22636 21643 22107 21644 22636 21644 22108 21644 22763 960 22234 960 22109 960 22109 960 22234 960 22232 960 22109 21645 22232 21645 22822 21645 22822 21646 22232 21646 22231 21646 22822 21647 22231 21647 22878 21647 22878 960 22231 960 22124 960 22697 21648 22114 21648 22113 21648 22441 15274 22695 15274 22110 15274 22441 21649 22110 21649 22111 21649 22111 21650 22110 21650 22699 21650 22111 21651 22699 21651 22113 21651 22113 21652 22699 21653 22112 21654 22113 15278 22112 15278 22697 15278 22114 21655 22697 21655 22115 21655 22115 21656 22697 21656 22702 21656 22115 21657 22702 21657 22116 21657 22116 21658 22702 21658 22117 21658 22116 21659 22117 21659 22438 21659 22438 21660 22117 21660 22118 21660 22438 21661 22118 21661 22431 21661 22118 21662 22119 21662 22431 21662 22431 21663 22119 21663 22120 21663 22431 21664 22120 21664 22121 21664 22121 15273 22120 15273 22122 15273 22121 21665 22122 21665 22432 21665 22123 21666 22124 21666 22603 21666 22603 21667 22124 21667 22126 21667 22603 21668 22126 21668 22125 21668 22126 21669 22127 21669 22125 21669 22125 21670 22127 21670 22229 21670 22125 21671 22229 21671 22602 21671 22224 21672 22132 21672 22225 21672 22225 21673 22132 21673 22128 21673 22225 21674 22128 21674 22129 21674 22129 21675 22128 21675 22130 21675 22129 21676 22130 21676 22131 21676 22131 21677 22130 21677 22602 21677 22131 21678 22602 21678 22227 21678 22227 21679 22602 21679 22229 21679 22432 21680 22122 21680 22133 21680 22133 21681 22122 21681 22132 21681 22133 21682 22132 21682 22817 21682 22817 21683 22132 21683 22224 21683 22815 960 22817 960 22224 960 22815 960 22224 960 22135 960 22224 960 22134 960 22135 960 22135 21684 22134 21684 22222 21684 22135 960 22222 960 22809 960 22809 21685 22222 21685 22152 21685 22809 960 22152 960 22808 960 22795 960 22262 960 22831 960 22831 960 22262 960 22136 960 22831 21686 22136 21686 22790 21686 22790 960 22136 960 22137 960 22790 21687 22137 21687 22138 21687 22138 960 22137 960 22260 960 22138 960 22260 960 22188 960 22805 960 22139 960 22804 960 22804 21688 22139 21688 22141 21688 22804 21689 22141 21689 22140 21689 22140 21690 22141 21690 22267 21690 22140 960 22267 960 22800 960 22800 960 22267 960 22142 960 22800 960 22142 960 22166 960 22166 960 22142 960 22143 960 22139 21691 22145 21691 22144 21691 22144 21692 22145 21692 22146 21692 22144 21693 22146 21693 22271 21693 22271 21694 22146 21694 22592 21694 22271 21695 22592 21695 22220 21695 22220 21696 22592 21696 22147 21696 22220 21697 22147 21697 22148 21697 22148 21698 22147 21698 22694 21698 22148 21699 22694 21699 22221 21699 22221 21700 22694 21700 22696 21700 22221 21701 22696 21701 22149 21701 22149 21702 22696 21702 22550 21702 22149 21703 22550 21703 22150 21703 22150 21704 22550 21704 22151 21704 22150 21705 22151 21705 22152 21705 22153 21706 22154 21706 22155 21706 22155 21707 22154 21707 22145 21707 22155 21708 22145 21708 22805 21708 22805 21709 22145 21709 22139 21709 22154 21710 22153 21710 22165 21710 22355 21711 22156 21711 22157 21711 22157 21712 22156 21712 22168 21712 22355 21713 22157 21713 22158 21713 22158 21714 22157 21714 22568 21714 22158 21715 22568 21715 22159 21715 22568 21716 22160 21716 22159 21716 22159 21717 22160 21717 22161 21717 22159 21718 22161 21718 22162 21718 22162 21719 22161 21719 22683 21719 22162 21720 22683 21720 22163 21720 22163 21721 22683 21721 22686 21721 22163 21721 22686 21721 22445 21721 22445 21722 22686 21723 22164 21724 22164 21725 22686 21725 22684 21725 22164 21726 22684 21726 22165 21726 22165 21727 22684 21727 22585 21727 22165 15462 22585 15462 22154 15462 22166 15464 22143 15464 22167 15464 22167 21728 22143 21728 22567 21728 22167 21729 22567 21729 22156 21729 22156 21730 22567 21730 22168 21730 22567 21731 22143 21731 22169 21731 22567 21732 22169 21732 22576 21732 22576 21733 22169 21733 22264 21733 22576 21734 22264 21734 22170 21734 22170 21735 22264 21735 22171 21735 22170 21736 22171 21736 22574 21736 22574 21737 22171 21737 22172 21737 22574 21738 22172 21738 22571 21738 22571 21739 22172 21739 22176 21739 22571 21740 22176 21740 22174 21740 22262 21741 22173 21741 22263 21741 22263 21742 22173 21742 22174 21742 22263 21743 22174 21743 22175 21743 22175 21744 22174 21744 22176 21744 22177 21745 22178 21745 22179 21745 22179 21746 22178 21746 22173 21746 22179 21747 22173 21747 22795 21747 22795 21748 22173 21748 22262 21748 22178 21749 22177 21749 22186 21749 22190 21750 22191 21750 22672 21750 22190 21750 22672 21750 22451 21750 22451 21751 22672 21751 22671 21751 22451 21752 22671 21752 22181 21752 22181 21753 22671 21753 22180 21753 22181 21754 22180 21754 22452 21754 22452 21755 22180 21755 22182 21755 22182 21756 22180 21756 22665 21756 22182 21757 22665 21757 22183 21757 22665 21758 22674 21758 22183 21758 22183 15498 22674 15498 22184 15498 22183 15499 22184 15499 22185 15499 22185 21759 22184 21760 22187 21761 22185 21762 22187 21762 22186 21762 22186 21763 22187 21763 22676 21763 22186 21764 22676 21764 22178 21764 22188 21765 22260 21765 22189 21765 22189 21766 22260 21766 22673 21766 22189 21767 22673 21767 22190 21767 22190 21768 22673 21768 22191 21768 22673 21769 22260 21769 22192 21769 22192 21770 22260 21770 22193 21770 22192 21771 22193 21771 22662 21771 22193 21772 22259 21772 22662 21772 22662 21773 22259 21773 22258 21773 22662 21774 22258 21774 22194 21774 22258 21775 22195 21775 22194 21775 22194 21776 22195 21776 22257 21776 22194 21777 22257 21777 22196 21777 22196 21778 22257 21778 22197 21778 22196 21779 22197 21779 22652 21779 22652 21780 22197 21780 22255 21780 22652 21781 22255 21781 22198 21781 22198 21782 22255 21782 22253 21782 22783 21783 22253 21783 22785 21783 22785 21784 22253 21784 22199 21784 22785 21785 22199 21785 22781 21785 22781 21786 22199 21786 22252 21786 22781 21787 22252 21787 22772 21787 22772 21788 22252 21788 22250 21788 22200 21789 22201 21789 22202 21789 22475 21790 22203 21790 22649 21790 22649 15147 22203 15147 22204 15147 22475 21791 22649 21791 22205 21791 22205 21792 22649 21792 22646 21792 22205 21793 22646 21794 22206 21795 22206 21796 22646 21796 22207 21796 22206 21797 22207 21797 22202 21797 22202 21798 22207 21798 22656 21798 22202 15156 22656 15156 22200 15156 22201 21799 22200 21799 22208 21799 22208 21800 22200 21800 22209 21800 22208 21801 22209 21801 22471 21801 22471 21802 22209 21802 22654 21802 22471 21803 22654 21803 22211 21803 22211 15164 22654 15164 22210 15164 22211 15164 22210 15164 22212 15164 22772 21804 22250 21804 22773 21804 22773 21805 22250 21805 22216 21805 22773 21806 22216 21806 22203 21806 22203 21807 22216 21807 22204 21807 22246 21808 22217 21808 22640 21808 22246 21809 22640 21809 22213 21809 22213 21810 22640 21810 22214 21810 22213 21811 22214 21811 22247 21811 22247 21812 22214 21812 22215 21812 22247 21813 22215 21813 22249 21813 22249 21814 22215 21814 22216 21814 22249 21815 22216 21815 22250 21815 22217 21816 22246 21816 22642 21816 22642 21817 22246 21817 22219 21817 22642 21818 22219 21818 22218 21818 22275 21819 22645 21819 22243 21819 22243 21820 22645 21820 22218 21820 22243 21821 22218 21821 22245 21821 22245 21822 22218 21822 22219 21822 22912 21823 22270 21823 22271 21823 22271 21824 22220 21824 22912 21824 22912 21825 22220 21825 22148 21825 22912 21826 22148 21826 22909 21826 22148 21827 22221 21827 22909 21827 22909 21828 22221 21828 22149 21828 22909 21829 22149 21829 22908 21829 22149 21830 22150 21830 22908 21830 22908 21831 22150 21831 22152 21831 22908 21832 22152 21832 22905 21832 22152 21833 22222 21833 22905 21833 22905 21834 22222 21834 22134 21834 22905 21835 22134 21835 22223 21835 22223 21836 22134 21836 22224 21836 22223 21837 22224 21837 22902 21837 22902 21838 22224 21838 22225 21838 22902 21839 22225 21839 22226 21839 22225 21840 22129 21840 22226 21840 22226 21841 22129 21841 22131 21841 22226 21842 22131 21842 22228 21842 22228 21843 22131 21843 22227 21843 22227 21844 22229 21844 22228 21844 22228 21845 22229 21845 22127 21845 22228 21846 22127 21846 22899 21846 22127 21847 22126 21847 22899 21847 22899 21848 22126 21848 22124 21848 22899 21849 22124 21849 22230 21849 22124 21850 22231 21850 22230 21850 22230 21851 22231 21851 22232 21851 22230 21851 22232 21851 22233 21851 22233 21852 22232 21852 22234 21852 22233 21853 22234 21853 22235 21853 22234 21854 22753 21854 22235 21854 22235 21855 22753 21855 22754 21855 22235 21856 22754 21856 22237 21856 22754 21857 22236 21857 22237 21857 22237 21858 22236 21858 22757 21858 22237 21859 22757 21859 22895 21859 22757 21860 22758 21860 22895 21860 22895 21861 22758 21861 22760 21861 22895 21862 22760 21862 22239 21862 22760 21863 22238 21863 22239 21863 22239 21864 22238 21864 22762 21864 22239 21865 22762 21865 22240 21865 22762 21866 22272 21866 22240 21866 22240 21867 22272 21867 22273 21867 22240 21868 22273 21868 22893 21868 22893 21869 22273 21869 22242 21869 22893 21869 22242 21869 22241 21869 22241 21870 22242 21870 22275 21870 22241 21871 22275 21871 22244 21871 22275 21872 22243 21872 22244 21872 22244 21873 22243 21873 22245 21873 22244 21874 22245 21874 22926 21874 22245 21875 22219 21875 22926 21875 22926 21876 22219 21876 22246 21876 22926 21877 22246 21877 22248 21877 22246 21878 22213 21878 22248 21878 22248 21879 22213 21879 22247 21879 22248 21880 22247 21880 22925 21880 22247 21881 22249 21881 22925 21881 22925 21882 22249 21882 22250 21882 22925 21883 22250 21883 22251 21883 22250 21884 22252 21884 22251 21884 22251 21885 22252 21885 22199 21885 22251 21886 22199 21886 22924 21886 22924 21887 22199 21887 22253 21887 22924 21888 22253 21888 22254 21888 22254 21889 22253 21889 22255 21889 22254 21890 22255 21890 22256 21890 22255 21891 22197 21891 22256 21891 22256 21892 22197 21892 22257 21892 22256 21893 22257 21893 22921 21893 22921 21894 22257 21894 22195 21894 22195 21895 22258 21895 22921 21895 22921 21896 22258 21896 22259 21896 22921 21897 22259 21897 22920 21897 22259 21898 22193 21898 22920 21898 22920 21899 22193 21899 22260 21899 22920 21900 22260 21900 22261 21900 22260 21901 22137 21901 22261 21901 22261 21902 22137 21902 22136 21902 22261 21902 22136 21902 22919 21902 22919 21903 22136 21903 22262 21903 22919 21904 22262 21904 22917 21904 22262 21905 22263 21906 22917 21907 22917 21908 22263 21908 22175 21908 22917 21909 22175 21909 22916 21909 22175 21910 22176 21910 22916 21910 22916 21911 22176 21911 22172 21911 22916 21912 22172 21912 22915 21912 22172 21913 22171 21913 22915 21913 22915 21914 22171 21914 22264 21914 22915 21915 22264 21915 22265 21915 22264 21916 22169 21916 22265 21916 22265 21917 22169 21917 22143 21917 22265 21918 22143 21918 22266 21918 22143 21919 22142 21919 22266 21919 22266 21920 22142 21920 22267 21920 22266 21921 22267 21921 22268 21921 22268 21922 22267 21922 22141 21922 22268 21923 22141 21923 22269 21923 22269 21924 22141 21924 22139 21924 22269 21925 22139 21925 22270 21925 22270 21926 22139 21926 22144 21926 22270 21927 22144 21927 22271 21927 22778 21928 22779 21928 22275 21928 22762 960 22774 960 22272 960 22272 21929 22774 21929 22274 21929 22272 21930 22274 21930 22273 21930 22273 21931 22274 21931 22778 21931 22273 960 22778 960 22242 960 22242 21932 22778 21932 22275 21932 22634 21933 22401 21933 22405 21933 22389 21934 22276 21934 22609 21934 22609 21935 22276 21935 22282 21935 22389 21936 22609 21936 22387 21936 22387 21937 22609 21937 22610 21937 22387 21938 22610 21938 22277 21938 22610 21939 22612 21939 22277 21939 22277 21940 22612 21940 22278 21940 22277 21941 22278 21941 22479 21941 22479 21942 22278 21942 22639 21942 22479 21943 22639 21943 22279 21943 22279 21944 22639 21944 22638 21944 22279 21945 22638 21945 22280 21945 22280 21946 22638 21946 22484 21946 22484 21946 22638 21946 22633 21946 22484 21947 22633 21947 22405 21947 22405 21947 22633 21947 22635 21947 22405 15207 22635 15207 22634 15207 22774 15209 22762 15209 22281 15209 22281 21948 22762 21948 22761 21948 22281 21949 22761 21949 22276 21949 22276 21950 22761 21950 22282 21950 22283 21951 22284 21951 22666 21951 22666 21952 22284 21953 22295 21954 22666 21955 22735 21955 22283 21955 22283 21956 22735 21956 22717 21956 22283 21957 22717 21957 22493 21957 22493 21958 22717 21958 22285 21958 22493 15564 22285 15564 22286 15564 22286 21959 22285 21959 22718 21959 22286 21960 22718 21960 22287 21960 22287 21961 22718 21961 22719 21961 22287 21962 22719 21962 22492 21962 22492 21963 22719 21963 22491 21963 22491 21964 22719 21964 22288 21964 22491 21965 22288 21965 22289 21965 22288 21966 22290 21966 22289 21966 22289 21967 22290 21967 22670 21967 22289 21968 22670 21968 22291 21968 22291 15551 22670 15551 22669 15551 22291 15551 22669 15551 22453 15551 22453 15552 22669 15552 22668 15552 22453 15552 22668 15552 22292 15552 22292 15554 22668 15554 22293 15554 22292 15555 22293 15555 22294 15555 22294 15556 22293 15556 22667 15556 22294 21969 22667 21969 22449 21969 22449 21970 22667 21970 22295 21970 22449 21970 22295 21970 22516 21970 22516 21971 22295 21971 22284 21971 22714 21972 22713 21972 22296 21972 22296 21973 22713 21973 22297 21973 22297 15507 22713 15507 22712 15507 22297 15508 22712 15508 22298 15508 22298 15509 22712 15509 22711 15509 22298 21974 22711 21974 22424 21974 22424 21975 22711 21975 22299 21975 22424 21975 22299 21975 22300 21975 22300 21976 22299 21976 22502 21976 22502 21977 22299 21978 22301 21979 22502 21980 22301 21980 22303 21980 22301 21981 22302 21981 22303 21981 22303 21982 22302 21982 22304 21982 22303 21983 22304 21983 22510 21983 22510 21984 22304 21984 22727 21984 22510 15517 22727 15517 22305 15517 22305 21985 22727 21985 22307 21985 22307 21986 22727 21986 22306 21986 22307 21987 22306 21987 22308 21987 22308 15556 22306 15556 22309 15556 22308 21969 22309 21969 22507 21969 22507 21988 22309 21988 22505 21988 22505 21989 22309 21989 22310 21989 22505 21990 22310 21990 22312 21990 22310 21991 22311 21991 22312 21991 22312 21992 22311 21992 22715 21992 22312 21993 22715 21993 22420 21993 22420 21994 22715 21994 22714 21994 22420 21994 22714 21994 22421 21994 22421 21995 22714 21995 22296 21995 22313 590 22541 590 22374 590 22518 590 22314 590 22517 590 22315 590 22480 590 22483 590 22212 21996 22316 21996 22466 21996 22317 590 22446 590 22447 590 22445 590 22164 590 22444 590 22442 21997 22373 21997 22318 21997 22319 590 22320 590 22519 590 22321 590 22322 590 22330 590 22345 21998 22343 21998 22323 21998 22323 21999 22343 21999 22324 21999 22323 22000 22324 22000 22325 22000 22325 590 22324 590 22326 590 22321 590 22330 590 22327 590 22394 590 22329 590 22328 590 22328 590 22329 590 22331 590 22328 590 22331 590 22330 590 22330 22001 22331 22001 22332 22001 22330 22002 22332 22002 22327 22002 22521 22003 22333 22003 22396 22003 22396 22004 22333 22004 22334 22004 22396 22005 22334 22005 22395 22005 22411 22006 22335 22006 22520 22006 22319 590 22519 590 22340 590 22494 22007 22342 22007 22336 22007 22336 22008 22337 22008 22494 22008 22494 590 22337 590 22338 590 22494 590 22338 590 22519 590 22519 22009 22338 22009 22339 22009 22519 22010 22339 22010 22340 22010 22494 22011 22341 22011 22342 22011 22342 590 22341 590 22343 590 22342 590 22343 590 22344 590 22344 590 22343 590 22345 590 22358 590 22525 590 22346 590 22346 590 22525 590 22343 590 22346 22012 22343 22012 22349 22012 22018 590 22347 590 22341 590 22341 590 22347 590 22348 590 22341 22013 22348 22013 22343 22013 22343 590 22348 590 22019 590 22343 22014 22019 22014 22349 22014 22350 590 22011 590 22446 590 22446 22015 22011 22015 22013 22015 22446 22016 22013 22016 22351 22016 22013 590 22352 590 22351 590 22351 22017 22352 22017 22353 22017 22351 22018 22353 22018 22341 22018 22341 590 22353 590 22016 590 22341 22019 22016 22019 22018 22019 22350 22020 22446 22020 22354 22020 22354 22021 22446 22021 22317 22021 22354 590 22317 590 22836 590 22355 590 22158 590 22525 590 22167 22022 22356 22022 22826 22022 22826 590 22356 590 22022 590 22826 22023 22022 22023 22834 22023 22834 22024 22022 22024 22357 22024 22834 590 22357 590 22836 590 22836 590 22357 590 22009 590 22836 590 22009 590 22354 590 22167 590 22156 590 22356 590 22356 22025 22156 22025 22355 22025 22356 590 22355 590 22023 590 22023 22026 22355 22026 22525 22026 22023 22027 22525 22027 22025 22027 22025 22028 22525 22028 22358 22028 22444 22029 22027 22029 22359 22029 22359 22030 22030 22030 22444 22030 22444 590 22030 590 22360 590 22444 590 22360 590 22324 590 22324 590 22360 590 22031 590 22031 590 22361 590 22324 590 22324 22031 22361 22031 22362 22031 22324 22032 22362 22032 22511 22032 22511 590 22362 590 22363 590 22511 590 22363 590 22513 590 22444 22033 22164 22033 22027 22033 22027 590 22164 590 22165 590 22027 590 22165 590 22364 590 22318 22034 22373 22034 22886 22034 22165 22035 22153 22035 22364 22035 22364 22036 22153 22036 22155 22036 22364 22037 22155 22037 22366 22037 22366 590 22155 590 22365 590 22366 590 22365 590 22367 590 22367 22038 22365 22038 22369 22038 22367 22039 22369 22039 22368 22039 22368 590 22369 590 22886 590 22368 22040 22886 22040 22370 22040 22370 22041 22886 22041 22373 22041 22370 22042 22373 22042 22371 22042 22512 22043 22036 22043 22440 22043 22036 22044 22038 22044 22440 22044 22440 590 22038 590 22372 590 22440 22045 22372 22045 22373 22045 22373 22046 22372 22046 22044 22046 22373 22047 22044 22047 22371 22047 22375 590 22049 590 22374 590 22375 590 22374 590 22051 590 22049 590 22376 590 22374 590 22374 22048 22376 22048 22047 22048 22374 22049 22047 22049 22377 22049 22377 590 22047 590 22046 590 22046 590 22045 590 22377 590 22377 22050 22045 22050 22378 22050 22377 22051 22378 22051 22426 22051 22426 22052 22378 22052 22379 22052 22426 590 22379 590 22428 590 22052 22053 22380 22053 22381 22053 22381 590 22380 590 22055 590 22381 590 22055 590 22382 590 22382 590 22055 590 22057 590 22382 590 22057 590 22876 590 22876 22054 22057 22054 22383 22054 22876 590 22383 590 22812 590 22060 22055 22384 22055 22062 22055 22062 22056 22384 22056 22812 22056 22062 22057 22812 22057 22063 22057 22063 590 22812 590 22383 590 22064 22058 22066 22058 22385 22058 22385 590 22066 590 22386 590 22385 590 22386 590 22387 590 22387 22059 22386 22059 22067 22059 22387 590 22067 590 22389 590 22389 22060 22067 22060 22070 22060 22388 590 22391 590 22390 590 22070 590 22390 590 22389 590 22389 590 22390 590 22391 590 22389 22061 22391 22061 22276 22061 22276 22062 22391 22062 22281 22062 22064 590 22385 590 22392 590 22392 590 22385 590 22396 590 22392 590 22396 590 22397 590 22393 22063 22509 22063 22080 22063 22394 22064 22328 22064 22395 22064 22395 22065 22328 22065 22393 22065 22395 590 22393 590 22396 590 22396 22066 22393 22066 22080 22066 22396 590 22080 590 22397 590 22077 590 22078 590 22869 590 22869 22067 22078 22067 22504 22067 22390 590 22072 590 22388 590 22388 22068 22072 22068 22398 22068 22388 590 22398 590 22399 590 22399 590 22398 590 22073 590 22399 590 22073 590 22869 590 22869 590 22073 590 22400 590 22869 590 22400 590 22077 590 22401 590 22402 590 22403 590 22483 22069 22484 22069 22095 22069 22401 22070 22403 22070 22405 22070 22855 22071 22091 22071 22403 22071 22403 22072 22091 22072 22404 22072 22403 590 22404 590 22405 590 22405 590 22404 590 22406 590 22405 22073 22406 22073 22484 22073 22484 590 22406 590 22093 590 22484 590 22093 590 22095 590 22476 22074 22409 22074 22854 22074 22854 22075 22409 22075 22407 22075 22854 22076 22407 22076 22855 22076 22855 22077 22407 22077 22408 22077 22855 22078 22408 22078 22091 22078 22085 590 22086 590 22472 590 22472 590 22086 590 22087 590 22472 22079 22087 22079 22476 22079 22476 22080 22087 22080 22089 22080 22476 22081 22089 22081 22409 22081 22095 590 22410 590 22483 590 22483 22082 22410 22082 22098 22082 22483 590 22098 590 22411 590 22098 22083 22412 22084 22411 22085 22411 22086 22412 22086 22413 22086 22411 22087 22413 22087 22414 22087 22414 590 22413 590 22415 590 22414 22088 22415 22088 22416 22088 22108 590 22866 590 22417 590 22417 590 22418 590 22108 590 22108 22089 22418 22089 22869 22089 22108 590 22869 590 22107 590 22504 22090 22505 22090 22312 22090 22102 590 22104 590 22420 590 22107 590 22869 590 22419 590 22419 21027 22869 21027 22504 21027 22419 590 22504 590 22104 590 22104 22091 22504 22091 22312 22091 22104 22092 22312 22092 22420 22092 22102 590 22420 590 22101 590 22101 22093 22420 22093 22421 22093 22101 590 22421 590 22422 590 22422 22094 22421 22094 22296 22094 22422 22095 22296 22095 22423 22095 22300 18970 22377 18970 22424 18970 22424 590 22377 590 22426 590 22424 590 22426 590 22298 590 22298 590 22426 590 22297 590 22430 22096 22425 22096 22426 22096 22296 590 22297 590 22423 590 22423 590 22297 590 22426 590 22423 22097 22426 22097 22427 22097 22427 22098 22426 22098 22425 22098 22428 590 22052 590 22426 590 22426 22099 22052 22099 22381 22099 22426 590 22381 590 22430 590 22430 22100 22381 22100 22429 22100 22430 22101 22429 22101 22766 22101 22438 590 22431 590 22384 590 22384 590 22431 590 22121 590 22384 22102 22121 22102 22812 22102 22812 22103 22121 22103 22432 22103 22812 590 22432 590 22133 590 22433 590 22434 590 22440 590 22541 590 22435 590 22374 590 22374 590 22435 590 22384 590 22374 22104 22384 22104 22051 22104 22051 22105 22384 22105 22060 22105 22437 22106 22436 22106 22115 22106 22435 22107 22543 22107 22384 22107 22384 590 22543 590 22547 590 22384 590 22547 590 22438 590 22438 22108 22547 22108 22437 22108 22438 22109 22437 22109 22116 22109 22116 590 22437 590 22115 590 22436 22110 22433 22110 22115 22110 22115 22111 22433 22111 22440 22111 22115 590 22440 590 22114 590 22114 590 22440 590 22113 590 22443 590 22439 590 22441 590 22113 590 22440 590 22111 590 22111 590 22440 590 22373 590 22111 590 22373 590 22441 590 22441 590 22373 590 22442 590 22441 22112 22442 22112 22443 22112 22158 590 22159 590 22525 590 22525 22113 22159 22113 22162 22113 22525 590 22162 590 22444 590 22444 22114 22162 22114 22163 22114 22444 590 22163 590 22445 590 22351 590 22185 590 22446 590 22446 22115 22185 22115 22186 22115 22446 22116 22186 22116 22447 22116 22447 22117 22186 22117 22177 22117 22447 590 22177 590 22448 590 22448 22118 22177 22118 22179 22118 22351 22119 22491 22119 22289 22119 22289 590 22182 590 22351 590 22351 22120 22182 22120 22183 22120 22351 22121 22183 22121 22185 22121 22451 590 22838 590 22190 590 22190 590 22838 590 22189 590 22516 22122 22450 22122 22449 22122 22449 590 22450 590 22838 590 22449 590 22838 590 22294 590 22294 22123 22838 22123 22451 22123 22294 590 22451 590 22292 590 22289 590 22291 590 22182 590 22182 590 22291 590 22453 590 22182 22124 22453 22124 22452 22124 22452 22125 22453 22125 22292 22125 22452 590 22292 590 22181 590 22181 590 22292 590 22451 590 22450 22126 22454 22126 21999 22126 22838 590 22455 590 22456 590 22456 22127 22455 22127 22457 22127 22456 22128 22457 22128 22458 22128 22458 590 22457 590 22462 590 22458 22129 22462 22129 22842 22129 22454 590 22450 590 22002 590 22002 590 22450 590 22517 590 22002 590 22517 590 22461 590 21999 590 21997 590 22450 590 22450 590 21997 590 22459 590 22450 590 22459 590 22838 590 22838 22130 22459 22130 21994 22130 22838 22131 21994 22131 22455 22131 22006 590 22005 590 22517 590 22517 22132 22005 22132 22460 22132 22517 590 22460 590 22461 590 22462 590 21991 590 22842 590 22842 22133 21991 22133 22463 22133 22842 22134 22463 22134 21988 22134 22314 590 22464 590 22517 590 22517 22135 22464 22135 22842 22135 22517 22136 22842 22136 22006 22136 22006 590 22842 590 21988 590 22464 590 22465 590 22842 590 22842 22137 22465 22137 22467 22137 22842 22138 22467 22138 22466 22138 22466 22139 22467 22139 22470 22139 22469 590 22468 590 22202 590 22202 590 22468 590 22206 590 22202 590 22201 590 22469 590 22469 22140 22201 22140 22208 22140 22469 590 22208 590 22470 590 22470 22141 22208 22141 22471 22141 22470 590 22471 590 22466 590 22466 590 22471 590 22211 590 22466 590 22211 590 22212 590 22472 22142 22205 22142 22206 22142 22496 590 22472 590 22473 590 22473 590 22472 590 22206 590 22473 590 22206 590 22474 590 22474 590 22206 590 22468 590 22477 590 22773 590 22203 590 22205 590 22472 590 22475 590 22475 590 22472 590 22476 590 22475 22143 22476 22143 22203 22143 22203 22144 22476 22144 22849 22144 22203 22145 22849 22145 22477 22145 22486 22146 22478 22146 22479 22146 22479 22147 22478 22147 22277 22147 22480 22148 22481 22148 22483 22148 22483 590 22481 590 22482 590 22483 590 22482 590 22484 590 22484 22149 22482 22149 22485 22149 22484 590 22485 590 22280 590 22280 22150 22485 22150 22486 22150 22280 22151 22486 22151 22279 22151 22279 22152 22486 22152 22479 22152 22478 22153 22487 22153 22277 22153 22277 22154 22487 22154 22488 22154 22277 22155 22488 22155 22387 22155 22387 590 22488 590 22489 590 22387 22156 22489 22156 22385 22156 22385 22157 22489 22157 22490 22157 22385 22158 22490 22158 22522 22158 22491 22159 22351 22159 22492 22159 22492 590 22351 590 22341 590 22492 590 22341 590 22287 590 22284 590 22283 590 22494 590 22494 590 22283 590 22493 590 22494 590 22493 590 22341 590 22341 22160 22493 22160 22286 22160 22341 22161 22286 22161 22287 22161 22085 590 22472 590 22495 590 22495 22162 22472 22162 22496 22162 22495 590 22496 590 22084 590 22084 22163 22496 22163 22497 22163 22084 590 22497 590 22416 590 22416 590 22497 590 22498 590 22416 22164 22498 22164 22414 22164 22414 590 22498 590 22499 590 22414 22165 22499 22165 22500 22165 22335 22166 22411 22166 22320 22166 22320 590 22411 590 22414 590 22320 590 22414 590 22519 590 22519 590 22414 590 22500 590 22519 590 22500 590 22501 590 22502 590 22303 590 22328 590 22328 590 22303 590 22510 590 22328 590 22510 590 22393 590 22078 590 22083 590 22504 590 22504 22167 22083 22167 22503 22167 22504 590 22503 590 22505 590 22505 22168 22503 22168 22506 22168 22505 590 22506 590 22507 590 22507 22169 22506 22169 22508 22169 22507 590 22508 590 22308 590 22308 22170 22508 22170 22509 22170 22308 590 22509 590 22307 590 22307 590 22509 590 22393 590 22307 590 22393 590 22305 590 22305 590 22393 590 22510 590 22434 590 22548 590 22440 590 22440 590 22548 590 22511 590 22440 590 22511 590 22512 590 22512 590 22511 590 22513 590 22548 590 22514 590 22511 590 22511 590 22514 590 22515 590 22511 590 22515 590 22538 590 22326 590 22324 590 22322 590 22322 590 22324 590 22511 590 22322 590 22511 590 22330 590 22330 22171 22511 22171 22538 22171 22330 22172 22538 22172 22540 22172 22516 590 22284 590 22450 590 22450 590 22284 590 22494 590 22450 590 22494 590 22517 590 22517 22173 22494 22173 22519 22173 22517 22174 22519 22174 22518 22174 22518 22175 22519 22175 22501 22175 22520 590 22521 590 22411 590 22411 22176 22521 22176 22396 22176 22411 590 22396 590 22483 590 22483 590 22396 590 22385 590 22483 590 22385 590 22315 590 22315 22177 22385 22177 22522 22177 22529 22178 22343 22178 22523 22178 22523 590 22343 590 22525 590 22523 22179 22525 22179 22524 22179 22524 590 22525 590 22526 590 22526 590 22525 590 22527 590 22527 590 22525 590 22444 590 22527 590 22444 590 22528 590 22529 590 22530 590 22343 590 22343 22180 22530 22180 22531 22180 22343 22181 22531 22181 22324 22181 22324 22182 22531 22182 22532 22182 22532 22183 22533 22183 22324 22183 22324 590 22533 590 22534 590 22324 590 22534 590 22444 590 22444 590 22534 590 22535 590 22444 22184 22535 22184 22528 22184 22540 22185 22313 22185 22330 22185 22330 22186 22313 22186 22374 22186 22330 590 22374 590 22328 590 22328 22187 22374 22187 22377 22187 22328 22188 22377 22188 22502 22188 22502 590 22377 590 22300 590 22700 22189 22536 22189 22548 22189 22548 22190 22536 22190 22514 22190 22536 22191 22732 22191 22514 22191 22514 22192 22732 22192 22731 22192 22514 22193 22731 22193 22515 22193 22515 22194 22731 22194 22537 22194 22515 22194 22537 22194 22538 22194 22538 15554 22537 15554 22539 15554 22538 15555 22539 15555 22540 15555 22540 22195 22539 22195 22730 22195 22540 15532 22730 15532 22313 15532 22313 22196 22730 22196 22541 22196 22541 22197 22730 22197 22542 22197 22541 22198 22542 22198 22435 22198 22542 22198 22751 22198 22435 22198 22435 15574 22751 15574 22544 15574 22435 15560 22544 15560 22543 15560 22543 22199 22544 22199 22545 22199 22543 22200 22545 22200 22547 22200 22547 15540 22545 15540 22546 15540 22547 22201 22546 22201 22437 22201 22437 22202 22546 22202 22703 22202 22437 15566 22703 15566 22436 15566 22436 15509 22703 15509 22701 15509 22436 21974 22701 21974 22433 21974 22433 15567 22701 15567 22700 15567 22433 15568 22700 15568 22434 15568 22434 22203 22700 22203 22548 22203 22302 22204 22301 22204 22549 22204 22550 22205 22551 22205 22151 22205 22764 960 22552 960 22752 960 22629 960 22553 960 22560 960 22037 960 22035 960 22729 960 22554 960 21962 960 22582 960 22680 22206 21965 22206 22681 22206 22681 960 21965 960 22587 960 22555 960 22583 960 22559 960 22559 960 22583 960 22557 960 21951 960 22556 960 22736 960 22736 22207 22556 22207 21949 22207 22736 960 21949 960 22557 960 22557 960 21949 960 22558 960 22557 22208 22558 22208 22559 22208 21951 960 22736 960 21954 960 21954 960 22736 960 22724 960 21954 960 22724 960 21955 960 22562 22209 21982 22209 22560 22209 22560 22210 21982 22210 21983 22210 21983 960 21984 960 22560 960 22560 22211 21984 22211 22561 22211 22560 22212 22561 22212 22724 22212 22724 22213 22561 22213 21957 22213 22724 22214 21957 22214 21955 22214 21976 960 21977 960 22607 960 22607 960 21977 960 21979 960 22607 960 21979 960 22562 960 22562 22215 21979 22215 21981 22215 22562 960 21981 960 21982 960 21938 22216 21937 22216 22606 22216 22606 22217 21937 22217 21935 22217 21942 960 22563 960 22750 960 22750 22218 22563 22218 21940 22218 22750 22219 21940 22219 22728 22219 22728 960 21940 960 21939 960 21965 960 21973 960 22587 960 22587 22220 21973 22220 22564 22220 22587 22221 22564 22222 22729 22223 22564 960 22565 960 22729 960 22729 22224 22565 22224 22566 22224 22729 22225 22566 22225 22750 22225 22750 22226 22566 22226 21945 22226 22750 22227 21945 22227 21942 22227 22168 22228 22567 22228 22576 22228 22024 960 22569 960 22568 960 22568 22229 22569 22229 22021 22229 22568 22230 22021 22230 22582 22230 22582 22231 22021 22231 22570 22231 22582 960 22570 960 22580 960 22579 960 22012 960 22675 960 22675 22232 22012 22232 22571 22232 22012 22233 22010 22233 22571 22233 22571 22234 22010 22234 22572 22234 22571 960 22572 960 22574 960 22574 960 22572 960 22573 960 22574 960 22573 960 22170 960 22170 22235 22573 22235 22575 22235 22170 960 22575 960 22576 960 22576 22236 22575 22236 22008 22236 22576 960 22008 960 22168 960 22168 22237 22008 22237 22024 22237 22168 960 22024 960 22157 960 22157 960 22024 960 22568 960 22557 22238 22015 22238 22577 22238 22577 22239 22015 22239 22578 22239 22577 960 22578 960 22675 960 22675 22240 22578 22240 22014 22240 22675 22241 22014 22241 22579 22241 22580 960 22581 960 22582 960 22582 22242 22581 22242 22583 22242 22582 22243 22583 22243 22554 22243 22554 22244 22583 22244 22555 22244 22581 960 22020 960 22583 960 22583 22245 22020 22245 22584 22245 22583 22246 22584 22246 22557 22246 22557 22247 22584 22247 22017 22247 22557 22248 22017 22248 22015 22248 22146 22249 22145 22249 22154 22249 22592 22250 22146 22250 22041 22250 22041 960 22146 960 22154 960 22041 22251 22154 22251 22026 22251 22026 960 22154 960 22585 960 22026 960 22585 960 22586 960 22586 960 22585 960 22684 960 22586 960 22684 960 22028 960 22028 960 22684 960 22029 960 22035 960 22034 960 22729 960 22729 960 22034 960 22033 960 22729 22252 22033 22252 22587 22252 22587 22253 22033 22253 22588 22253 22587 960 22588 960 22681 960 22681 22254 22588 22254 22032 22254 22681 22255 22032 22255 22589 22255 22698 960 22591 960 22590 960 22590 960 22591 960 22037 960 22041 22256 22042 22256 22592 22256 22592 22257 22042 22257 22593 22257 22592 22258 22593 22258 22147 22258 22147 22259 22593 22259 22043 22259 22147 960 22043 960 22694 960 22043 22260 22594 22260 22694 22260 22694 22261 22594 22261 22040 22261 22694 22262 22040 22262 22698 22262 22698 960 22040 960 22039 960 22698 22263 22039 22263 22591 22263 22549 960 22709 960 22595 960 22048 960 22599 960 22596 960 22596 960 22599 960 22549 960 22596 960 22549 960 22597 960 22597 960 22549 960 22595 960 22048 22264 22598 22264 22599 22264 22599 960 22598 960 22050 960 22599 22265 22050 22265 22704 22265 22050 22266 22600 22266 22704 22266 22704 960 22600 960 22059 960 22704 960 22059 960 22128 960 22059 960 22061 960 22128 960 22128 22267 22061 22267 22601 22267 22128 960 22601 960 22130 960 22130 22268 22601 22268 22058 22268 22130 22269 22058 22269 22602 22269 22602 22270 22058 22270 22056 22270 22602 22271 22056 22271 22125 22271 22125 22272 22056 22272 22054 22272 22125 22273 22054 22273 22603 22273 22603 22274 22054 22274 22053 22274 22603 22275 22053 22275 22705 22275 22705 22276 22053 22276 22604 22276 22705 22277 22604 22277 22710 22277 22607 22278 22611 22278 22608 22278 22608 960 22065 960 22607 960 22607 960 22065 960 22605 960 22607 960 22605 960 22079 960 21935 960 21976 960 22606 960 22606 960 21976 960 22607 960 22606 960 22607 960 22620 960 22620 22279 22607 22279 22079 22279 22071 960 22069 960 22611 960 22611 22280 22069 22280 22068 22280 22611 960 22068 960 22608 960 22282 960 22613 960 22609 960 22609 22281 22613 22281 22071 22281 22609 960 22071 960 22610 960 22610 960 22071 960 22611 960 22610 960 22611 960 22612 960 22282 960 22761 960 22613 960 22613 960 22761 960 22615 960 22613 22282 22615 22282 22614 22282 22614 22283 22615 22283 22759 22283 22614 960 22759 960 22617 960 22617 22284 22759 22284 22616 22284 22617 22285 22616 22285 22074 22285 22074 960 22616 960 22637 960 22074 960 22637 960 22618 960 22618 22286 22637 22286 22619 22286 22618 22287 22619 22287 22075 22287 22075 960 22619 960 22076 960 22620 22288 22621 22288 22606 22288 22606 22289 22621 22289 22081 22289 22606 960 22081 960 22622 960 22622 22290 22081 22290 22082 22290 22622 22291 22082 22291 22623 22291 22096 960 22094 960 22738 960 22553 22292 22624 22292 22560 22292 22560 22293 22624 22293 22625 22293 22560 960 22625 960 22562 960 22562 22294 22625 22294 22626 22294 22562 22295 22626 22295 22097 22295 22090 960 22627 960 22648 960 22648 960 22627 960 22088 960 22628 22296 22629 22296 22630 22296 22628 960 22630 960 22647 960 22094 960 22631 960 22738 960 22738 960 22631 960 22632 960 22738 22297 22632 22297 22633 22297 22633 22298 22632 22298 22092 22298 22644 960 22634 960 22092 960 22092 22299 22634 22299 22635 22299 22092 960 22635 960 22633 960 22752 960 22552 960 22755 960 22636 960 22106 960 22619 960 22619 22300 22106 22300 22622 22300 22619 22301 22622 22301 22076 22301 22076 22302 22622 22302 22623 22302 22552 960 22636 960 22755 960 22755 960 22636 960 22619 960 22755 22303 22619 22303 22756 22303 22756 22304 22619 22304 22637 22304 22633 960 22638 960 22738 960 22738 960 22638 960 22639 960 22738 960 22639 960 22611 960 22611 22305 22639 22305 22278 22305 22611 22306 22278 22306 22612 22306 22215 960 22214 960 22648 960 22648 22307 22214 22307 22640 22307 22648 960 22640 960 22090 960 22090 22308 22640 22308 22217 22308 22090 960 22217 960 22641 960 22641 960 22217 960 22642 960 22641 960 22642 960 22643 960 22643 22309 22642 22309 22218 22309 22643 960 22218 960 22644 960 22644 22310 22218 22310 22645 22310 22644 960 22645 960 22634 960 22207 960 22646 960 22630 960 22630 22311 22646 22311 22648 22311 22630 22312 22648 22312 22647 22312 22647 960 22648 960 22088 960 22216 22313 22215 22313 22204 22313 22204 960 22215 960 22648 960 22204 22314 22648 22314 22649 22314 22649 22315 22648 22315 22646 22315 22654 960 22652 960 22210 960 22210 22316 22652 22316 22198 22316 22650 960 22734 960 22651 960 22651 22317 22734 22317 22652 22317 22651 960 22652 960 22653 960 22653 22318 22652 22318 22654 22318 22653 960 22654 960 22655 960 22654 960 22209 960 22655 960 22655 22319 22209 22319 22200 22319 22655 960 22200 960 22657 960 22657 22320 22200 22320 22656 22320 22657 960 22656 960 22658 960 22658 22321 22656 22321 22207 22321 22658 960 22207 960 22659 960 22659 960 22207 960 22630 960 22659 960 22630 960 22721 960 22000 960 22001 960 22664 960 22664 960 22001 960 22003 960 22664 22322 22003 22322 22734 22322 22734 22323 22003 22323 22660 22323 22734 960 22660 960 22004 960 21995 22324 22192 22324 22661 22324 22661 22325 22192 22325 22662 22325 22661 22326 22662 22326 21993 22326 21993 22327 22662 22327 22194 22327 21993 22328 22194 22328 21992 22328 21992 960 22194 960 22196 960 21992 960 22196 960 21990 960 21990 22329 22196 22329 22652 22329 21990 960 22652 960 21989 960 21989 960 22652 960 22734 960 21989 960 22734 960 22007 960 22007 960 22734 960 22004 960 21995 960 22663 960 22192 960 22192 22330 22663 22330 21996 22330 22192 960 21996 960 22664 960 22664 960 21996 960 21998 960 22664 22331 21998 22331 22000 22331 22293 22332 22668 22332 22192 22332 22674 960 22665 960 22577 960 22577 960 22665 960 22670 960 22735 22333 22666 22333 22664 22333 22664 960 22666 960 22295 960 22664 22334 22295 22334 22192 22334 22192 22335 22295 22335 22667 22335 22192 22336 22667 22336 22293 22336 22180 22337 22668 22337 22665 22337 22665 22338 22668 22338 22669 22338 22665 22339 22669 22339 22670 22339 22180 960 22671 960 22668 960 22668 22340 22671 22340 22672 22340 22668 22341 22672 22341 22192 22341 22192 22342 22672 22342 22191 22342 22192 960 22191 960 22673 960 22674 22343 22577 22343 22184 22343 22184 22344 22577 22344 22675 22344 22184 960 22675 960 22187 960 22187 22345 22675 22345 22676 22345 22676 960 22675 960 22571 960 22676 960 22571 960 22178 960 22178 960 22571 960 22174 960 22178 960 22174 960 22173 960 22685 960 22677 960 22681 960 22681 960 22677 960 22678 960 22681 960 22678 960 22682 960 22679 960 22693 960 22582 960 21962 22346 22680 22346 22582 22346 22582 960 22680 960 22681 960 22582 22347 22681 22347 22679 22347 22679 22348 22681 22348 22682 22348 22689 22349 22688 22349 22683 22349 22683 22350 22688 22350 22686 22350 22589 22351 22029 22351 22681 22351 22681 22352 22029 22352 22684 22352 22681 960 22684 960 22685 960 22685 22353 22684 22353 22686 22353 22685 22354 22686 22354 22687 22354 22687 22355 22686 22355 22688 22355 22683 960 22161 960 22689 960 22689 960 22161 960 22160 960 22689 960 22160 960 22690 960 22690 22356 22160 22356 22568 22356 22690 960 22568 960 22691 960 22691 960 22568 960 22582 960 22691 960 22582 960 22692 960 22692 960 22582 960 22693 960 22698 960 22699 960 22694 960 22694 22357 22699 22357 22110 22357 22694 22358 22110 22358 22695 22358 22551 960 22550 960 22695 960 22695 960 22550 960 22696 960 22695 960 22696 960 22694 960 22590 22359 22536 22359 22700 22359 22700 960 22702 960 22590 960 22590 22360 22702 22360 22697 22360 22590 960 22697 960 22698 960 22698 22361 22697 22361 22112 22361 22698 22362 22112 22362 22699 22362 22546 960 22545 960 22704 960 22704 22363 22545 22363 22544 22363 22704 22364 22544 22364 22599 22364 22599 960 22544 960 22751 960 22700 960 22701 960 22702 960 22702 22365 22701 22365 22703 22365 22702 22366 22703 22366 22117 22366 22117 22367 22703 22367 22546 22367 22117 960 22546 960 22118 960 22118 22368 22546 22368 22704 22368 22118 960 22704 960 22119 960 22119 960 22704 960 22120 960 22120 960 22704 960 22122 960 22122 960 22704 960 22128 960 22122 22369 22128 22369 22132 22369 22099 22370 22706 22370 22705 22370 22705 960 22706 960 22707 960 22705 22371 22707 22371 22603 22371 22603 22372 22707 22372 22708 22372 22603 960 22708 960 22123 960 22301 22373 22299 22373 22549 22373 22549 960 22299 960 22705 960 22549 22374 22705 22374 22709 22374 22709 22375 22705 22375 22710 22375 22299 960 22711 960 22705 960 22705 22376 22711 22376 22712 22376 22705 960 22712 960 22099 960 22099 22377 22712 22377 22713 22377 22099 22378 22713 22378 22100 22378 22100 22379 22713 22379 22714 22379 22100 22380 22714 22380 22103 22380 22103 22381 22714 22381 22715 22381 22103 22382 22715 22382 22716 22382 22716 960 22715 960 22622 960 22716 22383 22622 22383 22105 22383 22105 960 22622 960 22106 960 22670 22384 22290 22384 22577 22384 22577 22385 22290 22385 22288 22385 22577 960 22288 960 22557 960 22557 22386 22288 22386 22719 22386 22717 22387 22736 22387 22285 22387 22285 22388 22736 22388 22557 22388 22285 960 22557 960 22718 960 22718 960 22557 960 22719 960 22629 960 22560 960 22630 960 22630 960 22560 960 22720 960 22630 960 22720 960 22721 960 22733 960 22722 960 22724 960 22722 960 22723 960 22724 960 22724 22389 22723 22389 22725 22389 22724 22390 22725 22390 22560 22390 22560 22391 22725 22391 22726 22391 22560 960 22726 960 22720 960 22727 22392 22304 22392 22728 22392 22715 960 22311 960 22622 960 22622 22393 22311 22393 22310 22393 22622 960 22310 960 22606 960 22606 22394 22310 22394 22309 22394 22606 22395 22309 22395 22306 22395 21939 960 21938 960 22728 960 22728 960 21938 960 22606 960 22728 960 22606 960 22727 960 22727 22396 22606 22396 22306 22396 22037 960 22729 960 22590 960 22590 22397 22729 22397 22732 22397 22590 960 22732 960 22536 960 22542 960 22730 960 22750 960 22730 960 22539 960 22750 960 22750 22398 22539 22398 22537 22398 22750 22399 22537 22399 22729 22399 22729 960 22537 960 22731 960 22729 960 22731 960 22732 960 22650 960 22733 960 22734 960 22734 22400 22733 22400 22724 22400 22734 960 22724 960 22664 960 22664 960 22724 960 22736 960 22664 960 22736 960 22735 960 22735 960 22736 960 22717 960 22611 22401 22749 22401 22737 22401 22611 22402 22737 22402 22738 22402 22738 960 22737 960 22739 960 22738 22403 22739 22403 22740 22403 22740 960 22741 960 22738 960 22738 22404 22741 22404 22562 22404 22738 960 22562 960 22096 960 22096 960 22562 960 22097 960 22741 960 22742 960 22562 960 22562 22405 22742 22405 22743 22405 22562 22406 22743 22406 22607 22406 22607 22407 22743 22407 22744 22407 22607 22408 22744 22408 22745 22408 22745 960 22746 960 22607 960 22607 22409 22746 22409 22747 22409 22607 22410 22747 22410 22611 22410 22611 960 22747 960 22748 960 22611 22411 22748 22411 22749 22411 22304 960 22302 960 22728 960 22728 960 22302 960 22549 960 22728 960 22549 960 22750 960 22750 960 22549 960 22599 960 22750 22412 22599 22412 22542 22412 22542 22413 22599 22413 22751 22413 22753 22414 22234 22415 22764 22416 22764 22417 22752 22417 22753 22417 22753 22418 22752 22418 22755 22418 22753 22419 22755 22419 22754 22419 22754 22420 22755 22420 22756 22420 22754 22421 22756 22421 22236 22421 22236 22422 22756 22422 22637 22422 22236 22423 22637 22423 22757 22423 22757 22424 22637 22424 22616 22424 22757 22425 22616 22425 22758 22425 22758 22426 22616 22426 22759 22426 22758 22427 22759 22427 22760 22427 22760 22428 22759 22428 22615 22428 22760 22429 22615 22429 22238 22429 22238 22430 22615 22430 22761 22430 22238 22431 22761 22431 22762 22431 22234 22432 22763 22432 22764 22432 22764 22433 22763 22433 22866 22433 22764 22434 22866 22434 22552 22434 22552 22435 22866 22435 22108 22435 22552 22436 22108 22436 22636 22436 22843 22437 22765 22437 22844 22437 22878 22438 22766 22438 22429 22438 22813 22439 22767 22439 22768 22439 22769 22440 22770 22440 22771 22440 22166 22441 22167 22441 22826 22441 22772 22442 22773 22442 22477 22442 22774 22443 22281 22443 22391 22443 22863 22444 22775 22444 22862 22444 22862 22445 22776 22445 22274 22445 22274 22446 22776 22446 22777 22446 22274 22447 22777 22447 22778 22447 22403 22448 22402 22448 22779 22448 22778 22449 22777 22449 22779 22449 22779 22450 22777 22450 22858 22450 22779 22451 22858 22451 22403 22451 22787 22452 22785 22452 22780 22452 22780 22453 22785 22453 22781 22453 22780 22454 22781 22454 22850 22454 22786 22455 22782 22455 22784 22455 22841 22456 22783 22456 22784 22456 22784 22457 22783 22457 22785 22457 22784 22458 22785 22458 22786 22458 22786 22459 22785 22459 22787 22459 22786 22460 22787 22460 22788 22460 22789 22461 22790 22461 22791 22461 22791 22462 22790 22462 22138 22462 22791 22463 22138 22463 22839 22463 22839 22464 22138 22465 22188 22466 22839 22467 22188 22467 22189 22467 22832 22468 22792 22468 22793 22468 22794 22469 22890 22470 22829 22471 22448 22472 22179 22472 22795 22472 22166 22473 22827 22473 22800 22473 22800 22474 22827 22474 22801 22474 22796 22475 22797 22475 22799 22475 22769 22476 22804 22476 22798 22476 22798 22477 22804 22477 22140 22477 22798 22478 22140 22478 22799 22478 22799 22479 22140 22479 22800 22479 22799 22480 22800 22481 22796 22482 22796 22483 22800 22483 22801 22483 22796 22484 22801 22484 22802 22484 22771 22485 22803 22485 22806 22485 22769 22486 22771 22486 22804 22486 22804 22487 22771 22487 22806 22487 22804 22488 22806 22488 22805 22488 22805 22489 22806 22489 22888 22489 22805 22490 22888 22490 22155 22490 22883 22491 22807 22491 22882 22491 22808 22492 22882 22492 22809 22492 22809 22493 22882 22493 22810 22493 22809 22494 22810 22494 22135 22494 22135 22495 22810 22495 22813 22495 22768 22496 22811 22496 22814 22496 22812 22497 22133 22497 22817 22497 22813 22498 22768 22498 22135 22498 22135 22499 22768 22499 22814 22499 22135 22500 22814 22500 22815 22500 22815 22501 22814 22501 22816 22501 22815 22502 22816 22502 22817 22502 22817 22503 22816 22503 22877 22503 22817 22504 22877 22504 22812 22504 22878 22505 22818 22505 22822 22505 22822 22506 22818 22506 22824 22506 22823 22507 22819 22507 22821 22507 22867 22508 22763 22508 22820 22508 22820 22509 22763 22509 22109 22509 22820 22510 22109 22510 22821 22510 22821 22511 22109 22511 22822 22511 22821 22512 22822 22512 22823 22512 22823 22513 22822 22514 22824 22515 22823 22516 22824 22516 22825 22516 22166 22517 22826 22517 22827 22517 22827 22518 22826 22518 22834 22518 22827 22519 22834 22519 22835 22519 22828 22520 22837 22520 22829 22520 22829 22521 22837 22521 22448 22521 22829 22522 22448 22523 22794 22524 22794 22525 22448 22525 22795 22525 22794 22526 22795 22526 22830 22526 22830 22527 22795 22527 22831 22527 22830 22528 22831 22528 22793 22528 22793 22529 22831 22529 22790 22529 22793 22530 22790 22530 22832 22530 22832 22531 22790 22531 22789 22531 22832 22532 22789 22532 22833 22532 22834 22533 22836 22533 22835 22533 22835 22534 22836 22534 22317 22534 22835 22535 22317 22535 22837 22535 22837 22536 22317 22536 22447 22536 22837 22537 22447 22537 22448 22537 22189 22538 22838 22538 22839 22538 22839 22539 22838 22539 22456 22539 22839 22540 22456 22540 22840 22540 22840 22541 22456 22541 22458 22541 22316 22542 22783 22542 22466 22542 22466 22543 22783 22543 22841 22543 22466 22544 22841 22544 22842 22544 22842 22545 22841 22545 22843 22545 22842 22546 22843 22546 22458 22546 22458 22547 22843 22547 22844 22547 22458 22548 22844 22548 22840 22548 22840 22549 22844 22549 22845 22549 22846 22550 22847 22550 22851 22550 22848 22551 22849 22551 22476 22551 22848 22552 22476 22552 22856 22552 22781 22553 22772 22553 22850 22553 22850 22554 22772 22554 22477 22554 22850 22555 22477 22555 22851 22555 22851 22556 22477 22556 22849 22556 22851 22557 22849 22557 22846 22557 22846 22558 22849 22558 22848 22558 22846 22559 22848 22560 22852 22561 22859 22562 22853 22562 22857 22562 22476 22563 22854 22563 22856 22563 22856 22564 22854 22564 22855 22564 22856 22565 22855 22565 22857 22565 22857 22566 22855 22566 22403 22566 22857 22567 22403 22567 22859 22567 22859 22568 22403 22568 22858 22568 22859 22569 22858 22569 22860 22569 22391 22570 22388 22570 22861 22570 22861 22571 22388 22571 22868 22571 22274 22572 22774 22572 22862 22572 22862 22573 22774 22573 22391 22573 22862 22574 22391 22574 22863 22574 22863 22575 22391 22575 22861 22575 22863 22576 22861 22577 22864 22578 22871 22579 22865 22579 22870 22579 22866 22580 22763 22580 22417 22580 22417 22581 22763 22581 22867 22581 22417 22582 22867 22582 22418 22582 22418 22583 22867 22583 22872 22583 22388 22584 22399 22584 22868 22584 22868 22585 22399 22585 22869 22585 22868 22586 22869 22586 22870 22586 22870 22587 22869 22587 22418 22587 22870 22588 22418 22589 22871 22590 22871 22591 22418 22591 22872 22591 22871 22592 22872 22592 22873 22592 22880 22593 22874 22594 22879 22595 22875 22596 22382 22596 22877 22596 22877 22597 22382 22597 22876 22597 22877 22598 22876 22598 22812 22598 22878 22599 22429 22599 22818 22599 22818 22600 22429 22600 22381 22600 22818 22601 22381 22601 22879 22601 22879 22602 22381 22602 22382 22602 22879 22603 22382 22603 22880 22603 22880 22604 22382 22604 22875 22604 22880 22605 22875 22605 22881 22605 22443 22606 22442 22606 22884 22606 22884 22607 22442 22607 22318 22607 22884 22608 22318 22608 22887 22608 22808 22609 22439 22609 22882 22609 22882 22610 22439 22610 22443 22610 22882 22611 22443 22611 22883 22611 22883 22612 22443 22612 22884 22612 22883 22613 22884 22613 22885 22613 22318 22614 22886 22614 22887 22614 22887 22615 22886 22615 22369 22615 22887 22616 22369 22616 22888 22616 22888 22617 22369 22617 22365 22617 22888 22618 22365 22618 22155 22618 22889 22619 22890 22619 22891 22619 22891 22620 22890 22620 22794 22620 22891 22621 22794 22621 22892 22621 22241 22622 22894 22622 22893 22622 22893 22623 22894 22623 22999 22623 22893 22624 22999 22624 22240 22624 22240 22625 22999 22625 22998 22625 22240 22626 22998 22626 22239 22626 22239 22627 22998 22627 22997 22627 22239 22628 22997 22628 22895 22628 22895 22629 22997 22629 22896 22629 22895 22630 22896 22630 22237 22630 22237 22631 22896 22631 22897 22631 22237 22631 22897 22631 22235 22631 22235 22632 22897 22632 22995 22632 22235 22633 22995 22633 22233 22633 22233 22634 22995 22634 22993 22634 22233 22635 22993 22635 22230 22635 22230 22636 22993 22636 22898 22636 22230 22637 22898 22637 22899 22637 22899 22638 22898 22638 22992 22638 22899 22639 22992 22639 22228 22639 22228 22640 22992 22640 22900 22640 22228 22641 22900 22641 22226 22641 22226 22642 22900 22642 22901 22642 22226 22643 22901 22643 22902 22643 22902 22644 22901 22644 22903 22644 22902 22645 22903 22645 22223 22645 22223 22646 22903 22646 22904 22646 22223 22647 22904 22647 22905 22647 22905 22648 22904 22648 22906 22648 22905 22648 22906 22648 22908 22648 22908 22649 22906 22649 22907 22649 22908 22649 22907 22649 22909 22649 22909 22650 22907 22650 22910 22650 22909 22651 22910 22651 22912 22651 22912 22652 22910 22652 22911 22652 22912 22653 22911 22653 22270 22653 22270 22654 22911 22654 22984 22654 22270 22655 22984 22655 22269 22655 22269 22656 22984 22656 22983 22656 22269 22657 22983 22657 22268 22657 22268 22658 22983 22658 22982 22658 22268 22659 22982 22659 22266 22659 22266 22660 22982 22660 22913 22660 22266 22661 22913 22661 22265 22661 22265 22662 22913 22662 22914 22662 22265 22663 22914 22663 22915 22663 22915 22664 22914 22664 23018 22664 22915 22665 23018 22665 22916 22665 22916 22666 23018 22666 23017 22666 22916 22666 23017 22666 22917 22666 22917 22667 23017 22667 22918 22667 22917 22668 22918 22668 22919 22668 22919 22669 22918 22669 23013 22669 22919 22670 23013 22670 22261 22670 22261 22671 23013 22671 23012 22671 22261 22672 23012 22672 22920 22672 22920 22673 23012 22673 22922 22673 22920 22674 22922 22674 22921 22674 22921 22675 22922 22675 23010 22675 22921 22676 23010 22676 22256 22676 22256 22677 23010 22677 23009 22677 22256 22678 23009 22678 22254 22678 22254 22679 23009 22679 22923 22679 22254 22680 22923 22680 22924 22680 22924 22681 22923 22681 23007 22681 22924 22682 23007 22682 22251 22682 22251 22683 23007 22683 23006 22683 22251 22683 23006 22683 22925 22683 22925 22684 23006 22684 23004 22684 22925 22685 23004 22685 22248 22685 22248 22686 23004 22686 22927 22686 22248 22687 22927 22687 22926 22687 22926 22688 22927 22688 23002 22688 22926 22689 23002 22689 22244 22689 22244 22690 23002 22690 23000 22690 22244 22691 23000 22691 22241 22691 22241 22692 23000 22692 22894 22692 22980 22693 22981 22693 22928 22693 22928 22694 22981 22694 22929 22694 22928 22695 22929 22695 22930 22695 22930 22696 22929 22696 23001 22696 22930 22696 23001 22696 22931 22696 22931 22697 23001 22697 23003 22697 22931 22698 23003 22698 22932 22698 22932 22699 23003 22699 22933 22699 22932 22699 22933 22699 22934 22699 22934 22700 22933 22700 23005 22700 22934 22701 23005 22701 22936 22701 22936 22702 23005 22702 22935 22702 22936 22703 22935 22703 22937 22703 22937 22704 22935 22704 22939 22704 22937 22705 22939 22705 22938 22705 22938 22706 22939 22706 23008 22706 22938 22707 23008 22707 22940 22707 22940 22708 23008 22708 23011 22708 22940 22709 23011 22709 22942 22709 22942 22710 23011 22710 22941 22710 22942 22711 22941 22711 22943 22711 22943 22712 22941 22712 22944 22712 22943 22713 22944 22713 22945 22713 22945 22714 22944 22714 23014 22714 22945 22715 23014 22715 22946 22715 22946 22716 23014 22716 23015 22716 22946 22716 23015 22716 22947 22716 22947 22717 23015 22717 22948 22717 22947 22718 22948 22718 22949 22718 22949 22719 22948 22719 23016 22719 22949 22720 23016 22720 22950 22720 22950 22721 23016 22721 23019 22721 22950 22722 23019 22722 22951 22722 22951 22723 23019 22723 23020 22723 22951 22724 23020 22724 22952 22724 22952 22725 23020 22725 23021 22725 22952 22726 23021 22726 22953 22726 22953 22727 23021 22727 22954 22727 22953 22728 22954 22728 22955 22728 22955 22729 22954 22729 22985 22729 22955 22730 22985 22730 22956 22730 22956 22731 22985 22731 22986 22731 22956 22732 22986 22732 22957 22732 22957 22733 22986 22733 22987 22733 22957 22734 22987 22734 22958 22734 22958 22735 22987 22735 22988 22735 22958 22736 22988 22736 22960 22736 22960 22737 22988 22737 22959 22737 22960 22738 22959 22738 22961 22738 22961 22739 22959 22739 22989 22739 22961 22740 22989 22740 22962 22740 22962 22741 22989 22741 22990 22741 22962 22742 22990 22742 22963 22742 22963 22743 22990 22743 22964 22743 22963 22744 22964 22744 22965 22744 22965 22745 22964 22745 22991 22745 22965 22746 22991 22746 22966 22746 22966 22747 22991 22747 22967 22747 22966 22748 22967 22748 22968 22748 22968 22749 22967 22749 22969 22749 22968 22750 22969 22750 22970 22750 22970 22751 22969 22751 22994 22751 22970 22752 22994 22752 22971 22752 22971 22753 22994 22753 22972 22753 22971 22754 22972 22754 22974 22754 22974 22755 22972 22755 22973 22755 22974 22756 22973 22756 22975 22756 22975 22757 22973 22757 22996 22757 22975 22758 22996 22758 22977 22758 22977 22759 22996 22759 22976 22759 22977 22760 22976 22760 22978 22760 22978 22761 22976 22761 22979 22761 22978 22762 22979 22762 22980 22762 22980 22763 22979 22763 22981 22763 22982 22764 22983 22764 22954 22764 22954 590 22983 590 22984 590 22954 22765 22984 22765 22985 22765 22985 590 22984 590 22911 590 22985 22766 22911 22766 22986 22766 22986 590 22911 590 22910 590 22986 22767 22910 22767 22987 22767 22987 590 22910 590 22907 590 22987 590 22907 590 22988 590 22988 22768 22907 22768 22906 22768 22988 22769 22906 22769 22959 22769 22959 22770 22906 22770 22904 22770 22959 590 22904 590 22989 590 22989 590 22904 590 22903 590 22989 590 22903 590 22990 590 22990 590 22903 590 22901 590 22990 22771 22901 22771 22964 22771 22964 590 22901 590 22900 590 22964 590 22900 590 22991 590 22991 590 22900 590 22992 590 22991 590 22992 590 22967 590 22967 590 22992 590 22898 590 22967 590 22898 590 22969 590 22969 590 22898 590 22993 590 22969 590 22993 590 22994 590 22994 590 22993 590 22995 590 22994 590 22995 590 22972 590 22972 22772 22995 22772 22897 22772 22972 590 22897 590 22973 590 22973 22773 22897 22773 22896 22773 22973 590 22896 590 22996 590 22996 590 22896 590 22997 590 22996 22774 22997 22774 22976 22774 22976 590 22997 590 22998 590 22976 590 22998 590 22979 590 22979 590 22998 590 22999 590 22979 590 22999 590 22981 590 22981 22775 22999 22775 22894 22775 22981 22776 22894 22776 22929 22776 22929 590 22894 590 23000 590 22929 590 23000 590 23001 590 23001 590 23000 590 23002 590 23001 22777 23002 22777 23003 22777 23003 590 23002 590 22927 590 23003 22778 22927 22778 22933 22778 22933 590 22927 590 23004 590 22933 590 23004 590 23005 590 23005 590 23004 590 23006 590 23005 590 23006 590 22935 590 22935 22779 23006 22779 23007 22779 22935 22780 23007 22780 22939 22780 22939 22781 23007 22781 22923 22781 22939 590 22923 590 23008 590 23008 22782 22923 22782 23009 22782 23008 590 23009 590 23011 590 23011 22783 23009 22783 23010 22783 23011 22784 23010 22784 22941 22784 22941 590 23010 590 22922 590 22941 22785 22922 22785 22944 22785 22944 590 22922 590 23012 590 22944 590 23012 590 23014 590 23014 590 23012 590 23013 590 23014 590 23013 590 23015 590 23015 22786 23013 22786 22918 22786 23015 590 22918 590 22948 590 22948 22787 22918 22787 23017 22787 22948 590 23017 590 23016 590 23016 590 23017 590 23018 590 23016 590 23018 590 23019 590 23019 22788 23018 22788 22914 22788 23019 590 22914 590 23020 590 23020 590 22914 590 22913 590 23020 590 22913 590 23021 590 23021 22789 22913 22789 22982 22789 23021 22790 22982 22790 22954 22790 23022 22791 23099 22791 23023 22791 23023 22792 23099 22792 23024 22792 23023 22793 23024 22793 23026 22793 23026 22794 23024 22794 23025 22794 23026 22794 23025 22794 23027 22794 23027 22795 23025 22795 23028 22795 23027 22796 23028 22796 23030 22796 23030 22797 23028 22797 23029 22797 23030 22798 23029 22798 23031 22798 23031 22799 23029 22799 23033 22799 23031 22800 23033 22800 23032 22800 23032 22801 23033 22801 23034 22801 23032 22802 23034 22802 23035 22802 23035 22803 23034 22803 23036 22803 23035 22804 23036 22804 23037 22804 23037 22805 23036 22805 23038 22805 23037 22805 23038 22805 23039 22805 23039 22806 23038 22806 23040 22806 23039 22807 23040 22807 23041 22807 23041 22808 23040 22808 23042 22808 23041 22808 23042 22808 23044 22808 23044 22809 23042 22809 23043 22809 23044 22810 23043 22810 23045 22810 23045 22811 23043 22811 23046 22811 23045 22812 23046 22812 23048 22812 23048 22813 23046 22813 23047 22813 23048 22814 23047 22814 23049 22814 23049 22815 23047 22815 23050 22815 23049 22816 23050 22816 23051 22816 23051 22817 23050 22817 23052 22817 23051 22817 23052 22817 23053 22817 23053 22818 23052 22818 23054 22818 23053 22819 23054 22819 23055 22819 23055 22820 23054 22820 23056 22820 23055 22821 23056 22821 23057 22821 23057 22822 23056 22822 23059 22822 23057 22823 23059 22823 23058 22823 23058 22824 23059 22824 23060 22824 23058 22825 23060 22825 23061 22825 23061 22826 23060 22826 23062 22826 23061 22827 23062 22827 23064 22827 23064 22828 23062 22828 23063 22828 23064 22829 23063 22829 23065 22829 23065 22830 23063 22830 23067 22830 23065 22831 23067 22831 23066 22831 23066 22832 23067 22832 23068 22832 23066 22832 23068 22832 23070 22832 23070 22833 23068 22833 23069 22833 23070 22834 23069 22834 23072 22834 23072 22835 23069 22835 23071 22835 23072 22836 23071 22836 23073 22836 23073 22837 23071 22837 23074 22837 23073 22838 23074 22838 23075 22838 23075 22839 23074 22839 23076 22839 23075 22840 23076 22840 23077 22840 23077 22841 23076 22841 23078 22841 23077 22842 23078 22842 23080 22842 23080 22843 23078 22843 23079 22843 23080 22844 23079 22844 23081 22844 23081 22845 23079 22845 23083 22845 23081 22846 23083 22846 23082 22846 23082 22847 23083 22847 23084 22847 23082 22848 23084 22848 23085 22848 23085 22849 23084 22849 23087 22849 23085 22849 23087 22849 23086 22849 23086 22850 23087 22850 23088 22850 23086 22851 23088 22851 23089 22851 23089 22852 23088 22852 23091 22852 23089 22853 23091 22853 23090 22853 23090 22854 23091 22854 23093 22854 23090 22855 23093 22855 23092 22855 23092 22856 23093 22856 23094 22856 23092 22857 23094 22857 23095 22857 23095 22858 23094 22858 23097 22858 23095 22859 23097 22859 23096 22859 23096 22860 23097 22860 23098 22860 23096 22861 23098 22861 23022 22861 23022 22862 23098 22862 23099 22862 23100 22863 23106 22863 23101 22863 23101 22864 23106 22864 23616 22864 23101 22865 23616 22865 23102 22865 23102 22866 23616 22866 23112 22866 23102 22867 23112 22867 23750 22867 23110 22868 23103 22868 23104 22868 23104 22869 23103 22869 23105 22869 23104 22870 23105 22870 23100 22870 23100 22871 23105 22871 23460 22871 23100 22872 23460 22872 23106 22872 23116 20347 23107 20347 23108 20347 23108 22873 23107 22873 23458 22873 23108 22874 23458 22874 23109 22874 23109 22875 23458 22875 23459 22875 23109 22876 23459 22876 23110 22876 23110 22877 23459 22877 23111 22877 23110 22878 23111 22878 23103 22878 23112 22879 23465 22879 23750 22879 23750 22880 23465 22880 23113 22880 23750 22881 23113 22881 23752 22881 23752 22882 23113 22882 23115 22882 23752 22883 23115 22883 23114 22883 23114 22884 23115 22884 23464 22884 23114 22885 23464 22885 23754 22885 23754 20353 23464 20353 23463 20353 23754 22886 23463 22886 23116 22886 23116 22887 23463 22887 23461 22887 23116 20354 23461 20354 23107 20354 23117 590 23397 590 23118 590 23117 590 23118 590 23398 590 23398 590 23118 590 23234 590 23398 590 23234 590 23389 590 23234 22888 23119 22888 23389 22888 23389 590 23119 590 23120 590 23389 22889 23120 22889 23390 22889 23390 22890 23120 22890 23122 22890 23390 590 23122 590 23121 590 23121 22891 23122 22891 23240 22891 23121 590 23240 590 23392 590 23139 22892 23123 22892 23124 22892 23124 22893 23123 22893 23624 22893 23124 22894 23624 22894 23125 22894 23264 22895 23126 22895 23127 22895 23264 22896 23127 22896 23128 22896 23128 22897 23127 22897 23376 22897 23128 22898 23376 22898 23129 22898 23129 22899 23376 22899 23130 22899 23129 22900 23130 22900 23131 22900 23131 22901 23130 22901 23375 22901 23131 22902 23375 22902 23133 22902 23133 22903 23375 22903 23132 22903 23133 22904 23132 22904 23262 22904 23262 22905 23132 22905 23134 22905 23262 22906 23134 22906 23135 22906 23135 22907 23134 22907 23136 22907 23135 22908 23136 22908 23278 22908 23278 22909 23136 22909 23437 22909 23278 22910 23437 22910 23137 22910 23137 22911 23437 22911 23372 22911 23137 22912 23372 22912 23138 22912 23138 22913 23372 22913 23374 22913 23138 22914 23374 22914 23139 22914 23139 22915 23374 22915 23373 22915 23139 22916 23373 22916 23123 22916 23127 590 23126 590 23140 590 23140 22917 23126 22917 23141 22917 23140 22918 23141 22918 23371 22918 23371 590 23141 590 23266 590 23371 590 23266 590 23363 590 23363 590 23266 590 23142 590 23363 590 23142 590 23364 590 23364 590 23142 590 23143 590 23364 590 23143 590 23367 590 23367 22919 23143 22919 23268 22919 23367 590 23268 590 23369 590 23144 22920 23242 22920 23256 22920 23120 22921 23237 22921 23329 22921 23145 22922 23146 22922 23219 22922 23149 22923 23150 22923 23147 22923 23147 22924 23150 22924 23162 22924 23147 22925 23162 22925 23148 22925 23149 22926 23151 22926 23150 22926 23150 22927 23151 22928 23152 22928 23150 22929 23152 22929 23153 22929 23154 22930 23155 22931 23159 22932 23159 22933 23155 22933 23156 22933 23159 22934 23156 22934 23157 22934 23157 22935 23158 22935 23159 22935 23159 22936 23158 22936 23160 22936 23159 22937 23160 22937 23195 22937 23165 22938 23161 22938 23162 22938 23162 22939 23161 22939 23452 22939 23162 22940 23452 22940 23148 22940 23163 22941 23167 22941 23165 22941 23165 22942 23167 22942 23164 22942 23165 22943 23164 22943 23161 22943 23171 22944 23172 22944 23163 22944 23163 22945 23172 22945 23166 22945 23163 22946 23166 22946 23167 22946 23183 22947 23185 22947 23168 22947 23168 22948 23185 22948 23169 22948 23168 22949 23169 22949 23171 22949 23171 22950 23169 22950 23170 22950 23171 22951 23170 22951 23172 22951 23173 22952 23174 22952 23289 22952 23176 22953 23175 22953 23177 22953 23176 22954 23177 22954 23179 22954 23193 22955 23189 22955 23177 22955 23177 22956 23189 22956 23178 22956 23177 22957 23178 22957 23179 22957 23174 22958 23180 22958 23289 22958 23289 22959 23180 22959 23181 22959 23289 22960 23181 22960 23183 22960 23183 22961 23181 22961 23182 22961 23183 22962 23182 22962 23564 22962 23564 22963 23660 22963 23183 22963 23183 22964 23660 22964 23184 22964 23183 22965 23184 22965 23185 22965 23186 22966 23187 22966 23193 22966 23193 22967 23187 22968 23188 22969 23193 22970 23188 22970 23189 22970 23305 22971 23190 22971 23306 22971 23306 22972 23190 22972 23191 22972 23306 22973 23191 22973 23192 22973 23192 22974 23191 22974 23186 22974 23192 22975 23186 22975 23308 22975 23308 22976 23186 22976 23193 22976 23160 22977 23194 22977 23195 22977 23195 22978 23194 22978 23196 22978 23195 22979 23196 22979 23305 22979 23305 22980 23196 22980 23197 22980 23305 22981 23197 22981 23190 22981 23201 22982 23288 22982 23198 22982 23198 22983 23288 22983 23199 22983 23198 22984 23199 22984 23200 22984 23200 22985 23199 22985 23612 22985 23201 22986 23202 22986 23288 22986 23288 22987 23202 22987 23203 22987 23288 22988 23203 22988 23204 22988 23205 22989 23206 22989 23328 22989 23328 22990 23206 22990 23207 22990 23328 22991 23207 22991 23208 22991 23208 22992 23209 22992 23328 22992 23328 22993 23209 22993 23238 22993 23328 22994 23238 22994 23210 22994 23146 22995 23145 22995 23211 22995 23211 22996 23145 22996 23212 22996 23211 22997 23212 22997 23213 22997 23213 22998 23212 22998 23214 22998 23213 22999 23214 22999 23215 22999 23215 23000 23214 23000 23614 23000 23215 23001 23614 23001 23199 23001 23199 23002 23614 23002 23613 23002 23199 23003 23613 23003 23612 23003 23229 23004 23216 23004 23217 23004 23217 23005 23216 23005 23467 23005 23217 23006 23467 23006 23219 23006 23219 23007 23467 23007 23218 23007 23219 23008 23218 23008 23145 23008 23270 23009 23224 23009 23226 23009 23220 23010 23269 23010 23223 23010 23220 23011 23223 23011 23221 23011 23230 23012 23232 23012 23223 23012 23223 23013 23232 23013 23222 23013 23223 23014 23222 23014 23221 23014 23224 23015 23225 23015 23226 23015 23226 23016 23225 23016 23227 23016 23226 23017 23227 23017 23217 23017 23217 23018 23227 23018 23228 23018 23217 23019 23228 23019 23229 23019 23234 23020 23118 23020 23230 23020 23230 23021 23118 23021 23231 23021 23230 23022 23231 23022 23232 23022 23230 23023 23233 23023 23234 23023 23234 23024 23233 23024 23235 23024 23234 23025 23235 23025 23119 23025 23119 23026 23235 23026 23120 23026 23120 23027 23235 23027 23236 23027 23120 23028 23236 23028 23237 23028 23238 23029 23239 23029 23210 23029 23210 23030 23239 23030 23240 23030 23210 23031 23240 23031 23329 23031 23329 23032 23240 23032 23122 23032 23329 23033 23122 23033 23120 23033 23244 23034 23246 23034 23241 23034 23241 23035 23246 23035 23242 23035 23241 23036 23242 23037 23243 23038 23243 23039 23242 23039 23144 23039 23244 23040 23245 23040 23246 23040 23246 23041 23245 23041 23247 23041 23246 23042 23247 23043 23248 23044 23249 23045 23250 23045 23315 23045 23315 23046 23250 23046 23251 23046 23315 23047 23251 23047 23252 23047 23252 23048 23253 23048 23315 23048 23315 23049 23253 23049 23254 23049 23315 23050 23254 23050 23316 23050 23257 23051 23636 23051 23256 23051 23256 23052 23636 23052 23255 23052 23256 23053 23255 23053 23144 23053 23498 23054 23496 23054 23257 23054 23257 23055 23496 23055 23495 23055 23257 23056 23495 23056 23636 23056 23257 23057 23258 23057 23498 23057 23498 23058 23258 23058 23260 23058 23498 23059 23260 23059 23259 23059 23259 23060 23260 23060 23626 23060 23626 23061 23260 23061 23263 23061 23626 23062 23263 23062 23623 23062 23323 23063 23128 23063 23261 23063 23261 23064 23128 23064 23129 23064 23261 23065 23129 23065 23131 23065 23131 23066 23133 23066 23261 23066 23261 23067 23133 23067 23262 23067 23261 23068 23262 23068 23135 23068 23278 23069 23137 23069 23279 23069 23279 23070 23137 23070 23138 23070 23138 23071 23139 23071 23279 23071 23279 23072 23139 23072 23124 23072 23279 23073 23124 23073 23263 23073 23263 23074 23124 23074 23125 23074 23263 23075 23125 23075 23623 23075 23141 23076 23126 23076 23323 23076 23323 23077 23126 23078 23264 23079 23323 23080 23264 23080 23128 23080 23317 23081 23142 23081 23265 23081 23265 23082 23142 23082 23266 23082 23265 23083 23266 23083 23319 23083 23319 23084 23266 23084 23141 23084 23319 23085 23141 23085 23321 23085 23321 23086 23141 23086 23323 23086 23254 23087 23267 23087 23316 23087 23316 23088 23267 23088 23268 23088 23316 23089 23268 23089 23317 23089 23317 23090 23268 23090 23143 23090 23317 23091 23143 23091 23142 23091 23269 23092 23270 23092 23223 23092 23223 23093 23270 23093 23226 23093 23223 23094 23226 23094 23271 23094 23271 23095 23226 23095 23272 23095 23271 23096 23272 23096 23299 23096 23299 23097 23272 23097 23274 23097 23299 23098 23274 23098 23273 23098 23273 23099 23274 23099 23275 23099 23273 23100 23275 23100 23301 23100 23301 23101 23275 23101 23276 23101 23301 23102 23276 23102 23302 23102 23302 23103 23276 23103 23277 23103 23302 23104 23277 23104 23159 23104 23159 23105 23277 23105 23150 23105 23159 23106 23150 23106 23154 23106 23154 23107 23150 23107 23153 23107 23135 23108 23278 23108 23261 23108 23261 23109 23278 23109 23279 23109 23261 23110 23279 23110 23324 23110 23324 23111 23279 23111 23281 23111 23324 23112 23281 23112 23280 23112 23280 23113 23281 23113 23282 23113 23280 23114 23282 23114 23283 23114 23283 23115 23282 23115 23284 23115 23283 23116 23284 23116 23285 23116 23285 23117 23284 23117 23286 23117 23285 23118 23286 23118 23325 23118 23325 23119 23286 23119 23287 23119 23325 23120 23287 23120 23328 23120 23328 23121 23287 23121 23288 23121 23328 23122 23288 23122 23205 23122 23205 23123 23288 23123 23204 23123 23175 23124 23173 23124 23177 23124 23177 23125 23173 23125 23289 23125 23177 23126 23289 23126 23309 23126 23309 23127 23289 23127 23290 23127 23309 23128 23290 23128 23312 23128 23312 23129 23290 23129 23291 23129 23312 23130 23291 23130 23293 23130 23293 23131 23291 23131 23292 23131 23293 23132 23292 23132 23294 23132 23294 23133 23292 23133 23295 23133 23294 23134 23295 23134 23296 23134 23296 23135 23295 23135 23297 23135 23296 23136 23297 23136 23315 23136 23315 23137 23297 23137 23246 23137 23315 23138 23246 23138 23249 23138 23249 23139 23246 23139 23248 23139 23237 960 23236 960 23388 960 23388 960 23236 960 23235 960 23388 960 23235 960 23387 960 23387 960 23235 960 23233 960 23387 960 23233 960 23298 960 23298 960 23233 960 23230 960 23298 960 23230 960 23396 960 23396 960 23230 960 23223 960 23396 960 23223 960 23400 960 23400 960 23223 960 23271 960 23400 960 23271 960 23428 960 23428 23140 23271 23140 23299 23140 23428 960 23299 960 23300 960 23300 960 23299 960 23273 960 23300 960 23273 960 23430 960 23430 960 23273 960 23301 960 23430 23141 23301 23141 23423 23141 23423 960 23301 960 23302 960 23423 23142 23302 23142 23421 23142 23421 960 23302 960 23159 960 23421 23143 23159 23143 23303 23143 23303 960 23159 960 23195 960 23303 23144 23195 23144 23304 23144 23304 960 23195 960 23305 960 23304 960 23305 960 23333 960 23333 960 23305 960 23306 960 23333 960 23306 960 23335 960 23335 23145 23306 23145 23192 23145 23335 23146 23192 23146 23307 23146 23307 23147 23192 23147 23308 23147 23307 23148 23308 23148 23338 23148 23338 960 23308 960 23193 960 23338 960 23193 960 23418 960 23418 960 23193 960 23177 960 23418 960 23177 960 23420 960 23420 23149 23177 23149 23309 23149 23420 960 23309 960 23310 960 23310 960 23309 960 23312 960 23310 960 23312 960 23311 960 23311 960 23312 960 23293 960 23311 960 23293 960 23313 960 23313 960 23293 960 23294 960 23313 960 23294 960 23314 960 23314 23150 23294 23150 23296 23150 23314 23151 23296 23151 23445 23151 23445 960 23296 960 23315 960 23445 960 23315 960 23368 960 23368 960 23315 960 23316 960 23368 960 23316 960 23366 960 23366 960 23316 960 23317 960 23366 960 23317 960 23365 960 23365 960 23317 960 23265 960 23365 23152 23265 23152 23318 23152 23318 960 23265 960 23319 960 23318 960 23319 960 23320 960 23320 960 23319 960 23321 960 23320 23153 23321 23153 23322 23153 23322 960 23321 960 23323 960 23322 23154 23323 23154 23438 23154 23438 23155 23323 23155 23261 23155 23438 960 23261 960 23440 960 23440 960 23261 960 23324 960 23440 960 23324 960 23442 960 23442 23156 23324 23156 23280 23156 23442 960 23280 960 23436 960 23436 960 23280 960 23283 960 23436 960 23283 960 23432 960 23432 960 23283 960 23285 960 23432 960 23285 960 23383 960 23383 960 23285 960 23325 960 23383 23157 23325 23157 23326 23157 23326 960 23325 960 23328 960 23326 960 23328 960 23327 960 23327 960 23328 960 23210 960 23327 960 23210 960 23391 960 23391 23158 23210 23158 23329 23158 23391 960 23329 960 23388 960 23388 960 23329 960 23237 960 23330 23159 23456 23159 23331 23159 23362 23160 23632 23160 23361 23160 23303 23161 23304 23161 23332 23161 23332 23162 23304 23162 23333 23162 23332 23163 23333 23163 23334 23163 23334 23164 23333 23164 23335 23164 23334 23165 23335 23165 23336 23165 23336 23166 23335 23166 23307 23166 23336 23167 23307 23167 23337 23167 23337 23168 23307 23168 23338 23168 23337 23169 23338 23169 23339 23169 23340 23170 23341 23170 23418 23170 23346 23171 23419 23171 23342 23171 23342 23172 23419 23172 23569 23172 23342 23173 23569 23173 23343 23173 23343 23174 23569 23174 23344 23174 23340 23175 23418 23176 23345 23177 23346 23178 23347 23178 23419 23178 23419 23179 23347 23179 23348 23179 23419 23180 23348 23180 23349 23180 23341 23181 23350 23181 23418 23181 23418 23182 23350 23182 23351 23182 23418 23183 23351 23183 23338 23183 23338 23184 23351 23184 23352 23184 23338 23185 23352 23185 23339 23185 23354 23186 23353 23186 23444 23186 23354 23187 23444 23188 23443 23189 23355 23190 23356 23190 23445 23190 23445 23191 23356 23191 23357 23191 23445 23192 23357 23192 23443 23192 23353 23193 23358 23193 23444 23193 23444 23194 23358 23194 23359 23194 23444 23195 23359 23195 23361 23195 23361 23196 23359 23196 23360 23196 23361 23197 23360 23197 23362 23197 23320 23198 23371 23198 23318 23198 23318 23199 23371 23199 23363 23199 23318 23200 23363 23200 23365 23200 23365 23201 23363 23201 23364 23201 23365 23202 23364 23202 23366 23202 23366 23203 23364 23203 23367 23203 23366 23204 23367 23204 23368 23204 23368 23205 23367 23205 23369 23205 23368 23206 23369 23206 23445 23206 23445 23207 23369 23207 23370 23207 23445 23208 23370 23208 23355 23208 23322 23209 23127 23209 23320 23209 23320 23210 23127 23210 23140 23210 23320 23211 23140 23211 23371 23211 23374 23212 23372 23212 23618 23212 23624 23213 23123 23213 23618 23213 23618 23214 23123 23214 23373 23214 23618 23215 23373 23215 23374 23215 23437 23216 23136 23216 23438 23216 23438 23217 23136 23217 23134 23217 23438 23218 23134 23218 23132 23218 23132 23219 23375 23219 23438 23219 23438 23220 23375 23220 23130 23220 23438 23221 23130 23221 23322 23221 23322 23222 23130 23222 23376 23222 23322 23223 23376 23223 23127 23223 23377 23224 23378 23224 23379 23224 23379 23225 23378 23225 23380 23225 23379 23226 23380 23226 23462 23226 23462 23227 23380 23227 23381 23227 23462 23228 23381 23228 23331 23228 23331 23229 23381 23229 23382 23229 23331 23230 23382 23230 23330 23230 23433 23231 23383 23231 23384 23231 23384 23232 23383 23232 23326 23232 23384 23233 23326 23233 23385 23233 23385 23234 23326 23234 23386 23234 23298 23235 23398 23235 23387 23235 23387 23236 23398 23236 23389 23236 23387 23237 23389 23237 23388 23237 23388 23238 23389 23238 23390 23238 23388 23239 23390 23239 23391 23239 23391 23240 23390 23240 23121 23240 23391 23241 23121 23241 23327 23241 23327 23242 23121 23242 23392 23242 23327 23243 23392 23243 23326 23243 23326 23244 23392 23244 23393 23244 23326 23245 23393 23245 23386 23245 23394 23246 23395 23246 23396 23246 23396 23247 23395 23247 23397 23247 23396 23248 23397 23248 23298 23248 23298 23249 23397 23249 23117 23249 23298 23250 23117 23250 23398 23250 23426 23251 23399 23252 23400 23253 23400 23254 23399 23254 23401 23254 23400 23255 23401 23255 23396 23255 23396 23256 23401 23256 23402 23256 23396 23257 23402 23257 23394 23257 23480 23258 23403 23258 23479 23258 23479 23259 23403 23259 23404 23259 23479 23260 23404 23260 23405 23260 23405 23261 23404 23261 23406 23261 23405 23262 23406 23262 23407 23262 23407 23263 23406 23263 23425 23263 23407 23264 23425 23264 23671 23264 23408 23265 23415 23265 23661 23265 23409 23266 23414 23266 23421 23266 23409 23267 23421 23267 23410 23267 23332 23268 23411 23268 23303 23268 23303 23269 23411 23269 23412 23269 23303 23270 23412 23270 23421 23270 23421 23271 23412 23271 23413 23271 23421 23272 23413 23272 23410 23272 23408 23273 23661 23273 23414 23273 23415 23274 23416 23274 23661 23274 23661 23275 23416 23275 23417 23275 23661 23276 23417 23276 23662 23276 23349 23277 23345 23277 23419 23277 23419 23278 23345 23278 23418 23278 23419 23279 23418 23279 23566 23279 23566 23280 23418 23280 23420 23280 23566 23281 23420 23281 23519 23281 23519 23282 23420 23282 23310 23282 23519 23283 23310 23283 23652 23283 23414 23284 23661 23284 23421 23284 23421 23285 23661 23285 23422 23285 23421 23286 23422 23286 23423 23286 23665 23287 23430 23287 23450 23287 23450 23288 23430 23288 23423 23288 23450 23289 23423 23289 23424 23289 23424 23290 23423 23290 23422 23290 23425 23291 23426 23291 23671 23291 23671 23292 23426 23292 23400 23292 23671 23293 23400 23293 23427 23293 23427 23294 23400 23294 23428 23294 23427 23295 23428 23295 23669 23295 23669 23296 23428 23296 23300 23296 23669 23297 23300 23297 23429 23297 23429 23298 23300 23298 23430 23298 23429 23299 23430 23299 23449 23299 23449 23300 23430 23300 23665 23300 23434 23301 23436 23301 23431 23301 23431 23302 23436 23302 23432 23302 23431 23303 23432 23303 23379 23303 23379 23304 23432 23304 23383 23304 23379 23305 23383 23305 23377 23305 23377 23306 23383 23306 23433 23306 23434 23307 23435 23307 23436 23307 23436 23308 23435 23308 23466 23308 23436 23309 23466 23309 23442 23309 23372 23310 23437 23310 23618 23310 23618 23311 23437 23311 23438 23311 23618 23312 23438 23312 23439 23312 23439 23313 23438 23313 23440 23313 23439 23314 23440 23314 23441 23314 23441 23315 23440 23315 23442 23315 23441 23316 23442 23316 23617 23316 23617 23317 23442 23317 23466 23317 23443 23318 23444 23318 23445 23318 23445 23319 23444 23319 23446 23319 23445 23320 23446 23320 23314 23320 23446 23321 23637 23321 23314 23321 23314 23322 23637 23322 23447 23322 23314 23323 23447 23323 23313 23323 23447 23324 23515 23324 23313 23324 23313 23325 23515 23325 23448 23325 23313 23326 23448 23326 23311 23326 23311 23327 23448 23327 23650 23327 23311 23328 23650 23328 23310 23328 23310 23329 23650 23329 23651 23329 23310 23330 23651 23330 23652 23330 23449 23331 23455 23331 23471 23331 23665 960 23450 960 23451 960 23452 23332 23161 23332 23578 23332 23453 960 23640 960 23620 960 23666 960 23454 960 23455 960 23456 23333 23457 23333 23458 23333 23458 960 23107 960 23456 960 23456 960 23107 960 23461 960 23456 960 23461 960 23331 960 23331 23334 23461 23334 23462 23334 23555 960 23111 960 23457 960 23457 960 23111 960 23459 960 23457 960 23459 960 23458 960 23106 960 23460 960 23548 960 23548 23335 23460 23335 23105 23335 23548 960 23105 960 23555 960 23555 23336 23105 23336 23103 23336 23555 23337 23103 23337 23111 23337 23461 23338 23463 23338 23462 23338 23462 23339 23463 23339 23464 23339 23462 960 23464 960 23379 960 23379 23340 23464 23340 23115 23340 23379 23341 23115 23341 23431 23341 23431 23342 23115 23342 23113 23342 23431 23343 23113 23343 23434 23343 23434 960 23113 960 23465 960 23434 960 23465 960 23435 960 23435 23344 23465 23344 23112 23344 23435 960 23112 960 23466 960 23466 960 23112 960 23616 960 23229 960 23480 960 23216 960 23216 960 23480 960 23525 960 23216 960 23525 960 23467 960 23405 23345 23468 23345 23469 23345 23454 23346 23470 23346 23455 23346 23455 960 23470 960 23472 960 23455 23347 23472 23347 23471 23347 23471 960 23472 960 23473 960 23471 960 23473 960 23670 960 23589 23348 23474 23348 23668 23348 23668 960 23474 960 23476 960 23476 23349 23474 23349 23475 23349 23476 960 23475 960 23488 960 23488 960 23475 960 23477 960 23488 23350 23477 23350 23478 23350 23405 960 23469 960 23479 960 23479 23351 23469 23351 23481 23351 23479 960 23481 960 23480 960 23480 23352 23481 23352 23482 23352 23480 23353 23482 23353 23525 23353 23525 23354 23482 23354 23483 23354 23525 23355 23483 23355 23484 23355 23485 960 23486 960 23478 960 23478 960 23486 960 23487 960 23478 23356 23487 23356 23488 23356 23489 960 23490 960 23492 960 23492 23357 23490 23357 23491 23357 23635 23358 23634 23358 23493 23358 23635 960 23493 960 23492 960 23492 23359 23493 23359 23494 23359 23492 960 23494 960 23489 960 23636 960 23495 960 23633 960 23633 960 23495 960 23496 960 23633 23360 23496 23360 23497 23360 23497 960 23496 960 23499 960 23496 960 23498 960 23499 960 23499 23361 23498 23361 23259 23361 23499 23362 23259 23362 23500 23362 23500 23363 23259 23363 23626 23363 23500 960 23626 960 23501 960 23501 23364 23626 23364 23620 23364 23501 960 23620 960 23638 960 23540 23365 23502 23365 23503 23365 23503 960 23502 960 23523 960 23503 960 23504 960 23540 960 23540 23366 23504 23366 23505 23366 23540 23367 23505 23367 23510 23367 23506 960 23507 960 23447 960 23565 960 23508 960 23509 960 23505 960 23511 960 23510 960 23510 23368 23511 23368 23512 23368 23510 23369 23512 23369 23513 23369 23447 960 23507 960 23515 960 23515 23370 23507 23370 23514 23370 23515 960 23514 960 23516 960 23517 960 23519 960 23518 960 23518 23371 23519 23371 23652 23371 23518 960 23652 960 23653 960 23508 23372 23520 23372 23509 23372 23509 960 23520 960 23521 960 23509 23373 23521 23373 23502 23373 23502 960 23521 960 23522 960 23502 960 23522 960 23523 960 23524 960 23525 960 23485 960 23485 23374 23525 23374 23484 23374 23485 960 23484 960 23486 960 23526 960 23528 960 23527 960 23527 23375 23528 23375 23525 23375 23527 23376 23525 23376 23529 23376 23529 960 23525 960 23524 960 23590 23377 23561 23377 23530 23377 23530 960 23561 960 23538 960 23531 960 23532 960 23589 960 23589 23378 23532 23378 23533 23378 23589 960 23533 960 23474 960 23544 960 23534 960 23502 960 23502 23379 23534 23379 23535 23379 23561 960 23536 960 23538 960 23538 23380 23536 23380 23537 23380 23538 23381 23537 23381 23539 23381 23539 960 23537 960 23535 960 23648 23382 23541 23382 23540 23382 23540 23383 23541 23383 23542 23383 23540 23384 23542 23384 23502 23384 23502 960 23542 960 23543 960 23502 23385 23543 23385 23544 23385 23551 960 23545 960 23622 960 23622 960 23545 960 23546 960 23622 960 23546 960 23620 960 23620 960 23546 960 23547 960 23620 23386 23547 23386 23453 23386 23555 960 23557 960 23548 960 23548 23387 23557 23387 23549 23387 23548 23388 23549 23388 23622 23388 23622 23389 23549 23389 23550 23389 23622 23390 23550 23390 23551 23390 23526 960 23552 960 23528 960 23528 23391 23552 23391 23553 23391 23528 960 23553 960 23457 960 23457 23392 23553 23392 23554 23392 23457 23393 23554 23393 23555 23393 23555 23394 23554 23394 23556 23394 23555 960 23556 960 23557 960 23558 960 23559 960 23561 960 23561 960 23559 960 23560 960 23561 23395 23560 23395 23536 23395 23578 960 23654 960 23558 960 23558 23396 23654 23396 23562 23396 23558 23397 23562 23397 23559 23397 23563 23398 23659 23398 23660 23398 23660 960 23564 960 23344 960 23517 960 23565 960 23519 960 23519 960 23565 960 23509 960 23519 960 23509 960 23566 960 23566 23399 23509 23399 23567 23399 23566 23400 23567 23400 23571 23400 23563 23401 23660 23401 23568 23401 23568 23402 23660 23402 23344 23402 23568 960 23344 960 23570 960 23570 23403 23344 23403 23569 23403 23570 23404 23569 23404 23571 23404 23571 23405 23569 23405 23419 23405 23571 23406 23419 23406 23566 23406 23537 960 23572 960 23535 960 23535 23407 23572 23407 23573 23407 23535 23408 23573 23408 23502 23408 23502 23409 23573 23409 23574 23409 23502 23410 23574 23410 23509 23410 23509 23411 23574 23411 23575 23411 23509 23412 23575 23412 23567 23412 23558 960 23595 960 23577 960 23580 960 23576 960 23578 960 23578 23413 23576 23413 23663 23413 23558 960 23577 960 23578 960 23578 23414 23577 23414 23579 23414 23578 23415 23579 23415 23580 23415 23581 960 23451 960 23582 960 23582 960 23451 960 23450 960 23582 960 23450 960 23583 960 23583 23416 23450 23416 23424 23416 23583 960 23424 960 23584 960 23584 960 23424 960 23422 960 23584 960 23422 960 23664 960 23581 23417 23585 23417 23451 23417 23451 23418 23585 23418 23586 23418 23451 960 23586 960 23589 960 23589 23419 23586 23419 23587 23419 23589 23420 23587 23420 23588 23420 23588 960 23591 960 23589 960 23589 960 23591 960 23561 960 23589 23421 23561 23421 23531 23421 23531 960 23561 960 23590 960 23591 960 23592 960 23561 960 23561 23422 23592 23422 23593 23422 23561 960 23593 960 23558 960 23558 23423 23593 23423 23594 23423 23558 960 23594 960 23595 960 23596 960 23597 960 23525 960 23528 23424 23598 23424 23599 23424 23599 960 23600 960 23528 960 23528 960 23600 960 23601 960 23528 23425 23601 23425 23525 23425 23525 960 23601 960 23602 960 23525 23426 23602 23426 23596 23426 23212 960 23603 960 23214 960 23214 23427 23603 23427 23604 23427 23214 960 23604 960 23614 960 23614 960 23604 960 23605 960 23614 23428 23605 23428 23615 23428 23597 960 23606 960 23525 960 23525 960 23606 960 23607 960 23525 960 23607 960 23467 960 23467 960 23607 960 23608 960 23467 960 23608 960 23218 960 23218 23429 23608 23429 23609 23429 23218 960 23609 960 23145 960 23145 23430 23609 23430 23610 23430 23145 960 23610 960 23212 960 23212 23431 23610 23431 23611 23431 23212 23432 23611 23432 23603 23432 23200 960 23612 960 23456 960 23456 23433 23612 23433 23613 23433 23456 23434 23613 23434 23457 23434 23457 23435 23613 23435 23614 23435 23457 960 23614 960 23528 960 23528 23436 23614 23436 23615 23436 23528 23437 23615 23437 23598 23437 23616 960 23106 960 23466 960 23466 23438 23106 23438 23548 23438 23466 960 23548 960 23617 960 23617 960 23548 960 23622 960 23617 960 23622 960 23441 960 23628 960 23685 960 23620 960 23623 23439 23125 23439 23624 23439 23624 23440 23618 23440 23619 23440 23685 960 23686 960 23620 960 23620 23441 23686 23441 23621 23441 23620 960 23621 960 23622 960 23622 23442 23621 23442 23688 23442 23622 960 23688 960 23689 960 23626 23443 23623 23443 23625 23443 23625 23444 23623 23444 23624 23444 23625 23445 23624 23445 23678 23445 23678 960 23624 960 23619 960 23625 960 23681 960 23626 960 23626 960 23681 960 23683 960 23626 960 23683 960 23620 960 23620 23446 23683 23446 23627 23446 23620 23447 23627 23447 23628 23447 23689 960 23629 960 23622 960 23622 960 23629 960 23630 960 23622 960 23630 960 23441 960 23441 23448 23630 23448 23631 23448 23441 23449 23631 23449 23439 23449 23439 23450 23631 23450 23691 23450 23439 23451 23691 23451 23618 23451 23618 960 23691 960 23675 960 23618 23452 23675 23452 23619 23452 23361 960 23632 960 23635 960 23635 23453 23632 23453 23243 23453 23635 23454 23243 23454 23144 23454 23633 960 23634 960 23636 960 23636 960 23634 960 23635 960 23636 23455 23635 23455 23255 23455 23255 23456 23635 23456 23144 23456 23361 960 23635 960 23444 960 23444 23457 23635 23457 23492 23457 23444 960 23492 960 23446 960 23637 23458 23510 23458 23447 23458 23447 960 23510 960 23513 960 23447 23459 23513 23459 23506 23459 23638 960 23620 960 23639 960 23639 23460 23620 23460 23640 23460 23639 960 23640 960 23641 960 23641 960 23640 960 23642 960 23641 23461 23642 23461 23643 23461 23643 960 23642 960 23644 960 23643 960 23644 960 23645 960 23645 960 23644 960 23646 960 23645 960 23646 960 23647 960 23647 960 23646 960 23648 960 23647 960 23648 960 23649 960 23649 960 23648 960 23540 960 23649 960 23540 960 23491 960 23491 960 23540 960 23510 960 23491 23462 23510 23462 23492 23462 23492 960 23510 960 23637 960 23492 960 23637 960 23446 960 23650 960 23448 960 23651 960 23651 23463 23448 23463 23515 23463 23651 960 23515 960 23652 960 23652 23464 23515 23464 23516 23464 23652 23465 23516 23465 23653 23465 23161 960 23164 960 23578 960 23578 960 23164 960 23167 960 23578 960 23167 960 23654 960 23654 960 23167 960 23166 960 23654 23466 23166 23466 23655 23466 23655 960 23166 960 23172 960 23655 960 23172 960 23656 960 23656 960 23172 960 23170 960 23656 23467 23170 23467 23657 23467 23657 23468 23170 23468 23169 23468 23657 23469 23169 23469 23658 23469 23658 960 23169 960 23185 960 23658 960 23185 960 23659 960 23659 23470 23185 23470 23184 23470 23659 23471 23184 23471 23660 23471 23422 960 23661 960 23662 960 23148 23472 23452 23472 23662 23472 23662 960 23452 960 23578 960 23662 23473 23578 23473 23422 23473 23422 23474 23578 23474 23663 23474 23422 960 23663 960 23664 960 23449 960 23665 960 23455 960 23455 23475 23665 23475 23451 23475 23455 960 23451 960 23666 960 23666 23476 23451 23476 23589 23476 23666 23477 23589 23477 23667 23477 23667 960 23589 960 23668 960 23427 960 23669 960 23471 960 23471 23478 23669 23478 23429 23478 23471 23479 23429 23479 23449 23479 23468 960 23405 960 23670 960 23670 23480 23405 23480 23407 23480 23670 960 23407 960 23471 960 23471 23481 23407 23481 23671 23481 23471 960 23671 960 23427 960 23625 23482 23672 23482 23673 23482 23625 23483 23673 23483 23681 23483 23678 23484 23680 23484 23625 23484 23625 23485 23680 23485 23674 23485 23625 23486 23674 23486 23672 23486 23675 23487 23676 23487 23619 23487 23619 23488 23676 23488 23677 23488 23619 23489 23677 23489 23678 23489 23678 23490 23677 23490 23679 23490 23678 23491 23679 23491 23680 23491 23673 23492 23733 23492 23681 23492 23681 23493 23733 23493 23731 23493 23681 23493 23731 23493 23683 23493 23683 23494 23731 23494 23682 23494 23683 23494 23682 23494 23627 23494 23627 23495 23682 23495 23684 23495 23627 23495 23684 23495 23628 23495 23628 23496 23684 23496 23726 23496 23628 23497 23726 23497 23685 23497 23685 23498 23726 23498 23728 23498 23685 23499 23728 23499 23686 23499 23686 23500 23728 23500 23687 23500 23686 23501 23687 23501 23621 23501 23621 23502 23687 23502 23729 23502 23621 23503 23729 23503 23688 23503 23688 23504 23729 23504 23749 23504 23688 23505 23749 23505 23689 23505 23689 23506 23749 23506 23747 23506 23689 23507 23747 23507 23629 23507 23629 23508 23747 23508 23690 23508 23629 23509 23690 23509 23630 23509 23630 23510 23690 23510 23746 23510 23630 23511 23746 23511 23631 23511 23631 23512 23746 23512 23720 23512 23631 23513 23720 23513 23691 23513 23691 23514 23720 23514 23719 23514 23691 23515 23719 23515 23675 23515 23675 23516 23719 23516 23692 23516 23675 23517 23692 23517 23676 23517 23693 590 23695 590 23694 590 23695 23518 23693 23518 23732 23518 23732 23519 23693 23519 23696 23519 23732 590 23696 590 23725 590 23738 590 23697 590 23740 590 23707 590 23699 590 23698 590 23698 23520 23699 23520 23700 23520 23698 590 23700 590 23694 590 23694 23521 23700 23521 23701 23521 23694 590 23701 590 23693 590 23724 590 23702 590 23727 590 23727 23522 23702 23522 23703 23522 23727 590 23703 590 23704 590 23704 590 23703 590 23705 590 23704 23523 23705 23523 23838 23523 23706 23524 23708 23524 23707 23524 23707 590 23708 590 23709 590 23707 23525 23709 23525 23699 23525 23699 23526 23709 23526 23710 23526 23699 590 23710 590 23711 590 23711 590 23710 590 23712 590 23711 590 23712 590 23717 590 23717 23527 23712 23527 23713 23527 23717 23528 23713 23528 23716 23528 23714 590 23745 590 23715 590 23715 23529 23745 23529 23840 23529 23716 590 23715 590 23717 590 23717 590 23715 590 23840 590 23717 590 23840 590 23705 590 23705 23530 23840 23530 23718 23530 23705 590 23718 590 23838 590 23719 590 23720 590 23721 590 23721 23531 23720 23531 23746 23531 23721 590 23746 590 23748 590 23827 23532 23729 23532 23722 23532 23722 590 23729 590 23723 590 23726 590 23684 590 23727 590 23727 590 23684 590 23732 590 23727 590 23732 590 23724 590 23724 590 23732 590 23725 590 23726 23533 23727 23533 23728 23533 23728 590 23727 590 23833 590 23728 23534 23833 23534 23687 23534 23687 23535 23833 23535 23831 23535 23687 590 23831 590 23729 590 23729 590 23831 590 23730 590 23729 23536 23730 23536 23723 23536 23684 590 23682 590 23732 590 23732 590 23682 590 23731 590 23732 590 23731 590 23734 590 23734 590 23731 590 23733 590 23734 590 23733 590 23673 590 23735 23537 23854 23537 23776 23537 23776 590 23854 590 23851 590 23776 590 23851 590 23849 590 23845 23538 23799 23538 23736 23538 23736 590 23799 590 23776 590 23736 590 23776 590 23737 590 23737 23539 23776 23539 23849 23539 23738 590 23740 590 23739 590 23739 23540 23740 23540 23799 23540 23739 590 23799 590 23741 590 23741 23541 23799 23541 23845 23541 23741 23542 23845 23542 23742 23542 23742 23543 23845 23543 23743 23543 23742 23544 23743 23544 23714 23544 23714 23545 23743 23545 23744 23545 23714 23546 23744 23546 23745 23546 23746 590 23690 590 23748 590 23748 23547 23690 23547 23747 23547 23748 23548 23747 23548 23827 23548 23827 23549 23747 23549 23749 23549 23827 590 23749 590 23729 590 23102 590 23750 590 23751 590 23751 23550 23750 23550 23752 23550 23751 590 23752 590 23753 590 23752 23551 23114 23551 23753 23551 23753 23552 23114 23552 23754 23552 23753 23553 23754 23553 23755 23553 23755 23554 23754 23554 23116 23554 23751 23555 23756 23555 23102 23555 23102 23556 23756 23556 23748 23556 23102 23557 23748 23557 23101 23557 23101 590 23748 590 23100 590 23757 590 23758 590 23776 590 23776 23558 23759 23558 23760 23558 23827 23559 23735 23559 23748 23559 23748 23560 23735 23560 23776 23560 23748 23561 23776 23561 23100 23561 23100 590 23776 590 23104 590 23116 590 23108 590 23755 590 23755 590 23108 590 23761 590 23755 23562 23761 23562 23763 23562 23763 23563 23761 23563 23762 23563 23763 590 23762 590 23764 590 23109 23564 23765 23564 23108 23564 23108 590 23765 590 23766 590 23108 590 23766 590 23761 590 23104 23565 23776 23565 23110 23565 23110 590 23776 590 23760 590 23110 590 23760 590 23109 590 23109 23566 23760 23566 23767 23566 23109 590 23767 590 23765 590 23771 590 23768 590 23777 590 23758 23567 23769 23567 23776 23567 23776 23568 23769 23568 23770 23568 23776 23569 23770 23569 23759 23569 23771 590 23777 590 23780 590 23772 590 23775 590 23776 590 23772 590 23776 590 23773 590 23773 590 23776 590 23815 590 23773 590 23815 590 23774 590 23775 23570 23778 23570 23776 23570 23776 590 23778 590 23780 590 23776 23571 23780 23571 23757 23571 23757 590 23780 590 23777 590 23778 590 23779 590 23780 590 23780 23572 23779 23572 23781 23572 23780 23573 23781 23573 23782 23573 23782 23574 23781 23574 23784 23574 23782 590 23784 590 23783 590 23783 23575 23784 23575 23785 23575 23783 23576 23785 23576 23786 23576 23786 590 23785 590 23787 590 23786 23577 23787 23577 23788 23577 23788 23578 23787 23578 23789 23578 23788 23579 23789 23579 23815 23579 23815 23580 23789 23580 23790 23580 23815 23581 23790 23581 23774 23581 23805 590 23791 590 23792 590 23793 23582 23794 23582 23796 23582 23792 590 23791 590 23794 590 23794 590 23791 590 23795 590 23794 23583 23795 23583 23796 23583 23796 590 23797 590 23793 590 23793 590 23797 590 23798 590 23793 590 23798 590 23799 590 23799 590 23798 590 23800 590 23799 590 23800 590 23776 590 23776 23584 23800 23584 23801 23584 23776 23585 23801 23585 23821 23585 23802 590 23803 590 23804 590 23804 23586 23803 23586 23809 23586 23804 23587 23809 23587 23807 23587 23805 590 23792 590 23806 590 23806 23588 23792 23588 23807 23588 23806 23589 23807 23589 23808 23589 23807 590 23809 590 23808 590 23808 590 23809 590 23810 590 23808 590 23810 590 23812 590 23812 23590 23810 23590 23811 23590 23812 23591 23811 23591 23821 23591 23824 23592 23813 23592 23776 23592 23776 23593 23813 23593 23814 23593 23776 23594 23814 23594 23815 23594 23815 23595 23814 23595 23816 23595 23815 23596 23816 23596 23817 23596 23817 23597 23816 23597 23818 23597 23817 23598 23818 23598 23819 23598 23811 23599 23820 23599 23821 23599 23821 590 23820 590 23822 590 23821 590 23822 590 23776 590 23776 23600 23822 23600 23823 23600 23776 23601 23823 23601 23824 23601 23853 23602 23735 23602 23825 23602 23825 23603 23735 23603 23827 23603 23825 23603 23827 23603 23826 23603 23826 23604 23827 23604 23722 23604 23826 23605 23722 23605 23828 23605 23828 23606 23722 23606 23723 23606 23828 23607 23723 23607 23829 23607 23829 23608 23723 23608 23730 23608 23829 23609 23730 23609 23830 23609 23830 23610 23730 23610 23831 23610 23830 23611 23831 23611 23832 23611 23832 23612 23831 23612 23833 23612 23832 23613 23833 23613 23834 23613 23834 23614 23833 23614 23727 23614 23834 23615 23727 23615 23835 23615 23835 23616 23727 23616 23704 23616 23835 23617 23704 23617 23836 23617 23836 23618 23704 23618 23838 23618 23836 23619 23838 23619 23837 23619 23837 23620 23838 23620 23718 23620 23837 23621 23718 23621 23839 23621 23839 23622 23718 23622 23840 23622 23839 23623 23840 23623 23841 23623 23841 23624 23840 23624 23745 23624 23841 23625 23745 23625 23842 23625 23842 23626 23745 23626 23744 23626 23842 23627 23744 23627 23843 23627 23843 23628 23744 23628 23743 23628 23843 23629 23743 23629 23844 23629 23844 23630 23743 23630 23845 23630 23844 23631 23845 23631 23846 23631 23846 23632 23845 23632 23736 23632 23846 23633 23736 23633 23847 23633 23847 23634 23736 23634 23737 23634 23847 23635 23737 23635 23848 23635 23848 23636 23737 23636 23849 23636 23848 23637 23849 23637 23850 23637 23850 23638 23849 23638 23851 23638 23850 23639 23851 23639 23852 23639 23852 23640 23851 23640 23854 23640 23852 23640 23854 23640 23853 23640 23853 23641 23854 23641 23735 23641 23856 23642 24010 23642 23855 23642 23856 23643 23855 23643 23941 23643 24010 23644 23856 23644 24012 23644 24012 23645 23856 23645 23857 23645 24012 23646 23857 23646 24013 23646 24013 23647 23857 23647 24014 23647 24014 23648 23857 23648 23859 23648 24014 23649 23859 23649 23858 23649 23863 23650 23864 23650 23859 23650 23859 23651 23864 23651 24015 23651 23859 23652 24015 23653 23858 23654 24019 23655 23861 23656 23860 23657 23860 23658 23861 23658 23862 23658 23860 23659 23862 23659 23863 23659 23863 23660 23862 23660 24016 23660 23863 23661 24016 23661 23864 23661 24019 23662 23860 23662 23866 23662 23866 23663 23860 23663 23865 23663 23866 23664 23865 23664 23867 23664 23867 23665 23865 23665 23868 23665 23868 23666 23865 23666 23869 23666 23868 23667 23869 23667 24021 23667 24021 23668 23869 23668 23870 23668 23870 23669 23869 23669 23871 23669 23870 23670 23871 23670 23874 23670 23872 23671 24024 23671 23871 23671 23871 23672 24024 23672 23873 23672 23871 23673 23873 23673 23874 23673 23877 23674 23875 23674 23876 23674 23876 23675 23875 23675 24026 23675 23876 23676 24026 23676 23872 23676 23872 23677 24026 23677 24025 23677 23872 23678 24025 23678 24024 23678 23877 23679 23876 23679 23878 23679 23878 23680 23876 23680 23879 23680 23878 23681 23879 23681 24027 23681 24027 23682 23879 23682 23880 23682 23880 23683 23879 23683 23881 23683 23880 23684 23881 23684 24028 23684 24028 23685 23881 23685 24029 23685 24029 23686 23881 23686 23882 23686 24029 23687 23882 23687 24030 23687 23886 23688 24033 23688 23882 23688 23882 23689 24033 23689 24032 23689 23882 23690 24032 23690 24030 23690 23883 23691 23885 23691 23884 23691 23884 23692 23885 23692 23887 23692 23884 23693 23887 23693 23886 23693 23886 23694 23887 23694 23888 23694 23886 23695 23888 23695 24033 23695 23883 23696 23884 23696 24036 23696 24036 23697 23884 23697 23890 23697 24036 23698 23890 23698 23889 23698 23889 23699 23890 23699 23891 23699 23891 23700 23890 23700 23895 23700 23891 23701 23895 23701 23892 23701 23893 23702 23894 23702 23895 23702 23895 23703 23894 23703 24038 23703 23895 23704 24038 23704 23892 23704 23896 23705 23897 23705 23893 23705 23893 23706 23897 23706 23898 23706 23893 23707 23898 23707 23894 23707 24042 23708 23899 23708 23900 23708 23900 23709 23899 23709 23901 23709 23900 23710 23901 23710 23896 23710 23896 23711 23901 23711 23902 23711 23896 23712 23902 23712 23897 23712 24042 23713 23900 23713 23903 23713 23903 23714 23900 23714 23904 23714 23903 23715 23904 23715 23905 23715 23907 23716 23909 23716 23904 23716 23904 23717 23909 23717 24044 23717 23904 23718 24044 23718 23905 23718 23911 23719 23906 23719 23907 23719 23907 23720 23906 23720 23908 23720 23907 23721 23908 23722 23909 23723 24049 23724 23910 23724 23913 23724 23913 23725 23910 23725 24047 23725 23913 23726 24047 23726 23911 23726 23911 23727 24047 23727 24046 23727 23911 23728 24046 23728 23906 23728 24049 23729 23913 23729 23912 23729 23912 23730 23913 23730 23915 23730 23912 23731 23915 23731 23914 23731 23914 23732 23915 23732 24051 23732 24051 23733 23915 23733 23916 23733 24051 23734 23916 23734 23917 23734 23917 23735 23916 23735 23918 23735 23918 23736 23916 23736 23919 23736 23918 23737 23919 23737 24055 23737 23920 23738 24058 23738 23919 23738 23919 23739 24058 23739 24056 23739 23919 23740 24056 23740 24055 23740 23924 23741 23925 23741 23920 23741 23920 23742 23925 23742 23921 23742 23920 23743 23921 23743 24058 23743 24061 23744 23922 23744 23923 23744 23923 23745 23922 23745 24060 23745 23923 23746 24060 23746 23924 23746 23924 23747 24060 23747 24059 23747 23924 23748 24059 23748 23925 23748 24061 23749 23923 23749 24064 23749 24064 23750 23923 23750 23927 23750 24064 23751 23927 23751 24065 23751 24065 23752 23927 23752 23926 23752 23926 23753 23927 23753 23929 23753 23926 23754 23929 23754 24066 23754 23928 23755 24069 23755 23929 23755 23929 23756 24069 23756 24067 23756 23929 23757 24067 23757 24066 23757 23933 23758 23930 23758 23928 23758 23928 23759 23930 23759 23931 23759 23928 23760 23931 23760 24069 23760 24073 23761 24072 23761 23932 23761 23932 23762 24072 23762 24071 23762 23932 23763 24071 23763 23933 23763 23933 23764 24071 23764 23934 23764 23933 23765 23934 23765 23930 23765 24073 23766 23932 23766 24074 23766 24074 23767 23932 23767 23935 23767 24074 23768 23935 23768 24075 23768 24075 23769 23935 23769 23936 23769 23936 23770 23935 23770 23937 23770 23936 23771 23937 23771 23938 23771 23939 23772 23940 23772 23937 23772 23937 23773 23940 23773 24077 23773 23937 23774 24077 23774 23938 23774 23855 23775 23942 23775 23941 23775 23941 23776 23942 23776 24080 23776 23941 23777 24080 23777 23939 23777 23939 23778 24080 23778 24079 23778 23939 23779 24079 23779 23940 23779 23970 960 24200 960 23943 960 23943 960 24200 960 23944 960 23943 23780 23944 23780 23957 23780 23949 23781 24228 23781 23945 23781 23945 960 24228 960 23946 960 23945 23782 23946 23782 23976 23782 23961 23783 23948 23783 23947 23783 23947 23784 23948 23784 24230 23784 23947 23785 24230 23785 23949 23785 23949 960 24230 960 23950 960 23949 960 23950 960 24228 960 23955 960 23951 960 23952 960 23952 23786 23951 23786 23963 23786 23952 23787 23963 23787 23953 23787 23954 960 24194 960 23955 960 23955 23788 24194 23788 24241 23788 23955 23789 24241 23789 23951 23789 23944 960 23956 960 23957 960 23957 23790 23956 23790 24197 23790 23957 960 24197 960 23958 960 23958 23791 24197 23791 24195 23791 23958 23792 24195 23792 23954 23792 23954 23793 24195 23793 23959 23793 23954 23794 23959 23794 24194 23794 23983 960 23960 960 23961 960 23961 960 23960 960 23962 960 23961 23795 23962 23795 23948 23795 23963 23796 24238 23796 23953 23796 23953 960 24238 960 23964 960 23953 960 23964 960 23965 960 23965 960 23964 960 24236 960 23965 960 24236 960 23979 960 23966 960 23968 960 23967 960 23967 23797 23968 23797 23969 23797 23967 23798 23969 23798 23970 23798 23970 960 23969 960 23971 960 23970 23799 23971 23799 24200 23799 23992 960 24222 960 23973 960 23973 23800 24222 23800 23972 23800 23973 960 23972 960 23974 960 23946 960 23975 960 23976 960 23976 23801 23975 23801 23977 23801 23976 23802 23977 23802 23978 23802 23978 23803 23977 23803 23988 23803 23978 960 23988 960 23989 960 24236 960 23980 960 23979 960 23979 960 23980 960 23982 960 23979 960 23982 960 23981 960 23981 23804 23982 23804 24233 23804 23981 960 24233 960 23983 960 23983 960 24233 960 24232 960 23983 960 24232 960 23960 960 23984 23805 24203 23805 23966 23805 23966 960 24203 960 23985 960 23966 23806 23985 23806 23968 23806 24001 960 23987 960 23986 960 23986 960 23987 960 24208 960 23986 960 24208 960 23994 960 23988 23807 23990 23807 23989 23807 23989 960 23990 960 23991 960 23989 960 23991 960 23992 960 23992 23808 23991 23808 23993 23808 23992 23809 23993 23809 24222 23809 24208 23810 24207 23810 23994 23810 23994 960 24207 960 23995 960 23994 23811 23995 23811 23996 23811 23996 960 23995 960 23997 960 23996 960 23997 960 23984 960 23984 960 23997 960 24205 960 23984 23812 24205 23812 24203 23812 24003 960 23998 960 23999 960 23999 960 23998 960 24000 960 23999 960 24000 960 24001 960 24001 960 24000 960 24209 960 24001 960 24209 960 23987 960 24002 960 24213 960 24003 960 24003 960 24213 960 24212 960 24003 960 24212 960 23998 960 24008 960 24009 960 24004 960 24004 23813 24009 23813 24215 23813 24004 960 24215 960 24002 960 24002 23814 24215 23814 24214 23814 24002 960 24214 960 24213 960 23972 960 24005 960 23974 960 23974 19068 24005 19068 24221 19068 23974 960 24221 960 24006 960 24006 23815 24221 23815 24007 23815 24006 23816 24007 23816 24008 23816 24008 23817 24007 23817 24218 23817 24008 960 24218 960 24009 960 24131 23818 24010 23818 24011 23818 24011 23819 24010 23819 24012 23819 24011 23820 24012 23820 24130 23820 24012 23821 24013 23821 24130 23821 24130 23822 24013 23822 24014 23822 24130 23823 24014 23823 24128 23823 24014 23824 23858 23824 24128 23824 24128 23825 23858 23825 24015 23825 24128 23826 24015 23826 24127 23826 24127 23827 24015 23827 23864 23827 24127 23828 23864 23828 24126 23828 23864 23829 24016 23829 24126 23829 24126 23830 24016 23830 23862 23830 24126 23831 23862 23831 24017 23831 23862 23832 23861 23832 24017 23832 24017 23833 23861 23833 24019 23833 24017 23834 24019 23834 24018 23834 24019 23835 23866 23835 24018 23835 24018 23836 23866 23836 23867 23836 24018 23837 23867 23837 24020 23837 23867 23838 23868 23838 24020 23838 24020 23839 23868 23839 24021 23839 24020 23840 24021 23840 24022 23840 24022 23841 24021 23841 23870 23841 24022 23842 23870 23842 24023 23842 23870 23843 23874 23843 24023 23843 24023 23844 23874 23844 23873 23844 24023 23845 23873 23845 24122 23845 24122 23846 23873 23846 24024 23846 24122 23847 24024 23847 24119 23847 24024 23848 24025 23848 24119 23848 24119 23849 24025 23850 24026 23851 24119 23852 24026 23852 24117 23852 24026 23853 23875 23853 24117 23853 24117 23854 23875 23854 23877 23854 24117 23855 23877 23855 24115 23855 24115 23856 23877 23856 23878 23856 24115 23857 23878 23857 24114 23857 24114 23858 23878 23858 24027 23858 24027 23859 23880 23859 24114 23859 24114 23860 23880 23860 24028 23860 24114 23861 24028 23861 24113 23861 24113 23862 24028 23862 24029 23862 24113 23863 24029 23863 24031 23863 24029 23864 24030 23864 24031 23864 24031 23865 24030 23865 24032 23865 24031 23866 24032 23866 24110 23866 24110 23867 24032 23867 24033 23867 24110 23868 24033 23868 24034 23868 24033 23869 23888 23869 24034 23869 24034 23870 23888 23870 23887 23870 24034 23871 23887 23871 24035 23871 23887 23872 23885 23872 24035 23872 24035 23873 23885 23873 23883 23873 24035 23874 23883 23874 24107 23874 24107 23875 23883 23875 24036 23875 24107 23876 24036 23876 24106 23876 24106 23877 24036 23877 23889 23877 23889 23878 23891 23878 24106 23878 24106 23879 23891 23879 23892 23879 24106 23880 23892 23880 24037 23880 24037 23881 23892 23881 24038 23881 24037 23882 24038 23882 24039 23882 24038 23883 23894 23883 24039 23883 24039 23884 23894 23884 23898 23884 24039 23885 23898 23885 24102 23885 24102 23886 23898 23886 23897 23886 24102 23887 23897 23887 24040 23887 23897 23888 23902 23888 24040 23888 24040 23889 23902 23889 23901 23889 24040 23890 23901 23890 24041 23890 23901 23891 23899 23891 24041 23891 24041 23892 23899 23892 24042 23892 24041 23893 24042 23893 24043 23893 24043 23894 24042 23894 23903 23894 24043 23895 23903 23895 24098 23895 23903 23896 23905 23896 24098 23896 24098 23897 23905 23898 24044 23899 24098 23900 24044 23900 24045 23900 24044 23901 23909 23901 24045 23901 24045 23902 23909 23903 23908 23904 24045 23905 23908 23905 24096 23905 23908 23906 23906 23906 24096 23906 24096 23907 23906 23907 24046 23907 24096 23908 24046 23908 24048 23908 24046 23909 24047 23909 24048 23909 24048 23910 24047 23910 23910 23910 24048 23911 23910 23911 24095 23911 24095 23912 23910 23913 24049 23912 24095 23914 24049 23914 24050 23914 24049 23915 23912 23915 24050 23915 24050 23916 23912 23916 23914 23916 24050 23917 23914 23917 24052 23917 24052 23918 23914 23918 24051 23918 24052 23919 24051 23919 24053 23919 24051 23920 23917 23920 24053 23920 24053 23921 23917 23921 23918 23921 24053 23922 23918 23922 24054 23922 23918 23923 24055 23923 24054 23923 24054 23924 24055 23924 24056 23924 24054 23925 24056 23925 24057 23925 24056 23926 24058 23926 24057 23926 24057 23927 24058 23927 23921 23927 24057 23928 23921 23928 24091 23928 23921 23929 23925 23929 24091 23929 24091 23930 23925 23930 24059 23930 24091 23931 24059 23931 24090 23931 24090 23932 24059 23932 24060 23932 24090 23933 24060 23933 24089 23933 24060 23934 23922 23934 24089 23934 24089 23935 23922 23935 24061 23935 24089 23936 24061 23936 24062 23936 24062 23937 24061 23937 24064 23937 24062 23938 24064 23938 24063 23938 24064 23939 24065 23939 24063 23939 24063 23940 24065 23940 23926 23940 24063 23941 23926 23941 24087 23941 23926 23942 24066 23942 24087 23942 24087 23943 24066 23943 24067 23943 24087 23944 24067 23944 24068 23944 24068 23945 24067 23945 24069 23945 24068 23946 24069 23946 24085 23946 24085 23947 24069 23947 23931 23947 23931 23948 23930 23948 24085 23948 24085 23949 23930 23949 23934 23949 24085 23950 23934 23950 24070 23950 24070 23951 23934 23951 24071 23951 24070 23952 24071 23952 24084 23952 24071 23953 24072 23953 24084 23953 24084 23954 24072 23954 24073 23954 24084 23955 24073 23955 24083 23955 24083 23956 24073 23956 24074 23956 24083 23957 24074 23957 24082 23957 24074 23958 24075 23958 24082 23958 24082 23959 24075 23959 23936 23959 24082 23960 23936 23960 24076 23960 23936 23961 23938 23961 24076 23961 24076 23962 23938 23962 24077 23962 24076 23963 24077 23963 24078 23963 24078 23964 24077 23964 23940 23964 24078 23965 23940 23965 24136 23965 23940 23966 24079 23966 24136 23966 24136 23967 24079 23967 24080 23967 24136 23968 24080 23968 24134 23968 24134 23969 24080 23969 23942 23969 24134 23970 23942 23970 24131 23970 24131 23971 23942 23971 23855 23971 24131 23972 23855 23972 24010 23972 24136 23973 24137 23973 24078 23973 24078 23974 24137 23974 24081 23974 24078 23975 24081 23975 24076 23975 24076 23976 24081 23976 24139 23976 24076 23977 24139 23977 24082 23977 24082 23978 24139 23978 24141 23978 24082 23979 24141 23979 24083 23979 24083 23980 24141 23980 24142 23980 24083 23981 24142 23981 24084 23981 24084 23982 24142 23982 24143 23982 24084 23983 24143 23983 24070 23983 24070 23984 24143 23984 24144 23984 24070 23985 24144 23985 24085 23985 24085 23986 24144 23986 24086 23986 24085 23987 24086 23987 24068 23987 24068 23988 24086 23988 24146 23988 24068 23989 24146 23989 24087 23989 24087 23990 24146 23990 24148 23990 24087 23991 24148 23991 24063 23991 24063 23992 24148 23992 24088 23992 24063 23993 24088 23993 24062 23993 24062 23994 24088 23994 24150 23994 24062 23995 24150 23995 24089 23995 24089 23996 24150 23996 24152 23996 24089 23997 24152 23997 24090 23997 24090 23998 24152 23998 24153 23998 24090 23999 24153 23999 24091 23999 24091 24000 24153 24000 24092 24000 24091 24001 24092 24001 24057 24001 24057 24002 24092 24002 24156 24002 24057 24003 24156 24003 24054 24003 24054 24004 24156 24004 24093 24004 24054 24005 24093 24005 24053 24005 24053 24006 24093 24006 24094 24006 24053 24007 24094 24007 24052 24007 24052 24008 24094 24008 24159 24008 24052 24009 24159 24009 24050 24009 24050 24010 24159 24010 24160 24010 24050 24011 24160 24011 24095 24011 24095 24012 24160 24012 24161 24012 24095 24013 24161 24013 24048 24013 24048 24014 24161 24014 24163 24014 24048 24015 24163 24015 24096 24015 24096 24016 24163 24016 24166 24016 24096 24017 24166 24017 24045 24017 24045 24018 24166 24018 24097 24018 24045 24019 24097 24019 24098 24019 24098 24020 24097 24020 24099 24020 24098 24021 24099 24021 24043 24021 24043 24022 24099 24022 24100 24022 24043 24023 24100 24023 24041 24023 24041 24024 24100 24024 24101 24024 24041 24025 24101 24025 24040 24025 24040 24026 24101 24026 24103 24026 24040 24027 24103 24027 24102 24027 24102 24028 24103 24028 24169 24028 24102 24029 24169 24029 24039 24029 24039 24030 24169 24030 24104 24030 24039 24031 24104 24031 24037 24031 24037 24032 24104 24032 24105 24032 24037 24033 24105 24033 24106 24033 24106 24034 24105 24034 24108 24034 24106 24035 24108 24035 24107 24035 24107 24036 24108 24036 24174 24036 24107 24037 24174 24037 24035 24037 24035 24038 24174 24039 24109 24040 24035 24041 24109 24041 24034 24041 24034 24042 24109 24042 24175 24042 24034 24043 24175 24043 24110 24043 24110 24044 24175 24044 24111 24044 24110 24045 24111 24045 24031 24045 24031 24046 24111 24046 24112 24046 24031 24047 24112 24047 24113 24047 24113 24048 24112 24048 24177 24048 24113 24049 24177 24049 24114 24049 24114 24050 24177 24050 24178 24050 24114 24051 24178 24051 24115 24051 24115 24052 24178 24052 24116 24052 24115 24053 24116 24053 24117 24053 24117 24054 24116 24054 24118 24054 24117 24055 24118 24055 24119 24055 24119 24056 24118 24056 24120 24056 24119 24057 24120 24057 24122 24057 24122 24058 24120 24058 24121 24058 24122 24059 24121 24059 24023 24059 24023 24060 24121 24060 24181 24060 24023 24061 24181 24061 24022 24061 24022 24062 24181 24062 24123 24062 24022 24063 24123 24063 24020 24063 24020 24064 24123 24064 24124 24064 24020 24065 24124 24065 24018 24065 24018 24066 24124 24066 24125 24066 24018 24067 24125 24067 24017 24067 24017 24068 24125 24068 24185 24068 24017 24069 24185 24069 24126 24069 24126 24070 24185 24070 24186 24070 24126 24071 24186 24071 24127 24071 24127 24072 24186 24072 24129 24072 24127 24073 24129 24073 24128 24073 24128 24074 24129 24074 24189 24074 24128 24075 24189 24075 24130 24075 24130 24076 24189 24076 24190 24076 24130 24077 24190 24077 24011 24077 24011 24078 24190 24078 24132 24078 24011 24079 24132 24079 24131 24079 24131 24080 24132 24080 24133 24080 24131 24081 24133 24081 24134 24081 24134 24082 24133 24082 24135 24082 24134 24083 24135 24083 24136 24083 24136 24084 24135 24084 24137 24084 24137 24085 24193 24085 24081 24085 24081 24086 24193 24086 24138 24086 24081 24087 24138 24087 24139 24087 24139 24088 24138 24088 24140 24088 24139 24089 24140 24089 24141 24089 24141 24090 24140 24090 24196 24090 24141 24091 24196 24091 24142 24091 24142 24092 24196 24092 24198 24092 24142 24093 24198 24093 24143 24093 24143 24094 24198 24094 24199 24094 24143 24095 24199 24095 24144 24095 24144 24096 24199 24096 24145 24096 24144 24097 24145 24097 24086 24097 24086 24098 24145 24098 24201 24098 24086 24099 24201 24099 24146 24099 24146 24100 24201 24100 24147 24100 24146 24101 24147 24101 24148 24101 24148 24102 24147 24102 24149 24102 24148 24103 24149 24103 24088 24103 24088 24104 24149 24104 24202 24104 24088 24105 24202 24105 24150 24105 24150 24106 24202 24106 24151 24106 24150 24107 24151 24107 24152 24107 24152 24108 24151 24108 24204 24108 24152 24109 24204 24109 24153 24109 24153 24110 24204 24110 24154 24110 24153 24111 24154 24111 24092 24111 24092 24112 24154 24112 24206 24112 24092 24113 24206 24113 24156 24113 24156 24114 24206 24114 24155 24114 24156 24115 24155 24115 24093 24115 24093 24116 24155 24116 24157 24116 24093 24117 24157 24117 24094 24117 24094 24118 24157 24118 24158 24118 24094 24119 24158 24119 24159 24119 24159 24120 24158 24120 24210 24120 24159 24121 24210 24121 24160 24121 24160 24122 24210 24122 24211 24122 24160 24123 24211 24123 24161 24123 24161 24124 24211 24124 24162 24124 24161 24125 24162 24125 24163 24125 24163 24126 24162 24126 24164 24126 24163 24127 24164 24127 24166 24127 24166 24128 24164 24128 24165 24128 24166 24129 24165 24129 24097 24129 24097 24130 24165 24130 24167 24130 24097 24131 24167 24131 24099 24131 24099 24132 24167 24132 24216 24132 24099 24133 24216 24133 24100 24133 24100 24134 24216 24134 24168 24134 24100 24135 24168 24135 24101 24135 24101 24136 24168 24136 24217 24136 24101 24137 24217 24137 24103 24137 24103 24138 24217 24138 24219 24138 24103 24139 24219 24139 24169 24139 24169 24140 24219 24140 24220 24140 24169 24141 24220 24141 24104 24141 24104 24142 24220 24142 24170 24142 24104 24143 24170 24143 24105 24143 24105 24144 24170 24144 24171 24144 24105 24145 24171 24145 24108 24145 24108 24146 24171 24146 24172 24146 24108 24147 24172 24147 24174 24147 24174 24148 24172 24148 24173 24148 24174 24149 24173 24149 24109 24149 24109 24150 24173 24150 24223 24150 24109 24151 24223 24151 24175 24151 24175 24152 24223 24152 24176 24152 24175 24153 24176 24153 24111 24153 24111 24154 24176 24154 24224 24154 24111 24155 24224 24155 24112 24155 24112 24156 24224 24156 24225 24156 24112 24157 24225 24157 24177 24157 24177 24158 24225 24158 24226 24158 24177 24159 24226 24159 24178 24159 24178 24160 24226 24160 24179 24160 24178 24161 24179 24161 24116 24161 24116 24162 24179 24162 24180 24162 24116 24163 24180 24163 24118 24163 24118 24164 24180 24164 24227 24164 24118 24165 24227 24165 24120 24165 24120 24166 24227 24166 24229 24166 24120 24167 24229 24167 24121 24167 24121 24168 24229 24168 24182 24168 24121 24169 24182 24169 24181 24169 24181 24170 24182 24170 24183 24170 24181 24171 24183 24171 24123 24171 24123 24172 24183 24172 24231 24172 24123 24173 24231 24173 24124 24173 24124 24174 24231 24174 24184 24174 24124 24175 24184 24175 24125 24175 24125 24176 24184 24176 24234 24176 24125 24177 24234 24177 24185 24177 24185 24178 24234 24178 24235 24178 24185 24179 24235 24179 24186 24179 24186 24180 24235 24180 24187 24180 24186 24181 24187 24181 24129 24181 24129 24182 24187 24182 24188 24182 24129 24183 24188 24183 24189 24183 24189 24184 24188 24184 24237 24184 24189 24185 24237 24185 24190 24185 24190 24186 24237 24186 24191 24186 24190 24187 24191 24187 24132 24187 24132 24188 24191 24188 24239 24188 24132 24189 24239 24189 24133 24189 24133 24190 24239 24190 24240 24190 24133 24191 24240 24191 24135 24191 24135 24192 24240 24192 24192 24192 24135 24193 24192 24193 24137 24193 24137 24194 24192 24194 24193 24194 24193 24195 24194 24195 24138 24195 24138 24196 24194 24196 23959 24196 24138 24197 23959 24197 24140 24197 24140 24198 23959 24198 24195 24198 24140 24199 24195 24199 24196 24199 24196 24200 24195 24200 24197 24200 24196 24201 24197 24201 24198 24201 24198 24202 24197 24202 23956 24202 24198 24203 23956 24203 24199 24203 24199 24204 23956 24204 23944 24204 24199 24205 23944 24205 24145 24205 24145 24206 23944 24206 24200 24206 24145 24207 24200 24207 24201 24207 24201 24208 24200 24208 23971 24208 24201 24209 23971 24209 24147 24209 24147 24210 23971 24210 23969 24210 24147 24211 23969 24211 24149 24211 24149 24212 23969 24212 23968 24212 24149 24213 23968 24213 24202 24213 24202 24214 23968 24214 23985 24214 24202 24215 23985 24215 24151 24215 24151 24216 23985 24216 24203 24216 24151 24217 24203 24217 24204 24217 24204 24218 24203 24218 24205 24218 24204 24219 24205 24219 24154 24219 24154 24220 24205 24220 23997 24220 24154 24221 23997 24221 24206 24221 24206 24222 23997 24222 23995 24222 24206 24223 23995 24223 24155 24223 24155 24224 23995 24224 24207 24224 24155 24225 24207 24225 24157 24225 24157 24226 24207 24226 24208 24226 24157 24227 24208 24227 24158 24227 24158 24228 24208 24228 23987 24228 24158 24229 23987 24229 24210 24229 24210 24230 23987 24230 24209 24230 24210 24231 24209 24231 24211 24231 24211 24232 24209 24232 24000 24232 24211 24233 24000 24233 24162 24233 24162 24234 24000 24234 23998 24234 24162 24235 23998 24235 24164 24235 24164 24236 23998 24236 24212 24236 24164 24237 24212 24237 24165 24237 24165 24238 24212 24238 24213 24238 24165 24239 24213 24239 24167 24239 24167 24240 24213 24240 24214 24240 24167 24241 24214 24241 24216 24241 24216 24242 24214 24242 24215 24242 24216 24243 24215 24243 24168 24243 24168 24244 24215 24244 24009 24244 24168 24245 24009 24245 24217 24245 24217 24246 24009 24246 24218 24246 24217 24247 24218 24247 24219 24247 24219 24248 24218 24248 24007 24248 24219 24249 24007 24249 24220 24249 24220 24250 24007 24250 24221 24250 24220 24251 24221 24251 24170 24251 24170 24252 24221 24252 24005 24252 24170 24253 24005 24253 24171 24253 24171 24254 24005 24254 23972 24254 24171 24255 23972 24255 24172 24255 24172 24256 23972 24256 24222 24256 24172 24257 24222 24257 24173 24257 24173 24258 24222 24258 23993 24258 24173 24259 23993 24259 24223 24259 24223 24260 23993 24260 23991 24260 24223 24261 23991 24261 24176 24261 24176 24262 23991 24262 23990 24262 24176 24263 23990 24263 24224 24263 24224 24264 23990 24264 23988 24264 24224 24265 23988 24265 24225 24265 24225 24266 23988 24266 23977 24266 24225 24267 23977 24267 24226 24267 24226 24268 23977 24268 23975 24268 24226 24269 23975 24269 24179 24269 24179 24270 23975 24270 23946 24270 24179 24271 23946 24271 24180 24271 24180 24272 23946 24272 24228 24272 24180 24273 24228 24273 24227 24273 24227 24274 24228 24274 23950 24274 24227 24275 23950 24275 24229 24275 24229 24276 23950 24276 24230 24276 24229 24277 24230 24277 24182 24277 24182 24278 24230 24278 23948 24278 24182 24279 23948 24279 24183 24279 24183 24280 23948 24280 23962 24280 24183 24281 23962 24281 24231 24281 24231 24282 23962 24282 23960 24282 24231 24283 23960 24283 24184 24283 24184 24284 23960 24284 24232 24284 24184 24285 24232 24285 24234 24285 24234 24286 24232 24286 24233 24286 24234 24287 24233 24287 24235 24287 24235 24288 24233 24288 23982 24288 24235 24289 23982 24289 24187 24289 24187 24290 23982 24290 23980 24290 24187 24291 23980 24291 24188 24291 24188 24292 23980 24292 24236 24292 24188 24293 24236 24293 24237 24293 24237 24294 24236 24294 23964 24294 24237 24295 23964 24295 24191 24295 24191 24296 23964 24296 24238 24296 24191 24297 24238 24297 24239 24297 24239 24298 24238 24298 23963 24298 24239 24299 23963 24299 24240 24299 24240 24300 23963 24300 23951 24300 24240 24301 23951 24301 24192 24301 24192 24302 23951 24302 24241 24302 24192 24303 24241 24303 24193 24303 24193 24304 24241 24304 24194 24304 24264 24305 24242 24305 24282 24305 24243 24306 24244 24306 24302 24306 24318 24307 24245 24307 24320 24307 24260 24308 24243 24308 24303 24308 24246 24309 24301 24309 24248 24309 24248 21107 24301 21107 24247 21107 24248 21107 24247 21107 24249 21107 24249 24310 24247 24310 24251 24310 24249 24311 24251 24311 24250 24311 24250 24312 24251 24312 24252 24312 24250 24313 24252 24313 24254 24313 24254 24314 24252 24314 24253 24314 24254 24315 24253 24315 24255 24315 24255 24316 24253 24316 24256 24316 24255 24317 24256 24317 24257 24317 24257 14595 24256 14595 24258 14595 24257 14596 24258 14596 24259 14596 24259 24318 24258 24318 24260 24318 24259 24319 24260 24319 24261 24319 24261 24320 24260 24320 24303 24320 24297 24321 24262 24321 24299 24321 24263 24322 24264 24322 24281 24322 24265 24323 24266 24323 24267 24323 24267 21124 24266 21124 24268 21124 24267 21125 24268 21125 24269 21125 24269 24324 24268 24324 24270 24324 24269 24325 24270 24325 24271 24325 24271 24326 24270 24326 24272 24326 24271 24327 24272 24327 24274 24327 24274 24328 24272 24328 24273 24328 24274 24329 24273 24329 24275 24329 24275 24330 24273 24330 24276 24330 24275 24331 24276 24331 24277 24331 24277 14577 24276 14577 24278 14577 24277 14578 24278 14578 24279 14578 24279 24332 24278 24332 24263 24332 24279 24333 24263 24333 24280 24333 24280 24334 24263 24334 24281 24334 24264 24335 24282 24335 24281 24335 24281 24336 24282 24336 24284 24336 24281 24337 24284 24337 24283 24337 24283 24338 24284 24338 24285 24338 24283 24339 24285 24339 24286 24339 24286 24340 24285 24340 24288 24340 24286 14625 24288 14625 24287 14625 24287 24341 24288 24341 24289 24341 24287 24342 24289 24342 24290 24342 24290 14628 24289 14628 24292 14628 24290 24343 24292 24343 24291 24343 24291 24344 24292 24344 24293 24344 24291 24345 24293 24345 24294 24345 24294 24346 24293 24346 24296 24346 24294 24347 24296 24347 24295 24347 24295 24348 24296 24348 24297 24348 24295 24349 24297 24349 24298 24349 24298 24350 24297 24350 24299 24350 24298 24351 24299 24351 24246 24351 24246 24352 24299 24352 24300 24352 24246 24353 24300 24353 24301 24353 24243 24354 24302 24354 24303 24354 24303 24355 24302 24355 24304 24355 24303 24355 24304 24355 24306 24355 24306 24356 24304 24356 24305 24356 24306 24356 24305 24356 24308 24356 24308 24357 24305 24357 24307 24357 24308 14606 24307 14606 24309 14606 24309 24358 24307 24358 24310 24358 24309 24359 24310 24359 24311 24359 24311 14609 24310 14609 24312 14609 24311 24360 24312 24360 24313 24360 24313 24361 24312 24361 24315 24361 24313 24362 24315 24362 24314 24362 24314 24363 24315 24363 24316 24363 24314 24364 24316 24364 24317 24364 24317 24365 24316 24365 24318 24365 24317 24366 24318 24366 24319 24366 24319 24367 24318 24367 24320 24367 24319 24368 24320 24368 24265 24368 24265 24369 24320 24369 24321 24369 24265 24370 24321 24370 24266 24370 24914 24371 24323 24371 24322 24371 24322 24372 24323 24372 24324 24372 24322 24373 24324 24373 24326 24373 24326 24374 24324 24374 24325 24374 24326 24375 24325 24375 24327 24375 24327 24376 24325 24376 24328 24376 24327 24377 24328 24377 24329 24377 24329 24378 24328 24378 24912 24378 24329 24378 24912 24378 24330 24378 24330 24379 24912 24379 24910 24379 24330 24380 24910 24380 25131 24380 25131 24381 24910 24381 24909 24381 25131 24382 24909 24382 24331 24382 24331 24383 24909 24383 24332 24383 24331 24384 24332 24384 25125 24384 25125 24385 24332 24385 24333 24385 25125 24386 24333 24386 25123 24386 25123 24387 24333 24387 24906 24387 25123 24387 24906 24387 24334 24387 24334 24388 24906 24388 24336 24388 24334 24389 24336 24389 24335 24389 24335 24390 24336 24390 24337 24390 24335 24391 24337 24391 25132 24391 25132 24392 24337 24392 24905 24392 25132 24393 24905 24393 25133 24393 25133 24394 24905 24394 24915 24394 25133 24395 24915 24395 25126 24395 25126 24396 24915 24396 24338 24396 25126 24397 24338 24397 25127 24397 25127 24398 24338 24398 24914 24398 25127 24399 24914 24399 24322 24399 24340 24400 24339 24400 24341 24400 24341 24401 24339 24401 25035 24401 24340 24402 24341 24402 24342 24402 24342 24403 24341 24403 24343 24403 24342 24404 24343 24404 24791 24404 24343 24405 25031 24405 24791 24405 24791 24406 25031 24406 25030 24406 24791 24406 25030 24406 24344 24406 24344 24407 25030 24407 24345 24407 24344 24408 24345 24408 24346 24408 24346 24409 24345 24409 25029 24409 24346 24410 25029 24410 24347 24410 24347 24411 25029 24411 25038 24411 24347 24412 25038 24412 24348 24412 25038 24413 25037 24413 24348 24413 24348 24414 25037 24415 24350 24416 24348 24417 24350 24417 24349 24417 24349 24418 24350 24418 24351 24418 24349 24419 24351 24419 24786 24419 24786 24420 24351 24420 24787 24420 24787 24421 24351 24421 24352 24421 24787 24422 24352 24422 24788 24422 24788 24423 24352 24423 25041 24423 24788 24424 25041 24424 24353 24424 24353 24425 25041 24425 24354 24425 24353 24426 24354 24426 24988 24426 24354 24427 24355 24427 24988 24427 24988 24428 24355 24428 25027 24428 24988 24429 25027 24429 24785 24429 24785 24430 25027 24430 24356 24430 24785 24430 24356 24430 24361 24430 24361 24431 24356 24431 24359 24431 24339 24432 24795 24432 25035 24432 25035 24433 24795 24433 24357 24433 25035 24433 24357 24433 25026 24433 25026 24434 24357 24434 24358 24434 25026 24435 24358 24435 24359 24435 24359 24436 24358 24436 24360 24436 24359 24437 24360 24437 24361 24437 25049 24438 24802 24438 24367 24438 24362 24439 24363 24439 24887 24439 24887 24440 24363 24440 24365 24440 24365 24380 24363 24380 24364 24380 24365 24441 24364 24441 24799 24441 24799 24442 24364 24442 25044 24442 24799 24443 25044 24443 24800 24443 24800 24444 25044 24444 25043 24444 24800 24445 25043 24445 24801 24445 24801 24446 25043 24446 24366 24446 24801 24447 24366 24447 24367 24447 24367 24448 24366 24448 24368 24448 24367 24449 24368 24449 25049 24449 24802 24450 25049 24450 24369 24450 24369 24451 25049 24451 24370 24451 24369 24452 24370 24452 24808 24452 24808 24453 24370 24453 24371 24453 24371 24454 24370 24454 24372 24454 24371 24455 24372 24455 24374 24455 24372 24456 24373 24456 24374 24456 24374 24457 24373 24457 25050 24457 24374 24458 25050 24458 24809 24458 25050 24459 24375 24459 24809 24459 24809 24460 24375 24460 24376 24460 24809 24460 24376 24460 24810 24460 24810 24461 24376 24461 25055 24461 24810 24462 25055 24462 24811 24462 24811 24431 25055 24431 25054 24431 24887 24463 24888 24463 24362 24463 24362 24464 24888 24464 24804 24464 24362 24464 24804 24464 25048 24464 25048 24465 24804 24465 24806 24465 25048 24466 24806 24466 24377 24466 24377 24467 24806 24467 24378 24467 24377 24468 24378 24468 25053 24468 25053 24469 24378 24469 24379 24469 25053 24470 24379 24470 25054 24470 25054 24471 24379 24471 24380 24471 25054 24437 24380 24437 24811 24437 25058 24472 24381 24472 24382 24472 24382 24473 24381 24473 24816 24473 24382 24474 24816 24474 25059 24474 25059 24475 24816 24475 24383 24475 25059 24476 24383 24476 25060 24476 25060 24477 24383 24477 24815 24477 25060 24478 24815 24478 25061 24478 25061 24406 24815 24406 24814 24406 25061 24479 24814 24479 25056 24479 25056 24480 24814 24480 24813 24480 25056 24481 24813 24481 25057 24481 25057 24482 24813 24482 24877 24482 25057 24482 24877 24482 25062 24482 24384 24483 24385 24483 25186 24483 25186 24484 24385 24484 24386 24484 25186 24485 24386 24485 25058 24485 25058 24486 24386 24486 24387 24486 25058 24487 24387 24487 24381 24487 25186 24488 24388 24488 24384 24488 24384 24489 24388 24489 25068 24489 24384 24490 25068 24490 24389 24490 24389 24491 25068 24491 24390 24491 24389 24491 24390 24491 24818 24491 24818 24492 24390 24492 24391 24492 24818 24493 24391 24493 24392 24493 24392 24494 24391 24494 25067 24494 24392 24495 25067 24495 24393 24495 24393 24496 25067 24496 25066 24496 24393 24497 25066 24497 24820 24497 24820 24498 25066 24498 24395 24498 25062 24499 24877 24499 25064 24499 25064 24500 24877 24500 24394 24500 25064 24501 24394 24501 24395 24501 24395 24502 24394 24502 24817 24502 24395 24503 24817 24503 24820 24503 25077 24372 24841 24372 24822 24372 24831 24504 24403 24504 25071 24504 24831 24505 25071 24505 24396 24505 24396 24506 25071 24506 25069 24506 24396 24506 25069 24506 24821 24506 24821 24507 25069 24507 25072 24507 24821 24508 25072 24508 24397 24508 24397 24509 25072 24509 24398 24509 24397 24510 24398 24510 24822 24510 24822 24511 24398 24511 25073 24511 24822 24373 25073 24373 25077 24373 24841 24371 25077 24371 24840 24371 24840 24512 25077 24512 24399 24512 24840 24513 24399 24513 24838 24513 24838 24514 24399 24514 24837 24514 24837 24515 24399 24515 25078 24515 24837 24516 25078 24516 24842 24516 25078 24517 24400 24517 24842 24517 24842 24518 24400 24518 24401 24518 24842 24519 24401 24519 24402 24519 24401 24520 25083 24520 24402 24520 24402 24521 25083 24521 25084 24521 24402 24522 25084 24522 24843 24522 24843 24523 25084 24523 25105 24523 24831 24524 24829 24524 24403 24524 24403 24525 24829 24525 24828 24525 24403 24525 24828 24525 24404 24525 24404 24526 24828 24526 24824 24526 24404 24464 24824 24464 24405 24464 24405 24465 24824 24465 24833 24465 24405 24466 24833 24466 25075 24466 25075 24527 24833 24527 24835 24527 25075 24528 24835 24528 24406 24528 24406 24529 24835 24529 24407 24529 24406 24530 24407 24530 25076 24530 25076 24531 24407 24532 24408 24533 25076 24534 24408 24534 25105 24534 25105 24535 24408 24535 24409 24535 25105 24494 24409 24494 24843 24494 24410 24536 25087 24536 24411 24536 24410 24537 24411 24537 24413 24537 24413 24538 24411 24538 24412 24538 24413 24539 24412 24539 24955 24539 24955 24540 24412 24540 24414 24540 24955 24524 24414 24524 24415 24524 24415 24541 24414 24541 25093 24541 24415 24542 25093 24542 24849 24542 24849 24543 25093 24543 24416 24543 24849 24544 24416 24544 24417 24544 24417 24545 24416 24545 24418 24545 24417 24545 24418 24545 24419 24545 24419 24546 24418 24546 25091 24546 24419 24547 25091 24547 24420 24547 25091 24548 25094 24548 24420 24548 24420 21 25094 21 25095 21 24420 24549 25095 24549 24421 24549 24421 24550 25095 24550 24422 24550 24421 24551 24422 24551 24851 24551 24851 24552 24422 24552 24853 24552 24853 24553 24422 24553 25100 24553 24853 24554 25100 24554 24846 24554 24846 24555 25100 24555 24423 24555 24846 24556 24423 24556 24848 24556 24848 24557 24423 24557 25098 24557 24848 24558 25098 24558 24424 24558 25098 24559 25097 24559 24424 24559 24424 24560 25097 24560 25089 24560 24424 24561 25089 24561 24427 24561 24427 24562 25089 24562 25088 24562 24410 24563 24857 24563 25087 24563 25087 24564 24857 24564 24425 24564 25087 24565 24425 24565 25085 24565 25085 24566 24425 24566 24856 24566 25085 24567 24856 24567 25086 24567 25086 24568 24856 24569 24855 24570 25086 24571 24855 24571 25088 24571 25088 24572 24855 24572 24426 24572 25088 24430 24426 24430 24427 24430 24871 24573 25182 24573 24428 24573 24871 24574 24428 24574 24429 24574 24429 15276 24428 15276 24430 15276 24429 24575 24430 24575 24431 24575 24431 24576 24430 24576 24866 24576 24866 24577 24430 24577 25181 24577 24866 24578 25181 24578 24432 24578 24432 24579 25181 24579 24434 24579 24432 24580 24434 24580 24433 24580 24433 24581 24434 24581 24435 24581 24433 24582 24435 24582 24436 24582 24436 24583 24435 24583 24437 24583 24436 24584 24437 24584 24861 24584 24861 24585 24437 24585 25187 24585 24861 24586 25187 24586 24439 24586 24439 24587 25187 24587 24438 24587 24439 24588 24438 24588 24440 24588 24440 24589 24438 24589 25106 24589 24440 24590 25106 24590 24858 24590 24441 24591 24442 24591 24629 24591 24629 24592 24442 24592 25183 24592 24629 24593 25183 24593 24871 24593 24871 24594 25183 24594 25182 24594 25183 24595 24442 24595 24443 24595 24443 24596 24442 24596 24444 24596 24443 24597 24444 24597 24445 24597 24444 24598 24534 24598 24445 24598 24445 24599 24534 24599 24532 24599 24445 24600 24532 24600 24449 24600 24446 24601 25180 24601 24531 24601 24531 24602 25180 24602 25179 24602 24531 24603 25179 24603 24447 24603 24447 24604 25179 24604 25065 24604 24447 24605 25065 24605 24448 24605 24448 24606 25065 24606 24449 24606 24448 24607 24449 24607 24450 24607 24450 24608 24449 24608 24532 24608 24451 960 24628 960 24446 960 24451 960 24446 960 24622 960 24446 24609 24530 24609 24622 24609 24622 24610 24530 24610 24452 24610 24622 960 24452 960 24621 960 24621 960 24452 960 24463 960 24621 960 24463 960 24619 960 24456 24611 24884 24611 24454 24611 24460 21712 25166 21712 24453 21712 24460 21711 24453 21711 24883 21711 24883 24612 24453 24612 25165 24612 24883 24613 25165 24613 24454 24613 24454 24614 25165 24614 24455 24614 24454 24615 24455 24615 24456 24615 24884 24616 24456 24616 24882 24616 24882 24617 24456 24617 25167 24617 24882 24618 25167 24618 24881 24618 24881 24619 25167 24619 25174 24619 24881 24620 25174 24620 24457 24620 24457 24621 25174 24621 24458 24621 24457 24622 24458 24622 24872 24622 24458 24623 25176 24624 24872 24625 24872 24626 25176 24626 25177 24626 24872 24627 25177 24627 24459 24627 24459 24628 25177 24628 25178 24628 24459 24629 25178 24629 24874 24629 24462 15464 24619 15464 24463 15464 25166 24630 24460 24630 24461 24630 24461 24631 24460 24631 24462 24631 24461 24632 24462 24632 24464 24632 24464 24633 24462 24633 24463 24633 24464 24634 24463 24634 25007 24634 25007 24635 24463 24635 24465 24635 25007 24636 24465 24636 24466 24636 24465 24637 24467 24637 24466 24637 24466 24638 24467 24638 24468 24638 24466 24639 24468 24639 24469 24639 24469 24640 24468 24640 24471 24640 24469 24641 24471 24641 24470 24641 24470 24642 24471 24642 25052 24642 25052 24643 24471 24643 24526 24643 25052 24644 24526 24644 24472 24644 24568 24645 24473 24645 24569 24645 24569 24646 24473 24646 24472 24646 24569 24647 24472 24647 24474 24647 24474 24648 24472 24648 24526 24648 25151 24649 24501 24649 24892 24649 24476 24650 24475 24650 25146 24650 24476 24651 25146 24651 24900 24651 24900 15149 25146 15149 25144 15149 24900 24652 25144 24652 24477 24652 24477 24653 25144 24653 25143 24653 24477 24654 25143 24654 24898 24654 24898 24655 25143 24655 25140 24655 24898 24656 25140 24656 24894 24656 24894 24657 25140 24657 25148 24657 24894 24658 25148 24658 24895 24658 24895 24659 25148 24659 25149 24659 24895 24659 25149 24659 24891 24659 24891 24660 25149 24660 25150 24660 24891 24661 25150 24661 24892 24661 24892 24662 25150 24662 24478 24662 24892 24649 24478 24649 25151 24649 24613 24663 24568 24663 24615 24663 24615 960 24568 960 24479 960 24615 24664 24479 24664 24606 24664 24606 960 24479 960 24567 960 24606 960 24567 960 24480 960 24480 960 24567 960 24566 960 24480 960 24566 960 24492 960 24492 960 24566 960 24564 960 24491 21749 24889 21749 24481 21749 24798 21750 24493 21750 24482 21750 24482 21750 24493 21750 24494 21750 24798 24665 24482 24665 24885 24665 24885 24666 24482 24666 25036 24666 24885 24667 25036 24667 24484 24667 25036 24668 24483 24668 24484 24668 24484 21753 24483 21753 25164 21753 24484 21754 25164 21754 24486 21754 24486 24669 25164 24669 24485 24669 24486 15497 24485 15497 24488 15497 24488 24670 24485 24670 24487 24670 24488 24670 24487 24670 24489 24670 24489 24671 24487 24671 24490 24671 24490 24672 24487 24672 25046 24672 24490 24673 25046 24673 24481 24673 24481 24674 25046 24674 25047 24674 24481 21764 25047 21764 24491 21764 24492 24675 24564 24675 24794 24675 24794 24676 24564 24676 24495 24676 24794 21767 24495 21767 24493 21767 24493 21768 24495 21768 24494 21768 24495 24677 24564 24677 24563 24677 24495 24678 24563 24678 25034 24678 25034 24679 24563 24679 24496 24679 25034 24680 24496 24680 25033 24680 25033 24681 24496 24681 24497 24681 25033 24682 24497 24682 25032 24682 25032 24683 24497 24683 24561 24683 25032 24684 24561 24684 24498 24684 24498 24685 24561 24685 24499 24685 24498 24686 24499 24686 24500 24686 24557 24687 24503 24687 24558 24687 24558 24688 24503 24688 24500 24688 24558 24689 24500 24689 24559 24689 24559 24690 24500 24690 24499 24690 24501 24691 25151 24691 24502 24691 24502 24692 25151 24692 24503 24692 24502 24693 24503 24693 24504 24693 24504 24694 24503 24694 24557 24694 24504 960 24557 960 24600 960 24600 24695 24557 24695 24505 24695 24600 960 24505 960 24506 960 24506 24696 24505 24696 24507 24696 24506 960 24507 960 24595 960 24595 24697 24507 24697 24508 24697 24595 24698 24508 24698 24596 24698 25147 24699 24508 24699 25130 24699 25130 24700 24508 24700 24509 24700 25130 24701 24509 24701 25129 24701 24509 24702 24510 24702 25129 24702 25129 24703 24510 24703 24516 24703 25129 24704 24516 24704 25128 24704 24511 24705 24512 24705 24552 24705 24552 24706 24512 24706 24513 24706 24552 24707 24513 24707 24553 24707 24553 24708 24513 24708 24514 24708 24553 24709 24514 24709 24515 24709 24515 24710 24514 24710 25128 24710 24515 24711 25128 24711 24554 24711 24554 24712 25128 24712 24516 24712 24517 960 24511 960 24585 960 24585 960 24511 960 24518 960 24585 24713 24518 24713 24519 24713 24519 24714 24518 24714 24520 24714 24519 24715 24520 24715 24693 24715 24693 960 24520 960 24702 960 24716 24716 24715 24716 24525 24716 24525 24717 24715 24717 24522 24717 24705 960 24706 960 24521 960 24521 960 24706 960 24523 960 24521 960 24523 960 24522 960 24522 960 24523 960 24524 960 24522 960 24524 960 24525 960 24527 24718 25403 24718 24474 24718 24474 24719 24526 24719 24527 24719 24527 24720 24526 24720 24471 24720 24527 24721 24471 24721 25401 24721 24471 24722 24468 24722 25401 24722 25401 24723 24468 24723 24467 24723 25401 24724 24467 24724 24528 24724 24467 24725 24465 24725 24528 24725 24528 24726 24465 24726 24463 24726 24528 24727 24463 24727 24529 24727 24463 15402 24452 15402 24529 15402 24529 24728 24452 24728 24530 24728 24529 24729 24530 24729 25397 24729 25397 24730 24530 24730 24446 24730 25397 24731 24446 24731 25396 24731 25396 24732 24446 24732 24531 24732 25396 24733 24531 24733 25394 24733 24531 24734 24447 24734 25394 24734 25394 24735 24447 24735 24448 24735 25394 24736 24448 24736 24533 24736 24533 24737 24448 24737 24450 24737 24450 24738 24532 24738 24533 24738 24533 24739 24532 24739 24534 24739 24533 24740 24534 24740 25393 24740 24534 24741 24444 24741 25393 24741 25393 24742 24444 24742 24442 24742 25393 24743 24442 24743 24535 24743 24442 24744 24573 24744 24535 24744 24535 24745 24573 24745 24571 24745 24535 24746 24571 24746 24536 24746 24536 24747 24571 24747 24721 24747 24536 24748 24721 24748 25391 24748 24721 24749 24720 24749 25391 24749 25391 24750 24720 24750 24537 24750 25391 24751 24537 24751 24539 24751 24537 24752 24538 24752 24539 24752 24539 24753 24538 24753 24540 24753 24539 24754 24540 24754 25388 24754 24540 24755 24541 24755 25388 24755 25388 24756 24541 24756 24722 24756 25388 24757 24722 24757 24542 24757 24722 24758 24543 24758 24542 24758 24542 24759 24543 24759 24716 24759 24542 24760 24716 24760 24544 24760 24716 24761 24525 24761 24544 24761 24544 15437 24525 15437 24524 15437 24544 15437 24524 15437 25385 15437 25385 24762 24524 24762 24523 24762 25385 15438 24523 15438 25425 15438 25425 24763 24523 24763 24706 24763 25425 24764 24706 24764 25423 24764 24706 24765 24545 24765 25423 24765 25423 24766 24545 24766 24696 24766 25423 24767 24696 24767 24546 24767 24696 24768 24697 24768 24546 24768 24546 24769 24697 24769 24547 24769 24546 24770 24547 24770 25421 24770 24547 24771 24699 24771 25421 24771 25421 24772 24699 24772 24548 24772 25421 24773 24548 24773 25420 24773 24548 24774 24549 24774 25420 24774 25420 24775 24549 24775 24702 24775 25420 24776 24702 24776 25419 24776 24702 15350 24520 15350 25419 15350 25419 24777 24520 24777 24518 24777 25419 24777 24518 24777 24550 24777 24550 24778 24518 24778 24511 24778 24550 24779 24511 24779 24551 24779 24551 24780 24511 24780 24552 24780 24551 24781 24552 24781 24555 24781 24555 24782 24552 24782 24553 24782 24553 24783 24515 24783 24555 24783 24555 24784 24515 24784 24554 24784 24555 24785 24554 24785 25417 24785 24554 24786 24516 24786 25417 24786 25417 24787 24516 24787 24510 24787 25417 24788 24510 24788 24556 24788 24510 24789 24509 24789 24556 24789 24556 24790 24509 24790 24508 24790 24556 24791 24508 24791 25414 24791 24508 24792 24507 24792 25414 24792 25414 24793 24507 24793 24505 24793 25414 24794 24505 24794 25413 24794 25413 24795 24505 24795 24557 24795 25413 24796 24557 24796 25411 24796 24557 24797 24558 24797 25411 24797 25411 24798 24558 24798 24559 24798 25411 24799 24559 24799 24560 24799 24559 24800 24499 24800 24560 24800 24560 24801 24499 24801 24561 24801 24560 24802 24561 24802 25408 24802 24561 24803 24497 24803 25408 24803 25408 24804 24497 24804 24496 24804 25408 24805 24496 24805 24562 24805 24496 24806 24563 24806 24562 24806 24562 24807 24563 24807 24564 24807 24562 24808 24564 24808 24565 24808 24564 24809 24566 24809 24565 24809 24565 24810 24566 24810 24567 24810 24565 15385 24567 15385 25406 15385 25406 15387 24567 15387 24479 15387 25406 24811 24479 24811 25404 24811 25404 24812 24479 24812 24568 24812 25404 24813 24568 24813 25403 24813 25403 24814 24568 24814 24569 24814 25403 24815 24569 24815 24474 24815 24570 24816 24721 24816 24635 24816 24635 24817 24721 24817 24571 24817 24635 24818 24571 24818 24572 24818 24572 24819 24571 24819 24573 24819 24572 24820 24573 24820 24441 24820 24441 24821 24573 24821 24442 24821 24574 24822 24575 24822 24576 24822 24577 24823 24578 24824 24625 24825 24642 24826 24579 24826 24641 24826 24693 24827 24694 24827 24655 24827 24715 24828 24717 24828 24823 24828 24667 24829 24580 24829 24666 24829 24666 24830 24581 24830 24522 24830 24522 24831 24581 24831 24582 24831 24522 24832 24582 24832 24521 24832 24583 24833 24845 24833 24705 24833 24521 24834 24582 24834 24705 24834 24705 24835 24582 24835 24584 24835 24705 24836 24584 24836 24583 24836 24591 24837 24585 24837 24586 24837 24586 24838 24585 24838 24519 24838 24586 24839 24519 24839 24654 24839 24587 24840 24588 24840 24590 24840 24589 24841 24517 24841 24590 24841 24590 24842 24517 24842 24585 24842 24590 24843 24585 24843 24587 24843 24587 24844 24585 24844 24591 24844 24587 24845 24591 24845 24592 24845 24593 24846 24506 24846 24594 24846 24594 24847 24506 24847 24595 24847 24594 24848 24595 24848 24645 24848 24645 24849 24595 24849 24596 24849 24645 24850 24596 24850 24903 24850 24601 24851 24597 24851 24599 24851 24642 24852 24504 24852 24598 24852 24598 24853 24504 24853 24600 24853 24598 24854 24600 24854 24599 24854 24599 24855 24600 24855 24506 24855 24599 24856 24506 24856 24601 24856 24601 24857 24506 24857 24593 24857 24601 24858 24593 24858 24602 24858 24492 24859 24794 24859 24638 24859 24609 24860 24480 24860 24603 24860 24603 24861 24480 24861 24492 24861 24608 24862 24604 24863 24607 24864 24616 24865 24615 24865 24605 24865 24605 24866 24615 24866 24606 24866 24605 24867 24606 24867 24607 24867 24607 24868 24606 24868 24480 24868 24607 24869 24480 24869 24608 24869 24608 24870 24480 24870 24609 24870 24608 24871 24609 24871 24610 24871 24890 24872 24613 24872 24692 24872 24614 24873 24611 24873 24612 24873 24692 24874 24613 24874 24612 24874 24612 24875 24613 24875 24615 24875 24612 24876 24615 24876 24614 24876 24614 24877 24615 24878 24616 24879 24614 24880 24616 24881 24617 24882 24688 24883 24618 24884 24686 24885 24619 24886 24686 24886 24621 24886 24621 24887 24686 24887 24620 24887 24621 24888 24620 24888 24622 24888 24622 24889 24620 24889 24577 24889 24625 24890 24623 24890 24626 24890 24875 24891 24624 24891 24628 24891 24577 24892 24625 24893 24622 24894 24622 24895 24625 24895 24626 24895 24622 24896 24626 24896 24451 24896 24451 24897 24626 24897 24627 24897 24451 24898 24627 24898 24628 24898 24628 24899 24627 24899 24678 24899 24628 24900 24678 24900 24875 24900 24441 24901 24629 24901 24630 24901 24631 24902 24572 24902 24680 24902 24680 24903 24572 24903 24441 24903 24636 24904 24632 24904 24633 24904 24673 24905 24570 24905 24634 24905 24634 24906 24570 24906 24635 24906 24634 24907 24635 24907 24633 24907 24633 24908 24635 24908 24572 24908 24633 24909 24572 24909 24636 24909 24636 24910 24572 24910 24631 24910 24636 24911 24631 24911 24637 24911 24492 24912 24638 24912 24603 24912 24603 24913 24638 24913 24796 24913 24603 24914 24796 24914 24639 24914 24640 24915 24643 24915 24641 24915 24641 24916 24643 24916 24644 24916 24641 24917 24644 24917 24642 24917 24642 24918 24644 24918 24502 24918 24642 24919 24502 24919 24504 24919 24796 24920 24797 24920 24639 24920 24639 24921 24797 24921 24793 24921 24639 24922 24793 24922 24643 24922 24643 24923 24793 24923 24759 24923 24643 24924 24759 24924 24644 24924 24903 24925 24902 24925 24645 24925 24645 24926 24902 24926 24911 24926 24645 24927 24911 24927 24646 24927 24646 24928 24911 24928 24647 24928 24758 24929 24517 24929 24916 24929 24916 24930 24517 24930 24589 24930 24916 24931 24589 24931 24913 24931 24913 24932 24589 24932 24574 24932 24913 24933 24574 24933 24647 24933 24647 24934 24574 24934 24576 24934 24647 24935 24576 24935 24646 24935 24646 24936 24576 24936 24648 24936 24656 24937 24649 24937 24650 24937 24651 24938 24652 24938 24850 24938 24651 24939 24850 24939 24653 24939 24519 24940 24693 24940 24654 24940 24654 24941 24693 24941 24655 24941 24654 24942 24655 24942 24650 24942 24650 24943 24655 24943 24652 24943 24650 24944 24652 24944 24656 24944 24656 24945 24652 24945 24651 24945 24656 24946 24651 24946 24657 24946 24661 24947 24658 24947 24659 24947 24850 24948 24660 24948 24653 24948 24653 24949 24660 24949 24852 24949 24653 24950 24852 24950 24659 24950 24659 24951 24852 24951 24583 24951 24659 24952 24583 24953 24661 24954 24661 24955 24583 24955 24584 24955 24661 24956 24584 24956 24662 24956 24823 24957 24664 24957 24663 24957 24663 24958 24664 24958 24665 24958 24522 24959 24715 24959 24666 24959 24666 24960 24715 24960 24823 24960 24666 24961 24823 24961 24667 24961 24667 24962 24823 24962 24663 24962 24667 24963 24663 24963 24668 24963 24669 24964 24670 24964 24675 24964 24671 24965 24570 24965 24672 24965 24672 24966 24570 24966 24673 24966 24672 24967 24673 24967 24859 24967 24859 24968 24673 24968 24674 24968 24664 24969 24839 24969 24665 24969 24665 24970 24839 24970 24860 24970 24665 24971 24860 24971 24675 24971 24675 24972 24860 24972 24859 24972 24675 24973 24859 24973 24669 24973 24669 24974 24859 24974 24674 24974 24669 24975 24674 24975 24676 24975 24682 24976 24677 24976 24681 24976 24683 24977 24819 24977 24678 24977 24678 24978 24819 24978 24679 24978 24678 24979 24679 24979 24875 24979 24441 24980 24630 24980 24680 24980 24680 24981 24630 24981 24870 24981 24680 24982 24870 24982 24681 24982 24681 24983 24870 24983 24819 24983 24681 24984 24819 24984 24682 24984 24682 24985 24819 24985 24683 24985 24682 24986 24683 24986 24684 24986 24687 24987 24685 24988 24689 24989 24689 24990 24685 24990 24760 24990 24689 24991 24760 24991 24691 24991 24619 24992 24462 24993 24686 24994 24686 24995 24462 24995 24687 24995 24686 24996 24687 24997 24688 24998 24688 24999 24687 24999 24689 24999 24688 25000 24689 25000 24690 25000 24760 25001 24803 25001 24691 25001 24691 25002 24803 25002 24807 25002 24691 25003 24807 25003 24692 25003 24692 25004 24807 25004 24805 25004 24692 25005 24805 25005 24890 25005 24693 15209 24702 15209 24694 15209 24694 25006 24702 25006 24701 25006 24694 25007 24701 25007 24936 25007 24936 21950 24701 21950 24695 21950 24706 25008 24704 25008 24545 25008 24545 25009 24704 25009 25099 25009 24545 25010 25099 25010 24696 25010 24696 25011 25099 25011 25096 25011 24696 25012 25096 25012 24697 25012 24697 25013 25096 25013 24698 25013 24697 25014 24698 25014 24547 25014 24547 25015 24698 25015 25009 25015 24547 25016 25009 25016 24699 25016 24699 25017 25009 25017 25008 25017 24699 25018 25008 25018 24548 25018 24548 25019 25008 25019 24700 25019 24548 25020 24700 25020 24549 25020 24549 25021 24700 25021 24701 25021 24549 25022 24701 25022 24702 25022 24703 25023 25101 25023 24845 25023 24845 25024 25101 25024 24704 25024 24845 25025 24704 25025 24705 25025 24705 25026 24704 25026 24706 25026 25101 21644 24703 21644 24847 21644 24709 21628 24708 21628 24707 21628 24707 21627 24708 21627 24719 21627 24709 25027 24707 25027 24710 25027 24710 25028 24707 25028 25074 25028 24710 25029 25074 25029 24939 25029 25074 25030 24711 25030 24939 25030 24939 25031 24711 25031 25108 25031 24939 25032 25108 25032 24948 25032 24948 21636 25108 21636 24712 21636 24948 15244 24712 15244 24947 15244 24947 25033 24712 25033 24713 25033 24947 25034 24713 25034 24946 25034 24946 25035 24713 25035 24943 25035 24943 25036 24713 25036 24714 25036 24943 25037 24714 25037 24847 25037 24847 25038 24714 25038 25102 25038 24847 21643 25102 21643 25101 21643 24715 25039 24716 25039 24717 25039 24717 25040 24716 25040 24718 25040 24717 15253 24718 15253 24708 15253 24708 25041 24718 25041 24719 25041 24720 25042 24721 25042 24724 25042 24724 25043 25010 25043 24720 25043 24720 25044 25010 25044 25103 25044 24720 25045 25103 25045 24537 25045 24537 25046 25103 25046 25107 25046 24537 25047 25107 25047 24538 25047 24538 25048 25107 25048 25081 25048 24538 25049 25081 25049 24540 25049 24540 25050 25081 25050 25080 25050 24540 25051 25080 25051 24541 25051 24541 25052 25080 25052 25079 25052 24541 25053 25079 25053 24722 25053 24722 25054 25079 25054 24723 25054 24722 25055 24723 25055 24543 25055 24543 25056 24723 25056 24718 25056 24543 25057 24718 25057 24716 25057 24721 25058 24570 25058 24724 25058 24724 25059 24570 25059 24671 25059 24724 25060 24671 25060 24725 25060 24725 25061 24671 25062 24858 25063 24725 25064 24858 25064 25106 25064 24938 21994 24726 21994 24727 21994 24727 15506 24726 15506 25214 15506 24727 25065 25214 25065 24940 25065 24940 15507 25214 15507 25216 15507 24940 15508 25216 15508 24941 15508 24941 15509 25216 15509 24728 15509 24941 21974 24728 21974 24729 21974 24729 21975 24728 21975 24730 21975 24729 21975 24730 21975 24732 21975 24732 25066 24730 25066 24731 25066 24732 15549 24731 15549 24733 15549 24733 21982 24731 21982 24734 21982 24733 21983 24734 21983 24937 21983 24937 21984 24734 21984 24735 21984 24937 15517 24735 15517 24942 15517 24942 25067 24735 25067 24736 25067 24942 25068 24736 25068 24738 25068 24738 15556 24736 15556 24737 15556 24738 21969 24737 21969 24944 21969 24944 25069 24737 25069 24739 25069 24944 25070 24739 25070 24945 25070 24945 15574 24739 15574 24740 15574 24945 15560 24740 15560 24938 15560 24938 21994 24740 21994 24726 21994 24755 25071 24741 25071 24865 25071 24865 25072 24741 25072 24867 25072 24867 25073 24741 25073 24742 25073 24867 25074 24742 25074 24743 25074 24743 15569 24742 15569 24744 15569 24743 15549 24744 15549 24869 15549 24869 22192 24744 22192 25184 22192 24869 22193 25184 22193 24864 22193 24864 25075 25184 25075 24745 25075 24745 25076 25184 25076 25006 25076 24745 25077 25006 25077 24746 25077 25006 25078 24747 25078 24746 25078 24746 25079 24747 25079 25217 25079 24746 25080 25217 25080 24748 25080 24748 25081 25217 25081 25203 25081 24748 25082 25203 25082 24965 25082 24965 25083 25203 25083 24832 25083 24832 25084 25203 25084 24749 25084 24832 25085 24749 25085 24834 25085 24834 15574 24749 15574 24750 15574 24834 15560 24750 15560 24836 15560 24836 25086 24750 25086 24862 25086 24862 25087 24750 25087 24751 25087 24862 25088 24751 25088 24752 25088 24751 25089 25204 25089 24752 25089 24752 25090 25204 25090 24753 25090 24752 25091 24753 25091 24754 25091 24754 25092 24753 25092 24755 25092 24754 25093 24755 25093 24756 25093 24756 25094 24755 25094 24865 25094 25001 25095 24757 25095 24876 25095 24930 590 24758 590 24916 590 24793 590 24792 590 24759 590 24685 590 24812 590 24760 590 24884 25096 24882 25096 24761 25096 24386 25097 24385 25097 24868 25097 24762 590 24961 590 24973 590 24763 25098 24967 25098 24764 25098 24763 590 24764 590 24783 590 24783 590 24764 590 24765 590 24783 590 24765 590 24766 590 24968 590 24770 590 24767 590 24767 25099 24770 25099 24771 25099 24827 590 24768 590 24826 590 24826 25100 24768 25100 24770 25100 24770 590 24768 590 24769 590 24770 590 24769 590 24771 590 24976 590 24772 590 24975 590 24977 590 24773 590 24978 590 24978 590 24773 590 24774 590 24978 25101 24774 25101 24775 25101 24762 25102 24973 25102 24776 25102 24781 25103 24777 25103 24778 25103 24778 590 24779 590 24781 590 24781 25104 24779 25104 24780 25104 24781 25105 24780 25105 24973 25105 24973 590 24780 590 24782 590 24973 590 24782 590 24776 590 24781 590 24789 590 24777 590 24777 590 24789 590 24783 590 24777 25106 24783 25106 24784 25106 24784 590 24783 590 24766 590 24785 590 24361 590 24886 590 24786 25107 24787 25107 24789 25107 24789 590 24787 590 24788 590 24789 590 24788 590 24783 590 24783 25108 24788 25108 24353 25108 24783 590 24353 590 24988 590 24791 590 24344 590 24792 590 24792 590 24344 590 24346 590 24792 590 24346 590 24790 590 24346 25109 24347 25109 24790 25109 24790 25110 24347 25110 24348 25110 24790 590 24348 590 24789 590 24789 25111 24348 25111 24349 25111 24789 590 24349 590 24786 590 24791 590 24792 590 24342 590 24342 25112 24792 25112 24793 25112 24342 25113 24793 25113 24797 25113 24798 25114 24885 25114 24886 25114 24794 590 24357 590 24638 590 24638 590 24357 590 24795 590 24638 590 24795 590 24796 590 24796 25115 24795 25115 24339 25115 24796 590 24339 590 24797 590 24797 590 24339 590 24340 590 24797 25116 24340 25116 24342 25116 24794 25117 24493 25117 24357 25117 24357 590 24493 590 24798 590 24357 25118 24798 25118 24358 25118 24358 590 24798 590 24886 590 24358 590 24886 590 24360 590 24360 590 24886 590 24361 590 24979 25119 24887 25119 24365 25119 24365 590 24799 590 24979 590 24979 25120 24799 25120 24800 25120 24979 590 24800 590 24763 590 24763 590 24800 590 24801 590 24369 590 24970 590 24802 590 24802 590 24970 590 24763 590 24802 590 24763 590 24367 590 24367 590 24763 590 24801 590 24760 590 24812 590 24803 590 24888 590 24890 590 24804 590 24804 590 24890 590 24805 590 24804 590 24805 590 24806 590 24806 590 24805 590 24807 590 24806 25121 24807 25121 24378 25121 24378 590 24807 590 24803 590 24378 25122 24803 25122 24379 25122 24379 590 24803 590 24812 590 24379 590 24812 590 24380 590 24374 590 24761 590 24371 590 24371 590 24761 590 24970 590 24371 25123 24970 25123 24808 25123 24808 590 24970 590 24369 590 24374 25124 24809 25124 24761 25124 24761 25125 24809 25125 24810 25125 24761 25126 24810 25126 24812 25126 24812 25127 24810 25127 24811 25127 24812 590 24811 590 24380 590 24813 590 24814 590 24876 590 24863 590 24381 590 24387 590 24813 590 24876 590 24877 590 24814 590 24815 590 24876 590 24876 25128 24815 25128 24383 25128 24876 25129 24383 25129 24863 25129 24863 590 24383 590 24816 590 24863 25130 24816 25130 24381 25130 24386 590 24868 590 24387 590 24394 590 24873 590 24817 590 24817 25131 24873 25131 24875 25131 24384 25132 24389 25132 24870 25132 24870 25133 24389 25133 24818 25133 24870 25134 24818 25134 24819 25134 24819 25135 24818 25135 24392 25135 24819 25136 24392 25136 24679 25136 24679 25137 24392 25137 24393 25137 24679 25138 24393 25138 24875 25138 24875 590 24393 590 24820 590 24875 25139 24820 25139 24817 25139 24822 25140 24709 25140 24397 25140 24397 590 24709 590 24710 590 24397 590 24710 590 24821 590 24821 590 24710 590 24830 590 24821 590 24830 590 24396 590 24664 25141 24823 25141 24841 25141 24822 590 24841 590 24709 590 24709 25142 24841 25142 24823 25142 24709 590 24823 590 24708 590 24708 590 24823 590 24717 590 24964 590 24833 590 24824 590 24824 590 24978 590 24964 590 24964 25143 24978 25143 24775 25143 24964 590 24775 590 24826 590 24826 25144 24775 25144 24825 25144 24826 25145 24825 25145 24827 25145 24824 25146 24828 25146 24978 25146 24978 590 24828 590 24829 590 24978 590 24829 590 24830 590 24830 25147 24829 25147 24831 25147 24830 25148 24831 25148 24396 25148 24964 590 24832 590 24833 590 24833 25149 24832 25149 24834 25149 24833 25150 24834 25150 24835 25150 24835 25151 24834 25151 24836 25151 24835 25152 24836 25152 24407 25152 24407 590 24836 590 24862 590 24842 590 24860 590 24837 590 24837 590 24860 590 24839 590 24837 590 24839 590 24838 590 24838 590 24839 590 24664 590 24838 590 24664 590 24840 590 24840 590 24664 590 24841 590 24842 25153 24402 25153 24860 25153 24860 590 24402 590 24843 590 24860 25154 24843 25154 24844 25154 24844 25155 24843 25155 24409 25155 24844 590 24409 590 24408 590 24703 590 24845 590 24583 590 24703 590 24583 590 24847 590 24852 590 24853 590 24583 590 24583 25156 24853 25156 24846 25156 24583 590 24846 590 24847 590 24847 25157 24846 25157 24848 25157 24847 590 24848 590 24943 590 24848 590 24424 590 24943 590 24943 25158 24424 25158 24427 25158 24943 25159 24427 25159 24854 25159 24415 590 24849 590 24932 590 24932 590 24849 590 24417 590 24932 590 24417 590 24850 590 24417 25160 24419 25160 24850 25160 24850 590 24419 590 24420 590 24850 590 24420 590 24660 590 24660 590 24420 590 24421 590 24660 590 24421 590 24852 590 24852 25161 24421 25161 24851 25161 24852 590 24851 590 24853 590 24427 590 24426 590 24854 590 24854 25162 24426 25162 24855 25162 24854 25163 24855 25163 24976 25163 24855 590 24856 590 24976 590 24976 590 24856 590 24425 590 24976 590 24425 590 24962 590 24962 25164 24425 25164 24857 25164 24962 25165 24857 25165 24410 25165 24858 25166 24671 25166 24672 25166 24672 590 24859 590 24858 590 24858 25167 24859 25167 24860 25167 24858 25168 24860 25168 24440 25168 24440 590 24860 590 24439 590 24439 25169 24860 25169 24844 25169 24439 25170 24844 25171 24861 25172 24436 590 24861 590 24754 590 24754 590 24861 590 24752 590 24752 25173 24861 25173 24844 25173 24752 590 24844 590 24862 590 24862 590 24844 590 24408 590 24862 25174 24408 25174 24407 25174 24387 590 24868 590 24863 590 24863 590 24868 590 24869 590 24863 590 24869 590 24864 590 24436 590 24754 590 24433 590 24433 25175 24754 25175 24756 25175 24433 590 24756 590 24432 590 24432 25176 24756 25176 24865 25176 24432 25177 24865 25177 24866 25177 24866 25178 24865 25178 24867 25178 24866 590 24867 590 24868 590 24868 25179 24867 25179 24743 25179 24868 25180 24743 25180 24869 25180 24871 590 24429 590 24868 590 24868 590 24429 590 24431 590 24868 25181 24431 25181 24866 25181 24385 25182 24384 25182 24868 25182 24868 25183 24384 25183 24870 25183 24868 25184 24870 25184 24871 25184 24871 25185 24870 25185 24630 25185 24871 590 24630 590 24629 590 24457 590 24872 590 24873 590 24873 590 24872 590 24459 590 24873 590 24459 590 24875 590 24875 590 24459 590 24874 590 24875 590 24874 590 24624 590 24757 25186 25002 25186 24876 25186 24876 25187 25002 25187 24873 25187 24876 25188 24873 25188 24877 25188 24877 590 24873 590 24394 590 24878 590 24879 590 24882 590 24882 590 24879 590 25005 590 24882 25189 25005 25189 24761 25189 25002 25190 24880 25190 24873 25190 24873 25191 24880 25191 25003 25191 24873 25192 25003 25192 24457 25192 24457 25193 25003 25193 24878 25193 24457 590 24878 590 24881 590 24881 25194 24878 25194 24882 25194 24462 590 24460 590 24687 590 24687 590 24460 590 24685 590 24685 590 24460 590 24812 590 24812 590 24460 590 24883 590 24812 590 24883 590 24761 590 24761 25195 24883 25195 24454 25195 24761 25196 24454 25196 24884 25196 24885 590 24484 590 24886 590 24886 590 24484 590 24486 590 24886 590 24486 590 24979 590 24979 590 24486 590 24488 590 24488 25197 24489 25197 24979 25197 24979 25198 24489 25198 24490 25198 24979 590 24490 590 24887 590 24887 25199 24490 25199 24481 25199 24887 590 24481 590 24888 590 24888 25200 24481 25200 24889 25200 24888 25201 24889 25201 24890 25201 24790 25202 24891 25202 24792 25202 24792 590 24891 590 24892 590 24792 590 24892 590 24759 590 24759 25203 24892 25203 24501 25203 24759 590 24501 590 24644 590 24644 590 24501 590 24502 590 24908 25204 24971 25204 24907 25204 24893 25205 24894 25205 24790 25205 24790 25206 24894 25206 24895 25206 24790 25207 24895 25207 24891 25207 24893 590 24896 590 24894 590 24894 25208 24896 25208 24897 25208 24894 590 24897 590 24898 590 24898 25209 24897 25209 24899 25209 24898 590 24899 590 24477 590 24477 590 24899 590 24900 590 24899 590 24901 590 24900 590 24900 590 24901 590 24902 590 24900 25210 24902 25210 24476 25210 24476 25211 24902 25211 24903 25211 24906 590 24333 590 24907 590 24915 590 24905 590 24904 590 24904 25212 24905 25212 24337 25212 24904 25213 24337 25213 24907 25213 24907 590 24337 590 24336 590 24907 25214 24336 25214 24906 25214 24333 590 24332 590 24907 590 24907 25215 24332 25215 24902 25215 24907 590 24902 590 24908 590 24908 25216 24902 25216 24901 25216 24332 25217 24909 25217 24902 25217 24902 25218 24909 25218 24910 25218 24902 590 24910 590 24911 590 24911 25219 24910 25219 24912 25219 24911 590 24912 590 24647 590 24647 25220 24912 25220 24328 25220 24647 25221 24328 25221 24913 25221 24913 590 24328 590 24325 590 24913 25222 24325 25222 24324 25222 24324 590 24323 590 24913 590 24913 25223 24323 25223 24914 25223 24913 590 24914 590 24904 590 24904 25224 24914 25224 24338 25224 24904 25225 24338 25225 24915 25225 24913 25226 24917 25226 24916 25226 24916 25227 24917 25227 24918 25227 24974 25228 24919 25228 24904 25228 24904 25229 24919 25229 24920 25229 24904 25230 24920 25230 24913 25230 24913 25231 24920 25231 24921 25231 24913 590 24921 590 24917 590 24922 590 24924 590 24923 590 24923 590 24924 590 24933 590 24932 25232 24925 25232 24933 25232 24923 590 24926 590 24922 590 24922 25233 24926 25233 24927 25233 24922 590 24927 590 24918 590 24918 590 24927 590 24928 590 24918 25234 24928 25234 24916 25234 24916 25235 24928 25235 24929 25235 24916 25236 24929 25236 24930 25236 24956 590 24932 590 24931 590 24931 590 24932 590 24933 590 24931 25237 24933 25237 24934 25237 24934 25238 24933 25238 24924 25238 24655 25239 24694 25239 24936 25239 24925 25240 24932 25240 24935 25240 24935 25241 24932 25241 24850 25241 24935 590 24850 590 24936 590 24936 590 24850 590 24652 590 24936 590 24652 590 24655 590 24854 25242 24937 25242 24942 25242 24938 25243 24727 25243 24948 25243 24948 25244 24727 25244 24939 25244 24727 25245 24940 25245 24939 25245 24939 25246 24940 25246 24941 25246 24939 590 24941 590 24710 590 24710 25247 24941 25247 24729 25247 24710 25248 24729 25248 24830 25248 24830 590 24729 590 24732 590 24830 25249 24732 25249 24733 25249 24942 590 24738 590 24854 590 24854 25250 24738 25250 24944 25250 24854 25251 24944 25251 24943 25251 24943 590 24944 590 24945 590 24943 590 24945 590 24946 590 24946 590 24945 590 24938 590 24946 590 24938 590 24947 590 24947 25252 24938 25252 24948 25252 24972 25253 24949 25253 24781 25253 24781 25254 24949 25254 24950 25254 24781 25255 24950 25255 24789 25255 24789 25256 24950 25256 24951 25256 24951 590 24952 590 24789 590 24789 25257 24952 25257 24953 25257 24789 25258 24953 25258 24790 25258 24790 590 24953 590 24954 590 24790 590 24954 590 24893 590 24415 590 24932 590 24955 590 24955 25259 24932 25259 24956 25259 24955 590 24956 590 24413 590 24413 25260 24956 25260 24957 25260 24413 25261 24957 25261 24410 25261 24410 25262 24957 25262 24958 25262 24410 590 24958 590 24962 590 24962 25263 24958 25263 24959 25263 24962 25264 24959 25264 24960 25264 24772 590 24976 590 24961 590 24961 590 24976 590 24962 590 24961 25265 24962 25265 24973 25265 24973 25266 24962 25266 24960 25266 24973 25267 24960 25267 24963 25267 24745 25268 24746 25268 24826 25268 24826 590 24746 590 24748 590 24826 25269 24748 25269 24964 25269 24964 25270 24748 25270 24965 25270 24964 25271 24965 25271 24832 25271 24966 25272 24998 25272 24970 25272 24967 590 24763 590 24968 590 24968 25273 24763 25273 24970 25273 24968 590 24970 590 24770 590 24770 25274 24970 25274 24998 25274 24770 25275 24998 25275 25000 25275 25005 25276 24969 25276 24761 25276 24761 590 24969 590 24994 590 24761 590 24994 590 24970 590 24970 25277 24994 25277 24996 25277 24970 25278 24996 25278 24966 25278 24971 25279 24972 25279 24907 25279 24907 590 24972 590 24781 590 24907 25280 24781 25280 24904 25280 24904 590 24781 590 24973 590 24904 590 24973 590 24974 590 24974 25281 24973 25281 24963 25281 24975 590 24977 590 24976 590 24976 590 24977 590 24978 590 24976 590 24978 590 24854 590 24854 25282 24978 25282 24830 25282 24854 25283 24830 25283 24937 25283 24937 590 24830 590 24733 590 24979 25284 24980 25284 24981 25284 24979 590 24981 590 24886 590 24886 25285 24981 25285 24982 25285 24886 25286 24982 25286 24986 25286 24992 590 24983 590 24763 590 24763 25287 24983 25287 24984 25287 24763 590 24984 590 24979 590 24979 590 24984 590 24985 590 24979 590 24985 590 24980 590 24986 590 24987 590 24886 590 24886 25288 24987 25288 24783 25288 24886 590 24783 590 24785 590 24785 25289 24783 25289 24988 25289 24987 25290 24989 25290 24783 25290 24783 590 24989 590 24990 590 24783 590 24990 590 24763 590 24763 25291 24990 25291 24991 25291 24763 25292 24991 25292 24992 25292 25000 590 25001 590 24770 590 24770 590 25001 590 24876 590 24770 25293 24876 25293 24826 25293 24826 590 24876 590 24863 590 24826 25294 24863 25294 24745 25294 24745 590 24863 590 24864 590 24993 25295 24995 25295 24994 25295 24994 25296 24995 25296 24996 25296 24995 25297 25210 25297 24996 25297 24996 15554 25210 15554 24997 15554 24996 15555 24997 15555 24966 15555 24966 22195 24997 22195 24999 22195 24966 15532 24999 15532 24998 15532 24998 25298 24999 25298 25211 25298 24998 15533 25211 15533 25000 15533 25000 15534 25211 15534 25208 15534 25000 25299 25208 25299 25001 25299 25001 25300 25208 25300 24757 25300 24757 25301 25208 25301 25207 25301 24757 25302 25207 25302 25002 25302 25207 25303 25169 25304 25002 25305 25002 15540 25169 15540 25171 15540 25002 25306 25171 25306 24880 25306 24880 15542 25171 15542 25172 15542 24880 15543 25172 15543 25003 15543 25003 21961 25172 21961 25004 21961 25003 21962 25004 21962 24878 21962 24878 25307 25004 25307 25175 25307 24878 25308 25175 25308 24879 25308 24879 25309 25175 25309 25173 25309 24879 25310 25173 25310 25005 25310 25005 15551 25173 15551 24993 15551 25005 15551 24993 15551 24969 15551 24969 25311 24993 25311 24994 25311 24747 960 25006 960 25218 960 25007 25312 24461 25312 24464 25312 25008 25313 25009 25313 25109 25313 24724 25314 24725 25314 25010 25314 25094 960 25091 960 25109 960 24373 25315 24372 25315 25209 25315 25280 960 25011 960 25016 960 25275 960 25014 960 25012 960 25040 25316 25281 25316 25039 25316 25281 25317 25286 25317 25045 25317 25045 960 25286 960 25294 960 25045 960 25294 960 25023 960 25310 960 25042 960 25273 960 25273 960 25042 960 25013 960 25012 960 25014 960 25013 960 25013 25318 25014 25318 25274 25318 25013 25319 25274 25319 25273 25319 25011 25320 25015 25320 25016 25320 25016 960 25015 960 25279 960 25016 25321 25279 25321 25012 25321 25012 25322 25279 25322 25276 25322 25012 25323 25276 25323 25275 25323 25017 960 25303 960 25018 960 25018 25324 25303 25324 25305 25324 25018 25325 25305 25325 25198 25325 25297 960 25298 960 25070 960 25070 960 25298 960 25019 960 25070 960 25019 960 25017 960 25017 960 25019 960 25020 960 25017 25326 25020 25326 25303 25326 25265 25327 25264 25327 25205 25327 25205 960 25264 960 25263 960 25269 960 25021 960 25219 960 25219 960 25021 960 25268 960 25219 960 25268 960 25206 960 25206 25328 25268 25328 25266 25328 25294 25329 25022 25330 25023 25331 25023 960 25022 960 25024 960 25023 960 25024 960 25209 960 25024 960 25260 960 25209 960 25209 960 25260 960 25271 960 25209 25332 25271 25332 25219 25332 25219 25333 25271 25333 25025 25333 25219 25334 25025 25334 25269 25334 24494 25335 24495 25335 25034 25335 25026 960 24359 960 25036 960 25036 960 24359 960 24356 960 25036 960 24356 960 25039 960 25039 25336 24356 25336 25027 25336 25039 25337 25027 25337 24355 25337 25028 960 25029 960 24345 960 25028 25338 24345 25338 24498 25338 24345 25339 25030 25339 24498 25339 24498 25340 25030 25340 25031 25340 24498 25341 25031 25341 25032 25341 25032 960 25031 960 24343 960 25032 960 24343 960 25033 960 25033 960 24343 960 24341 960 25033 25342 24341 25342 25034 25342 25034 25343 24341 25343 25035 25343 25034 19201 25035 19201 24494 19201 24494 25344 25035 25344 25026 25344 24494 960 25026 960 24482 960 24482 960 25026 960 25036 960 25013 15921 24350 15921 25188 15921 25188 25345 24350 25345 25037 25345 25188 960 25037 960 25028 960 25028 25346 25037 25346 25038 25346 25028 960 25038 960 25029 960 24355 960 24354 960 25039 960 25039 25347 24354 25347 25042 25347 25039 25348 25042 25348 25040 25348 25040 25349 25042 25349 25310 25349 24354 960 25041 960 25042 960 25042 25350 25041 25350 24352 25350 25042 25351 24352 25351 25013 25351 25013 25352 24352 25352 24351 25352 25013 960 24351 960 24350 960 25043 960 25044 960 25045 960 24472 25353 24473 25353 24491 25353 25045 25354 25044 25354 25046 25354 25044 960 24364 960 25046 960 25046 25355 24364 25355 24363 25355 25046 960 24363 960 25047 960 25047 960 24363 960 24362 960 25047 960 24362 960 24491 960 24491 25356 24362 25356 25048 25356 24491 25357 25048 25357 24472 25357 24472 25358 25048 25358 25052 25358 24372 960 24370 960 25209 960 25209 25359 24370 25359 25049 25359 25209 960 25049 960 25023 960 25023 25360 25049 25360 24368 25360 25023 960 24368 960 25045 960 25045 25361 24368 25361 24366 25361 25045 960 24366 960 25043 960 25051 960 25050 960 25168 960 25168 960 25050 960 24373 960 24469 25362 24376 25362 25051 25362 25051 25363 24376 25363 24375 25363 25051 960 24375 960 25050 960 25048 960 24377 960 25052 960 25052 25364 24377 25364 25053 25364 25052 25365 25053 25365 24470 25365 24470 960 25053 960 25054 960 24470 25366 25054 25366 24469 25366 24469 25367 25054 25367 25055 25367 24469 25368 25055 25368 24376 25368 25056 960 25057 960 25170 960 25170 25369 25057 25369 25063 25369 25218 25370 25058 25370 24382 25370 24382 25371 25059 25371 25218 25371 25218 960 25059 960 25060 960 25218 25372 25060 25372 25170 25372 25170 25373 25060 25373 25061 25373 25170 25374 25061 25374 25056 25374 25057 25375 25062 25375 25063 25375 25063 960 25062 960 25064 960 25063 25376 25064 25376 25179 25376 25064 960 24395 960 25179 960 25179 960 24395 960 25066 960 25179 25377 25066 25377 25065 25377 25065 25378 25066 25378 25067 25378 25065 960 25067 960 24449 960 24449 25379 25067 25379 24391 25379 24449 960 24391 960 24445 960 24445 25380 24391 25380 24390 25380 24445 960 24390 960 24443 960 24443 25381 24390 25381 25068 25381 24443 25382 25068 25382 25185 25382 25185 25383 25068 25383 24388 25383 25185 25384 24388 25384 25186 25384 24403 960 24404 960 25070 960 25215 25385 25069 25385 25070 25385 25070 25386 25069 25386 25071 25386 25070 25387 25071 25387 24403 25387 25263 25388 25297 25388 25205 25388 25205 25389 25297 25389 25070 25389 25205 25390 25070 25390 24405 25390 24405 960 25070 960 24404 960 25073 960 24398 960 25215 960 25215 960 24398 960 25072 960 25215 960 25072 960 25069 960 24719 960 25077 960 24707 960 24707 25391 25077 25391 25073 25391 24707 960 25073 960 25074 960 25074 960 25073 960 25215 960 25074 25392 25215 25392 24711 25392 24405 25393 25075 25393 25205 25393 25205 25394 25075 25394 24406 25394 25205 25395 24406 25395 25104 25395 25104 25396 24406 25396 25076 25396 25104 25397 25076 25397 25105 25397 24719 25398 24718 25398 25077 25398 25077 960 24718 960 24723 960 25077 25399 24723 25399 24399 25399 24399 25400 24723 25400 25079 25400 24399 960 25079 960 25078 960 25078 960 25079 960 25080 960 25078 960 25080 960 24400 960 24400 25401 25080 25401 25081 25401 24400 960 25081 960 24401 960 24401 25402 25081 25402 25082 25402 24401 960 25082 960 25083 960 25083 25403 25082 25403 25084 25403 25085 960 25086 960 25017 960 25085 960 25017 960 25087 960 25087 25404 25017 25404 25018 25404 25087 25405 25018 25405 24411 25405 25088 960 25089 960 25090 960 25092 25406 24414 25406 25018 25406 25018 960 24414 960 24412 960 25018 25407 24412 25407 24411 25407 25091 25408 24418 25408 25109 25408 25109 960 24418 960 24416 960 25109 960 24416 960 25092 960 25092 25409 24416 25409 25093 25409 25092 25410 25093 25410 24414 25410 25109 25411 25009 25411 25094 25411 25094 960 25009 960 24698 960 25094 960 24698 960 25095 960 25095 960 24698 960 25096 960 25095 25412 25096 25412 24422 25412 24422 960 25096 960 25099 960 24422 25413 25099 25413 25100 25413 25089 960 25097 960 25090 960 25090 25414 25097 25414 25098 25414 25090 960 25098 960 24714 960 24714 25415 25098 25415 24423 25415 25099 960 24704 960 25100 960 25100 25416 24704 25416 25101 25416 25100 15847 25101 15847 24423 15847 24423 25417 25101 25417 25102 25417 24423 25418 25102 25418 24714 25418 25010 25419 24725 25419 25103 25419 25106 960 24438 960 25082 960 25082 25420 24438 25420 25104 25420 25082 25421 25104 25421 25084 25421 25084 25422 25104 25422 25105 25422 24725 960 25106 960 25103 960 25103 960 25106 960 25082 960 25103 25423 25082 25423 25107 25423 25107 25424 25082 25424 25081 25424 24714 960 24713 960 25090 960 25090 960 24713 960 24712 960 25090 960 24712 960 25215 960 25215 960 24712 960 25108 960 25215 960 25108 960 24711 960 25109 25425 25110 25425 24695 25425 25008 960 25109 960 24700 960 24700 960 25109 960 24695 960 24700 25426 24695 25426 24701 25426 25110 960 25109 960 25111 960 25111 25427 25109 25427 25092 25427 25111 960 25092 960 25122 960 25122 25428 25092 25428 25202 25428 25122 960 25202 960 25119 960 25112 960 24513 960 25113 960 25113 960 24513 960 24512 960 25212 25429 25134 25429 25114 25429 25114 960 25134 960 24513 960 25114 960 24513 960 25115 960 25115 960 24513 960 25112 960 25115 960 25112 960 25116 960 25116 960 25112 960 25118 960 25116 25430 25118 25430 25117 25430 25117 25431 25118 25431 25120 25431 25117 25432 25120 25432 25119 25432 25119 960 25120 960 25121 960 25119 25433 25121 25433 25122 25433 25123 25434 24334 25434 25124 25434 25123 25435 25124 25435 25125 25435 25125 960 25124 960 25130 960 25125 25436 25130 25436 24331 25436 25126 960 25127 960 25134 960 25134 25437 25127 25437 24322 25437 25134 960 24322 960 24513 960 24513 25438 24322 25438 24326 25438 24513 25439 24326 25439 24514 25439 24514 25440 24326 25440 24327 25440 24514 960 24327 960 25128 960 25128 25441 24327 25441 24329 25441 25128 25442 24329 25442 25129 25442 25129 25443 24329 25443 24330 25443 25129 960 24330 960 25130 960 25130 25444 24330 25444 25131 25444 25130 25445 25131 25445 24331 25445 24334 25446 24335 25446 25124 25446 25124 25447 24335 25447 25132 25447 25124 960 25132 960 25134 960 25134 25448 25132 25448 25133 25448 25134 25449 25133 25449 25126 25449 25130 960 25135 960 25145 960 25136 960 25137 960 25124 960 25124 25450 25137 25450 25138 25450 25124 25451 25138 25451 25130 25451 25130 25452 25138 25452 25139 25452 25130 25453 25139 25453 25135 25453 25148 960 25140 960 25188 960 25188 960 25140 960 25142 960 25143 960 25145 960 25140 960 25140 25454 25145 25454 25141 25454 25140 25455 25141 25455 25142 25455 25143 960 25144 960 25145 960 25145 25456 25144 25456 25146 25456 25145 25457 25146 25457 25130 25457 25130 25458 25146 25458 24475 25458 25130 25459 24475 25459 25147 25459 25148 960 25188 960 25149 960 25149 25460 25188 25460 25028 25460 25149 960 25028 960 25150 960 25150 25461 25028 25461 24478 25461 24478 960 25028 960 24498 960 24478 960 24498 960 25151 960 25151 25462 24498 25462 24500 25462 25151 960 24500 960 24503 960 24487 25463 25158 25463 25152 25463 25157 960 25153 960 25045 960 25281 960 25045 960 25039 960 25039 960 25045 960 25153 960 25039 25464 25153 25464 25154 25464 24487 25465 25152 25465 25046 25465 25046 960 25152 960 25155 960 25046 25466 25155 25466 25045 25466 25045 25467 25155 25467 25156 25467 25045 25468 25156 25468 25157 25468 25158 25469 24487 25469 25159 25469 25159 25470 24487 25470 24485 25470 25159 960 24485 960 25160 960 25154 25471 25161 25471 25039 25471 25039 25472 25161 25472 25162 25472 25039 960 25162 960 25036 960 25036 25473 25162 25473 25163 25473 25036 960 25163 960 24483 960 24483 25474 25163 25474 25160 25474 24483 25475 25160 25475 25164 25475 25164 960 25160 960 24485 960 25051 960 25165 960 24469 960 24469 25476 25165 25476 24453 25476 24469 25477 24453 25477 25166 25477 24461 25478 25007 25478 25166 25478 25166 25479 25007 25479 24466 25479 25166 960 24466 960 24469 960 25168 960 24995 960 24993 960 24993 960 25167 960 25168 960 25168 25480 25167 25480 24456 25480 25168 25481 24456 25481 25051 25481 25051 25482 24456 25482 24455 25482 25051 25483 24455 25483 25165 25483 25169 25484 25170 25484 25171 25484 25171 25485 25170 25485 25063 25485 25171 25486 25063 25486 25172 25486 25172 960 25063 960 25004 960 24993 960 25173 960 25167 960 25167 25487 25173 25487 25175 25487 25167 960 25175 960 25174 960 25174 960 25175 960 25004 960 25174 960 25004 960 24458 960 24458 960 25004 960 25063 960 24458 25488 25063 25488 25176 25488 25176 960 25063 960 25177 960 25177 960 25063 960 25178 960 25178 960 25063 960 25179 960 25178 960 25179 960 25180 960 25181 960 24430 960 25185 960 25185 25489 24430 25489 24428 25489 25185 960 24428 960 24443 960 24443 960 24428 960 25182 960 24443 960 25182 960 25183 960 25006 960 25184 960 25218 960 25218 960 25184 960 25185 960 25218 25490 25185 25490 25058 25490 25058 25491 25185 25491 25186 25491 25184 960 24744 960 25185 960 25185 25492 24744 25492 24742 25492 25185 960 24742 960 25181 960 25181 25493 24742 25493 24741 25493 25181 25494 24741 25494 24434 25494 24434 25495 24741 25495 24755 25495 24434 960 24755 960 24435 960 24435 25496 24755 25496 24753 25496 24435 960 24753 960 24437 960 24437 25497 24753 25497 25104 25497 24437 25498 25104 25498 25187 25498 25187 25499 25104 25499 24438 25499 25142 25500 25189 25500 25188 25500 25188 960 25189 960 25190 960 25188 25501 25190 25501 25013 25501 25013 25502 25190 25502 25194 25502 25191 960 25012 960 25192 960 25192 960 25012 960 25013 960 25192 25503 25013 25503 25193 25503 25193 960 25013 960 25194 960 25195 25504 25196 25504 25016 25504 25195 960 25016 960 25213 960 25196 25505 25197 25505 25016 25505 25016 25506 25197 25506 25018 25506 25016 25507 25018 25507 25280 25507 25280 25508 25018 25508 25198 25508 25197 960 25199 960 25018 960 25018 25509 25199 25509 25200 25509 25018 25510 25200 25510 25092 25510 25092 25511 25200 25511 25201 25511 25092 25512 25201 25512 25202 25512 25203 960 25217 960 25206 960 24753 25513 25204 25513 25104 25513 25104 960 25204 960 24751 960 25104 960 24751 960 25205 960 25205 960 24751 960 24750 960 25205 25514 24750 25514 24749 25514 25266 960 25265 960 25206 960 25206 960 25265 960 25205 960 25206 960 25205 960 25203 960 25203 25515 25205 25515 24749 25515 25207 960 25208 960 25219 960 24373 25516 25209 25516 25168 25516 25168 25517 25209 25517 25210 25517 25168 25518 25210 25518 24995 25518 25208 25519 25211 25519 25219 25519 25219 25520 25211 25520 24999 25520 25219 25521 24999 25521 25209 25521 25209 25522 24999 25522 24997 25522 25209 25523 24997 25523 25210 25523 25212 960 25213 960 25134 960 25134 25524 25213 25524 25016 25524 25134 960 25016 960 25124 960 25124 960 25016 960 25012 960 25124 25525 25012 25525 25136 25525 25136 25526 25012 25526 25191 25526 25214 25527 24726 25527 25215 25527 25215 960 24726 960 24740 960 25215 25528 24740 25528 25090 25528 25090 960 24740 960 24739 960 24739 960 24737 960 25090 960 25090 25529 24737 25529 25017 25529 25090 25530 25017 25530 25088 25530 25088 960 25017 960 25086 960 24737 25531 24736 25531 25017 25531 25017 25532 24736 25532 24735 25532 25017 960 24735 960 25070 960 25070 960 24735 960 24734 960 25070 960 24734 960 24731 960 24731 960 24730 960 25070 960 25070 960 24730 960 24728 960 25070 960 24728 960 25215 960 25215 25533 24728 25533 25216 25533 25215 25534 25216 25534 25214 25534 25217 960 24747 960 25206 960 25206 25535 24747 25535 25218 25535 25206 25536 25218 25536 25219 25536 25219 25537 25218 25537 25170 25537 25219 25538 25170 25538 25207 25538 25207 960 25170 960 25169 960 25223 25539 25221 25539 25220 25539 25220 25540 25221 25540 25267 25540 25259 960 25261 960 25270 960 25270 25541 25261 25541 25221 25541 25270 25542 25221 25542 25222 25542 25222 25543 25221 25543 25223 25543 25226 25544 25225 25544 25224 25544 25224 960 25225 960 25272 960 25224 960 25277 960 25226 960 25226 25545 25277 25545 25278 25545 25226 960 25278 960 25227 960 25227 960 25278 960 25228 960 25235 25546 25229 25546 25243 25546 25243 25547 25229 25547 25308 25547 25255 25548 25253 25548 25230 25548 25230 25549 25231 25549 25255 25549 25255 25550 25231 25550 25232 25550 25255 25551 25232 25551 25256 25551 25232 25552 25295 25552 25256 25552 25256 25553 25295 25553 25288 25553 25256 25554 25288 25554 25234 25554 25288 25555 25233 25555 25234 25555 25234 25556 25233 25556 25289 25556 25234 25557 25289 25557 25258 25557 25258 25558 25289 25558 25291 25558 25258 25559 25291 25559 25248 25559 25291 25560 25312 25560 25248 25560 25248 25561 25312 25561 25311 25561 25248 25562 25311 25562 25235 25562 25235 25563 25311 25563 25309 25563 25235 25564 25309 25564 25229 25564 25262 25565 25236 25565 25296 25565 25296 25566 25236 25566 25237 25566 25245 25567 25244 25567 25238 25567 25238 25568 25244 25568 25307 25568 25307 25569 25306 25569 25238 25569 25238 25570 25306 25570 25304 25570 25238 25571 25304 25571 25246 25571 25304 25572 25239 25572 25246 25572 25246 25573 25239 25573 25302 25573 25246 25574 25302 25574 25247 25574 25247 25575 25302 25576 25301 25577 25247 25578 25301 25578 25249 25578 25301 25579 25300 25579 25249 25579 25249 25580 25300 25581 25299 25582 25249 25583 25299 25583 25251 25583 25299 25584 25240 25584 25251 25584 25251 25585 25240 25585 25241 25585 25251 25586 25241 25586 25237 25586 25237 25587 25241 25587 25242 25587 25237 25588 25242 25588 25296 25588 25243 14670 25308 14670 25272 14670 25243 25589 25272 25589 25245 25589 25245 25590 25272 25590 25225 25590 25245 14670 25225 14670 25244 14670 25371 960 25369 960 25245 960 25245 25591 25369 25591 25243 25591 25245 25592 25238 25592 25371 25592 25371 960 25238 960 25246 960 25371 25593 25246 25593 25374 25593 25374 960 25246 960 25247 960 25374 25594 25247 25594 25250 25594 25369 960 25357 960 25243 960 25243 25595 25357 25595 25358 25595 25243 960 25358 960 25235 960 25235 25596 25358 25596 25353 25596 25257 960 25258 960 25353 960 25353 960 25258 960 25248 960 25353 25597 25248 25597 25235 25597 25247 960 25249 960 25250 960 25250 960 25249 960 25251 960 25250 960 25251 960 25252 960 25252 25598 25251 25598 25237 25598 25252 960 25237 960 25378 960 25378 25599 25237 25599 25236 25599 25378 25600 25236 25600 25254 25600 25254 960 25236 960 25253 960 25254 960 25253 960 25350 960 25350 960 25253 960 25255 960 25350 25601 25255 25601 25354 25601 25354 960 25255 960 25256 960 25354 960 25256 960 25257 960 25257 960 25256 960 25234 960 25257 25602 25234 25602 25258 25602 25236 25603 25262 25603 25261 25603 25236 25604 25261 25604 25253 25604 25253 25605 25261 25605 25259 25605 25253 14695 25259 14695 25230 14695 25295 25606 25232 25606 25260 25606 25261 25607 25262 25607 25296 25607 25221 25608 25261 25608 25263 25608 25263 25609 25264 25609 25221 25609 25221 25610 25264 25610 25265 25610 25221 25611 25265 25611 25267 25611 25231 25612 25230 25612 25259 25612 25265 25613 25266 25613 25267 25613 25267 25614 25266 25614 25268 25614 25267 25615 25268 25615 25220 25615 25220 25616 25268 25616 25021 25616 25220 25617 25021 25617 25223 25617 25223 25618 25021 25618 25269 25618 25223 25619 25269 25619 25222 25619 25222 25620 25269 25620 25025 25620 25222 25621 25025 25621 25270 25621 25270 25622 25025 25622 25271 25622 25270 25623 25271 25623 25259 25623 25259 25624 25271 25624 25260 25624 25259 25625 25260 25625 25231 25625 25231 25626 25260 25626 25232 25626 25224 25627 25272 25627 25273 25627 25273 25628 25272 25628 25308 25628 25273 25629 25274 25629 25224 25629 25224 25630 25274 25630 25014 25630 25224 25631 25014 25631 25277 25631 25014 25632 25275 25632 25277 25632 25277 25633 25275 25633 25276 25633 25277 25634 25276 25634 25278 25634 25278 25635 25276 25635 25279 25635 25278 25636 25279 25636 25228 25636 25228 25637 25279 25637 25015 25637 25228 25638 25015 25638 25227 25638 25227 25639 25015 25639 25011 25639 25227 25640 25011 25640 25226 25640 25226 25641 25011 25641 25280 25641 25226 25642 25280 25642 25225 25642 25225 25643 25280 25643 25198 25643 25225 25644 25198 25644 25244 25644 25329 25645 25327 25645 25312 25645 25312 25646 25327 25646 25325 25646 25312 25647 25325 25647 25326 25647 25321 25648 25322 25648 25281 25648 25281 25649 25322 25649 25282 25649 25283 25650 25345 25650 25294 25650 25294 25651 25345 25651 25284 25651 25294 25652 25284 25652 25313 25652 25282 25653 25315 25653 25281 25653 25281 25654 25315 25654 25318 25654 25281 25655 25318 25655 25286 25655 25286 25656 25318 25656 25285 25656 25286 25657 25285 25657 25294 25657 25294 25658 25285 25658 25343 25658 25294 25659 25343 25659 25283 25659 25342 25660 25287 25661 25288 25662 25288 25663 25287 25663 25340 25663 25340 25664 25334 25664 25288 25664 25288 25665 25334 25665 25335 25665 25288 25666 25335 25666 25233 25666 25233 25667 25335 25667 25336 25667 25233 25668 25336 25668 25289 25668 25289 25669 25336 25669 25290 25669 25289 25670 25290 25670 25291 25670 25291 25671 25290 25671 25292 25671 25291 25672 25292 25672 25312 25672 25312 25673 25292 25673 25293 25673 25312 25674 25293 25674 25329 25674 25313 25675 25342 25675 25294 25675 25294 25676 25342 25676 25288 25676 25294 25677 25288 25677 25022 25677 25022 25678 25288 25678 25295 25678 25022 25679 25295 25679 25024 25679 25024 25680 25295 25680 25260 25680 25261 25681 25296 25681 25263 25681 25263 25682 25296 25682 25242 25682 25263 25683 25242 25683 25297 25683 25242 25684 25241 25684 25297 25684 25297 25685 25241 25685 25240 25685 25297 25686 25240 25686 25298 25686 25298 25687 25240 25687 25299 25687 25298 25688 25299 25688 25019 25688 25299 25689 25300 25690 25019 25691 25019 25692 25300 25692 25301 25692 25019 25693 25301 25693 25020 25693 25020 25694 25301 25695 25302 25696 25020 25697 25302 25697 25303 25697 25303 25698 25302 25698 25239 25698 25303 25699 25239 25699 25305 25699 25239 25700 25304 25700 25305 25700 25305 25701 25304 25701 25306 25701 25305 25702 25306 25702 25198 25702 25198 25703 25306 25703 25307 25703 25198 25704 25307 25704 25244 25704 25308 25705 25229 25705 25273 25705 25273 25706 25229 25706 25309 25706 25273 25707 25309 25707 25310 25707 25310 25708 25309 25708 25311 25708 25310 25709 25311 25709 25040 25709 25040 25710 25311 25710 25312 25710 25040 25711 25312 25711 25281 25711 25281 25712 25312 25712 25326 25712 25281 25713 25326 25713 25321 25713 25313 25714 25284 25714 25349 25714 25356 25715 25314 25715 25327 25715 25327 25716 25314 25716 25325 25716 25322 25717 25362 25717 25282 25717 25282 25718 25362 25718 25316 25718 25282 25719 25316 25719 25315 25719 25315 25720 25316 25720 25317 25720 25315 25721 25317 25721 25318 25721 25318 25722 25317 25722 25319 25722 25318 25723 25319 25723 25285 25723 25326 25724 25320 25724 25321 25724 25321 25725 25320 25725 25323 25725 25321 25726 25323 25726 25322 25726 25322 25727 25323 25727 25364 25727 25322 25728 25364 25728 25362 25728 25359 25729 25324 25729 25326 25729 25326 25730 25324 25730 25361 25730 25326 25731 25361 25731 25320 25731 25325 25732 25314 25732 25326 25732 25326 25733 25314 25733 25360 25733 25326 25734 25360 25734 25359 25734 25356 25735 25327 25735 25328 25735 25328 25736 25327 25736 25329 25736 25328 25737 25329 25737 25330 25737 25330 25738 25329 25738 25293 25738 25330 25739 25293 25739 25331 25739 25331 25740 25293 25740 25292 25740 25331 25741 25292 25741 25337 25741 25340 25742 25332 25742 25334 25742 25334 25743 25332 25743 25333 25743 25334 25744 25333 25744 25335 25744 25335 25745 25333 25745 25355 25745 25335 25746 25355 25746 25336 25746 25336 25747 25355 25747 25337 25747 25336 25748 25337 25748 25290 25748 25290 25749 25337 25749 25292 25749 25342 25750 25338 25750 25287 25750 25287 25751 25338 25751 25339 25751 25287 25752 25339 25752 25340 25752 25340 25753 25339 25753 25341 25753 25340 25754 25341 25754 25332 25754 25381 25755 25352 25755 25342 25755 25342 25756 25352 25756 25351 25756 25342 25757 25351 25757 25338 25757 25313 25758 25349 25758 25342 25758 25342 25759 25349 25759 25383 25759 25342 25760 25383 25760 25381 25760 25285 25761 25319 25761 25343 25761 25343 25762 25319 25762 25344 25762 25343 25763 25344 25763 25283 25763 25283 25764 25344 25764 25346 25764 25283 25765 25346 25765 25345 25765 25345 25766 25346 25766 25347 25766 25345 25767 25347 25767 25284 25767 25284 25768 25347 25768 25348 25768 25284 25769 25348 25769 25349 25769 25316 25770 25362 25770 25367 25770 25333 25771 25332 25771 25354 25771 25347 25772 25365 25772 25348 25772 25348 25773 25365 25773 25382 25773 25348 25774 25382 25774 25349 25774 25339 25775 25338 25775 25350 25775 25350 25776 25338 25776 25351 25776 25350 25777 25351 25777 25254 25777 25254 25778 25351 25778 25352 25778 25254 25779 25352 25780 25381 25781 25354 25782 25332 25782 25350 25782 25350 25783 25332 25783 25341 25783 25350 25784 25341 25785 25339 25786 25328 25787 25330 25787 25353 25787 25353 25788 25330 25788 25331 25788 25353 25789 25331 25789 25257 25789 25257 25790 25331 25790 25337 25790 25257 25791 25337 25791 25354 25791 25354 25792 25337 25792 25355 25792 25354 25793 25355 25793 25333 25793 25328 25794 25353 25794 25356 25794 25356 25795 25353 25795 25358 25795 25356 25796 25358 25796 25314 25796 25361 25797 25324 25797 25357 25797 25357 25798 25324 25798 25359 25798 25357 25799 25359 25799 25358 25799 25358 25800 25359 25800 25360 25800 25358 25801 25360 25801 25314 25801 25323 25802 25320 25802 25363 25802 25363 25803 25320 25803 25361 25803 25363 25804 25361 25804 25368 25804 25367 25805 25362 25805 25363 25805 25363 25806 25362 25806 25364 25806 25363 25807 25364 25807 25323 25807 25347 25808 25346 25808 25365 25808 25365 25809 25346 25809 25344 25809 25365 25810 25344 25810 25366 25810 25366 25811 25344 25811 25319 25811 25366 25812 25319 25812 25367 25812 25367 25813 25319 25813 25317 25813 25367 25814 25317 25814 25316 25814 25361 25815 25357 25815 25368 25815 25368 25816 25357 25816 25369 25816 25368 25816 25369 25816 25370 25816 25370 25817 25369 25817 25371 25817 25370 25817 25371 25817 25372 25817 25372 25818 25371 25818 25374 25818 25372 25819 25374 25819 25373 25819 25373 25820 25374 25820 25375 25820 25375 25821 25374 25821 25250 25821 25375 25822 25250 25822 25376 25822 25376 25823 25250 25823 25252 25823 25376 25824 25252 25824 25377 25824 25377 25825 25252 25825 25378 25825 25377 25826 25378 25826 25379 25826 25379 25827 25378 25827 25254 25827 25379 25828 25254 25828 25380 25828 25380 25829 25254 25829 25381 25829 25380 25830 25381 25830 25382 25830 25382 25831 25381 25831 25383 25831 25382 25832 25383 25832 25349 25832 25425 25833 25426 25833 25385 25833 25385 25834 25426 25834 25384 25834 25385 25835 25384 25835 24544 25835 24544 25836 25384 25836 25386 25836 24544 25837 25386 25837 24542 25837 24542 25838 25386 25838 25387 25838 24542 25839 25387 25839 25388 25839 25388 25840 25387 25840 25389 25840 25388 25840 25389 25840 24539 25840 24539 25841 25389 25841 25390 25841 24539 25842 25390 25842 25391 25842 25391 25843 25390 25843 25493 25843 25391 25844 25493 25844 24536 25844 24536 25845 25493 25845 25392 25845 24536 25846 25392 25846 24535 25846 24535 25847 25392 25847 25492 25847 24535 25848 25492 25848 25393 25848 25393 25849 25492 25849 25490 25849 25393 25850 25490 25850 24533 25850 24533 25851 25490 25851 25489 25851 24533 25852 25489 25852 25394 25852 25394 25853 25489 25853 25488 25853 25394 25854 25488 25854 25396 25854 25396 25855 25488 25855 25395 25855 25396 25856 25395 25856 25397 25856 25397 25857 25395 25857 25398 25857 25397 25858 25398 25858 24529 25858 24529 25859 25398 25859 25399 25859 24529 16312 25399 16312 24528 16312 24528 25860 25399 25860 25400 25860 24528 16314 25400 16314 25401 16314 25401 25861 25400 25861 25402 25861 25401 25862 25402 25862 24527 25862 24527 25863 25402 25863 25485 25863 24527 25864 25485 25864 25403 25864 25403 25865 25485 25865 25483 25865 25403 25866 25483 25866 25404 25866 25404 25867 25483 25867 25405 25867 25404 25868 25405 25868 25406 25868 25406 25869 25405 25869 25482 25869 25406 25870 25482 25870 24565 25870 24565 25871 25482 25871 25480 25871 24565 25872 25480 25872 24562 25872 24562 25873 25480 25873 25407 25873 24562 25873 25407 25873 25408 25873 25408 25874 25407 25874 25514 25874 25408 25875 25514 25875 24560 25875 24560 25876 25514 25876 25409 25876 24560 25877 25409 25877 25411 25877 25411 25878 25409 25878 25410 25878 25411 25879 25410 25879 25413 25879 25413 25880 25410 25880 25412 25880 25413 25881 25412 25881 25414 25881 25414 25882 25412 25882 25415 25882 25414 25883 25415 25883 24556 25883 24556 25884 25415 25884 25416 25884 24556 25885 25416 25885 25417 25885 25417 25886 25416 25886 25509 25886 25417 25887 25509 25887 24555 25887 24555 25888 25509 25888 25508 25888 24555 25889 25508 25889 24551 25889 24551 25890 25508 25890 25418 25890 24551 25891 25418 25891 24550 25891 24550 25892 25418 25892 25505 25892 24550 25893 25505 25893 25419 25893 25419 25894 25505 25894 25503 25894 25419 16275 25503 16275 25420 16275 25420 25895 25503 25895 25502 25895 25420 16277 25502 16277 25421 16277 25421 25896 25502 25896 25422 25896 25421 25897 25422 25897 24546 25897 24546 25898 25422 25898 25500 25898 24546 25899 25500 25899 25423 25899 25423 25900 25500 25900 25424 25900 25423 25901 25424 25901 25425 25901 25425 25902 25424 25902 25426 25902 25479 25903 25496 25903 25427 25903 25427 25904 25496 25904 25497 25904 25427 25905 25497 25905 25428 25905 25428 25906 25497 25906 25498 25906 25428 25907 25498 25907 25429 25907 25429 25908 25498 25908 25499 25908 25429 25909 25499 25909 25430 25909 25430 25910 25499 25910 25501 25910 25430 25911 25501 25911 25431 25911 25431 25912 25501 25912 25432 25912 25431 25912 25432 25912 25433 25912 25433 25913 25432 25913 25504 25913 25433 25914 25504 25914 25434 25914 25434 25915 25504 25915 25506 25915 25434 25916 25506 25916 25435 25916 25435 25917 25506 25917 25507 25917 25435 25918 25507 25918 25436 25918 25436 25919 25507 25919 25510 25919 25436 25920 25510 25920 25437 25920 25437 25921 25510 25921 25511 25921 25437 25922 25511 25922 25438 25922 25438 25923 25511 25923 25512 25923 25438 25924 25512 25924 25439 25924 25439 25925 25512 25925 25513 25925 25439 25926 25513 25926 25440 25926 25440 25927 25513 25927 25441 25927 25440 25928 25441 25928 25442 25928 25442 25929 25441 25929 25444 25929 25442 25930 25444 25930 25443 25930 25443 25931 25444 25931 25515 25931 25443 25932 25515 25932 25445 25932 25445 25933 25515 25933 25516 25933 25445 25934 25516 25934 25446 25934 25446 25935 25516 25935 25447 25935 25446 25936 25447 25936 25448 25936 25448 25937 25447 25937 25481 25937 25448 25938 25481 25938 25449 25938 25449 25939 25481 25939 25450 25939 25449 25940 25450 25940 25451 25940 25451 25941 25450 25941 25484 25941 25451 25942 25484 25942 25452 25942 25452 25943 25484 25943 25453 25943 25452 25944 25453 25944 25454 25944 25454 25945 25453 25945 25486 25945 25454 25946 25486 25946 25455 25946 25455 25947 25486 25947 25456 25947 25455 25948 25456 25948 25457 25948 25457 25949 25456 25949 25487 25949 25457 25950 25487 25950 25458 25950 25458 25951 25487 25951 25459 25951 25458 25952 25459 25952 25460 25952 25460 25953 25459 25953 25461 25953 25460 25954 25461 25954 25462 25954 25462 25955 25461 25955 25463 25955 25462 25955 25463 25955 25465 25955 25465 25956 25463 25956 25464 25956 25465 25957 25464 25957 25466 25957 25466 25958 25464 25958 25491 25958 25466 25959 25491 25959 25467 25959 25467 25960 25491 25960 25468 25960 25467 25961 25468 25961 25469 25961 25469 25962 25468 25962 25471 25962 25469 25963 25471 25963 25470 25963 25470 25964 25471 25964 25472 25964 25470 25965 25472 25965 25473 25965 25473 25966 25472 25966 25494 25966 25473 25967 25494 25967 25474 25967 25474 25968 25494 25968 25495 25968 25474 25968 25495 25968 25476 25968 25476 25969 25495 25969 25475 25969 25476 25970 25475 25970 25477 25970 25477 25971 25475 25971 25478 25971 25477 25972 25478 25972 25479 25972 25479 25973 25478 25973 25496 25973 25480 25974 25482 25974 25481 25974 25481 590 25482 590 25405 590 25481 25975 25405 25975 25450 25975 25450 25976 25405 25976 25483 25976 25450 25977 25483 25977 25484 25977 25484 25978 25483 25978 25485 25978 25484 590 25485 590 25453 590 25453 590 25485 590 25402 590 25453 25979 25402 25979 25486 25979 25486 25980 25402 25980 25400 25980 25486 25981 25400 25981 25456 25981 25456 590 25400 590 25399 590 25456 590 25399 590 25487 590 25487 590 25399 590 25398 590 25487 25982 25398 25982 25459 25982 25459 590 25398 590 25395 590 25459 25983 25395 25983 25461 25983 25461 590 25395 590 25488 590 25461 25984 25488 25984 25463 25984 25463 25985 25488 25985 25489 25985 25463 25986 25489 25986 25464 25986 25464 590 25489 590 25490 590 25464 590 25490 590 25491 590 25491 25987 25490 25987 25492 25987 25491 25988 25492 25988 25468 25988 25468 25989 25492 25989 25392 25989 25468 590 25392 590 25471 590 25471 590 25392 590 25493 590 25471 590 25493 590 25472 590 25472 25990 25493 25990 25390 25990 25472 590 25390 590 25494 590 25494 590 25390 590 25389 590 25494 590 25389 590 25495 590 25495 590 25389 590 25387 590 25495 590 25387 590 25475 590 25475 590 25387 590 25386 590 25475 590 25386 590 25478 590 25478 590 25386 590 25384 590 25478 590 25384 590 25496 590 25496 590 25384 590 25426 590 25496 590 25426 590 25497 590 25497 590 25426 590 25424 590 25497 590 25424 590 25498 590 25498 590 25424 590 25500 590 25498 590 25500 590 25499 590 25499 590 25500 590 25422 590 25499 590 25422 590 25501 590 25501 25991 25422 25991 25502 25991 25501 590 25502 590 25432 590 25432 590 25502 590 25503 590 25432 590 25503 590 25504 590 25504 25992 25503 25992 25505 25992 25504 590 25505 590 25506 590 25506 590 25505 590 25418 590 25506 25993 25418 25993 25507 25993 25507 590 25418 590 25508 590 25507 25994 25508 25994 25510 25994 25510 590 25508 590 25509 590 25510 25995 25509 25995 25511 25995 25511 590 25509 590 25416 590 25511 25996 25416 25996 25512 25996 25512 25997 25416 25997 25415 25997 25512 590 25415 590 25513 590 25513 25998 25415 25998 25412 25998 25513 590 25412 590 25441 590 25441 25999 25412 25999 25410 25999 25441 590 25410 590 25444 590 25444 26000 25410 26000 25409 26000 25444 590 25409 590 25515 590 25515 26001 25409 26001 25514 26001 25515 26002 25514 26002 25516 26002 25516 26003 25514 26003 25407 26003 25516 590 25407 590 25447 590 25447 26004 25407 26004 25480 26004 25447 590 25480 590 25481 590 25534 16424 25517 16424 25546 16424 25518 16423 25519 16423 25520 16423 25573 16442 25521 16442 25522 16442 25530 26005 25518 26005 25596 26005 25561 26006 25562 26006 25580 26006 25580 26007 25562 26007 25523 26007 25580 26008 25523 26008 25584 26008 25584 26009 25523 26009 25524 26009 25584 26010 25524 26010 25585 26010 25585 16449 25524 16449 25525 16449 25585 16449 25525 16449 25586 16449 25586 26011 25525 26011 25526 26011 25586 26012 25526 26012 25590 26012 25590 16452 25526 16452 25527 16452 25590 16453 25527 16453 25591 16453 25591 26013 25527 26013 25528 26013 25591 26014 25528 26014 25593 26014 25593 16456 25528 16456 25530 16456 25593 16457 25530 16457 25529 16457 25529 26015 25530 26015 25596 26015 25531 16425 25532 16425 25533 16425 25545 26016 25534 26016 25547 26016 25610 26017 25535 26017 25614 26017 25614 26018 25535 26018 25537 26018 25614 26019 25537 26019 25536 26019 25536 26020 25537 26020 25538 26020 25536 26021 25538 26021 25617 26021 25617 16432 25538 16432 25539 16432 25617 16432 25539 16432 25540 16432 25540 26022 25539 26022 25541 26022 25540 26023 25541 26023 25543 26023 25543 16435 25541 16435 25542 16435 25543 16436 25542 16436 25620 16436 25620 26024 25542 26024 25544 26024 25620 26025 25544 26025 25622 26025 25622 16439 25544 16439 25545 16439 25622 16440 25545 16440 25624 16440 25624 26026 25545 26026 25547 26026 25534 16479 25546 16479 25547 16479 25547 16480 25546 16480 25548 16480 25547 16481 25548 16481 25627 16481 25627 16482 25548 16482 25549 16482 25627 16483 25549 16483 25550 16483 25550 16484 25549 16484 25551 16484 25550 16485 25551 16485 25630 16485 25630 26027 25551 26027 25553 26027 25630 26028 25553 26028 25552 26028 25552 26029 25553 26029 25554 26029 25552 26029 25554 26029 25556 26029 25556 26030 25554 26030 25555 26030 25556 26031 25555 26031 25557 26031 25557 26032 25555 26032 25558 26032 25557 26033 25558 26033 25559 26033 25559 16493 25558 16493 25531 16493 25559 16494 25531 16494 25578 16494 25578 16495 25531 16495 25533 16495 25578 26034 25533 26034 25561 26034 25561 16497 25533 16497 25560 16497 25561 26035 25560 26035 25562 26035 25518 16459 25520 16459 25596 16459 25596 16460 25520 16460 25563 16460 25596 16461 25563 16461 25599 16461 25599 16462 25563 16462 25564 16462 25599 16463 25564 16463 25566 16463 25566 16464 25564 16464 25565 16464 25566 16465 25565 16465 25601 16465 25601 26036 25565 26036 25567 26036 25601 26037 25567 26037 25568 26037 25568 26038 25567 26038 25569 26038 25568 26039 25569 26039 25570 26039 25570 26040 25569 26040 25571 26040 25570 26041 25571 26041 25605 26041 25605 26042 25571 26042 25572 26042 25605 26042 25572 26042 25606 26042 25606 16473 25572 16473 25573 16473 25606 16474 25573 16474 25609 16474 25609 16475 25573 16475 25522 16475 25609 26043 25522 26043 25610 26043 25610 16477 25522 16477 25574 16477 25610 26044 25574 26044 25535 26044 25631 26045 25556 26045 25575 26045 25575 960 25556 960 25557 960 25575 960 25557 960 25576 960 25576 26046 25557 26046 25559 26046 25576 26047 25559 26047 25577 26047 25577 960 25559 960 25578 960 25577 960 25578 960 25579 960 25579 26048 25578 26048 25561 26048 25579 26049 25561 26049 25581 26049 25581 960 25561 960 25580 960 25581 26050 25580 26050 25582 26050 25582 960 25580 960 25584 960 25582 26051 25584 26051 25583 26051 25583 960 25584 960 25585 960 25583 26052 25585 26052 25587 26052 25587 26053 25585 26053 25586 26053 25587 26054 25586 26054 25588 26054 25588 26055 25586 26055 25590 26055 25588 960 25590 960 25589 960 25589 26056 25590 26056 25591 26056 25589 960 25591 960 25592 960 25592 26057 25591 26057 25593 26057 25592 26058 25593 26058 25594 26058 25594 26059 25593 26059 25529 26059 25594 960 25529 960 25595 960 25595 960 25529 960 25596 960 25595 960 25596 960 25597 960 25597 26060 25596 26060 25599 26060 25597 26061 25599 26061 25598 26061 25598 960 25599 960 25566 960 25598 960 25566 960 25600 960 25600 26062 25566 26062 25601 26062 25600 960 25601 960 25602 960 25602 960 25601 960 25568 960 25602 26063 25568 26063 25603 26063 25603 960 25568 960 25570 960 25603 960 25570 960 25604 960 25604 960 25570 960 25605 960 25604 960 25605 960 25607 960 25607 26064 25605 26064 25606 26064 25607 960 25606 960 25608 960 25608 960 25606 960 25609 960 25608 960 25609 960 25611 960 25611 960 25609 960 25610 960 25611 26065 25610 26065 25612 26065 25612 960 25610 960 25614 960 25612 26066 25614 26066 25613 26066 25613 26067 25614 26067 25536 26067 25613 26068 25536 26068 25615 26068 25615 960 25536 960 25617 960 25615 960 25617 960 25616 960 25616 960 25617 960 25540 960 25616 960 25540 960 25618 960 25618 26069 25540 26069 25543 26069 25618 960 25543 960 25619 960 25619 26070 25543 26070 25620 26070 25619 960 25620 960 25621 960 25621 26071 25620 26071 25622 26071 25621 960 25622 960 25623 960 25623 960 25622 960 25624 960 25623 960 25624 960 25625 960 25625 26072 25624 26072 25547 26072 25625 960 25547 960 25626 960 25626 26073 25547 26073 25627 26073 25626 960 25627 960 25628 960 25628 26074 25627 26074 25550 26074 25628 960 25550 960 25629 960 25629 26075 25550 26075 25630 26075 25629 960 25630 960 25631 960 25631 960 25630 960 25552 960 25631 960 25552 960 25556 960 26087 26076 25632 26076 26088 26076 26088 26077 25632 26077 25633 26077 26088 26078 25633 26078 25634 26078 25634 590 25633 590 25635 590 25634 590 25635 590 25636 590 25636 590 25635 590 26248 590 25636 26079 26248 26079 26085 26079 26085 590 26248 590 26249 590 26085 590 26249 590 26082 590 26082 590 26249 590 25637 590 26082 590 25637 590 26262 590 25640 590 26124 590 26304 590 26304 26080 26124 26080 25638 26080 25638 590 26124 590 25639 590 25638 26081 25639 26081 26306 26081 26306 590 25639 590 26127 590 26306 590 26127 590 26308 590 25640 590 26304 590 26123 590 26123 590 26304 590 25641 590 26123 26082 25641 26082 25642 26082 25642 26083 25641 26083 26315 26083 25642 590 26315 590 26313 590 25646 590 25673 590 25643 590 25644 26084 25645 26084 25669 26084 25646 590 25643 590 25686 590 25666 590 25669 590 25647 590 25647 26085 25669 26085 25648 26085 25647 590 25648 590 25650 590 25650 590 25648 590 25649 590 25650 590 25649 590 25651 590 25651 26086 25649 26086 25652 26086 25651 590 25652 590 25653 590 25653 590 25652 590 25662 590 25653 26087 25662 26087 25660 26087 25659 590 25661 590 25654 590 25654 590 25661 590 25655 590 25688 590 25657 590 25656 590 25656 590 25657 590 25658 590 25672 26088 25674 26088 25659 26088 25659 590 25674 590 25660 590 25659 590 25660 590 25661 590 25661 26089 25660 26089 25662 26089 25699 26090 25663 26090 25664 26090 25658 590 25665 590 25656 590 25656 26091 25665 26091 25667 26091 25656 26092 25667 26092 25666 26092 25666 26093 25667 26093 25668 26093 25666 590 25668 590 25669 590 25669 590 25668 590 25670 590 25669 26094 25670 26094 25644 26094 25671 590 25643 590 25672 590 25672 590 25643 590 25673 590 25672 26095 25673 26095 25674 26095 25671 26096 25675 26096 25643 26096 25643 590 25675 590 25676 590 25643 26097 25676 26097 25677 26097 25677 590 25676 590 25679 590 25677 26098 25679 26098 25678 26098 25678 26099 25679 26099 25706 26099 25680 26100 25681 26100 25682 26100 25682 590 25681 590 25683 590 25682 26101 25683 26101 25684 26101 25643 26102 25685 26102 25686 26102 25686 590 25685 590 25687 590 25686 26103 25687 26103 25688 26103 25688 26104 25687 26104 25689 26104 25688 26105 25689 26105 25657 26105 25689 26106 25690 26106 25657 26106 25657 590 25690 590 25691 590 25657 26107 25691 26107 25710 26107 25710 26108 25691 26108 25692 26108 25710 26109 25692 26109 25708 26109 25693 590 25694 590 25763 590 25693 590 25763 590 25695 590 25694 26110 25696 26110 25763 26110 25763 590 25696 590 25697 590 25763 590 25697 590 25698 590 25698 26111 25703 26111 25702 26111 25699 590 25664 590 25700 590 25700 26112 25664 26112 25702 26112 25700 590 25702 590 25701 590 25701 590 25702 590 25703 590 25701 26113 25703 26113 25704 26113 25704 26114 25703 26114 25705 26114 25704 590 25705 590 25706 590 25706 26115 25705 26115 25707 26115 25706 26116 25707 26116 25678 26116 25708 590 25709 590 25710 590 25710 26117 25709 26117 25711 26117 25710 590 25711 590 25712 590 25712 26118 25711 26118 25681 26118 25712 590 25681 590 25713 590 25713 590 25681 590 25680 590 25711 26119 25695 26119 25681 26119 25681 590 25695 590 25763 590 25681 26120 25763 26120 25714 26120 25714 26121 25763 26121 25738 26121 25714 590 25794 590 25681 590 25681 590 25794 590 25715 590 25681 590 25715 590 25716 590 25716 26122 25715 26122 25717 26122 25715 26123 25718 26123 25717 26123 25717 26124 25718 26124 25723 26124 25717 590 25723 590 25721 590 25719 590 25720 590 25801 590 25801 590 25720 590 25721 590 25801 26125 25721 26125 25722 26125 25722 590 25721 590 25723 590 25724 590 25725 590 25726 590 25724 590 25726 590 25747 590 25719 26126 25730 26126 25720 26126 25720 590 25730 590 25733 590 25720 26127 25733 26127 25728 26127 25728 26128 25733 26128 25727 26128 25728 26129 25727 26129 25729 26129 25797 590 25731 590 25730 590 25730 590 25731 590 25732 590 25730 26130 25732 26130 25733 26130 25748 590 25734 590 25763 590 25763 26131 25734 26131 25735 26131 25735 590 25736 590 25763 590 25763 26132 25736 26132 25737 26132 25763 26133 25737 26133 25740 26133 25738 590 25763 590 25739 590 25739 26134 25763 26134 25740 26134 25739 26135 25740 26135 25797 26135 25797 26136 25740 26136 25741 26136 25797 26137 25741 26137 25731 26137 25760 26138 25742 26138 25743 26138 25760 26139 25743 26139 25763 26139 25763 26140 25743 26140 25744 26140 25763 590 25744 590 25745 590 25745 26141 25746 26141 25763 26141 25763 590 25746 590 25747 590 25763 26142 25747 26142 25748 26142 25748 590 25747 590 25726 590 25746 590 25749 590 25747 590 25747 26143 25749 26143 25750 26143 25747 26144 25750 26144 25751 26144 25751 590 25750 590 25752 590 25751 590 25752 590 25753 590 25753 26145 25752 26145 25755 26145 25753 590 25755 590 25754 590 25754 26146 25755 26146 25756 26146 25754 590 25756 590 25757 590 25757 26147 25756 26147 25758 26147 25757 590 25758 590 25760 590 25760 26148 25758 26148 25759 26148 25760 26149 25759 26149 25742 26149 25761 590 25777 590 25763 590 25781 26150 25779 26150 25762 26150 25781 590 25762 590 25766 590 25698 590 25702 590 25763 590 25763 590 25702 590 25764 590 25763 26151 25764 26151 25761 26151 25762 26152 25765 26152 25766 26152 25766 590 25765 590 25767 590 25766 590 25767 590 25768 590 25768 590 25767 590 25769 590 25768 590 25769 590 25702 590 25702 590 25769 590 25770 590 25702 26153 25770 26153 25764 26153 25775 590 25771 590 25763 590 25787 26154 25773 26154 25772 26154 25772 590 25773 590 25774 590 25775 26155 25763 26155 25776 26155 25776 590 25763 590 25777 590 25776 26156 25777 26156 25778 26156 25779 26157 25781 26157 25780 26157 25780 590 25781 590 25782 590 25780 590 25782 590 25786 590 25778 590 25777 590 25783 590 25783 590 25777 590 25784 590 25783 590 25784 590 25785 590 25785 590 25784 590 25786 590 25785 590 25786 590 25787 590 25787 590 25786 590 25782 590 25787 26158 25782 26158 25773 26158 25771 26159 25788 26159 25763 26159 25763 26160 25788 26160 25789 26160 25763 26161 25789 26161 25760 26161 25760 590 25789 590 25790 590 25760 590 25790 590 25791 590 25791 590 25790 590 25792 590 25791 590 25792 590 25793 590 25714 26162 25796 26162 25794 26162 25794 26163 25796 26163 25983 26163 25794 26164 25983 26164 25715 26164 25715 26165 25983 26165 25819 26165 25715 26166 25819 26166 25718 26166 25739 26167 25822 26167 25738 26167 25738 26168 25822 26168 25795 26168 25738 26169 25795 26169 25714 26169 25714 26170 25795 26170 25820 26170 25714 26171 25820 26171 25796 26171 25719 26172 25809 26172 25730 26172 25730 26173 25809 26173 25813 26173 25730 26174 25813 26174 25797 26174 25797 26175 25813 26175 25798 26175 25797 26176 25798 26176 25739 26176 25739 26177 25798 26177 25799 26177 25739 26178 25799 26178 25822 26178 25819 26179 25818 26179 25718 26179 25718 26180 25818 26180 25816 26180 25718 26181 25816 26181 25723 26181 25723 26182 25816 26182 25815 26182 25723 26183 25815 26183 25722 26183 25722 26184 25815 26184 25800 26184 25722 26185 25800 26185 25801 26185 25801 26186 25800 26186 25814 26186 25801 26187 25814 26187 25719 26187 25719 26188 25814 26188 25811 26188 25719 26189 25811 26189 25809 26189 26343 26190 26036 26190 25802 26190 25803 960 25943 960 25804 960 25805 960 25806 960 26034 960 25902 960 25850 960 25988 960 25807 960 25826 960 25829 960 26037 960 25808 960 26036 960 25810 26191 25812 26191 25813 26191 25813 960 25809 960 25810 960 25810 960 25809 960 25811 960 25810 26192 25811 26192 26298 26192 26298 960 25811 960 26296 960 25821 26193 25799 26193 25812 26193 25812 26194 25799 26194 25798 26194 25812 26195 25798 26195 25813 26195 25811 960 25814 960 26296 960 26296 960 25814 960 25800 960 26296 960 25800 960 26345 960 26345 26196 25800 26196 25815 26196 26345 960 25815 960 26346 960 26346 26197 25815 26197 25816 26197 26346 960 25816 960 25817 960 25817 26198 25816 26198 25818 26198 25817 960 25818 960 26348 960 26348 26199 25818 26199 25819 26199 26348 26200 25819 26200 25984 26200 25984 26201 25819 26201 25983 26201 25796 26202 25820 26202 25904 26202 25904 960 25820 960 25795 960 25904 960 25795 960 25821 960 25821 26203 25795 26203 25822 26203 25821 26204 25822 26204 25799 26204 26106 26205 25833 26205 26107 26205 26107 26206 25833 26206 25887 26206 26107 26207 25887 26207 26108 26207 25830 960 26041 960 25831 960 25808 960 25823 960 26036 960 26036 26208 25823 26208 25824 26208 26036 960 25824 960 25802 960 25802 960 25824 960 25825 960 25802 960 25825 960 26043 960 25837 26209 25827 26209 25836 26209 25836 960 25827 960 25826 960 25826 960 25827 960 25828 960 25826 960 25828 960 25829 960 25830 960 25831 960 26322 960 26322 26210 25831 26210 25832 26210 26322 960 25832 960 25833 960 25833 960 25832 960 25834 960 25833 26211 25834 26211 25887 26211 25887 26212 25834 26212 25835 26212 25887 26213 25835 26213 25882 26213 25839 960 25881 960 25883 960 25836 26214 25838 26214 25837 26214 25837 26215 25838 26215 25839 26215 25837 960 25839 960 25840 960 25840 26216 25839 26216 25883 26216 25864 960 25841 960 25842 960 25842 26217 25841 26217 25843 26217 25893 960 25844 960 25846 960 25846 26218 25844 26218 25845 26218 25846 26219 25845 26219 25847 26219 25847 960 25845 960 25848 960 25847 26220 25848 26220 25849 26220 25849 960 25848 960 25851 960 25849 26221 25851 26221 25850 26221 25850 960 25851 960 25852 960 25850 960 25852 960 25988 960 25853 960 26017 960 25854 960 25854 960 26017 960 26015 960 25854 960 26015 960 26013 960 26014 960 26145 960 26012 960 26012 26222 26145 26222 26146 26222 26012 960 26146 960 25855 960 25855 960 26146 960 25860 960 25852 26223 25856 26223 25988 26223 25988 26224 25856 26224 25857 26224 25988 26225 25857 26225 26008 26225 26008 26226 25857 26226 25858 26226 26008 960 25858 960 25859 960 25859 26227 25858 26227 25860 26227 25859 960 25860 960 26150 960 26150 960 25860 960 26146 960 25861 960 25842 960 25862 960 25862 960 25842 960 25932 960 25862 960 25932 960 25872 960 25861 960 25863 960 25842 960 25842 960 25863 960 26019 960 25842 960 26019 960 25864 960 25864 960 26019 960 26017 960 25864 960 26017 960 25865 960 25865 960 26017 960 25853 960 25866 26228 25867 26228 25869 26228 25867 960 25868 960 25869 960 25869 960 25868 960 25870 960 25869 960 25870 960 25932 960 25932 26229 25870 26229 25871 26229 25932 26230 25871 26230 25872 26230 25863 960 25873 960 26019 960 26019 26231 25873 26231 25874 26231 26019 26232 25874 26232 26020 26232 25875 960 26354 960 25876 960 25876 26233 26354 26233 26353 26233 25876 960 26353 960 26021 960 25921 26234 25922 26234 25878 26234 25878 26235 25922 26235 25877 26235 25878 960 25877 960 25879 960 25879 960 25877 960 26022 960 25880 26236 25887 26236 25881 26236 25881 26237 25887 26237 25882 26237 25881 26238 25882 26238 25883 26238 25884 960 25964 960 25885 960 25885 960 25964 960 25887 960 25885 26239 25887 26239 25886 26239 25886 26240 25887 26240 25880 26240 25955 26241 25913 26241 25888 26241 25888 960 25889 960 25955 960 25955 26242 25889 26242 25890 26242 25955 960 25890 960 25829 960 25829 960 25890 960 25891 960 25829 960 25891 960 25807 960 25932 26243 25897 26243 25911 26243 25892 26244 25842 26244 25893 26244 25893 26245 25842 26245 25843 26245 25893 26246 25843 26246 25844 26246 25892 26247 25894 26247 25842 26247 25842 26248 25894 26248 25895 26248 25842 960 25895 960 25932 960 25932 26249 25895 26249 25896 26249 25932 960 25896 960 25897 960 25898 960 25899 960 25992 960 25992 26250 25899 26250 25900 26250 25992 960 25900 960 25988 960 25988 960 25900 960 25901 960 25988 960 25901 960 25902 960 25821 960 25903 960 25904 960 25904 26251 25903 26251 25905 26251 25904 26252 25905 26252 25992 26252 25992 26253 25905 26253 25906 26253 25992 26254 25906 26254 25898 26254 25884 26255 25907 26255 25964 26255 25964 960 25907 960 25908 960 25964 960 25908 960 25812 960 25812 960 25908 960 25909 960 25812 26256 25909 26256 25821 26256 25821 26257 25909 26257 25910 26257 25821 960 25910 960 25903 960 25911 960 25912 960 25929 960 25929 26258 25912 26258 25913 26258 25929 960 25913 960 25914 960 25914 960 25913 960 25955 960 25914 960 25955 960 25915 960 25915 960 25955 960 25919 960 26034 960 25916 960 25918 960 25918 960 25916 960 25917 960 25918 960 25917 960 25919 960 25923 26259 26033 26259 25920 26259 25920 960 26081 960 25925 960 25921 960 25866 960 25922 960 25922 960 25866 960 25869 960 25922 960 25869 960 26337 960 26337 26260 25869 26260 25935 26260 26337 26261 25935 26261 25928 26261 25923 960 25920 960 25924 960 25924 26262 25920 26262 25925 26262 25924 960 25925 960 25926 960 25926 26263 25925 26263 25927 26263 25926 960 25927 960 25928 960 25928 960 25927 960 26256 960 25928 960 26256 960 26337 960 25929 26264 25930 26264 25911 26264 25911 26265 25930 26265 25931 26265 25911 960 25931 960 25932 960 25932 26266 25931 26266 25933 26266 25932 960 25933 960 25869 960 25869 26267 25933 26267 25934 26267 25869 26268 25934 26268 25935 26268 25952 26269 25936 26269 25918 26269 25918 960 25936 960 25937 960 25918 960 25937 960 26034 960 26034 960 25937 960 25938 960 25938 26270 25939 26270 26034 26270 26034 26271 25939 26271 25940 26271 26034 26272 25940 26272 26035 26272 25941 960 25804 960 25942 960 25942 960 25804 960 25943 960 25942 960 25943 960 25944 960 25944 26273 25943 26273 25945 26273 25944 26274 25945 26274 25946 26274 25946 26275 25945 26275 25947 26275 25946 26276 25947 26276 25948 26276 25941 26277 25949 26277 25804 26277 25804 26278 25949 26278 25950 26278 25804 960 25950 960 25829 960 25829 26279 25950 26279 25951 26279 25919 960 25955 960 25918 960 25918 26280 25955 26280 25957 26280 25918 960 25957 960 25952 960 25951 26281 25953 26281 25829 26281 25829 26282 25953 26282 25954 26282 25829 26283 25954 26283 25955 26283 25955 26284 25954 26284 25956 26284 25955 960 25956 960 25957 960 25970 960 25958 960 25960 960 25960 26285 25958 26285 25959 26285 25960 26286 25959 26286 25981 26286 25981 26287 25959 26287 25961 26287 25981 26288 25961 26288 25982 26288 25962 960 25963 960 25964 960 25964 26289 25963 26289 25973 26289 25977 960 25965 960 25887 960 25887 26290 25965 26290 25966 26290 25887 960 25966 960 26108 960 26108 26291 25966 26291 25967 26291 26108 26292 25967 26292 25968 26292 25968 960 25967 960 25969 960 25968 26293 25969 26293 26110 26293 26110 960 25969 960 25971 960 26110 26294 25971 26294 25970 26294 25970 26295 25971 26295 25972 26295 25970 960 25972 960 25958 960 25973 960 25974 960 25964 960 25964 26296 25974 26296 25975 26296 25964 26297 25975 26297 25887 26297 25887 960 25975 960 25976 960 25887 26298 25976 26298 25977 26298 25978 26299 25979 26299 25810 26299 25810 26300 25979 26300 25980 26300 25810 26301 25980 26301 25812 26301 25812 960 25980 960 25981 960 25812 26302 25981 26302 25964 26302 25964 960 25981 960 25982 960 25964 26303 25982 26303 25962 26303 25983 960 25796 960 25984 960 25984 26304 25796 26304 25904 26304 25984 960 25904 960 25985 960 25985 26305 25904 26305 25992 26305 25985 960 25992 960 25997 960 25986 960 25987 960 25988 960 26003 26306 26008 26306 26001 26306 26005 960 25989 960 26006 960 25987 960 25990 960 25988 960 25988 26307 25990 26307 25991 26307 25988 26308 25991 26308 25992 26308 25992 960 25991 960 25993 960 25992 960 25993 960 25994 960 25994 960 25995 960 25992 960 25992 26309 25995 26309 25996 26309 25992 26310 25996 26310 25997 26310 25997 960 25996 960 25998 960 25997 26311 25998 26311 26349 26311 26349 26312 25998 26312 25999 26312 26349 26313 25999 26313 25989 26313 25989 960 25999 960 26000 960 25989 26314 26000 26314 26006 26314 26001 960 26002 960 26003 960 26003 26315 26002 26315 26005 26315 26003 26316 26005 26316 26004 26316 26004 26317 26005 26317 26006 26317 26003 960 26007 960 26008 960 26008 26318 26007 26318 26009 26318 26008 26319 26009 26319 25988 26319 25988 26320 26009 26320 26010 26320 25988 26321 26010 26321 25986 26321 26269 26322 26011 26322 26015 26322 26015 960 26011 960 26140 960 26015 26323 26140 26323 26142 26323 26012 26324 26013 26324 26014 26324 26014 26325 26013 26325 26015 26325 26014 26326 26015 26326 26143 26326 26143 26327 26015 26327 26142 26327 26269 960 26015 960 26352 960 26352 960 26015 960 26017 960 26352 26328 26017 26328 26016 26328 26016 26329 26017 26329 26018 26329 26018 960 26017 960 26019 960 26018 960 26019 960 26353 960 26353 960 26019 960 26020 960 26353 26330 26020 26330 26021 26330 25875 960 26022 960 26354 960 26354 960 26022 960 25877 960 26354 26331 25877 26331 26023 26331 26023 960 25877 960 26024 960 26023 26332 26024 26332 26355 26332 25806 960 26064 960 26034 960 26034 26333 26064 26333 26062 26333 26034 960 26062 960 25916 960 25916 26334 26062 26334 26066 26334 25916 960 26066 960 26025 960 26025 26335 26066 26335 26026 26335 26025 960 26026 960 26027 960 26027 26336 26026 26336 26068 26336 26027 960 26068 960 26029 960 26029 26337 26068 26337 26028 26337 26029 960 26028 960 26030 960 26030 960 26028 960 26031 960 26030 960 26031 960 26033 960 26033 26338 26031 26338 26032 26338 26033 26339 26032 26339 25920 26339 25947 26340 26331 26340 26334 26340 26051 960 25805 960 26334 960 26334 960 25805 960 26034 960 26334 960 26034 960 25947 960 25947 26341 26034 26341 26035 26341 25947 26342 26035 26342 25948 26342 26343 960 25803 960 26036 960 26036 960 25803 960 25804 960 26036 960 25804 960 26037 960 26037 960 25804 960 25829 960 26037 960 25829 960 26038 960 26038 960 25829 960 25828 960 26045 960 26039 960 25802 960 25802 26343 26039 26343 26040 26343 25802 960 26040 960 26343 960 26041 960 25830 960 26043 960 26043 960 25830 960 26042 960 26043 26344 26042 26344 25802 26344 25802 960 26042 960 26044 960 25802 960 26044 960 26045 960 26281 590 26046 590 26282 590 26282 590 26046 590 26166 590 26282 590 26166 590 26273 590 26273 26345 26166 26345 26164 26345 26273 590 26164 590 26274 590 26274 590 26164 590 26170 590 26274 26346 26170 26346 26275 26346 26275 26347 26170 26347 26047 26347 26275 26348 26047 26348 26276 26348 26276 590 26047 590 26048 590 26276 590 26048 590 26277 590 26150 26349 26049 26349 26149 26349 26124 26350 26125 26350 26128 26350 26110 26351 26102 26351 26109 26351 26052 26352 26181 26352 26050 26352 26050 26353 26181 26353 26061 26353 26050 26354 26061 26354 26051 26354 26052 26355 26053 26355 26181 26355 26181 26356 26053 26356 26054 26356 26181 26357 26054 26357 26182 26357 26180 26358 26055 26358 26059 26358 26059 26359 26055 26359 26056 26359 26059 26360 26056 26360 26057 26360 26057 26361 26058 26361 26059 26361 26059 26362 26058 26362 26060 26362 26059 26363 26060 26363 26215 26363 26063 26364 25806 26364 26061 26364 26061 26365 25806 26365 25805 26365 26061 26366 25805 26366 26051 26366 26065 26367 26062 26367 26063 26367 26063 26368 26062 26368 26064 26368 26063 26369 26064 26369 25806 26369 26069 26370 26026 26370 26065 26370 26065 26371 26026 26371 26066 26371 26065 26372 26066 26372 26062 26372 26079 26373 26031 26373 26067 26373 26067 26374 26031 26374 26028 26374 26067 26375 26028 26375 26069 26375 26069 26376 26028 26376 26068 26376 26069 26377 26068 26377 26026 26377 26192 26378 26076 26378 26070 26378 26071 26379 26191 26379 26072 26379 26071 26380 26072 26380 26073 26380 26222 26381 26074 26381 26072 26381 26072 26382 26074 26382 26075 26382 26072 26383 26075 26383 26073 26383 26076 26384 26077 26384 26070 26384 26070 26385 26077 26385 26078 26385 26070 26386 26078 26386 26079 26386 26079 26387 26078 26387 26080 26387 26079 26388 26080 26388 26081 26388 26081 26389 25920 26389 26079 26389 26079 26390 25920 26390 26032 26390 26079 26391 26032 26391 26031 26391 26085 26392 26082 26392 26222 26392 26222 26393 26082 26393 26083 26393 26222 26394 26083 26394 26074 26394 26216 26395 25634 26395 26219 26395 26219 26396 25634 26396 25636 26396 26219 26397 25636 26397 26084 26397 26084 26398 25636 26398 26085 26398 26084 26399 26085 26399 26221 26399 26221 26400 26085 26400 26222 26400 26060 26401 26086 26401 26215 26401 26215 26402 26086 26402 26087 26402 26215 26403 26087 26403 26216 26403 26216 26404 26087 26404 26088 26404 26216 26405 26088 26405 25634 26405 26091 26406 26190 26406 26090 26406 26090 26407 26190 26407 26089 26407 26090 26408 26089 26408 25978 26408 26091 26409 26092 26409 26190 26409 26190 26410 26092 26410 26093 26410 26190 26411 26093 26411 26094 26411 26095 26412 26096 26412 26243 26412 26243 26413 26096 26413 26097 26413 26243 26414 26097 26414 26098 26414 26098 26415 26099 26415 26243 26415 26243 26416 26099 26416 26100 26416 26243 26417 26100 26417 26101 26417 26105 26418 25980 26418 26089 26418 26089 26419 25980 26419 25979 26419 26089 26420 25979 26420 25978 26420 26102 26421 26110 26421 26103 26421 26103 26422 26110 26422 25970 26422 26103 26423 25970 26423 26104 26423 26104 26424 25970 26424 25960 26424 26104 26425 25960 26425 26105 26425 26105 26426 25960 26426 25981 26426 26105 26427 25981 26427 25980 26427 26106 26428 26107 26428 26120 26428 26120 26429 26107 26429 26108 26429 26120 26430 26108 26430 26109 26430 26109 26431 26108 26431 25968 26431 26109 26432 25968 26432 26110 26432 26111 26433 26112 26433 26173 26433 26113 26434 26171 26434 26172 26434 26113 26435 26172 26435 26116 26435 26122 26436 26114 26436 26172 26436 26172 26437 26114 26437 26115 26437 26172 26438 26115 26438 26116 26438 26112 26439 26117 26439 26173 26439 26173 26440 26117 26440 26118 26440 26173 26441 26118 26441 26120 26441 26120 26442 26118 26442 26119 26442 26120 26443 26119 26443 26106 26443 26123 26444 25642 26444 26122 26444 26122 26445 25642 26445 26121 26445 26122 26446 26121 26446 26114 26446 26122 26447 26206 26447 26123 26447 26123 26448 26206 26448 26205 26448 26123 26449 26205 26449 25640 26449 25640 26450 26205 26450 26124 26450 26124 26451 26205 26451 26204 26451 26124 26452 26204 26452 26125 26452 26100 26453 26126 26453 26101 26453 26101 26454 26126 26454 26127 26454 26101 26455 26127 26455 26128 26455 26128 26456 26127 26456 25639 26456 26128 26457 25639 26457 26124 26457 26130 26458 26201 26458 26129 26458 26129 26459 26201 26459 26141 26459 26129 26460 26141 26460 26140 26460 26130 26461 26131 26461 26201 26461 26201 26462 26131 26462 26132 26462 26201 26463 26132 26463 26133 26463 26202 26464 26134 26465 26138 26466 26138 26467 26134 26467 26135 26467 26138 26468 26135 26468 26136 26468 26136 26469 26137 26469 26138 26469 26138 26470 26137 26470 26167 26470 26138 26471 26167 26471 26139 26471 26140 26472 26141 26472 26142 26472 26142 26473 26141 26473 26144 26473 26142 26474 26144 26474 26143 26474 26143 26475 26144 26475 26014 26475 26014 26476 26144 26476 26147 26476 26014 26477 26147 26477 26145 26477 26049 26478 26150 26478 26147 26478 26147 26479 26150 26479 26146 26479 26147 26480 26146 26480 26145 26480 26002 26481 26001 26481 26148 26481 26148 26482 26001 26482 26008 26482 26148 26483 26008 26483 26149 26483 26149 26484 26008 26484 25859 26484 26149 26485 25859 26485 26150 26485 26151 26486 26152 26486 26184 26486 26153 26487 26154 26487 26183 26487 26153 26488 26183 26488 26155 26488 26160 26489 26162 26489 26183 26489 26183 26490 26162 26491 26156 26492 26183 26493 26156 26493 26155 26493 26152 26494 26157 26494 26184 26494 26184 26495 26157 26495 26158 26495 26184 26496 26158 26496 26148 26496 26148 26497 26158 26497 26159 26497 26148 26498 26159 26498 26002 26498 26166 26499 26046 26499 26160 26499 26160 26500 26046 26500 26161 26500 26160 26501 26161 26501 26162 26501 26169 26502 26170 26502 26163 26502 26163 26503 26170 26503 26164 26503 26163 26504 26164 26504 26234 26504 26234 26505 26164 26505 26166 26505 26234 26506 26166 26506 26165 26506 26165 26507 26166 26507 26160 26507 26167 26508 26168 26508 26139 26508 26139 26509 26168 26509 26048 26509 26139 26510 26048 26510 26169 26510 26169 26511 26048 26511 26047 26511 26169 26512 26047 26512 26170 26512 26171 26513 26111 26513 26172 26513 26172 26514 26111 26514 26173 26514 26172 26515 26173 26515 26207 26515 26207 26516 26173 26516 26174 26516 26207 26517 26174 26517 26175 26517 26175 26518 26174 26518 26176 26518 26175 26519 26176 26519 26208 26519 26208 26520 26176 26520 26177 26520 26208 26521 26177 26521 26211 26521 26211 26522 26177 26522 26178 26522 26211 26523 26178 26523 26213 26523 26213 26524 26178 26524 26179 26524 26213 26525 26179 26525 26059 26525 26059 26526 26179 26526 26181 26526 26059 26527 26181 26527 26180 26527 26180 26528 26181 26528 26182 26528 26154 26529 26151 26529 26183 26529 26183 26530 26151 26530 26184 26530 26183 26531 26184 26531 26236 26531 26236 26532 26184 26532 26185 26532 26236 26533 26185 26533 26238 26533 26238 26534 26185 26534 26186 26534 26238 26535 26186 26535 26239 26535 26239 26536 26186 26536 26187 26536 26239 26537 26187 26537 26241 26537 26241 26538 26187 26538 26188 26538 26241 26539 26188 26539 26242 26539 26242 26540 26188 26540 26189 26540 26242 26541 26189 26541 26243 26541 26243 26542 26189 26542 26190 26542 26243 26543 26190 26543 26095 26543 26095 26544 26190 26544 26094 26544 26191 26545 26192 26545 26072 26545 26072 26546 26192 26546 26070 26546 26072 26547 26070 26547 26193 26547 26193 26548 26070 26548 26194 26548 26193 26549 26194 26549 26195 26549 26195 26550 26194 26550 26196 26550 26195 26551 26196 26551 26197 26551 26197 26552 26196 26552 26198 26552 26197 26553 26198 26553 26228 26553 26228 26554 26198 26554 26199 26554 26228 26555 26199 26555 26229 26555 26229 26556 26199 26556 26200 26556 26229 26557 26200 26557 26138 26557 26138 26558 26200 26558 26201 26558 26138 26559 26201 26559 26202 26559 26202 26560 26201 26560 26133 26560 26125 26561 26204 26561 26203 26561 26203 960 26204 960 26205 960 26203 960 26205 960 26303 960 26303 960 26205 960 26206 960 26303 26562 26206 26562 26314 26562 26314 960 26206 960 26122 960 26314 960 26122 960 26319 960 26319 960 26122 960 26172 960 26319 960 26172 960 26341 960 26341 26563 26172 26563 26207 26563 26341 960 26207 960 26342 960 26342 960 26207 960 26175 960 26342 26564 26175 26564 26209 26564 26209 960 26175 960 26208 960 26209 960 26208 960 26210 960 26210 960 26208 960 26211 960 26210 26565 26211 26565 26339 26565 26339 960 26211 960 26213 960 26339 26566 26213 26566 26212 26566 26212 960 26213 960 26059 960 26212 960 26059 960 26214 960 26214 960 26059 960 26215 960 26214 26567 26215 26567 26247 26567 26247 26568 26215 26568 26216 26568 26247 960 26216 960 26217 960 26217 960 26216 960 26219 960 26217 960 26219 960 26218 960 26218 960 26219 960 26084 960 26218 960 26084 960 26220 960 26220 960 26084 960 26221 960 26220 960 26221 960 26250 960 26250 26569 26221 26569 26222 26569 26250 26570 26222 26570 26336 26570 26336 960 26222 960 26072 960 26336 960 26072 960 26223 960 26223 960 26072 960 26193 960 26223 960 26193 960 26224 960 26224 960 26193 960 26195 960 26224 26571 26195 26571 26225 26571 26225 960 26195 960 26197 960 26225 960 26197 960 26226 960 26226 960 26197 960 26228 960 26226 960 26228 960 26227 960 26227 960 26228 960 26229 960 26227 960 26229 960 26230 960 26230 26572 26229 26572 26138 26572 26230 26573 26138 26573 26231 26573 26231 960 26138 960 26139 960 26231 26574 26139 26574 26232 26574 26232 960 26139 960 26169 960 26232 26575 26169 26575 26233 26575 26233 960 26169 960 26163 960 26233 26576 26163 26576 26272 26576 26272 960 26163 960 26234 960 26272 960 26234 960 26271 960 26271 960 26234 960 26165 960 26271 960 26165 960 26280 960 26280 960 26165 960 26160 960 26280 26577 26160 26577 26350 26577 26350 960 26160 960 26183 960 26350 960 26183 960 26235 960 26235 26578 26183 26578 26236 26578 26235 26579 26236 26579 26237 26579 26237 26580 26236 26580 26238 26580 26237 960 26238 960 26347 960 26347 960 26238 960 26239 960 26347 26581 26239 26581 26240 26581 26240 26582 26239 26582 26241 26582 26240 960 26241 960 26344 960 26344 960 26241 960 26242 960 26344 960 26242 960 26307 960 26307 26583 26242 26583 26243 26583 26307 960 26243 960 26305 960 26305 26584 26243 26584 26101 26584 26305 960 26101 960 26244 960 26244 26585 26101 26585 26128 26585 26244 26586 26128 26586 26203 26586 26203 26587 26128 26587 26125 26587 26245 26588 25810 26588 26298 26588 26246 26589 26011 26589 26269 26589 26214 26590 26247 26590 25633 26590 25633 26591 26247 26591 26217 26591 25633 26592 26217 26592 25635 26592 25635 26593 26217 26593 26218 26593 25635 26594 26218 26594 26248 26594 26248 26595 26218 26595 26220 26595 26248 26596 26220 26596 26249 26596 26249 26597 26220 26597 26250 26597 26249 26598 26250 26598 25637 26598 26251 26599 26259 26599 26336 26599 26255 26600 26256 26600 26252 26600 26252 26601 26256 26601 25927 26601 26252 26602 25927 26602 26253 26602 26253 26603 25927 26603 25925 26603 26251 26604 26336 26604 26254 26604 26255 26605 26257 26605 26256 26605 26256 26606 26257 26606 26258 26606 26256 26607 26258 26607 26335 26607 26259 26608 26260 26608 26336 26608 26336 26609 26260 26609 26261 26609 26336 26610 26261 26610 26250 26610 26250 26611 26261 26611 26262 26611 26250 26612 26262 26612 25637 26612 26263 26613 26264 26613 26352 26613 26263 26614 26352 26614 26351 26614 26279 26615 26265 26615 26230 26615 26230 26616 26265 26616 26266 26616 26230 26617 26266 26617 26351 26617 26264 26618 26267 26618 26352 26618 26352 26619 26267 26619 26268 26619 26352 26620 26268 26620 26269 26620 26269 26621 26268 26621 26270 26621 26269 26622 26270 26622 26246 26622 26271 26623 26273 26623 26272 26623 26272 26624 26273 26624 26274 26624 26272 26625 26274 26625 26233 26625 26233 26626 26274 26626 26275 26626 26233 26627 26275 26627 26232 26627 26232 26628 26275 26628 26276 26628 26232 26629 26276 26629 26231 26629 26231 26630 26276 26630 26277 26630 26231 26631 26277 26631 26230 26631 26230 26632 26277 26632 26278 26632 26230 26633 26278 26633 26279 26633 26280 26634 26281 26634 26271 26634 26271 26635 26281 26635 26282 26635 26271 26636 26282 26636 26273 26636 25989 26637 26005 26637 26283 26637 26283 26638 26284 26638 25989 26638 25989 26639 26284 26639 26285 26639 25989 26640 26285 26640 26286 26640 26287 26641 26288 26641 26350 26641 26350 26642 26288 26642 26289 26642 26289 26643 26290 26643 26350 26643 26350 26644 26290 26644 26291 26644 26350 26645 26291 26645 26280 26645 26280 26646 26291 26646 26292 26646 26280 26647 26292 26647 26281 26647 26293 26648 26294 26648 26345 26648 26345 26649 26294 26649 26295 26649 26345 26650 26295 26650 26296 26650 26296 26651 26295 26651 26297 26651 26296 26652 26297 26652 26298 26652 26298 26653 26297 26653 26299 26653 26298 26654 26299 26654 26245 26654 26300 26655 26344 26655 26301 26655 26301 26656 26344 26656 26307 26656 26301 26657 26307 26657 26302 26657 26302 26658 26307 26658 26310 26658 26314 26659 25641 26659 26303 26659 26303 26660 25641 26660 26304 26660 26303 26661 26304 26661 26203 26661 26203 26662 26304 26662 25638 26662 26203 26663 25638 26663 26244 26663 26244 26664 25638 26664 26306 26664 26244 26665 26306 26665 26305 26665 26305 26666 26306 26666 26308 26666 26305 26667 26308 26667 26307 26667 26307 26668 26308 26668 26309 26668 26307 26669 26309 26669 26310 26669 26311 26670 26312 26670 26319 26670 26319 26671 26312 26671 26313 26671 26319 26672 26313 26672 26314 26672 26314 26673 26313 26673 26315 26673 26314 26674 26315 26674 25641 26674 26316 26675 26317 26675 26341 26675 26341 26676 26317 26676 26318 26676 26341 26677 26318 26677 26319 26677 26319 26678 26318 26678 26320 26678 26319 26679 26320 26679 26311 26679 25833 26680 26321 26680 26322 26680 26322 26681 26321 26681 26323 26681 26322 26682 26323 26682 25830 26682 25830 26683 26323 26683 26324 26683 25830 26684 26324 26684 26042 26684 26042 26685 26324 26685 26340 26685 26042 26686 26340 26687 26044 26688 26330 26689 26325 26689 26331 26689 26326 26690 26338 26690 26212 26690 26326 26691 26212 26691 26327 26691 25633 26692 25632 26692 26214 26692 26214 26693 25632 26693 26328 26693 26214 26694 26328 26694 26212 26694 26212 26695 26328 26695 26329 26695 26212 26696 26329 26696 26327 26696 26330 26697 26331 26697 26338 26697 26325 26698 26332 26698 26331 26698 26331 26699 26332 26699 26333 26699 26331 26700 26333 26700 26334 26700 26335 26701 26254 26701 26256 26701 26256 26702 26254 26702 26336 26702 26256 26703 26336 26703 26337 26703 26337 26704 26336 26704 26223 26704 26337 26705 26223 26705 25922 26705 25922 26706 26223 26706 26224 26706 25922 26707 26224 26707 25877 26707 26338 26708 26331 26708 26212 26708 26212 26709 26331 26709 25947 26709 26212 26710 25947 26710 26339 26710 25803 26711 26210 26711 25943 26711 25943 26712 26210 26712 26339 26712 25943 26713 26339 26713 25945 26713 25945 26714 26339 26714 25947 26714 26340 26715 26316 26715 26044 26715 26044 26716 26316 26716 26341 26716 26044 26717 26341 26717 26045 26717 26045 26718 26341 26718 26342 26718 26045 26719 26342 26719 26039 26719 26039 26720 26342 26720 26209 26720 26039 26721 26209 26721 26040 26721 26040 26722 26209 26722 26210 26722 26040 26723 26210 26723 26343 26723 26343 26724 26210 26724 25803 26724 26300 26725 26293 26725 26344 26725 26344 26726 26293 26726 26345 26726 26344 26727 26345 26727 26240 26727 26240 26728 26345 26728 26346 26728 26240 26729 26346 26729 26347 26729 25984 26730 26237 26730 26348 26730 26348 26731 26237 26731 26347 26731 26348 26732 26347 26732 25817 26732 25817 26733 26347 26733 26346 26733 26286 26734 26287 26734 25989 26734 25989 26735 26287 26735 26350 26735 25989 26736 26350 26736 26349 26736 26349 26737 26350 26737 26235 26737 26349 26738 26235 26738 25997 26738 25997 26739 26235 26739 26237 26739 25997 26740 26237 26740 25985 26740 25985 26741 26237 26741 25984 26741 26351 26742 26352 26742 26230 26742 26230 26743 26352 26743 26016 26743 26230 26744 26016 26744 26227 26744 26016 26745 26018 26745 26227 26745 26227 26746 26018 26746 26353 26746 26227 26747 26353 26747 26226 26747 26353 26748 26354 26748 26226 26748 26226 26749 26354 26749 26023 26749 26226 26750 26023 26750 26225 26750 26225 26751 26023 26751 26355 26751 26225 26752 26355 26752 26224 26752 26224 26753 26355 26753 26024 26753 26224 26754 26024 26754 25877 26754 26402 960 26357 960 26356 960 26356 960 26357 960 26358 960 26356 960 26358 960 26360 960 26360 26755 26358 26755 26359 26755 26360 26756 26359 26756 26361 26756 26361 960 26359 960 26362 960 26361 26757 26362 26757 26363 26757 26363 960 26362 960 26364 960 26363 960 26364 960 26365 960 26365 960 26364 960 26366 960 26365 960 26366 960 26367 960 26367 26758 26366 26758 26369 26758 26367 26759 26369 26759 26368 26759 26368 960 26369 960 26370 960 26368 960 26370 960 26372 960 26372 960 26370 960 26371 960 26372 960 26371 960 26373 960 26373 960 26371 960 26374 960 26373 960 26374 960 26375 960 26375 960 26374 960 26376 960 26375 960 26376 960 26377 960 26377 960 26376 960 26403 960 26377 960 26403 960 26404 960 26428 960 26379 960 26378 960 26378 26760 26379 26760 26381 26760 26378 26761 26381 26761 26380 26761 26380 960 26381 960 26382 960 26380 26762 26382 26762 26384 26762 26384 960 26382 960 26383 960 26384 26763 26383 26763 26385 26763 26385 960 26383 960 26386 960 26385 26764 26386 26764 26387 26764 26387 960 26386 960 26389 960 26387 26765 26389 26765 26388 26765 26388 26766 26389 26766 26391 26766 26388 26767 26391 26767 26390 26767 26390 960 26391 960 26392 960 26390 26768 26392 26768 26393 26768 26393 960 26392 960 26394 960 26393 960 26394 960 26395 960 26395 26769 26394 26769 26396 26769 26395 960 26396 960 26397 960 26397 26770 26396 26770 26398 26770 26397 960 26398 960 26399 960 26399 26771 26398 26771 26400 26771 26399 960 26400 960 26402 960 26402 960 26400 960 26401 960 26402 960 26401 960 26357 960 26403 26772 26405 26772 26404 26772 26404 960 26405 960 26406 960 26404 960 26406 960 26407 960 26407 26773 26406 26773 26408 26773 26407 26774 26408 26774 26410 26774 26410 960 26408 960 26409 960 26410 960 26409 960 26411 960 26411 26775 26409 26775 26412 26775 26411 960 26412 960 26413 960 26413 960 26412 960 26414 960 26413 960 26414 960 26415 960 26415 26776 26414 26776 26416 26776 26415 960 26416 960 26417 960 26417 26777 26416 26777 26418 26777 26417 26778 26418 26778 26420 26778 26420 26779 26418 26779 26419 26779 26420 960 26419 960 26421 960 26421 960 26419 960 26422 960 26421 26780 26422 26780 26423 26780 26423 26781 26422 26781 26425 26781 26423 26782 26425 26782 26424 26782 26424 26783 26425 26783 26426 26783 26424 960 26426 960 26427 960 26427 26784 26426 26784 26429 26784 26427 26785 26429 26785 26428 26785 26428 26786 26429 26786 26430 26786 26428 960 26430 960 26379 960 26508 26787 26431 26787 26432 26787 26432 26788 26431 26788 26433 26788 26432 26789 26433 26789 26435 26789 26435 26790 26433 26790 26434 26790 26435 26791 26434 26791 26436 26791 26436 26792 26434 26792 26437 26792 26436 26793 26437 26793 26438 26793 26438 26794 26437 26794 26440 26794 26438 26795 26440 26795 26439 26795 26439 26796 26440 26796 26441 26796 26439 26797 26441 26797 26442 26797 26442 26798 26441 26798 26443 26798 26442 26798 26443 26798 26444 26798 26444 26799 26443 26799 26446 26799 26444 26799 26446 26799 26445 26799 26445 26800 26446 26800 26447 26800 26445 26801 26447 26801 26448 26801 26448 26802 26447 26802 26450 26802 26448 26802 26450 26802 26449 26802 26449 26803 26450 26803 26451 26803 26449 26804 26451 26804 26452 26804 26452 26805 26451 26805 26453 26805 26452 26806 26453 26806 26454 26806 26454 26807 26453 26807 26456 26807 26454 26808 26456 26808 26455 26808 26455 26809 26456 26809 26458 26809 26455 26810 26458 26810 26457 26810 26457 26811 26458 26811 26459 26811 26457 26812 26459 26812 26460 26812 26460 26813 26459 26813 26462 26813 26460 26813 26462 26813 26461 26813 26461 26814 26462 26814 26464 26814 26461 26814 26464 26814 26463 26814 26463 26815 26464 26815 26466 26815 26463 26816 26466 26816 26465 26816 26465 26817 26466 26817 26468 26817 26465 26818 26468 26818 26467 26818 26467 26819 26468 26819 26470 26819 26467 26820 26470 26820 26469 26820 26469 26821 26470 26821 26472 26821 26469 26822 26472 26822 26471 26822 26471 26823 26472 26823 26473 26823 26471 26824 26473 26824 26474 26824 26474 26825 26473 26825 26475 26825 26474 26826 26475 26826 26476 26826 26476 26827 26475 26827 26478 26827 26476 26828 26478 26828 26477 26828 26477 26829 26478 26829 26479 26829 26477 26830 26479 26830 26480 26830 26480 26831 26479 26831 26482 26831 26480 26832 26482 26832 26481 26832 26481 26833 26482 26833 26484 26833 26481 26834 26484 26834 26483 26834 26483 26835 26484 26835 26485 26835 26483 26836 26485 26836 26486 26836 26486 26837 26485 26837 26487 26837 26486 26837 26487 26837 26489 26837 26489 26838 26487 26838 26488 26838 26489 26839 26488 26839 26490 26839 26490 26840 26488 26840 26491 26840 26490 26841 26491 26841 26492 26841 26492 26842 26491 26842 26493 26842 26492 26843 26493 26843 26494 26843 26494 26844 26493 26844 26495 26844 26494 26845 26495 26845 26496 26845 26496 26846 26495 26846 26498 26846 26496 26847 26498 26847 26497 26847 26497 26848 26498 26848 26499 26848 26497 26848 26499 26848 26500 26848 26500 26849 26499 26849 26501 26849 26500 26849 26501 26849 26502 26849 26502 26850 26501 26850 26503 26850 26502 26851 26503 26851 26504 26851 26504 26852 26503 26852 26505 26852 26504 26853 26505 26853 26506 26853 26506 26854 26505 26854 26507 26854 26506 26855 26507 26855 26508 26855 26508 26787 26507 26787 26431 26787 26509 26856 26641 26856 26630 26856 26630 26857 26641 26857 26643 26857 26630 26858 26643 26858 26631 26858 26637 26859 26510 26859 26630 26859 26630 960 26510 960 26511 960 26630 26860 26511 26860 26509 26860 26520 26861 26512 26861 26544 26861 26544 26862 26512 26862 26633 26862 26551 26863 26526 26863 26513 26863 26513 26864 26629 26864 26551 26864 26551 26865 26629 26865 26514 26865 26551 26866 26514 26866 26515 26866 26514 26867 26659 26867 26515 26867 26515 26868 26659 26868 26653 26868 26515 26869 26653 26869 26552 26869 26653 26870 26516 26870 26552 26870 26552 26871 26516 26871 26517 26871 26552 26872 26517 26872 26546 26872 26546 26873 26517 26873 26654 26873 26546 26874 26654 26874 26519 26874 26654 26875 26671 26875 26519 26875 26519 26876 26671 26876 26518 26876 26519 26877 26518 26877 26520 26877 26520 26878 26518 26878 26672 26878 26520 26879 26672 26879 26512 26879 26521 26880 26525 26880 26522 26880 26522 26881 26525 26881 26622 26881 26522 960 26622 960 26523 960 26624 960 26524 960 26622 960 26622 26882 26524 26882 26626 26882 26622 26883 26626 26883 26523 26883 26621 17963 26525 17963 26550 17963 26550 26884 26525 26884 26521 26884 26550 26885 26521 26885 26526 26885 26526 17963 26521 17963 26513 17963 26621 26886 26550 26886 26527 26886 26527 26887 26550 26887 26541 26887 26528 26888 26542 26888 26529 26888 26529 26889 26542 26889 26670 26889 26670 26890 26669 26890 26529 26890 26529 26891 26669 26891 26668 26891 26529 26892 26668 26892 26531 26892 26668 26893 26530 26893 26531 26893 26531 26894 26530 26894 26532 26894 26531 26895 26532 26895 26533 26895 26533 26896 26532 26896 26534 26896 26533 26897 26534 26897 26536 26897 26534 26898 26535 26898 26536 26898 26536 26899 26535 26899 26664 26899 26536 26900 26664 26900 26538 26900 26664 26901 26537 26901 26538 26901 26538 26902 26537 26902 26539 26902 26538 26903 26539 26903 26541 26903 26541 26904 26539 26904 26540 26904 26541 26905 26540 26905 26527 26905 26544 17940 26633 17940 26631 17940 26544 26906 26631 26906 26528 26906 26528 26907 26631 26907 26643 26907 26528 17940 26643 17940 26542 17940 26547 960 26520 960 26543 960 26543 26908 26520 26908 26544 26908 26543 960 26544 960 26571 960 26568 960 26552 960 26545 960 26545 26909 26552 26909 26546 26909 26545 960 26546 960 26547 960 26547 26910 26546 26910 26519 26910 26547 26911 26519 26911 26520 26911 26548 960 26538 960 26549 960 26549 26912 26538 26912 26541 26912 26549 960 26541 960 26589 960 26589 26913 26541 26913 26550 26913 26589 960 26550 960 26561 960 26561 960 26550 960 26526 960 26561 26914 26526 26914 26563 26914 26563 960 26526 960 26551 960 26563 26915 26551 26915 26568 26915 26568 26916 26551 26916 26515 26916 26568 960 26515 960 26552 960 26553 960 26531 960 26585 960 26585 960 26531 960 26533 960 26585 960 26533 960 26548 960 26548 26917 26533 26917 26536 26917 26548 26918 26536 26918 26538 26918 26571 960 26544 960 26581 960 26581 26919 26544 26919 26528 26919 26581 26920 26528 26920 26553 26920 26553 26921 26528 26921 26529 26921 26553 26922 26529 26922 26531 26922 26597 26923 26554 26923 26575 26923 26555 26924 26562 26924 26568 26924 26619 26925 26556 26925 26557 26925 26557 26926 26556 26926 26592 26926 26557 26927 26592 26927 26594 26927 26558 26928 26559 26928 26563 26928 26563 26929 26559 26929 26560 26929 26563 26930 26560 26930 26561 26930 26561 26931 26560 26931 26612 26931 26561 26932 26612 26932 26593 26932 26568 26933 26562 26933 26563 26933 26563 26934 26562 26934 26564 26934 26563 26935 26564 26935 26558 26935 26606 26936 26565 26936 26547 26936 26547 26937 26565 26937 26566 26937 26547 26938 26566 26938 26545 26938 26545 26939 26566 26939 26567 26939 26545 26940 26567 26940 26568 26940 26568 26941 26567 26941 26569 26941 26568 26942 26569 26942 26555 26942 26606 26943 26547 26943 26570 26943 26570 26944 26547 26944 26543 26944 26570 26945 26543 26945 26604 26945 26574 26946 26603 26946 26571 26946 26571 26947 26603 26947 26602 26947 26571 26948 26602 26948 26543 26948 26543 26949 26602 26949 26572 26949 26543 26950 26572 26950 26604 26950 26577 26951 26573 26951 26576 26951 26576 26952 26573 26952 26574 26952 26576 26953 26574 26953 26580 26953 26575 26954 26554 26954 26576 26954 26576 26955 26554 26955 26601 26955 26576 26956 26601 26956 26577 26956 26619 26957 26618 26957 26556 26957 26556 26958 26618 26958 26616 26958 26556 26959 26616 26959 26578 26959 26578 26960 26616 26960 26615 26960 26578 26961 26615 26961 26575 26961 26575 26962 26615 26962 26579 26962 26575 26963 26579 26963 26597 26963 26574 26964 26571 26964 26580 26964 26580 26965 26571 26965 26581 26965 26580 26965 26581 26965 26582 26965 26582 26966 26581 26966 26553 26966 26582 26967 26553 26967 26583 26967 26583 26968 26553 26968 26585 26968 26583 26969 26585 26969 26584 26969 26584 26970 26585 26970 26586 26970 26586 26971 26585 26971 26548 26971 26586 26972 26548 26972 26587 26972 26587 26973 26548 26973 26549 26973 26587 26974 26549 26974 26588 26974 26588 26975 26549 26975 26589 26975 26588 26976 26589 26976 26590 26976 26590 26977 26589 26977 26561 26977 26590 26978 26561 26978 26591 26978 26591 26979 26561 26979 26593 26979 26591 26980 26593 26980 26592 26980 26592 26981 26593 26981 26613 26981 26592 26982 26613 26982 26594 26982 26650 26983 26595 26983 26594 26983 26570 26984 26604 26984 26605 26984 26605 26985 26604 26985 26644 26985 26600 26986 26554 26986 26596 26986 26596 26987 26554 26987 26597 26987 26596 26988 26597 26988 26598 26988 26598 26989 26597 26989 26579 26989 26598 26990 26579 26990 26647 26990 26647 26991 26579 26991 26615 26991 26647 26992 26615 26992 26648 26992 26645 26993 26573 26993 26599 26993 26599 26994 26573 26994 26577 26994 26599 26995 26577 26995 26600 26995 26600 26996 26577 26996 26601 26996 26600 26997 26601 26997 26554 26997 26602 26998 26603 26998 26645 26998 26645 26999 26603 26999 26574 26999 26645 27000 26574 27000 26573 27000 26644 27001 26604 27001 26645 27001 26645 27002 26604 27002 26572 27002 26645 27003 26572 27003 26602 27003 26570 27004 26605 27004 26606 27004 26606 27005 26605 27005 26657 27005 26606 27006 26657 27006 26565 27006 26565 27007 26657 27007 26656 27007 26565 27008 26656 27008 26566 27008 26566 27009 26656 27009 26610 27009 26566 27010 26610 27010 26567 27010 26611 27011 26562 27011 26607 27011 26607 27012 26562 27012 26555 27012 26607 27013 26555 27013 26608 27013 26608 27014 26555 27014 26569 27014 26608 27015 26569 27015 26609 27015 26609 27016 26569 27016 26567 27016 26609 27017 26567 27017 26655 27017 26655 27018 26567 27018 26610 27018 26651 27019 26559 27019 26652 27019 26652 27020 26559 27020 26558 27020 26652 27021 26558 27021 26611 27021 26611 27022 26558 27022 26564 27022 26611 27023 26564 27023 26562 27023 26593 27024 26612 27024 26651 27024 26651 27025 26612 27025 26560 27025 26651 27026 26560 27026 26559 27026 26650 27027 26594 27027 26651 27027 26651 27028 26594 27028 26613 27028 26651 27029 26613 27029 26593 27029 26648 27030 26615 27030 26614 27030 26614 27031 26615 27031 26616 27031 26614 27032 26616 27032 26617 27032 26617 27033 26616 27033 26618 27033 26617 27034 26618 27034 26620 27034 26620 27035 26618 27035 26619 27035 26620 27036 26619 27036 26595 27036 26595 27037 26619 27037 26557 27037 26595 27038 26557 27038 26594 27038 26525 27039 26621 27039 26527 27039 26622 27040 26525 27040 27283 27040 27283 27041 27234 27041 26622 27041 26622 27042 27234 27042 26623 27042 26622 27043 26623 27043 26624 27043 26629 27044 26513 27044 26521 27044 26623 27045 27237 27045 26624 27045 26624 27046 27237 27046 27236 27046 26624 27047 27236 27047 26524 27047 26524 27048 27236 27048 26625 27048 26524 27049 26625 27049 26626 27049 26626 27050 26625 27050 27235 27050 26626 27051 27235 27051 26523 27051 26523 27052 27235 27052 26627 27052 26523 27053 26627 27053 26522 27053 26522 27054 26627 27054 26628 27054 26522 27055 26628 27055 26521 27055 26521 27056 26628 27056 26658 27056 26521 27057 26658 27057 26629 27057 26629 27058 26658 27058 26514 27058 26630 27059 26631 27059 26632 27059 26632 27060 26631 27060 26633 27060 26632 27061 26633 27061 26512 27061 26632 27062 27231 27062 26630 27062 26630 27063 27231 27063 26634 27063 26630 27064 26634 27064 26637 27064 26634 27065 26635 27065 26637 27065 26637 27066 26635 27066 26636 27066 26637 27067 26636 27067 26510 27067 26510 27068 26636 27068 26638 27068 26510 27069 26638 27069 26511 27069 26511 27070 26638 27070 27229 27070 26511 27071 27229 27071 26509 27071 26509 27072 27229 27072 26639 27072 26509 27073 26639 27073 26641 27073 26641 27074 26639 27074 26640 27074 26641 27075 26640 27075 26643 27075 26643 27076 26640 27076 26642 27076 26643 27077 26642 27077 26542 27077 26657 27078 26605 27078 26671 27078 26605 27079 26644 27079 26671 27079 26671 27080 26644 27080 26645 27080 26671 27081 26645 27081 26646 27081 26645 27082 26599 27082 26646 27082 26646 27083 26599 27083 26600 27083 26646 27084 26600 27084 26596 27084 26620 27085 26595 27085 26649 27085 26620 27086 26649 27086 26617 27086 26596 27087 26598 27087 26646 27087 26646 27088 26598 27088 26647 27088 26646 27089 26647 27089 27227 27089 27227 27090 26647 27090 26648 27090 27227 27091 26648 27091 26649 27091 26649 27092 26648 27092 26614 27092 26649 27093 26614 27093 26617 27093 26595 27094 26650 27094 26649 27094 26649 27095 26650 27095 26651 27095 26649 27096 26651 27096 26653 27096 26653 27097 26651 27097 26652 27097 26653 27098 26652 27098 26611 27098 26611 27099 26607 27099 26653 27099 26653 27100 26607 27100 26608 27100 26653 27101 26608 27101 26516 27101 26516 27102 26608 27102 26609 27102 26516 27103 26609 27103 26517 27103 26517 27104 26609 27104 26655 27104 26517 27105 26655 27105 26654 27105 26654 27106 26655 27106 26610 27106 26654 27107 26610 27107 26671 27107 26671 27108 26610 27108 26656 27108 26671 27109 26656 27109 26657 27109 26514 27110 26658 27110 26659 27110 26659 27111 26658 27111 26660 27111 26659 27112 26660 27112 26653 27112 26653 27113 26660 27113 26661 27113 26653 27114 26661 27114 26649 27114 26525 27115 26527 27115 27283 27115 27283 27116 26527 27116 26540 27116 27283 27117 26540 27117 26662 27117 26662 27118 26540 27118 26539 27118 26662 27119 26539 27119 26663 27119 26663 27120 26539 27120 26537 27120 26663 27121 26537 27121 26665 27121 26537 27122 26664 27122 26665 27122 26665 27123 26664 27123 26535 27123 26665 27124 26535 27124 27233 27124 26535 27125 26534 27125 27233 27125 27233 27126 26534 27126 26532 27126 27233 27127 26532 27127 26666 27127 26666 27128 26532 27128 26530 27128 26666 27129 26530 27129 26667 27129 26530 27130 26668 27130 26667 27130 26667 27131 26668 27131 26669 27131 26667 27132 26669 27132 26642 27132 26642 27133 26669 27133 26670 27133 26642 27134 26670 27134 26542 27134 26646 27135 27255 27135 26671 27135 26671 27136 27255 27136 27256 27136 26671 27137 27256 27137 26518 27137 26518 27138 27256 27138 26632 27138 26518 27139 26632 27139 26672 27139 26672 27140 26632 27140 26512 27140 26688 27141 26673 27141 26689 27141 26689 27142 26673 27142 26674 27142 26689 27143 26674 27143 26675 27143 26675 27144 26674 27144 26676 27144 26675 27145 26676 27145 27344 27145 27344 27146 26676 27146 26677 27146 27344 27147 26677 27147 27343 27147 27343 27148 26677 27148 26678 27148 27343 27149 26678 27149 27342 27149 27342 27150 26678 27150 27148 27150 27342 27151 27148 27151 26679 27151 26679 27152 27148 27152 26680 27152 26679 27153 26680 27153 26681 27153 26681 27154 26680 27154 27147 27154 26681 27155 27147 27155 27347 27155 27347 27156 27147 27156 27143 27156 27347 27157 27143 27157 26682 27157 26682 27158 27143 27158 27144 27158 26682 27159 27144 27159 27349 27159 27349 27160 27144 27160 27145 27160 27349 27161 27145 27161 26683 27161 26683 27162 27145 27162 26684 27162 26683 27163 26684 27163 27350 27163 27350 27164 26684 27164 27150 27164 27350 27165 27150 27165 26685 27165 26685 27166 27150 27166 26686 27166 26685 27167 26686 27167 27351 27167 27351 27168 26686 27168 26687 27168 27351 27169 26687 27169 27345 27169 27345 27170 26687 27170 26688 27170 27345 27171 26688 27171 26689 27171 26690 27172 27245 27172 27246 27172 26690 27173 27246 27173 26691 27173 26691 27174 27246 27174 26692 27174 26691 27175 26692 27175 26693 27175 26693 27176 26692 27176 27248 27176 26693 27177 27248 27177 26694 27177 26694 27178 27248 27178 26696 27178 26694 27179 26696 27179 26695 27179 26695 27180 26696 27180 27250 27180 26695 27181 27250 27181 26697 27181 26697 27182 27250 27182 27251 27182 26697 27183 27251 27183 27032 27183 27032 27184 27251 27184 27254 27184 27032 27185 27254 27185 26699 27185 27254 27186 26698 27186 26699 27186 26699 27187 26698 27187 27252 27187 26699 27188 27252 27188 27034 27188 27034 27189 27252 27189 26701 27189 27034 27190 26701 27190 26700 27190 26700 27191 26701 27191 26702 27191 26700 27192 26702 27192 27028 27192 27028 27193 26702 27193 27029 27193 27029 27194 26702 27194 27258 27194 27029 27194 27258 27194 26703 27194 26703 27195 27258 27195 27257 27195 26703 27196 27257 27196 26704 27196 27257 27197 26705 27197 26704 27197 26704 27198 26705 27198 27243 27198 26704 27199 27243 27199 26706 27199 26706 27200 27243 27200 27241 27200 26706 27201 27241 27201 27031 27201 27031 27202 27241 27202 26709 27202 26690 27203 27039 27203 27245 27203 27245 27204 27039 27204 27036 27204 27245 27205 27036 27205 26707 27205 26707 27206 27036 27206 27133 27206 26707 27207 27133 27207 26709 27207 26709 27208 27133 27208 26708 27208 26709 27209 26708 27209 27031 27209 27049 27210 27044 27210 27265 27210 27265 27211 27044 27211 26710 27211 26726 27212 26711 27212 26725 27212 26725 27213 26711 27213 26712 27213 26712 27178 26711 27178 27263 27178 26712 27179 27263 27179 26713 27179 26713 27181 27263 27181 27264 27181 26713 27181 27264 27181 27043 27181 27043 27214 27264 27214 26714 27214 27043 27215 26714 27215 26715 27215 26715 27216 26714 27216 27267 27216 26715 27217 27267 27217 26710 27217 26710 27218 27267 27218 27266 27218 26710 27219 27266 27219 27265 27219 27049 27220 27265 27220 27048 27220 27048 27221 27265 27221 26716 27221 27048 27222 26716 27222 27047 27222 27047 27223 26716 27223 26717 27223 27047 27224 26717 27224 26719 27224 26717 27225 26718 27225 26719 27225 26719 27226 26718 27226 27270 27226 26719 27227 27270 27227 26721 27227 27270 27228 26720 27228 26721 27228 26721 27229 26720 27229 26722 27229 26721 27230 26722 27230 26723 27230 26723 27231 26722 27231 26724 27231 26723 27231 26724 27231 26733 27231 26733 27160 26724 27160 27269 27160 26725 27232 27053 27232 26726 27232 26726 27233 27053 27233 26727 27233 26726 27234 26727 27234 27261 27234 27261 27235 26727 27235 26728 27235 27261 27236 26728 27236 26729 27236 26729 27237 26728 27237 27055 27237 26729 27238 27055 27238 26730 27238 26730 27239 27055 27239 26731 27239 26730 27240 26731 27240 27269 27240 27269 27241 26731 27241 26732 27241 27269 27160 26732 27160 26733 27160 26748 27242 26734 27242 27271 27242 27271 27243 26734 27243 27059 27243 27271 27244 27059 27244 26735 27244 26735 27245 27059 27245 27058 27245 26735 27246 27058 27246 27273 27246 27273 27181 27058 27181 26736 27181 27273 27181 26736 27181 27274 27181 27274 27247 26736 27247 26737 27247 27274 27248 26737 27248 27275 27248 27275 27249 26737 27249 26738 27249 27275 27250 26738 27250 26739 27250 26739 27251 26738 27251 27119 27251 26739 27252 27119 27252 27276 27252 26751 27253 26740 27253 27277 27253 27277 27254 26740 27254 26742 27254 27277 27255 26742 27255 26741 27255 26741 27256 26742 27256 26743 27256 26741 27256 26743 27256 27279 27256 27279 27257 26743 27257 27064 27257 27279 27258 27064 27258 27280 27258 27280 27259 27064 27259 26744 27259 27280 27260 26744 27260 26745 27260 26745 27261 26744 27261 27112 27261 26745 27262 27112 27262 26746 27262 26746 49 27112 49 26747 49 26746 27263 26747 27264 27281 27265 27281 27266 26747 27266 26749 27266 27281 27267 26749 27267 26748 27267 26748 27268 26749 27268 27061 27268 26748 27269 27061 27269 26734 27269 27276 27270 27119 27270 26750 27270 26750 27271 27119 27271 27062 27271 26750 27272 27062 27272 26751 27272 26751 27272 27062 27272 27063 27272 26751 27273 27063 27273 26740 27273 26752 27274 26753 27274 27070 27274 26760 27275 26762 27275 26754 27275 26760 27276 26754 27276 27066 27276 27066 27181 26754 27181 27282 27181 27066 27277 27282 27277 27067 27277 27067 27278 27282 27278 27286 27278 27067 27279 27286 27279 27069 27279 27069 27280 27286 27280 26755 27280 27069 27281 26755 27281 27070 27281 27070 27282 26755 27282 27288 27282 27070 27211 27288 27211 26752 27211 26753 27268 26752 27268 26756 27268 26756 27283 26752 27283 26757 27283 26756 27284 26757 27284 27078 27284 27078 27222 26757 27222 27077 27222 27077 27285 26757 27285 27294 27285 27077 27286 27294 27286 26758 27286 27294 27287 27295 27287 26758 27287 26758 27288 27295 27288 27299 27288 26758 27289 27299 27289 27080 27289 27299 27290 26759 27290 27080 27290 27080 27291 26759 27291 27313 27291 27080 27292 27313 27292 27082 27292 27082 27293 27313 27293 26766 27293 26760 27294 27072 27294 26762 27294 26762 27295 27072 27295 26761 27295 26762 27296 26761 27296 27285 27296 27285 27297 26761 27297 27074 27297 27285 27298 27074 27298 27284 27298 27284 27235 27074 27235 27075 27235 27284 27299 27075 27299 27289 27299 27289 27300 27075 27300 26763 27300 27289 27301 26763 27301 26765 27301 26765 27302 26763 27302 26764 27302 26765 27303 26764 27303 27291 27303 27291 27304 26764 27304 27083 27304 27291 27305 27083 27305 26766 27305 26766 27306 27083 27306 26767 27306 26766 27307 26767 27307 27082 27307 27186 27308 27302 27308 26768 27308 27186 27173 26768 27173 27185 27173 27185 27309 26768 27309 27226 27309 27185 27310 27226 27310 27183 27310 27183 27311 27226 27311 27403 27311 27183 27312 27403 27312 27087 27312 27087 27313 27403 27313 27307 27313 27087 27314 27307 27314 26769 27314 26769 27315 27307 27315 27325 27315 26769 27181 27325 27181 26770 27181 26770 27316 27325 27316 27306 27316 26770 27317 27306 27317 26771 27317 26771 27318 27306 27318 27305 27318 26771 27319 27305 27319 26772 27319 27305 27282 27319 27282 26772 27282 26772 27320 27319 27320 27321 27320 26772 27321 27321 27321 27090 27321 27090 27322 27321 27322 26773 27322 27090 27323 26773 27323 26774 27323 26774 27324 26773 27324 27091 27324 27091 27325 26773 27325 27323 27325 27091 27326 27323 27326 26775 27326 26775 27194 27323 27194 27309 27194 26775 27261 27309 27261 26776 27261 26776 27327 27309 27327 26777 27327 26776 27328 26777 27328 26778 27328 26777 27329 27308 27329 26778 27329 26778 27330 27308 27330 27301 27330 26778 27198 27301 27198 26781 27198 26781 27331 27301 27331 27300 27331 27186 27332 27093 27332 27302 27332 27302 27333 27093 27333 27096 27333 27302 27334 27096 27334 27303 27334 27303 27335 27096 27335 27095 27335 27303 27336 27095 27336 27304 27336 27304 27337 27095 27337 26779 27337 27304 27338 26779 27338 27300 27338 27300 27306 26779 27306 26780 27306 27300 27339 26780 27339 26781 27339 27114 18538 27388 18538 26782 18538 27114 18539 26782 18539 27111 18539 27111 27340 26782 27340 27386 27340 27111 27340 27386 27340 26783 27340 26783 27341 27386 27341 26784 27341 26784 27342 27386 27342 27390 27342 26784 27343 27390 27343 27106 27343 27106 27344 27390 27344 27394 27344 27106 27345 27394 27345 27104 27345 27104 27346 27394 27346 26785 27346 27104 27347 26785 27347 26786 27347 26786 27348 26785 27348 26787 27348 26786 27349 26787 27349 26788 27349 26788 27350 26787 27350 27396 27350 26788 27351 27396 27351 27101 27351 27101 27352 27396 27352 27312 27352 27101 18551 27312 18551 27100 18551 27100 27353 27312 27353 26789 27353 27100 27354 26789 27354 27444 27354 27262 18699 27051 18699 27050 18699 27134 18700 27037 18700 27244 18700 27244 18701 27037 18701 26790 18701 27134 27355 27244 27355 26791 27355 26791 27355 27244 27355 26792 27355 26791 27356 26792 27356 26793 27356 26792 27357 26794 27357 26793 27357 26793 27358 26794 27358 27363 27358 26793 27359 27363 27359 26795 27359 26795 18707 27363 18707 26796 18707 26795 18708 26796 18708 26797 18708 26797 18709 26796 18709 26798 18709 26797 18710 26798 18710 26799 18710 26799 27360 26798 27360 27045 27360 27045 27361 26798 27361 27259 27361 27045 18713 27259 18713 27050 18713 27050 18714 27259 18714 26800 18714 27050 18715 26800 18715 27262 18715 26801 27362 26802 27362 26803 27362 26803 960 26802 960 26896 960 26803 960 26896 960 27504 960 27504 960 26896 960 26804 960 27504 960 26804 960 27556 960 27556 960 26804 960 26805 960 27377 27363 27132 27363 27131 27363 27128 18400 27369 18400 26806 18400 27128 18399 26806 18399 27130 18399 27130 18401 26806 18401 27379 18401 27130 27364 27379 27364 27131 27364 27131 18403 27379 18403 26807 18403 27131 27365 26807 27365 27377 27365 27132 27366 27377 27366 27121 27366 27121 27367 27377 27367 27376 27367 27121 27368 27376 27368 27127 27368 27127 27369 27376 27369 26808 27369 27127 27370 26808 27370 27126 27370 27126 27371 26808 27371 27382 27371 27126 27372 27382 27372 27116 27372 27382 27373 27383 27373 27116 27373 27116 27374 27383 27374 26809 27374 27116 27375 26809 27375 27117 27375 27117 18412 26809 18412 26810 18412 27117 18413 26810 18413 26818 18413 26811 27376 26805 27376 27389 27376 27389 27377 26805 27377 26895 27377 27389 27378 26895 27378 27278 27378 26895 27379 26894 27379 27278 27379 27278 27380 26894 27380 26812 27380 27278 27381 26812 27381 26813 27381 26812 27382 26814 27382 26813 27382 26813 27383 26814 27383 26815 27383 26813 27384 26815 27384 26816 27384 26816 27385 26815 27385 26892 27385 26816 27386 26892 27386 27385 27386 27385 27387 26892 27387 26891 27387 27385 18568 26891 18568 26817 18568 26817 27388 26891 27388 26890 27388 26818 27389 26810 27389 27494 27389 27494 27390 26810 27390 26817 27390 27494 27391 26817 27391 26819 27391 26819 27392 26817 27392 26890 27392 26820 960 26819 960 26890 960 26820 960 26890 960 27496 960 26890 960 26889 960 27496 960 27496 960 26889 960 26821 960 27496 27393 26821 27393 27491 27393 27491 18535 26821 18535 26822 18535 27491 27394 26822 27394 27564 27394 27225 27395 26822 27395 27370 27395 27370 27396 26822 27396 26823 27396 27370 27397 26823 27397 27371 27397 26823 27398 26824 27398 27371 27398 27371 27399 26824 27399 26825 27399 27371 27400 26825 27400 27367 27400 27367 27401 26825 27401 26826 27401 27367 27402 26826 27402 27268 27402 27268 27403 26826 27403 27260 27403 27260 27404 26826 27404 26827 27404 27260 18690 26827 18690 26828 18690 26831 27405 26829 27405 26928 27405 26928 27406 26829 27406 26828 27406 26928 27407 26828 27407 26886 27407 26886 27408 26828 27408 26827 27408 26830 960 26831 960 27480 960 27480 960 26831 960 26926 960 27480 960 26926 960 26832 960 26832 27409 26926 27409 26833 27409 26832 960 26833 960 27481 960 27481 27410 26833 27410 26834 27410 27481 27411 26834 27411 27477 27411 27477 27412 26834 27412 26835 27412 27239 27413 26835 27413 26836 27413 27239 27414 26836 27414 27240 27414 27240 27415 26836 27415 26925 27415 27240 27416 26925 27416 26838 27416 26838 27417 26925 27417 26837 27417 26838 27418 26837 27418 27247 27418 27247 27419 26837 27419 26839 27419 27247 27420 26839 27420 27249 27420 27249 27421 26839 27421 26922 27421 27249 27422 26922 27422 27358 27422 26840 27423 26841 27423 26920 27423 26920 27424 26841 27424 27358 27424 26920 27425 27358 27425 26921 27425 26921 27426 27358 27426 26922 27426 27466 960 26911 960 26842 960 26842 960 26911 960 26910 960 26842 27427 26910 27427 26843 27427 26843 960 26910 960 26844 960 26843 960 26844 960 26845 960 26845 27428 26844 27428 26909 27428 27514 960 26840 960 27515 960 27515 18475 26840 18475 26846 18475 27515 960 26846 960 27470 960 27470 960 26846 960 26918 960 27470 960 26918 960 26847 960 26847 27429 26918 27429 26862 27429 26847 960 26862 960 27472 960 26848 27430 27137 27430 26857 27430 26861 18436 27355 18436 26849 18436 26861 18435 26849 18435 27142 18435 27142 27431 26849 27431 26850 27431 27142 27431 26850 27431 26851 27431 26851 27432 26850 27432 26852 27432 26851 27433 26852 27433 26854 27433 26854 27434 26852 27434 26853 27434 26854 27435 26853 27435 26855 27435 26855 27436 26853 27436 27352 27436 26855 27437 27352 27437 27138 27437 27138 27438 27352 27438 26856 27438 27138 27439 26856 27439 27135 27439 27135 27440 26856 27440 27356 27440 27135 27441 27356 27441 26857 27441 26857 18449 27356 18449 26858 18449 26857 27430 26858 27430 26848 27430 27472 27442 26862 27442 26859 27442 26859 27443 26862 27443 26860 27443 26859 27444 26860 27444 26861 27444 26861 18455 26860 18455 27355 18455 26860 27445 26862 27445 27346 27445 27346 27446 26862 27446 26916 27446 27346 27447 26916 27447 26864 27447 26916 27448 26863 27448 26864 27448 26864 27449 26863 27449 26870 27449 26864 27450 26870 27450 26865 27450 26911 27451 26871 27451 26866 27451 26866 27452 26871 27452 27339 27452 26866 27453 27339 27453 26867 27453 26867 27454 27339 27454 26868 27454 26867 27455 26868 27455 26914 27455 26914 27456 26868 27456 26865 27456 26914 27457 26865 27457 26869 27457 26869 27458 26865 27458 26870 27458 27001 18470 27336 18470 27524 18470 27524 27459 27336 27459 26871 27459 27524 27460 26871 27460 27466 27460 27466 27461 26871 27461 26911 27461 26872 27462 27160 27462 27159 27462 26873 18416 27170 18416 27329 18416 27329 18415 27170 18415 27327 18415 26873 18417 27329 18417 26874 18417 26874 27463 27329 27463 26875 27463 26874 18419 26875 18419 27158 18419 27158 27464 26875 27464 27332 27464 27158 27465 27332 27465 27159 27465 27159 27466 27332 27466 27331 27466 27159 27467 27331 27467 26872 27467 27160 27468 26872 27468 27162 27468 27162 27469 26872 27469 26876 27469 27162 27470 26876 27470 27163 27470 27163 27471 26876 27471 27335 27471 27163 27471 27335 27471 26877 27471 26877 18431 27335 18431 27336 18431 26877 18432 27336 18432 27001 18432 26845 27472 26909 27472 27169 27472 27169 27473 26909 27473 27326 27473 27169 27474 27326 27474 27170 27474 27170 27475 27326 27475 27327 27475 26878 27476 27324 27476 26879 27476 26879 27477 27324 27477 26880 27477 26879 27478 26880 27478 26904 27478 26904 27479 26880 27479 27322 27479 26904 18485 27322 18485 26881 18485 26881 27480 27322 27480 27320 27480 26881 27481 27320 27481 26905 27481 26905 27482 27320 27482 27318 27482 26905 27483 27318 27483 26882 27483 26882 27484 27318 27484 27317 27484 26882 27485 27317 27485 26883 27485 26883 27486 27317 27486 26884 27486 26883 27487 26884 27487 26908 27487 26908 27488 26884 27488 27326 27488 26908 27489 27326 27489 26909 27489 27595 27490 26885 27490 26886 27490 26886 27491 26827 27491 27595 27491 27595 27492 26827 27492 26826 27492 27595 27493 26826 27493 27594 27493 26826 27494 26825 27494 27594 27494 27594 27495 26825 27495 26824 27495 27594 27496 26824 27496 26887 27496 26824 27497 26823 27497 26887 27497 26887 27498 26823 27498 26822 27498 26887 27499 26822 27499 26888 27499 26822 18638 26821 18638 26888 18638 26888 18639 26821 18639 26889 18639 26888 18640 26889 18640 27590 18640 27590 18641 26889 18641 26890 18641 27590 27500 26890 27500 27589 27500 27589 27501 26890 27501 26891 27501 27589 18644 26891 18644 26893 18644 26891 27502 26892 27502 26893 27502 26893 27503 26892 27503 26815 27503 26893 27504 26815 27504 27586 27504 27586 27505 26815 27505 26814 27505 26814 27506 26812 27506 27586 27506 27586 27507 26812 27507 26894 27507 27586 27508 26894 27508 27584 27508 26894 27509 26895 27509 27584 27509 27584 27510 26895 27510 26805 27510 27584 27511 26805 27511 27583 27511 26805 27512 26804 27512 27583 27512 27583 27513 26804 27513 26896 27513 27583 27513 26896 27513 27581 27513 27581 27514 26896 27514 26802 27514 27581 27515 26802 27515 27579 27515 26802 27516 26897 27516 27579 27516 27579 27517 26897 27517 27437 27517 27579 27518 27437 27518 27577 27518 27437 27519 27438 27519 27577 27519 27577 27520 27438 27520 27439 27520 27577 27521 27439 27521 26898 27521 27439 27522 27440 27522 26898 27522 26898 27523 27440 27523 26899 27523 26898 27524 26899 27524 26900 27524 26899 27525 27442 27525 26900 27525 26900 27526 27442 27526 26901 27526 26900 27527 26901 27527 27575 27527 26901 18672 26902 18672 27575 18672 27575 18673 26902 18673 26903 18673 27575 18673 26903 18673 27574 18673 27574 18674 26903 18674 26929 18674 27574 18675 26929 18675 27573 18675 27573 27528 26929 27528 26878 27528 27573 18677 26878 18677 27611 18677 26878 27529 26879 27529 27611 27529 27611 27530 26879 27530 26904 27530 27611 27531 26904 27531 27610 27531 26904 27532 26881 27532 27610 27532 27610 27533 26881 27533 26905 27533 27610 27534 26905 27534 26906 27534 26905 27535 26882 27535 26906 27535 26906 27536 26882 27536 26883 27536 26906 27537 26883 27537 26907 27537 26883 27538 26908 27538 26907 27538 26907 27539 26908 27539 26909 27539 26907 27540 26909 27540 27607 27540 26909 18587 26844 18587 27607 18587 27607 18588 26844 18588 26910 18588 27607 18589 26910 18589 27606 18589 27606 18590 26910 18590 26911 18590 27606 27541 26911 27541 26912 27541 26912 27542 26911 27542 26866 27542 26912 18593 26866 18593 26913 18593 26913 27543 26866 27543 26867 27543 26867 27544 26914 27544 26913 27544 26913 27545 26914 27545 26869 27545 26913 27546 26869 27546 26915 27546 26869 27547 26870 27547 26915 27547 26915 27548 26870 27548 26863 27548 26915 27549 26863 27549 27604 27549 26863 27550 26916 27550 27604 27550 27604 27551 26916 27551 26862 27551 27604 27552 26862 27552 26917 27552 26862 27553 26918 27553 26917 27553 26917 27554 26918 27554 26846 27554 26917 27555 26846 27555 26919 27555 26919 27556 26846 27556 26840 27556 26919 27557 26840 27557 27601 27557 26840 27558 26920 27558 27601 27558 27601 27559 26920 27559 26921 27559 27601 27560 26921 27560 26923 27560 26921 27561 26922 27561 26923 27561 26923 27562 26922 27562 26839 27562 26923 27563 26839 27563 26924 27563 26839 27564 26837 27564 26924 27564 26924 27565 26837 27565 26925 27565 26924 27566 26925 27566 27600 27566 26925 27567 26836 27567 27600 27567 27600 27568 26836 27568 26835 27568 27600 27569 26835 27569 27597 27569 26835 18620 26834 18620 27597 18620 27597 18621 26834 18621 26833 18621 27597 18621 26833 18621 27596 18621 27596 18622 26833 18622 26926 18622 27596 18623 26926 18623 26927 18623 26927 27570 26926 27570 26831 27570 26927 18625 26831 18625 26885 18625 26885 27571 26831 27571 26928 27571 26885 27572 26928 27572 26886 27572 27460 960 27459 960 26878 960 26901 27573 27454 27573 26902 27573 26902 27574 27454 27574 27544 27574 26902 960 27544 960 26903 960 26903 27575 27544 27575 27460 27575 26903 960 27460 960 26929 960 26929 960 27460 960 26878 960 26930 18500 27084 18500 27086 18500 27068 18501 26940 18501 26933 18501 26933 18502 26940 18502 26931 18502 27068 27576 26933 27576 26932 27576 26932 27577 26933 27577 27287 27577 26932 27578 27287 27578 26935 27578 27287 27578 26934 27578 26935 27578 26935 27579 26934 27579 27316 27579 26935 27580 27316 27580 27173 27580 27173 18508 27316 18508 27315 18508 27173 18509 27315 18509 26936 18509 26936 18510 27315 18510 26937 18510 26936 18511 26937 18511 27176 18511 27176 27581 26937 27581 27175 27581 27175 27582 26937 27582 26938 27582 27175 18514 26938 18514 27086 18514 27086 18515 26938 18515 27310 18515 27086 18516 27310 18516 26930 18516 27454 18517 26901 18517 26939 18517 26939 27583 26901 27583 27292 27583 26939 27584 27292 27584 26940 27584 26940 27585 27292 27585 26931 27585 26941 27586 26942 27586 27206 27586 27206 27587 26942 27587 26943 27587 27206 27588 26943 27588 26944 27588 26944 18766 26943 18766 27362 18766 26944 18767 27362 18767 26945 18767 26945 27589 27362 27589 26946 27589 26945 27590 26946 27590 26947 27590 26947 27591 26946 27591 27361 27591 26947 27592 27361 27592 26948 27592 26948 27593 27361 27593 27360 27593 26948 27594 27360 27594 27204 27594 27204 27595 27360 27595 26949 27595 27204 27595 26949 27595 26950 27595 26950 18775 26949 18775 27359 18775 26950 18776 27359 18776 26951 18776 26951 18777 27359 18777 26952 18777 26951 18778 26952 18778 26953 18778 26953 18798 26952 18798 27366 18798 26953 18799 27366 18799 27207 18799 27207 27596 27366 27596 26954 27596 27207 19028 26954 19028 27208 19028 27208 27597 26954 27597 27364 27597 27208 27598 27364 27598 26941 27598 26941 27599 27364 27599 26942 27599 26972 18793 27354 18793 26955 18793 26955 27600 27354 27600 27180 27600 27354 27601 27424 27601 27180 27601 27180 18796 27424 18796 27400 18796 27180 18797 27400 18797 26956 18797 26956 18798 27400 18798 27401 18798 26956 18799 27401 18799 26958 18799 26958 27602 27401 27602 26957 27602 26958 27603 26957 27603 27178 27603 27178 27604 26957 27604 26959 27604 27178 27605 26959 27605 26960 27605 26960 19031 26959 19031 26961 19031 26961 27606 26959 27606 26962 27606 26961 18807 26962 18807 27141 18807 26962 18808 26963 18808 27141 18808 27141 19032 26963 19032 26964 19032 27141 19032 26964 19032 26965 19032 26965 18810 26964 18810 26967 18810 26965 18811 26967 18811 26966 18811 26966 19035 26967 19035 27353 19035 26966 19036 27353 19036 27139 19036 27139 18787 27353 18787 26968 18787 27139 18788 26968 18788 26969 18788 26969 18789 26968 18789 26970 18789 26969 18790 26970 18790 26971 18790 26971 27607 26970 27607 26972 27607 26971 27607 26972 27607 27199 27607 27199 18792 26972 18792 26955 18792 27177 27608 26973 27608 26974 27608 26974 27609 26973 27609 27429 27609 26974 27610 27429 27610 27171 27610 27171 18719 27429 18719 26976 18719 27171 18720 26976 18720 26975 18720 26975 27611 26976 27611 26977 27611 26975 27612 26977 27612 26978 27612 26978 27613 26977 27613 27431 27613 26978 27614 27431 27614 26979 27614 26979 27615 27431 27615 26980 27615 26979 27616 26980 27616 27172 27616 27172 27617 26980 27617 26982 27617 27172 27617 26982 27617 26981 27617 26981 18728 26982 18728 26983 18728 26981 18729 26983 18729 27174 18729 27174 18730 26983 18730 27430 18730 27174 18731 27430 18731 26985 18731 26985 27618 27430 27618 26984 27618 26985 27618 26984 27618 26986 27618 26986 27619 26984 27619 26987 27619 26986 27620 26987 27620 26988 27620 26988 27621 26987 27621 27425 27621 26988 27622 27425 27622 27177 27622 27177 27623 27425 27623 26973 27623 27393 27624 27392 27624 26998 27624 26998 27625 27392 27625 26989 27625 26989 18757 27392 18757 27391 18757 26989 18758 27391 18758 27108 18758 27108 18759 27391 18759 26990 18759 27108 18760 26990 18760 27109 18760 27109 27626 26990 27626 27399 27626 27109 27626 27399 27626 27110 27626 27110 18762 27399 18762 26991 18762 26991 18739 27399 18739 27398 18739 26991 27627 27398 27627 27194 27627 27398 27628 27432 27628 27194 27628 27194 18742 27432 18742 26992 18742 27194 18743 26992 18743 26993 18743 26993 18732 26992 18732 26994 18732 26993 18733 26994 18733 27196 18733 27196 27629 26994 27629 27197 27629 27197 27630 26994 27630 27414 27630 27197 27631 27414 27631 26995 27631 26995 27632 27414 27632 27417 27632 26995 27633 27417 27633 26996 27633 26996 27634 27417 27634 27076 27634 27076 27635 27417 27635 27416 27635 27076 18750 27416 18750 26997 18750 27416 18751 27415 18751 26997 18751 26997 27636 27415 27636 27395 27636 26997 27636 27395 27636 27103 27636 27103 18753 27395 18753 27393 18753 27103 18754 27393 18754 27105 18754 27105 27637 27393 27637 26998 27637 26999 590 27220 590 27000 590 27202 590 27152 590 27146 590 27001 27638 27524 27638 27002 27638 27520 27639 27035 27639 27003 27639 27004 590 27057 590 27005 590 27132 590 27121 590 27129 590 26708 27640 27133 27640 27209 27640 27006 590 27191 590 27201 590 27030 27641 27008 27641 27007 27641 27008 27642 27030 27642 27009 27642 27009 27643 27030 27643 27042 27643 27009 590 27042 590 27198 590 27010 27644 27211 27644 27011 27644 27011 590 27211 590 27012 590 27013 590 27014 590 27015 590 27015 27645 27014 27645 27016 27645 27015 590 27016 590 27211 590 27211 590 27016 590 27017 590 27211 590 27017 590 27012 590 27092 27646 27190 27646 27018 27646 27203 590 27019 590 27073 590 27073 590 27019 590 27020 590 27073 590 27020 590 27021 590 27181 27647 27022 27647 27023 27647 27006 590 27201 590 27027 590 27023 590 27024 590 27181 590 27181 27648 27024 27648 27025 27648 27181 590 27025 590 27201 590 27201 590 27025 590 27026 590 27201 590 27026 590 27027 590 26700 590 27028 590 27033 590 27033 27649 27028 27649 27029 27649 27033 590 27029 590 27030 590 27030 27650 27029 27650 26703 27650 26703 590 26704 590 27030 590 27030 27651 26704 27651 26706 27651 27030 27652 26706 27652 27209 27652 27209 590 26706 590 27031 590 27209 590 27031 590 26708 590 27035 27653 26693 27653 26694 27653 26694 590 26695 590 27035 590 27035 590 26695 590 26697 590 27035 590 26697 590 27179 590 26697 590 27032 590 27179 590 27179 590 27032 590 26699 590 27179 590 26699 590 27033 590 27033 27654 26699 27654 27034 27654 27033 27655 27034 27655 26700 27655 27035 590 27520 590 26693 590 26693 27656 27520 27656 27038 27656 26693 590 27038 590 26691 590 27133 590 27036 590 27134 590 27134 27657 27036 27657 27037 27657 26691 27658 27038 27658 26690 27658 26690 27659 27038 27659 27507 27659 26690 590 27507 590 27039 590 27039 27660 27507 27660 27040 27660 27039 590 27040 590 27036 590 27036 27661 27040 27661 27041 27661 27036 590 27041 590 27037 590 26712 27662 26713 27662 27205 27662 27205 590 26713 590 27043 590 27205 27663 27043 27663 27042 27663 27042 27664 27043 27664 26715 27664 27049 27665 27046 27665 27044 27665 27044 27666 27046 27666 27042 27666 27044 27667 27042 27667 26710 27667 26710 590 27042 590 26715 590 27050 27668 27053 27668 26725 27668 26712 590 27205 590 26725 590 26725 27669 27205 27669 27045 27669 26725 27670 27045 27670 27050 27670 27005 590 27057 590 27056 590 26719 590 27129 590 27047 590 27047 27671 27129 27671 27046 27671 27047 590 27046 590 27048 590 27048 590 27046 590 27049 590 26733 590 27057 590 26723 590 26723 27672 27057 27672 27129 27672 26723 590 27129 590 26721 590 26721 27673 27129 27673 26719 27673 27050 27674 27051 27674 27053 27674 27053 27675 27051 27675 27052 27675 27053 590 27052 590 26727 590 26727 27676 27052 27676 27568 27676 26727 27677 27568 27677 26728 27677 26728 27678 27568 27678 27054 27678 26728 27679 27054 27679 27055 27679 27055 590 27054 590 27056 590 27055 590 27056 590 26731 590 26731 27680 27056 27680 27057 27680 26731 590 27057 590 26732 590 26732 590 27057 590 26733 590 26738 27681 26737 27681 27000 27681 26738 590 27000 590 27119 590 26737 27682 26736 27682 27000 27682 27000 27683 26736 27683 27058 27683 27000 590 27058 590 27060 590 27060 590 27058 590 27059 590 27059 590 26734 590 27060 590 27060 590 26734 590 27061 590 27060 590 27061 590 27107 590 27107 27684 27061 27684 26749 27684 27107 27685 26749 27685 26747 27685 27062 27686 27124 27686 27063 27686 27063 590 27124 590 27118 590 27112 590 26744 590 27113 590 27113 590 26744 590 27064 590 27113 27687 27064 27687 27559 27687 27559 590 27064 590 26743 590 27559 27688 26743 27688 27555 27688 27555 590 26743 590 26742 590 27555 27689 26742 27689 27118 27689 27118 27690 26742 27690 26740 27690 27118 590 26740 590 27063 590 26760 590 27066 590 27065 590 27065 590 27066 590 27067 590 27065 27691 27067 27691 26932 27691 26932 590 27067 590 27069 590 26932 590 27069 590 27068 590 27068 27692 27069 27692 27070 27692 27079 590 27071 590 26753 590 27070 27693 26753 27693 27068 27693 27068 27694 26753 27694 27071 27694 27068 27695 27071 27695 26940 27695 26940 590 27071 590 26939 590 27195 27696 27075 27696 27074 27696 26760 590 27065 590 27072 590 27072 590 27065 590 27073 590 27072 590 27073 590 26761 590 27013 590 27015 590 27021 590 27021 590 27015 590 27195 590 27021 590 27195 590 27073 590 27073 590 27195 590 27074 590 27073 27697 27074 27697 26761 27697 27195 27698 27197 27698 27075 27698 27075 27699 27197 27699 26995 27699 27075 590 26995 590 26763 590 26763 590 26995 590 26996 590 26763 590 26996 590 26764 590 26764 27700 26996 27700 27076 27700 26764 27701 27076 27702 27083 27703 26758 590 27081 590 27077 590 27077 590 27081 590 27548 590 27077 590 27548 590 27078 590 27078 27704 27548 27704 27079 27704 27078 590 27079 590 26756 590 26756 590 27079 590 26753 590 26758 27705 27080 27705 27081 27705 27081 27706 27080 27706 27082 27706 27081 27707 27082 27707 27102 27707 27102 590 27082 590 26767 590 27102 27708 26767 27708 27083 27708 27084 27709 27458 27709 27457 27709 27084 590 27457 590 27086 590 27094 590 27175 590 26781 590 27085 590 27091 590 27457 590 27457 27710 27091 27710 26775 27710 27457 27711 26775 27711 27086 27711 27086 27712 26775 27712 26776 27712 27086 590 26776 590 27175 590 27175 590 26776 590 26778 590 27175 27713 26778 27713 26781 27713 27087 27714 26769 27714 27165 27714 27165 27715 26769 27715 26770 27715 27165 590 26770 590 27088 590 26770 27716 26771 27716 27088 27716 27088 590 26771 590 26772 590 27088 590 26772 590 27089 590 27089 590 26772 590 27090 590 27089 27717 27090 27717 27085 27717 27085 27718 27090 27718 26774 27718 27085 27719 26774 27719 27091 27719 27092 590 27096 590 27187 590 27187 27720 27096 27720 27093 27720 27187 27721 27093 27721 27186 27721 26781 27722 26780 27722 27094 27722 27094 590 26780 590 26779 590 27094 590 26779 590 27092 590 27092 27723 26779 27723 27095 27723 27092 27724 27095 27724 27096 27724 27444 27725 27097 27725 27098 27725 27098 590 27099 590 27444 590 27444 27726 27099 27726 27081 27726 27444 590 27081 590 27100 590 27100 27727 27081 27727 27101 27727 27101 590 27081 590 27102 590 27101 27728 27102 27728 26788 27728 27083 590 27076 590 27102 590 27102 27729 27076 27729 26997 27729 27102 590 26997 590 26788 590 26788 27730 26997 27730 27103 27730 26788 590 27103 590 26786 590 26786 27731 27103 27731 27104 27731 27104 590 27103 590 27105 590 27104 27732 27105 27732 27106 27732 27106 590 27105 590 26998 590 27106 590 26998 590 26784 590 26784 590 26998 590 26989 590 26784 590 26989 590 27107 590 26989 27733 27108 27733 27107 27733 27107 27734 27108 27734 27109 27734 27107 590 27109 590 27060 590 27060 590 27109 590 27110 590 27114 590 27111 590 27107 590 27107 590 27111 590 26783 590 27107 27735 26783 27735 26784 27735 26747 590 27112 590 27107 590 27107 27736 27112 27736 27113 27736 27107 590 27113 590 27114 590 27114 27737 27113 27737 27115 27737 27114 590 27115 590 27499 590 27126 27738 27116 27738 27124 27738 27124 27739 27116 27739 27117 27739 27124 590 27117 590 27118 590 27118 27740 27117 27740 26818 27740 27118 27741 26818 27741 27494 27741 27220 27742 27123 27742 27000 27742 27000 27743 27123 27743 27124 27743 27000 590 27124 590 27119 590 27119 590 27124 590 27062 590 27223 590 27120 590 27121 590 27121 27744 27120 27744 27122 27744 27121 590 27122 590 27129 590 27123 590 27221 590 27124 590 27124 27745 27221 27745 27125 27745 27124 27746 27125 27746 27126 27746 27126 590 27125 590 27223 590 27126 27747 27223 27747 27127 27747 27127 590 27223 590 27121 590 27450 590 27128 590 27562 590 27562 590 27128 590 27004 590 27004 590 27128 590 27057 590 27057 27748 27128 27748 27130 27748 27057 590 27130 590 27129 590 27129 27749 27130 27749 27131 27749 27129 27750 27131 27750 27132 27750 27133 590 27134 590 27209 590 27209 27751 27134 27751 26791 27751 27209 27752 26791 27752 26793 27752 26795 590 26797 590 27205 590 27205 27753 26797 27753 26799 27753 27205 27754 26799 27754 27045 27754 27179 590 27135 590 27035 590 27035 27755 27135 27755 26857 27755 27035 590 26857 590 27003 590 27003 590 26857 590 27137 590 27003 27756 27137 27757 27136 27758 27136 27759 27137 27759 27476 27759 27141 27760 26855 27760 27179 27760 27179 27761 26855 27761 27138 27761 27179 27762 27138 27762 27135 27762 27139 590 26969 590 27142 590 27142 27763 26969 27763 27140 27763 27142 590 27140 590 26861 590 26861 27764 27140 27764 26859 27764 27141 27765 26965 27765 26855 27765 26855 27766 26965 27766 26966 27766 26855 27767 26966 27767 26854 27767 26854 27768 26966 27768 27139 27768 26854 27769 27139 27769 26851 27769 26851 27770 27139 27770 27142 27770 26971 590 27199 590 27200 590 27143 590 27200 590 27144 590 27144 27771 27200 27771 27145 27771 27145 590 27200 590 26684 590 26684 590 27200 590 27146 590 26684 590 27146 590 27150 590 27143 27772 27147 27772 27200 27772 27200 27773 27147 27773 27140 27773 27200 27774 27140 27774 26971 27774 26971 590 27140 590 26969 590 27147 27775 26680 27775 27140 27775 27140 27776 26680 27776 27148 27776 27140 27777 27148 27777 27522 27777 27522 27778 27148 27778 26678 27778 27522 27779 26678 27779 27149 27779 27149 27780 26678 27780 26677 27780 27149 590 26677 590 27151 590 26688 590 26687 590 27146 590 27146 27781 26687 27781 26686 27781 27146 27782 26686 27782 27150 27782 26677 27783 26676 27783 27151 27783 27151 590 26676 590 26674 590 27151 590 26674 590 26673 590 27152 590 27156 590 27146 590 27146 590 27156 590 27151 590 27146 27784 27151 27784 26688 27784 26688 590 27151 590 26673 590 27153 27785 27002 27785 27154 27785 27154 27786 27002 27786 27151 27786 27154 590 27151 590 27155 590 27155 27787 27151 27787 27156 27787 27161 590 27157 590 27159 590 27159 27788 27157 27788 27158 27788 27165 27789 26874 27789 27158 27789 27159 590 27160 590 27161 590 27161 590 27160 590 27162 590 27161 590 27162 590 27153 590 27153 590 27162 590 27163 590 27153 590 27163 590 27002 590 27002 27790 27163 27790 26877 27790 27002 27791 26877 27791 27001 27791 27164 590 27165 590 27166 590 27166 27792 27165 27792 27158 27792 27166 590 27158 590 27167 590 27167 590 27158 590 27157 590 27168 590 27169 590 27170 590 26874 5222 27165 5222 26873 5222 26873 590 27165 590 27088 590 26873 590 27088 590 27170 590 27170 27793 27088 27793 27531 27793 27170 590 27531 590 27168 590 26981 27794 27174 27794 27094 27794 26935 27795 27171 27795 26975 27795 26935 590 26975 590 26932 590 26932 27796 26975 27796 26978 27796 26932 27797 26978 27797 27065 27797 27065 27798 26978 27798 26979 27798 27065 590 26979 590 27172 590 27171 590 26935 590 26974 590 26974 27799 26935 27799 27173 27799 26974 590 27173 590 27177 590 27174 590 26985 590 27094 590 27094 27800 26985 27800 26986 27800 27094 590 26986 590 27175 590 27175 27801 26986 27801 26988 27801 27175 27802 26988 27802 27176 27802 27176 27803 26988 27803 27177 27803 27176 590 27177 590 26936 590 26936 590 27177 590 27173 590 26956 27804 26958 27804 27033 27804 26958 590 27178 590 27033 590 27033 590 27178 590 26960 590 27033 590 26960 590 27179 590 27179 27805 26960 27805 26961 27805 27179 27806 26961 27806 27141 27806 26955 27807 27180 27807 27181 27807 27180 590 26956 590 27181 590 27181 27808 26956 27808 27033 27808 27181 590 27033 590 27022 590 27022 27809 27033 27809 27030 27809 27022 590 27030 590 27182 590 27182 27810 27030 27810 27007 27810 27087 590 27165 590 27183 590 27183 590 27165 590 27164 590 27183 27811 27164 27811 27185 27811 27185 27812 27164 27812 27184 27812 27185 27813 27184 27813 27186 27813 27186 27814 27184 27814 27188 27814 27186 27815 27188 27815 27187 27815 27187 590 27188 590 27189 590 27187 27816 27189 27816 27192 27816 27190 590 27092 590 27191 590 27191 590 27092 590 27187 590 27191 590 27187 590 27201 590 27201 27817 27187 27817 27192 27817 27201 27818 27192 27818 27193 27818 26991 590 27194 590 27015 590 27015 27819 27194 27819 26993 27819 27015 27820 26993 27820 27195 27820 27195 27821 26993 27821 27196 27821 27195 27822 27196 27822 27197 27822 27217 590 27219 590 27046 590 27122 27823 27224 27823 27129 27823 27129 27824 27224 27824 27213 27824 27129 590 27213 590 27046 590 27046 27825 27213 27825 27215 27825 27046 27826 27215 27826 27217 27826 27198 590 27042 590 27010 590 27010 590 27042 590 27046 590 27010 590 27046 590 27211 590 27211 27827 27046 27827 27219 27827 27211 27828 27219 27828 27210 27828 27199 590 26955 590 27200 590 27200 27829 26955 27829 27181 27829 27200 590 27181 590 27146 590 27146 590 27181 590 27201 590 27146 590 27201 590 27202 590 27202 590 27201 590 27193 590 27018 27830 27203 27830 27092 27830 27092 27831 27203 27831 27073 27831 27092 27832 27073 27832 27094 27832 27094 590 27073 590 27065 590 27094 590 27065 590 26981 590 26981 590 27065 590 27172 590 27206 590 26944 590 27209 590 27030 590 27204 590 27042 590 27042 27833 27204 27833 26950 27833 27042 27834 26950 27834 26951 27834 26793 27835 26795 27835 27209 27835 27209 590 26795 590 27205 590 27209 590 27205 590 27206 590 27206 590 27205 590 26941 590 26951 27836 26953 27836 27042 27836 27042 27837 26953 27837 27207 27837 27042 27838 27207 27838 27205 27838 27205 27839 27207 27839 27208 27839 27205 27840 27208 27840 26941 27840 26944 590 26945 590 27209 590 27209 27841 26945 27841 26947 27841 27209 590 26947 590 27030 590 27030 27842 26947 27842 26948 27842 27030 27843 26948 27843 27204 27843 27210 27844 26999 27844 27211 27844 27211 590 26999 590 27000 590 27211 590 27000 590 27015 590 27015 590 27000 590 27060 590 27015 590 27060 590 26991 590 26991 590 27060 590 27110 590 27372 18739 27212 18739 27213 18739 27213 27845 27212 27845 27215 27845 27212 27846 27214 27846 27215 27846 27215 18742 27214 18742 27216 18742 27215 18743 27216 18743 27217 18743 27217 19035 27216 19035 27218 19035 27217 27847 27218 27847 27219 27847 27219 18735 27218 18735 27419 18735 27219 18735 27419 18735 27210 18735 27210 27848 27419 27848 27418 27848 27210 27848 27418 27848 26999 27848 26999 27849 27418 27849 27220 27849 27220 18748 27418 18748 27434 18748 27220 18750 27434 18750 27123 18750 27434 18751 27435 18751 27123 18751 27123 18752 27435 18752 27373 18752 27123 27850 27373 27850 27221 27850 27221 27851 27373 27851 27222 27851 27221 18754 27222 18754 27125 18754 27125 18755 27222 18755 27374 18755 27125 18756 27374 18756 27223 18756 27223 27852 27374 27852 27381 27852 27223 27853 27381 27853 27120 27853 27120 27854 27381 27854 27380 27854 27120 18760 27380 18760 27122 18760 27122 27626 27380 27626 27372 27626 27122 27626 27372 27626 27224 27626 27224 18762 27372 18762 27213 18762 27370 27855 27368 27855 27225 27855 27443 960 27445 960 27311 960 27403 960 27226 960 27404 960 26718 960 26717 960 27420 960 27255 960 26646 960 27242 960 27227 960 26649 960 27365 960 27365 27856 26649 27856 27238 27856 27256 960 27228 960 26632 960 26632 27857 27228 27857 27230 27857 26636 960 27423 960 26638 960 26638 960 27423 960 27408 960 26638 27858 27408 27858 27229 27858 26636 27859 26635 27859 27423 27859 27423 960 26635 960 26634 960 27423 960 26634 960 27230 960 27230 27860 26634 27860 27231 27860 27230 960 27231 960 26632 960 27427 27861 26666 27861 27404 27861 27404 27862 26666 27862 26667 27862 26667 960 26642 960 27404 960 27404 960 26642 960 26640 960 27404 27863 26640 27863 27408 27863 27408 960 26640 960 26639 960 27408 27864 26639 27864 27229 27864 26662 960 26663 960 27232 960 27232 960 26663 960 26665 960 27232 27865 26665 27865 27427 27865 27427 960 26665 960 27233 960 27427 27866 27233 27866 26666 27866 26623 960 27234 960 27413 960 27413 27867 27234 27867 27283 27867 27235 960 26625 960 27433 960 27433 27868 26625 27868 27236 27868 27433 960 27236 960 27412 960 27412 960 27236 960 27237 960 27420 960 26628 960 27433 960 27433 960 26628 960 26627 960 27433 27869 26627 27869 27235 27869 26649 27870 26661 27870 27238 27870 27238 960 26661 960 26660 960 27238 960 26660 960 27420 960 27420 960 26660 960 26658 960 27420 960 26658 960 26628 960 26790 27871 27239 27871 27240 27871 26707 960 26709 960 26792 960 26792 27872 26709 27872 27241 27872 26792 960 27241 960 27242 960 27242 27873 27241 27873 27243 27873 27242 960 27243 960 26705 960 26792 27874 27244 27874 26707 27874 26707 960 27244 960 26790 960 26707 960 26790 960 27245 960 27245 27875 26790 27875 27240 27875 27245 960 27240 960 27246 960 27246 27876 27240 27876 26838 27876 27246 960 26838 960 26692 960 26692 27877 26838 27877 27247 27877 26692 960 27247 960 27248 960 27248 27878 27247 27878 27249 27878 27248 27879 27249 27879 26696 27879 26696 960 27249 960 27250 960 27250 960 27249 960 27357 960 27250 27880 27357 27880 27251 27880 27230 960 27252 960 27253 960 27253 27881 27252 27881 26698 27881 27253 14067 26698 14067 27357 14067 27357 27882 26698 27882 27254 27882 27357 960 27254 960 27251 960 26705 960 27257 960 27242 960 27242 27883 27257 27883 27228 27883 27242 27884 27228 27884 27255 27884 27255 960 27228 960 27256 960 27257 27885 27258 27885 27228 27885 27228 27886 27258 27886 26702 27886 27228 960 26702 960 27230 960 27230 27887 26702 27887 26701 27887 27230 27888 26701 27888 27252 27888 26714 960 27264 960 27365 960 27365 960 27264 960 27259 960 26828 960 26829 960 27262 960 27260 27889 26828 27889 27261 27889 27261 27890 26828 27890 27262 27890 27261 960 27262 960 26726 960 26726 27891 27262 27891 26800 27891 26726 960 26800 960 26711 960 26711 27892 26800 27892 27259 27892 26711 960 27259 960 27263 960 27263 960 27259 960 27264 960 26717 960 26716 960 27420 960 27420 27893 26716 27893 27265 27893 27420 27894 27265 27894 27238 27894 27238 960 27265 960 27266 960 27238 960 27266 960 27365 960 27365 960 27266 960 27267 960 27365 27895 27267 27895 26714 27895 27378 960 27270 960 27375 960 27375 27896 27270 27896 26718 27896 27261 960 26729 960 27260 960 27260 960 26729 960 26730 960 27260 960 26730 960 27268 960 27268 27897 26730 27897 27269 27897 27268 960 27269 960 27367 960 27269 960 26724 960 27367 960 27367 27898 26724 27898 26722 27898 27367 27899 26722 27899 27378 27899 27378 27900 26722 27900 26720 27900 27378 27901 26720 27901 27270 27901 27272 27902 27275 27902 26739 27902 27271 27903 27397 27903 26748 27903 26748 27904 27397 27904 27387 27904 26748 27905 27387 27905 27281 27905 27272 960 26739 960 27384 960 27271 960 26735 960 27397 960 27397 27906 26735 27906 27273 27906 27397 27907 27273 27907 27272 27907 27272 27908 27273 27908 27274 27908 27272 27909 27274 27909 27275 27909 26739 960 27276 960 27384 960 27384 960 27276 960 26750 960 27384 27910 26750 27910 27385 27910 26750 960 26751 960 27385 960 27385 960 26751 960 27277 960 27385 27911 27277 27911 26816 27911 26816 27912 27277 27912 26741 27912 26816 960 26741 960 26813 960 26813 960 26741 960 27279 960 26813 27913 27279 27913 27278 27913 27278 960 27279 960 27280 960 27278 960 27280 960 27389 960 27389 27914 27280 27914 26745 27914 27389 960 26745 960 27387 960 27387 27915 26745 27915 26746 27915 27387 960 26746 960 27281 960 27232 27916 26762 27916 27285 27916 27428 960 27282 960 27232 960 27232 27917 27282 27917 26754 27917 27232 960 26754 960 26762 960 27283 960 26662 960 27413 960 27413 960 26662 960 27232 960 27413 960 27232 960 27284 960 27284 960 27232 960 27285 960 27288 960 26755 960 27428 960 27428 960 26755 960 27286 960 27428 27918 27286 27918 27282 27918 26931 27919 26752 27919 26933 27919 26933 27920 26752 27920 27288 27920 26933 27921 27288 27921 27287 27921 27287 27922 27288 27922 27428 27922 27287 27923 27428 27923 26934 27923 27284 960 27289 960 27413 960 27413 960 27289 960 26765 960 27413 960 26765 960 27290 960 27290 27924 26765 27924 27291 27924 27290 27925 27291 27925 26766 27925 26931 27926 27292 27926 26752 27926 26752 27927 27292 27927 27441 27927 26752 960 27441 960 26757 960 26757 27928 27441 27928 27293 27928 26757 960 27293 960 27294 960 27294 27929 27293 27929 27296 27929 27294 960 27296 960 27295 960 27295 27930 27296 27930 27297 27930 27295 960 27297 960 27299 960 27299 960 27297 960 27298 960 27299 960 27298 960 26759 960 26759 960 27298 960 27313 960 27300 27931 27301 27931 27426 27931 27226 27932 26768 27932 27404 27932 27404 27933 26768 27933 27302 27933 27404 960 27302 960 27427 960 27427 960 27302 960 27303 960 27427 960 27303 960 27304 960 27307 960 27403 960 27406 960 27319 27934 27305 27934 27328 27934 27328 960 27305 960 27306 960 27307 960 27406 960 27325 960 27301 960 27308 960 27426 960 27426 27935 27308 27935 26777 27935 27426 960 26777 960 26938 960 26938 27936 26777 27936 27309 27936 27323 960 26930 960 27309 960 27309 960 26930 960 27310 960 27309 27937 27310 27937 26938 27937 27311 960 27445 960 27314 960 26789 960 27312 960 27298 960 27298 960 27312 960 27290 960 27298 960 27290 960 27313 960 27313 27938 27290 27938 26766 27938 27445 27939 26789 27939 27314 27939 27314 27940 26789 27940 27298 27940 27314 960 27298 960 27436 960 27436 960 27298 960 27297 960 26938 27941 26937 27941 27426 27941 27426 27942 26937 27942 27315 27942 27426 27943 27315 27943 27428 27943 27428 27944 27315 27944 27316 27944 27428 960 27316 960 26934 960 26884 960 27317 960 27328 960 27328 960 27317 960 27318 960 27328 27945 27318 27945 27319 27945 27319 27946 27318 27946 27320 27946 27319 960 27320 960 27321 960 27321 27947 27320 27947 27322 27947 27321 960 27322 960 26773 960 26773 27948 27322 27948 26880 27948 26773 960 26880 960 27323 960 27323 27949 26880 27949 27324 27949 27323 27950 27324 27950 26930 27950 27332 960 26875 960 27406 960 27406 27951 26875 27951 27328 27951 27406 960 27328 960 27325 960 27325 960 27328 960 27306 960 27326 960 26884 960 27327 960 27327 27952 26884 27952 27328 27952 27327 960 27328 960 27329 960 27329 27953 27328 27953 26875 27953 27341 27954 26872 27954 27330 27954 27330 27955 26872 27955 27331 27955 27330 27956 27331 27956 27333 27956 27333 960 27331 960 27332 960 27333 27957 27332 27957 27334 27957 27334 27958 27332 27958 27406 27958 27334 960 27406 960 27407 960 27335 960 27339 960 27336 960 27336 960 27339 960 26871 960 27421 960 27338 960 27337 960 27337 960 27338 960 27339 960 27337 960 27339 960 27340 960 27340 960 27339 960 27335 960 27340 960 27335 960 27341 960 27341 960 27335 960 26876 960 27341 960 26876 960 26872 960 26679 960 27346 960 27342 960 27342 27959 27346 27959 26864 27959 27342 960 26864 960 27343 960 27343 960 26864 960 26865 960 27343 960 26865 960 27344 960 27344 960 26865 960 26868 960 27344 27960 26868 27960 26675 27960 26675 27961 26868 27961 27339 27961 26675 960 27339 960 26689 960 26689 960 27339 960 27338 960 26689 960 27338 960 27345 960 27345 27962 27338 27962 27351 27962 26679 960 26681 960 27346 960 27346 27963 26681 27963 27347 27963 27346 960 27347 960 27348 960 27348 960 27347 960 26682 960 27348 27964 26682 27964 27349 27964 27349 960 26683 960 27348 960 27348 27965 26683 27965 27350 27965 27348 27966 27350 27966 27338 27966 27338 960 27350 960 26685 960 27338 27967 26685 27967 27351 27967 27352 960 26853 960 27253 960 27253 960 26853 960 26964 960 27346 960 26968 960 27353 960 27424 27968 27354 27968 27348 27968 27348 27969 27354 27969 26972 27969 27348 960 26972 960 27346 960 27346 960 26972 960 26970 960 27346 960 26970 960 26968 960 26852 27970 27353 27970 26853 27970 26853 27971 27353 27971 26967 27971 26853 27972 26967 27972 26964 27972 26852 27973 26850 27973 27353 27973 27353 960 26850 960 26849 960 27353 960 26849 960 27346 960 27346 27974 26849 27974 27355 27974 27346 19196 27355 19196 26860 19196 27352 27975 27253 27975 26856 27975 26856 960 27253 960 27357 960 26856 960 27357 960 27356 960 27356 960 27357 960 26858 960 26858 960 27357 960 27249 960 26858 960 27249 960 26848 960 26848 27976 27249 27976 27358 27976 26848 960 27358 960 26841 960 26949 27977 27360 27977 27242 27977 26646 960 27227 960 27242 960 27242 27978 27227 27978 27365 27978 27242 960 27365 960 26949 960 26949 960 27365 960 27359 960 27360 960 27361 960 27242 960 27242 27979 27361 27979 26946 27979 27242 960 26946 960 26792 960 26792 27980 26946 27980 27362 27980 26792 27981 27362 27981 26794 27981 26794 27982 27362 27982 26943 27982 26794 960 26943 960 27363 960 27363 27983 26943 27983 26942 27983 27363 27984 26942 27984 26796 27984 26796 960 26942 960 27364 960 26796 27985 27364 27985 26798 27985 26798 27986 27364 27986 26954 27986 26798 27987 26954 27987 27259 27987 27259 27988 26954 27988 27366 27988 27259 27989 27366 27989 27365 27989 27365 3099 27366 3099 26952 3099 27365 27990 26952 27990 27359 27990 27378 960 27379 960 27367 960 27367 27991 27379 27991 26806 27991 27367 27992 26806 27992 27369 27992 27368 27993 27370 27993 27369 27993 27369 960 27370 960 27371 960 27369 27994 27371 27994 27367 27994 27375 27995 27212 27995 27372 27995 27435 960 27272 960 27373 960 27373 960 27272 960 27384 960 27373 27996 27384 27996 27222 27996 27222 27997 27384 27997 27374 27997 27372 27998 27376 27998 27375 27998 27375 960 27376 960 27377 960 27375 960 27377 960 27378 960 27378 960 27377 960 26807 960 27378 27999 26807 27999 27379 27999 27372 960 27380 960 27376 960 27376 28000 27380 28000 27381 28000 27376 28001 27381 28001 26808 28001 26808 28002 27381 28002 27374 28002 26808 28003 27374 28003 27382 28003 27382 960 27374 960 27384 960 27382 960 27384 960 27383 960 27383 28004 27384 28004 26809 28004 26809 28005 27384 28005 26810 28005 26810 960 27384 960 27385 960 26810 960 27385 960 26817 960 27390 960 27386 960 27387 960 27387 28006 27386 28006 26782 28006 27387 28007 26782 28007 27389 28007 27389 28008 26782 28008 27388 28008 27389 19163 27388 19163 26811 19163 27387 15845 27391 15845 27390 15845 27390 960 27391 960 27392 960 27390 960 27392 960 27394 960 27394 28009 27392 28009 27393 28009 27394 960 27393 960 26785 960 26785 28010 27393 28010 27395 28010 26785 960 27395 960 26787 960 26787 960 27395 960 27290 960 26787 960 27290 960 27396 960 27396 960 27290 960 27312 960 27432 28011 27398 28011 27397 28011 27397 28012 27398 28012 27399 28012 27397 28013 27399 28013 27387 28013 27387 28014 27399 28014 26990 28014 27387 960 26990 960 27391 960 26964 960 26963 960 27253 960 27253 28015 26963 28015 26962 28015 27253 28016 26962 28016 27230 28016 27230 28017 26962 28017 26959 28017 27400 28018 27423 28018 27401 28018 27401 960 27423 960 27230 960 27401 28019 27230 28019 26957 28019 26957 28020 27230 28020 26959 28020 27422 960 27402 960 27408 960 27403 28021 27404 28021 27406 28021 27406 28022 27404 28022 27405 28022 27406 28023 27405 28023 27407 28023 27402 960 27409 960 27408 960 27408 28024 27409 28024 27410 28024 27408 28025 27410 28025 27404 28025 27404 28026 27410 28026 27411 28026 27404 28027 27411 28027 27405 28027 27412 28028 26994 28028 26992 28028 27237 28029 26623 28029 27412 28029 27412 960 26623 960 27413 960 27412 28030 27413 28030 26994 28030 26994 960 27413 960 27414 960 27395 960 27415 960 27290 960 27290 28031 27415 28031 27416 28031 27290 960 27416 960 27413 960 27413 28032 27416 28032 27417 28032 27413 28033 27417 28033 27414 28033 27434 960 27418 960 27433 960 26718 28034 27420 28034 27375 28034 27375 960 27420 960 27214 960 27375 28035 27214 28035 27212 28035 27418 960 27419 960 27433 960 27433 28036 27419 28036 27218 28036 27433 28037 27218 28037 27420 28037 27420 28038 27218 28038 27216 28038 27420 960 27216 960 27214 960 27421 28039 27422 28039 27338 28039 27338 28040 27422 28040 27408 28040 27338 28041 27408 28041 27348 28041 27348 960 27408 960 27423 960 27348 960 27423 960 27424 960 27424 960 27423 960 27400 960 27425 960 26987 960 27426 960 26987 960 26984 960 27426 960 27426 28042 26984 28042 27427 28042 27426 960 27427 960 27300 960 27300 28043 27427 28043 27304 28043 27425 960 27426 960 26973 960 26973 28044 27426 28044 27428 28044 26973 28045 27428 28045 27429 28045 26984 960 27430 960 27427 960 27427 28046 27430 28046 26983 28046 27427 28047 26983 28047 27232 28047 27232 28048 26983 28048 26982 28048 27232 28049 26982 28049 26980 28049 26980 960 27431 960 27232 960 27232 28050 27431 28050 26977 28050 27232 960 26977 960 27428 960 27428 28051 26977 28051 26976 28051 27428 28052 26976 28052 27429 28052 26992 960 27432 960 27412 960 27412 960 27432 960 27397 960 27412 28053 27397 28053 27433 28053 27433 960 27397 960 27272 960 27433 960 27272 960 27434 960 27434 28054 27272 28054 27435 28054 26897 28055 26802 28055 27443 28055 27443 28056 27311 28056 26897 28056 26897 28057 27311 28057 27314 28057 26897 28058 27314 28058 27437 28058 27437 28059 27314 28059 27436 28059 27437 28060 27436 28060 27438 28060 27438 28061 27436 28061 27297 28061 27438 28062 27297 28062 27439 28062 27439 28063 27297 28063 27296 28063 27439 28064 27296 28064 27440 28064 27440 28065 27296 28065 27293 28065 27440 28066 27293 28066 26899 28066 26899 28067 27293 28067 27441 28067 26899 28068 27441 28068 27442 28068 27442 28069 27441 28069 27292 28069 27442 28070 27292 28070 26901 28070 26802 28071 26801 28071 27443 28071 27443 28072 26801 28072 27097 28072 27443 28073 27097 28073 27445 28073 27445 28074 27097 28074 27444 28074 27445 28075 27444 28075 26789 28075 27541 28076 27446 28076 27542 28076 27526 28077 27447 28077 27527 28077 27495 28078 27448 28078 27449 28078 27564 28079 27450 28079 27562 28079 27451 28080 27452 28080 27453 28080 27477 28081 27041 28081 27040 28081 26845 28082 27169 28082 27168 28082 27454 28083 26939 28083 27071 28083 27542 28084 27455 28084 27456 28084 27461 28085 27460 28085 27544 28085 27457 28086 27458 28086 27459 28086 27460 28087 27461 28087 27459 28087 27459 28088 27461 28088 27539 28088 27459 28089 27539 28089 27457 28089 27462 28090 26842 28090 27463 28090 27463 28091 26842 28091 26843 28091 27463 28092 26843 28092 27464 28092 27468 28093 27465 28093 27467 28093 27525 28094 27466 28094 27467 28094 27467 28095 27466 28095 26842 28095 27467 28096 26842 28096 27468 28096 27468 28097 26842 28097 27462 28097 27468 28098 27462 28098 27469 28098 27518 28099 27470 28099 27471 28099 27471 28100 27470 28100 26847 28100 27471 28101 26847 28101 27521 28101 27521 28102 26847 28102 27472 28102 27521 28103 27472 28103 26859 28103 27517 28104 27473 28104 27516 28104 27512 28105 27474 28105 27475 28105 27136 28106 27476 28106 27514 28106 27477 28107 27508 28107 27481 28107 27481 28108 27508 28108 27484 28108 27483 28109 27478 28109 27482 28109 27451 28110 27480 28110 27479 28110 27479 28111 27480 28111 26832 28111 27479 28112 26832 28112 27482 28112 27482 28113 26832 28113 27481 28113 27482 28114 27481 28114 27483 28114 27483 28115 27481 28115 27484 28115 27483 28116 27484 28116 27571 28116 27453 28117 27485 28117 27486 28117 27451 28118 27453 28118 27480 28118 27480 28119 27453 28119 27486 28119 27480 28120 27486 28120 26830 28120 26830 28121 27486 28121 27567 28121 26830 28122 27567 28122 27052 28122 27487 28123 27488 28123 27489 28123 27495 28124 27496 28124 27490 28124 27490 28125 27496 28125 27491 28125 27490 28126 27491 28126 27489 28126 27449 28127 27492 28127 27493 28127 27118 28128 27494 28128 26819 28128 27495 28129 27449 28129 27496 28129 27496 28130 27449 28130 27493 28130 27496 28131 27493 28131 26820 28131 26820 28132 27493 28132 27497 28132 26820 28133 27497 28133 26819 28133 26819 28134 27497 28134 27498 28134 26819 28135 27498 28135 27118 28135 27556 28136 27499 28136 27115 28136 27500 28137 27504 28137 27557 28137 27557 28138 27504 28138 27556 28138 27505 28139 27501 28139 27503 28139 27547 28140 26801 28140 27502 28140 27502 28141 26801 28141 26803 28141 27502 28142 26803 28142 27503 28142 27503 28143 26803 28143 27504 28143 27503 28144 27504 28144 27505 28144 27505 28145 27504 28145 27500 28145 27505 28146 27500 28146 27506 28146 27477 28147 27040 28147 27508 28147 27508 28148 27040 28148 27507 28148 27508 28149 27507 28149 27509 28149 27510 28150 27511 28150 27475 28150 27475 28151 27511 28151 27136 28151 27475 28152 27136 28152 27512 28152 27512 28153 27136 28153 27514 28153 27512 28154 27514 28154 27513 28154 27513 28155 27514 28155 27515 28155 27513 28156 27515 28156 27516 28156 27516 28157 27515 28157 27470 28157 27516 28158 27470 28158 27517 28158 27517 28159 27470 28159 27518 28159 27517 28160 27518 28160 27519 28160 27507 28161 27038 28161 27509 28161 27509 28162 27038 28162 27520 28162 27509 28163 27520 28163 27511 28163 27511 28164 27520 28164 27003 28164 27511 28165 27003 28165 27136 28165 26859 28166 27140 28166 27521 28166 27521 28167 27140 28167 27522 28167 27521 28168 27522 28168 27523 28168 27523 28169 27522 28169 27149 28169 27524 28170 27466 28170 27002 28170 27002 28171 27466 28171 27525 28171 27002 28172 27525 28172 27151 28172 27151 28173 27525 28173 27526 28173 27151 28174 27526 28174 27149 28174 27149 28175 27526 28175 27527 28175 27149 28176 27527 28176 27523 28176 27523 28177 27527 28177 27528 28177 27532 28178 27529 28178 27530 28178 27533 28179 27531 28179 27088 28179 27533 28180 27088 28180 27538 28180 26843 28181 26845 28181 27464 28181 27464 28182 26845 28182 27168 28182 27464 28183 27168 28183 27530 28183 27530 28184 27168 28184 27531 28184 27530 28185 27531 28185 27532 28185 27532 28186 27531 28186 27533 28186 27532 28187 27533 28187 27534 28187 27535 28188 27536 28188 27537 28188 27088 28189 27089 28189 27538 28189 27538 28190 27089 28190 27085 28190 27538 28191 27085 28191 27537 28191 27537 28192 27085 28192 27457 28192 27537 28193 27457 28193 27535 28193 27535 28194 27457 28194 27539 28194 27535 28195 27539 28195 27540 28195 27079 28196 27549 28196 27541 28196 27079 28197 27541 28197 27071 28197 27071 28198 27541 28198 27542 28198 27071 28199 27542 28199 27454 28199 27454 28200 27542 28200 27456 28200 27454 28201 27456 28201 27544 28201 27544 28202 27456 28202 27543 28202 27544 28203 27543 28203 27461 28203 27550 28204 27545 28204 27546 28204 27097 28205 26801 28205 27098 28205 27098 28206 26801 28206 27547 28206 27098 28207 27547 28207 27099 28207 27099 28208 27547 28208 27551 28208 27079 28209 27548 28209 27549 28209 27549 28210 27548 28210 27081 28210 27549 28211 27081 28211 27546 28211 27546 28212 27081 28212 27099 28212 27546 28213 27099 28213 27550 28213 27550 28214 27099 28214 27551 28214 27550 28215 27551 28215 27552 28215 27553 28216 27554 28216 27558 28216 27560 28217 27559 28217 27498 28217 27498 28218 27559 28218 27555 28218 27498 28219 27555 28219 27118 28219 27556 28220 27115 28220 27557 28220 27557 28221 27115 28221 27113 28221 27557 28222 27113 28222 27558 28222 27558 28223 27113 28223 27559 28223 27558 28224 27559 28224 27553 28224 27553 28225 27559 28225 27560 28225 27553 28226 27560 28226 27561 28226 27562 28227 27004 28227 27565 28227 27565 28228 27004 28228 27005 28228 27565 28229 27005 28229 27563 28229 27491 28230 27564 28230 27489 28230 27489 28231 27564 28231 27562 28231 27489 28232 27562 28232 27487 28232 27487 28233 27562 28233 27565 28233 27487 28234 27565 28234 27566 28234 27005 28235 27056 28235 27563 28235 27563 28236 27056 28236 27054 28236 27563 28237 27054 28237 27567 28237 27567 28238 27054 28238 27568 28238 27567 28239 27568 28239 27052 28239 27569 28240 27571 28240 27570 28240 27570 28241 27571 28241 27484 28241 27570 28242 27484 28242 27572 28242 27573 19468 27612 19468 27574 19468 27574 19469 27612 19469 27686 19469 27574 19469 27686 19469 27575 19469 27575 28243 27686 28243 27576 28243 27575 28244 27576 28244 26900 28244 26900 28245 27576 28245 27685 28245 26900 28246 27685 28246 26898 28246 26898 19474 27685 19474 27578 19474 26898 19475 27578 19475 27577 19475 27577 19476 27578 19476 27683 19476 27577 19477 27683 19477 27579 19477 27579 28247 27683 28247 27580 28247 27579 28248 27580 28248 27581 28248 27581 28249 27580 28249 27582 28249 27581 28250 27582 28250 27583 28250 27583 19482 27582 19482 27679 19482 27583 19483 27679 19483 27584 19483 27584 28251 27679 28251 27585 28251 27584 28252 27585 28252 27586 28252 27586 28253 27585 28253 27587 28253 27586 28254 27587 28254 26893 28254 26893 19488 27587 19488 27588 19488 26893 19489 27588 19489 27589 19489 27589 19490 27588 19490 27591 19490 27589 19491 27591 19491 27590 19491 27590 19492 27591 19492 27592 19492 27590 19493 27592 19493 26888 19493 26888 28255 27592 28255 27593 28255 26888 28256 27593 28256 26887 28256 26887 19496 27593 19496 27674 19496 26887 19497 27674 19497 27594 19497 27594 28257 27674 28257 27673 28257 27594 28258 27673 28258 27595 28258 27595 19500 27673 19500 27671 19500 27595 19501 27671 19501 26885 19501 26885 19502 27671 19502 27670 19502 26885 19503 27670 19503 26927 19503 26927 19504 27670 19504 27669 19504 26927 19431 27669 19431 27596 19431 27596 19432 27669 19432 27668 19432 27596 19432 27668 19432 27597 19432 27597 28259 27668 28259 27598 28259 27597 28260 27598 28260 27600 28260 27600 28261 27598 28261 27599 28261 27600 28262 27599 28262 26924 28262 26924 19437 27599 19437 27706 19437 26924 19438 27706 19438 26923 19438 26923 19439 27706 19439 27703 19439 26923 19440 27703 19440 27601 19440 27601 28263 27703 28263 27602 28263 27601 28264 27602 28264 26919 28264 26919 28265 27602 28265 27603 28265 26919 28266 27603 28266 26917 28266 26917 19445 27603 19445 27700 19445 26917 19446 27700 19446 27604 19446 27604 28267 27700 28267 27699 28267 27604 28268 27699 28268 26915 28268 26915 28269 27699 28269 27697 28269 26915 28270 27697 28270 26913 28270 26913 19451 27697 19451 27605 19451 26913 19452 27605 19452 26912 19452 26912 19453 27605 19453 27695 19453 26912 19454 27695 19454 27606 19454 27606 19455 27695 19455 27694 19455 27606 19456 27694 19456 27607 19456 27607 28271 27694 28271 27608 28271 27607 28272 27608 28272 26907 28272 26907 19459 27608 19459 27691 19459 26907 19460 27691 19460 26906 19460 26906 28273 27691 28273 27609 28273 26906 28274 27609 28274 27610 28274 27610 19463 27609 19463 27690 19463 27610 19464 27690 19464 27611 19464 27611 19465 27690 19465 27689 19465 27611 19466 27689 19466 27573 19466 27573 19467 27689 19467 27612 19467 27666 28275 27613 28275 27614 28275 27614 28276 27613 28276 27687 28276 27614 28277 27687 28277 27615 28277 27615 28278 27687 28278 27688 28278 27615 28279 27688 28279 27617 28279 27617 28280 27688 28280 27616 28280 27617 28281 27616 28281 27618 28281 27618 28282 27616 28282 27619 28282 27618 28283 27619 28283 27620 28283 27620 28284 27619 28284 27692 28284 27620 28285 27692 28285 27621 28285 27621 28286 27692 28286 27693 28286 27621 28287 27693 28287 27622 28287 27622 28288 27693 28288 27696 28288 27622 28289 27696 28289 27623 28289 27623 28290 27696 28290 27624 28290 27623 28291 27624 28291 27625 28291 27625 28292 27624 28292 27626 28292 27625 28293 27626 28293 27627 28293 27627 28294 27626 28294 27628 28294 27627 28295 27628 28295 27629 28295 27629 28296 27628 28296 27698 28296 27629 28297 27698 28297 27630 28297 27630 28298 27698 28298 27701 28298 27630 28299 27701 28299 27631 28299 27631 28300 27701 28300 27702 28300 27631 28301 27702 28301 27632 28301 27632 28302 27702 28302 27634 28302 27632 28303 27634 28303 27633 28303 27633 28304 27634 28304 27704 28304 27633 28305 27704 28305 27635 28305 27635 28306 27704 28306 27705 28306 27635 28307 27705 28307 27636 28307 27636 28308 27705 28308 27637 28308 27636 28309 27637 28309 27638 28309 27638 28310 27637 28310 27667 28310 27638 28311 27667 28311 27639 28311 27639 28312 27667 28312 27640 28312 27639 28313 27640 28313 27641 28313 27641 28314 27640 28314 27672 28314 27641 28315 27672 28315 27642 28315 27642 28316 27672 28316 27643 28316 27642 28317 27643 28317 27644 28317 27644 28318 27643 28318 27645 28318 27644 28319 27645 28319 27646 28319 27646 28320 27645 28320 27675 28320 27646 28321 27675 28321 27647 28321 27647 28322 27675 28322 27648 28322 27647 28322 27648 28322 27649 28322 27649 28323 27648 28323 27676 28323 27649 28324 27676 28324 27650 28324 27650 28325 27676 28325 27677 28325 27650 28326 27677 28326 27652 28326 27652 28327 27677 28327 27651 28327 27652 28328 27651 28328 27654 28328 27654 28329 27651 28329 27653 28329 27654 28330 27653 28330 27655 28330 27655 28331 27653 28331 27678 28331 27655 28332 27678 28332 27656 28332 27656 28333 27678 28333 27680 28333 27656 28334 27680 28334 27657 28334 27657 28335 27680 28335 27681 28335 27657 28336 27681 28336 27658 28336 27658 28337 27681 28337 27682 28337 27658 28337 27682 28337 27659 28337 27659 28338 27682 28338 27684 28338 27659 28339 27684 28339 27660 28339 27660 28340 27684 28340 27661 28340 27660 28341 27661 28341 27662 28341 27662 28342 27661 28342 27663 28342 27662 28343 27663 28343 27664 28343 27664 28344 27663 28344 27665 28344 27664 28345 27665 28345 27666 28345 27666 28275 27665 28275 27613 28275 27598 590 27668 590 27667 590 27667 28346 27668 28346 27669 28346 27667 590 27669 590 27640 590 27640 28347 27669 28347 27670 28347 27640 590 27670 590 27672 590 27672 590 27670 590 27671 590 27672 590 27671 590 27643 590 27643 590 27671 590 27673 590 27643 590 27673 590 27645 590 27645 590 27673 590 27674 590 27645 590 27674 590 27675 590 27675 590 27674 590 27593 590 27675 590 27593 590 27648 590 27648 590 27593 590 27592 590 27648 590 27592 590 27676 590 27676 28348 27592 28348 27591 28348 27676 590 27591 590 27677 590 27677 590 27591 590 27588 590 27677 28349 27588 28349 27651 28349 27651 28350 27588 28350 27587 28350 27651 28351 27587 28351 27653 28351 27653 28352 27587 28352 27585 28352 27653 590 27585 590 27678 590 27678 590 27585 590 27679 590 27678 590 27679 590 27680 590 27680 28353 27679 28353 27582 28353 27680 28354 27582 28354 27681 28354 27681 590 27582 590 27580 590 27681 590 27580 590 27682 590 27682 590 27580 590 27683 590 27682 28355 27683 28355 27684 28355 27684 590 27683 590 27578 590 27684 590 27578 590 27661 590 27661 590 27578 590 27685 590 27661 28356 27685 28356 27663 28356 27663 28357 27685 28357 27576 28357 27663 590 27576 590 27665 590 27665 28358 27576 28358 27686 28358 27665 590 27686 590 27613 590 27613 28359 27686 28359 27612 28359 27613 590 27612 590 27687 590 27687 28360 27612 28360 27689 28360 27687 590 27689 590 27688 590 27688 28361 27689 28361 27690 28361 27688 590 27690 590 27616 590 27616 590 27690 590 27609 590 27616 28362 27609 28362 27619 28362 27619 590 27609 590 27691 590 27619 590 27691 590 27692 590 27692 590 27691 590 27608 590 27692 590 27608 590 27693 590 27693 590 27608 590 27694 590 27693 590 27694 590 27696 590 27696 590 27694 590 27695 590 27696 590 27695 590 27624 590 27624 28363 27695 28363 27605 28363 27624 590 27605 590 27626 590 27626 590 27605 590 27697 590 27626 590 27697 590 27628 590 27628 590 27697 590 27699 590 27628 590 27699 590 27698 590 27698 590 27699 590 27700 590 27698 590 27700 590 27701 590 27701 590 27700 590 27603 590 27701 590 27603 590 27702 590 27702 590 27603 590 27602 590 27702 590 27602 590 27634 590 27634 590 27602 590 27703 590 27634 590 27703 590 27704 590 27704 28364 27703 28364 27706 28364 27704 590 27706 590 27705 590 27705 28365 27706 28365 27599 28365 27705 590 27599 590 27637 590 27637 590 27599 590 27598 590 27637 590 27598 590 27667 590 27820 28366 27821 28366 27707 28366 27707 28367 27947 28368 27820 28369 27820 28370 27947 28370 27708 28370 27820 28371 27708 28371 27819 28371 27819 28372 27708 28372 27709 28372 27819 28373 27709 28373 27817 28373 27709 28374 27950 28374 27817 28374 27817 28375 27950 28375 27710 28375 27817 28376 27710 28376 27711 28376 27711 28377 27710 28377 27712 28377 27711 28378 27712 28378 27714 28378 27712 28379 27713 28379 27714 28379 27714 28380 27713 28380 27954 28380 27714 28381 27954 28381 27715 28381 27954 28382 27952 28382 27715 28382 27715 28383 27952 28383 27716 28383 27715 28384 27716 28384 27814 28384 27814 28385 27716 28385 27717 28385 27814 28386 27717 28386 27718 28386 27717 28387 27958 28387 27718 28387 27718 28388 27958 28388 27719 28388 27718 28389 27719 28389 27721 28389 27721 28390 27719 28390 27720 28390 27721 28391 27720 28391 27811 28391 27720 28392 27722 28392 27811 28392 27811 28393 27722 28393 27724 28393 27811 28394 27724 28394 27723 28394 27724 28395 27960 28395 27723 28395 27723 28396 27960 28396 27725 28396 27723 28397 27725 28397 27808 28397 27808 28398 27725 28398 27959 28398 27808 28399 27959 28399 27726 28399 27959 28400 27727 28400 27726 28400 27726 28401 27727 28401 27962 28401 27726 28402 27962 28402 27805 28402 27805 28403 27962 28403 27963 28403 27805 28404 27963 28404 27728 28404 27963 28405 27964 28405 27728 28405 27728 28406 27964 28406 27965 28406 27728 28407 27965 28407 27729 28407 27965 28408 27967 28408 27729 28408 27729 28409 27967 28409 27730 28409 27729 28410 27730 28410 27802 28410 27802 28411 27730 28411 27731 28411 27802 28412 27731 28412 27800 28412 27731 28413 27969 28413 27800 28413 27800 28414 27969 28414 27733 28414 27800 28415 27733 28415 27732 28415 27732 28416 27733 28416 27734 28416 27732 28417 27734 28417 27735 28417 27734 28418 27972 28418 27735 28418 27735 28419 27972 28419 27736 28419 27735 28420 27736 28420 27797 28420 27736 28421 27975 28421 27797 28421 27797 28422 27975 28422 27738 28422 27797 28423 27738 28423 27737 28423 27737 28424 27738 28424 27974 28424 27737 28425 27974 28425 27795 28425 27974 28426 27739 28426 27795 28426 27795 28427 27739 28427 27973 28427 27795 28428 27973 28428 27793 28428 27793 28429 27973 28429 27977 28429 27793 28430 27977 28430 27741 28430 27977 28431 27740 28431 27741 28431 27741 28432 27740 28432 27978 28432 27741 28433 27978 28433 27742 28433 27978 28434 27743 28434 27742 28434 27742 28435 27743 28435 27744 28435 27742 28436 27744 28436 27789 28436 27789 28437 27744 28437 27745 28437 27789 28438 27745 28438 27788 28438 27745 28439 27746 28439 27788 28439 27788 28440 27746 28440 27747 28440 27788 28441 27747 28441 27786 28441 27786 28442 27747 28442 27748 28442 27786 28443 27748 28443 27750 28443 27748 28444 27981 28444 27750 28444 27750 28445 27981 28445 27749 28445 27750 28446 27749 28446 27784 28446 27749 28447 27986 28447 27784 28447 27784 28448 27986 28448 27985 28448 27784 28449 27985 28449 27751 28449 27751 28450 27985 28450 27984 28450 27751 28451 27984 28451 27752 28451 27984 28452 27983 28452 27752 28452 27752 28453 27983 28453 27753 28453 27752 28454 27753 28454 27780 28454 27780 28455 27753 28455 27987 28455 27780 28456 27987 28456 27754 28456 27987 28457 27988 28457 27754 28457 27754 28458 27988 28458 27989 28458 27754 28459 27989 28459 27755 28459 27989 28460 27990 28460 27755 28460 27755 28461 27990 28461 27994 28461 27755 28462 27994 28462 27756 28462 27756 28463 27994 28463 27992 28463 27756 28464 27992 28464 27779 28464 27992 28465 27995 28465 27779 28465 27779 28466 27995 28466 27758 28466 27779 28467 27758 28467 27757 28467 27757 28468 27758 28468 27759 28468 27757 28469 27759 28469 27761 28469 27759 28470 27996 28470 27761 28470 27761 28471 27996 28471 27760 28471 27761 28472 27760 28472 27762 28472 27760 28473 28001 28473 27762 28473 27762 28474 28001 28474 28000 28474 27762 28475 28000 28475 27776 28475 27776 28476 28000 28476 27999 28476 27776 28477 27999 28477 27775 28477 27999 28478 27997 28478 27775 28478 27775 28479 27997 28479 27763 28479 27775 28480 27763 28480 27764 28480 27764 28481 27763 28481 27765 28481 27764 28482 27765 28482 27774 28482 27765 28483 27766 28483 27774 28483 27774 28484 27766 28484 27767 28484 27774 28485 27767 28485 27768 28485 27767 28486 28003 28486 27768 28486 27768 28487 28003 28488 27769 28488 27768 28489 27769 28489 27772 28489 27772 28490 27769 28490 28008 28490 27772 28491 28008 28491 27771 28491 28008 28492 27770 28492 27771 28492 27771 28493 27770 28493 28006 28493 27771 28494 28006 28494 27824 28494 27824 28495 28006 28495 28005 28495 27824 28496 28005 28496 27821 28496 27821 28497 28005 28497 27949 28497 27821 28498 27949 28498 27707 28498 27771 28499 27873 28499 27772 28499 27772 28500 27873 28500 27773 28500 27772 28501 27773 28501 27768 28501 27768 28502 27773 28502 27826 28502 27768 28503 27826 28503 27774 28503 27774 28504 27826 28504 27828 28504 27774 28505 27828 28505 27764 28505 27764 28506 27828 28506 27829 28506 27764 28507 27829 28507 27775 28507 27775 28508 27829 28508 27832 28508 27775 28509 27832 28509 27776 28509 27776 28510 27832 28510 27834 28510 27776 28511 27834 28511 27762 28511 27762 28512 27834 28512 27777 28512 27762 28513 27777 28513 27761 28513 27761 28514 27777 28514 27778 28514 27761 28515 27778 28515 27757 28515 27757 28516 27778 28516 27836 28516 27757 28517 27836 28517 27779 28517 27779 28518 27836 28518 27837 28518 27779 28519 27837 28519 27756 28519 27756 28520 27837 28520 27838 28520 27756 28521 27838 28521 27755 28521 27755 28522 27838 28522 27841 28522 27755 28523 27841 28523 27754 28523 27754 28524 27841 28524 27842 28524 27754 28525 27842 28525 27780 28525 27780 28526 27842 28526 27781 28526 27780 28527 27781 28527 27752 28527 27752 28528 27781 28528 27782 28528 27752 28529 27782 28529 27751 28529 27751 28530 27782 28530 27783 28530 27751 28531 27783 28531 27784 28531 27784 28532 27783 28532 27785 28532 27784 28533 27785 28533 27750 28533 27750 28534 27785 28534 27846 28534 27750 28535 27846 28535 27786 28535 27786 28536 27846 28536 27787 28536 27786 28537 27787 28537 27788 28537 27788 28538 27787 28538 27847 28538 27788 28539 27847 28539 27789 28539 27789 28540 27847 28540 27790 28540 27789 28541 27790 28541 27742 28541 27742 28542 27790 28542 27791 28542 27742 28543 27791 28543 27741 28543 27741 28544 27791 28544 27792 28544 27741 28545 27792 28545 27793 28545 27793 28546 27792 28546 27794 28546 27793 28547 27794 28547 27795 28547 27795 28548 27794 28548 27796 28548 27795 28549 27796 28549 27737 28549 27737 28550 27796 28550 27853 28550 27737 28551 27853 28551 27797 28551 27797 28552 27853 28552 27798 28552 27797 28553 27798 28553 27735 28553 27735 28554 27798 28554 27856 28554 27735 28555 27856 28555 27732 28555 27732 28556 27856 28556 27799 28556 27732 28557 27799 28557 27800 28557 27800 28558 27799 28558 27801 28558 27800 28559 27801 28559 27802 28559 27802 28560 27801 28560 27803 28560 27802 28561 27803 28561 27729 28561 27729 28562 27803 28562 27858 28562 27729 28563 27858 28563 27728 28563 27728 28564 27858 28564 27804 28564 27728 28565 27804 28565 27805 28565 27805 28566 27804 28566 27806 28566 27805 28567 27806 28567 27726 28567 27726 28568 27806 28568 27807 28568 27726 28569 27807 28569 27808 28569 27808 28570 27807 28570 27809 28570 27808 28571 27809 28571 27723 28571 27723 28572 27809 28572 27810 28572 27723 28573 27810 28573 27811 28573 27811 28574 27810 28574 27812 28574 27811 28575 27812 28575 27721 28575 27721 28576 27812 28576 27864 28576 27721 28577 27864 28577 27718 28577 27718 28578 27864 28578 27813 28578 27718 28579 27813 28579 27814 28579 27814 28580 27813 28580 27815 28580 27814 28581 27815 28581 27715 28581 27715 28582 27815 28582 27866 28582 27715 28583 27866 28583 27714 28583 27714 28584 27866 28584 27816 28584 27714 28585 27816 28585 27711 28585 27711 28586 27816 28586 27867 28586 27711 28587 27867 28587 27817 28587 27817 28588 27867 28588 27818 28588 27817 28589 27818 28589 27819 28589 27819 28590 27818 28590 27868 28590 27819 28591 27868 28591 27820 28591 27820 28592 27868 28592 27822 28592 27820 28593 27822 28593 27821 28593 27821 28594 27822 28594 27823 28594 27821 28595 27823 28595 27824 28595 27824 28596 27823 28596 27870 28596 27824 28597 27870 28597 27771 28597 27771 28598 27870 28598 27873 28598 27873 28599 27825 28599 27773 28599 27773 28600 27825 28600 27827 28600 27773 28601 27827 28601 27826 28601 27826 28602 27827 28602 27876 28602 27826 28603 27876 28603 27828 28603 27828 28604 27876 28604 27830 28604 27828 28605 27830 28605 27829 28605 27829 28606 27830 28606 27831 28606 27829 28607 27831 28607 27832 28607 27832 28608 27831 28608 27833 28608 27832 28609 27833 28609 27834 28609 27834 28610 27833 28610 27881 28610 27834 28611 27881 28611 27777 28611 27777 28612 27881 28612 27835 28612 27777 28613 27835 28613 27778 28613 27778 28614 27835 28614 27884 28614 27778 28615 27884 28615 27836 28615 27836 28616 27884 28616 27887 28616 27836 28617 27887 28617 27837 28617 27837 28618 27887 28618 27839 28618 27837 28619 27839 28619 27838 28619 27838 28620 27839 28620 27840 28620 27838 28621 27840 28621 27841 28621 27841 28622 27840 28622 27890 28622 27841 28623 27890 28623 27842 28623 27842 28624 27890 28624 27892 28624 27842 28625 27892 28625 27781 28625 27781 28626 27892 28626 27893 28626 27781 28627 27893 28627 27782 28627 27782 28628 27893 28628 27843 28628 27782 28629 27843 28629 27783 28629 27783 28630 27843 28630 27844 28630 27783 28631 27844 28631 27785 28631 27785 28632 27844 28632 27845 28632 27785 28633 27845 28633 27846 28633 27846 28634 27845 28634 27898 28634 27846 28635 27898 28635 27787 28635 27787 28636 27898 28636 27848 28636 27787 28637 27848 28637 27847 28637 27847 28638 27848 28638 27901 28638 27847 28639 27901 28639 27790 28639 27790 28640 27901 28640 27849 28640 27790 28641 27849 28641 27791 28641 27791 28642 27849 28642 27850 28642 27791 28643 27850 28643 27792 28643 27792 28644 27850 28644 27851 28644 27792 28645 27851 28645 27794 28645 27794 28646 27851 28646 27908 28646 27794 28647 27908 28647 27796 28647 27796 28648 27908 28648 27852 28648 27796 28649 27852 28649 27853 28649 27853 28650 27852 28650 27854 28650 27853 28651 27854 28651 27798 28651 27798 28652 27854 28652 27855 28652 27798 28653 27855 28653 27856 28653 27856 28654 27855 28654 27912 28654 27856 28655 27912 28655 27799 28655 27799 28656 27912 28656 27914 28656 27799 28657 27914 28657 27801 28657 27801 28658 27914 28658 27916 28658 27801 28659 27916 28659 27803 28659 27803 28660 27916 28660 27857 28660 27803 28661 27857 28661 27858 28661 27858 28662 27857 28662 27859 28662 27858 28663 27859 28663 27804 28663 27804 28664 27859 28664 27860 28664 27804 28665 27860 28665 27806 28665 27806 28666 27860 28666 27921 28666 27806 28667 27921 28667 27807 28667 27807 28668 27921 28668 27861 28668 27807 28669 27861 28669 27809 28669 27809 28670 27861 28670 27862 28670 27809 28671 27862 28671 27810 28671 27810 28672 27862 28672 27863 28672 27810 28673 27863 28673 27812 28673 27812 28674 27863 28674 27926 28674 27812 28675 27926 28675 27864 28675 27864 28676 27926 28676 27928 28676 27864 28677 27928 28677 27813 28677 27813 28678 27928 28678 27865 28678 27813 28679 27865 28679 27815 28679 27815 28680 27865 28680 27932 28680 27815 28681 27932 28681 27866 28681 27866 28682 27932 28682 27933 28682 27866 28683 27933 28683 27816 28683 27816 28684 27933 28684 27935 28684 27816 28685 27935 28685 27867 28685 27867 28686 27935 28686 27936 28686 27867 28687 27936 28687 27818 28687 27818 28688 27936 28688 27938 28688 27818 28689 27938 28689 27868 28689 27868 28690 27938 28690 27940 28690 27868 28691 27940 28691 27822 28691 27822 28692 27940 28692 27869 28692 27822 28693 27869 28693 27823 28693 27823 28694 27869 28694 27871 28694 27823 28695 27871 28695 27870 28695 27870 28696 27871 28696 27872 28696 27870 28697 27872 28697 27873 28697 27873 28698 27872 28698 27825 28698 27825 28699 27874 28699 27827 28699 27827 28700 27874 28700 27875 28700 27827 28701 27875 28701 27876 28701 27876 28702 27875 28702 27877 28702 27876 28703 27877 28703 27830 28703 27830 28704 27877 28704 27878 28704 27830 28705 27878 28705 27831 28705 27831 28706 27878 28706 27879 28706 27831 28707 27879 28707 27833 28707 27833 28708 27879 28708 27880 28708 27833 28709 27880 28709 27881 28709 27881 28710 27880 28710 27882 28710 27881 28711 27882 28711 27835 28711 27835 28712 27882 28712 27883 28712 27835 28713 27883 28713 27884 28713 27884 28714 27883 28714 27885 28714 27884 28715 27885 28715 27887 28715 27887 28716 27885 28716 27886 28716 27887 28717 27886 28717 27839 28717 27839 28718 27886 28718 27888 28718 27839 28719 27888 28719 27840 28719 27840 28720 27888 28720 27889 28720 27840 28721 27889 28721 27890 28721 27890 28722 27889 28722 27891 28722 27890 28723 27891 28723 27892 28723 27892 28724 27891 28724 27894 28724 27892 28725 27894 28725 27893 28725 27893 28726 27894 28726 27895 28726 27893 28727 27895 28727 27843 28727 27843 28728 27895 28728 27896 28728 27843 28729 27896 28729 27844 28729 27844 28730 27896 28730 27897 28730 27844 28731 27897 28731 27845 28731 27845 28732 27897 28732 27899 28732 27845 28733 27899 28733 27898 28733 27898 28734 27899 28734 27900 28734 27898 28735 27900 28735 27848 28735 27848 28736 27900 28736 27902 28736 27848 28737 27902 28737 27901 28737 27901 28738 27902 28738 27903 28738 27901 28739 27903 28739 27849 28739 27849 28740 27903 28740 27904 28740 27849 28741 27904 28741 27850 28741 27850 28742 27904 28742 27905 28742 27850 28743 27905 28743 27851 28743 27851 28744 27905 28744 27906 28744 27851 28745 27906 28745 27908 28745 27908 28746 27906 28746 27907 28746 27908 28747 27907 28747 27852 28747 27852 28748 27907 28748 27909 28748 27852 28749 27909 28749 27854 28749 27854 28750 27909 28750 27910 28750 27854 28751 27910 28751 27855 28751 27855 28752 27910 28752 27911 28752 27855 28753 27911 28753 27912 28753 27912 28754 27911 28754 27913 28754 27912 28755 27913 28755 27914 28755 27914 28756 27913 28756 27915 28756 27914 28757 27915 28757 27916 28757 27916 28758 27915 28758 27917 28758 27916 28759 27917 28759 27857 28759 27857 28760 27917 28760 27918 28760 27857 28761 27918 28761 27859 28761 27859 28762 27918 28762 27919 28762 27859 28763 27919 28763 27860 28763 27860 28764 27919 28764 27920 28764 27860 28765 27920 28765 27921 28765 27921 28766 27920 28766 27922 28766 27921 28767 27922 28767 27861 28767 27861 28768 27922 28768 27923 28768 27861 28769 27923 28769 27862 28769 27862 28770 27923 28770 27924 28770 27862 28771 27924 28771 27863 28771 27863 28772 27924 28772 27925 28772 27863 28773 27925 28773 27926 28773 27926 28774 27925 28774 27927 28774 27926 28775 27927 28775 27928 28775 27928 28776 27927 28776 27929 28776 27928 28777 27929 28777 27865 28777 27865 28778 27929 28778 27930 28778 27865 28779 27930 28779 27932 28779 27932 28780 27930 28780 27931 28780 27932 28781 27931 28781 27933 28781 27933 28782 27931 28782 27934 28782 27933 28783 27934 28783 27935 28783 27935 28784 27934 28784 27937 28784 27935 28785 27937 28785 27936 28785 27936 28786 27937 28786 27939 28786 27936 28787 27939 28787 27938 28787 27938 28788 27939 28788 27941 28788 27938 28789 27941 28789 27940 28789 27940 28790 27941 28790 27942 28790 27940 28791 27942 28791 27869 28791 27869 28792 27942 28792 27943 28792 27869 28793 27943 28793 27871 28793 27871 28794 27943 28794 27944 28794 27871 28795 27944 28795 27872 28795 27872 28796 27944 28796 27945 28796 27872 28797 27945 28797 27825 28797 27825 28798 27945 28798 27874 28798 28007 28799 27948 28799 27949 28799 27709 28800 27708 28800 27946 28800 27946 28801 27708 28801 27947 28801 27946 28802 27947 28802 27948 28802 27948 28803 27947 28803 27707 28803 27948 28804 27707 28804 27949 28804 27709 28805 27946 28805 27950 28805 27950 28806 27946 28806 27951 28806 27950 28807 27951 28807 27710 28807 27710 28808 27951 28808 27712 28808 27712 28809 27951 28809 27953 28809 27712 28810 27953 28810 27713 28810 27955 28811 27952 28811 27953 28811 27953 28812 27952 28812 27954 28812 27953 28813 27954 28813 27713 28813 27957 28814 27717 28814 27955 28814 27955 28815 27717 28815 27716 28815 27955 28816 27716 28816 27952 28816 27956 28817 27719 28817 27957 28817 27957 28818 27719 28818 27958 28818 27957 28819 27958 28819 27717 28819 28145 28820 27722 28820 27956 28820 27956 28821 27722 28821 27720 28821 27956 28822 27720 28822 27719 28822 27959 28823 27725 28823 28143 28823 28143 28824 27725 28824 27960 28824 28143 28825 27960 28825 28145 28825 28145 28826 27960 28826 27724 28826 28145 28827 27724 28827 27722 28827 27959 28828 28143 28828 27727 28828 27727 28829 28143 28829 27961 28829 27727 28830 27961 28830 27962 28830 27962 28831 27961 28831 27963 28831 27963 28832 27961 28832 28141 28832 27963 28833 28141 28833 27964 28833 27966 28834 27967 28834 28141 28834 28141 28835 27967 28835 27965 28835 28141 28836 27965 28836 27964 28836 27968 28837 27731 28837 27966 28837 27966 28838 27731 28838 27730 28838 27966 28839 27730 28839 27967 28839 27971 28840 27733 28840 27968 28840 27968 28841 27733 28841 27969 28841 27968 28842 27969 28842 27731 28842 27970 28843 27972 28843 27971 28843 27971 28844 27972 28844 27734 28844 27971 28845 27734 28845 27733 28845 28137 28846 27975 28846 27970 28846 27970 28847 27975 28847 27736 28847 27970 28848 27736 28848 27972 28848 27973 28849 27739 28849 27976 28849 27976 28850 27739 28850 27974 28850 27976 28851 27974 28851 28137 28851 28137 28852 27974 28852 27738 28852 28137 28853 27738 28853 27975 28853 27973 28854 27976 28854 27977 28854 27977 28855 27976 28855 28136 28855 27977 28856 28136 28856 27740 28856 27740 28857 28136 28857 27978 28857 27978 28858 28136 28858 27980 28858 27978 28859 27980 28859 27743 28859 27979 28860 27745 28860 27980 28860 27980 28861 27745 28861 27744 28861 27980 28862 27744 28862 27743 28862 28165 28863 27747 28863 27979 28863 27979 28864 27747 28864 27746 28864 27979 28865 27746 28865 27745 28865 27982 28866 27981 28866 28165 28866 28165 28867 27981 28867 27748 28867 28165 28868 27748 28868 27747 28868 28164 28869 27986 28869 27982 28869 27982 28870 27986 28870 27749 28870 27982 28871 27749 28871 27981 28871 27753 28872 27983 28872 28162 28872 28162 28873 27983 28873 27984 28873 28162 28874 27984 28874 28164 28874 28164 28875 27984 28875 27985 28875 28164 28876 27985 28876 27986 28876 27753 28877 28162 28877 27987 28877 27987 28878 28162 28878 28161 28878 27987 28879 28161 28879 27988 28879 27988 28880 28161 28880 27989 28880 27989 28881 28161 28881 27993 28881 27989 28882 27993 28882 27990 28882 27991 28883 27992 28883 27993 28883 27993 28884 27992 28884 27994 28884 27993 28885 27994 28885 27990 28885 28159 28886 27758 28886 27991 28886 27991 28887 27758 28887 27995 28887 27991 28888 27995 28888 27992 28888 28158 28889 27996 28889 28159 28889 28159 28890 27996 28890 27759 28890 28159 28891 27759 28891 27758 28891 28156 28892 28001 28892 28158 28892 28158 28893 28001 28893 27760 28893 28158 28894 27760 28895 27996 28896 27763 28897 27997 28898 27998 28899 27998 28900 27997 28900 27999 28900 27998 28901 27999 28901 28156 28901 28156 28902 27999 28903 28000 28904 28156 28905 28000 28905 28001 28905 27763 28906 27998 28906 27765 28906 27765 28907 27998 28907 28002 28907 27765 28908 28002 28908 27766 28908 27766 28909 28002 28910 27767 28911 27767 28912 28002 28912 28153 28912 27767 28913 28153 28913 28003 28913 28004 28914 28008 28914 28153 28914 28153 28915 28008 28915 27769 28915 28153 28916 27769 28916 28003 28916 27949 28917 28005 28917 28007 28917 28007 28918 28005 28918 28006 28918 28007 28919 28006 28919 28004 28919 28004 28920 28006 28920 27770 28920 28004 28921 27770 28921 28008 28921 28039 28922 28009 28922 28040 28922 28053 28923 28010 28923 28055 28923 28066 28924 28011 28924 28012 28924 28013 28925 28053 28925 28054 28925 28014 28926 28015 28926 28016 28926 28016 28927 28015 28927 28017 28927 28016 28928 28017 28928 28019 28928 28019 28929 28017 28929 28018 28929 28019 28930 28018 28930 28078 28930 28078 28931 28018 28931 28020 28931 28078 28932 28020 28932 28021 28932 28021 28933 28020 28933 28022 28933 28021 28934 28022 28934 28080 28934 28080 28935 28022 28935 28023 28935 28080 28936 28023 28936 28024 28936 28024 28937 28023 28937 28025 28937 28024 28937 28025 28937 28081 28937 28081 28938 28025 28938 28013 28938 28081 28938 28013 28938 28026 28938 28026 28939 28013 28939 28054 28939 28050 28940 28027 28940 28051 28940 28028 28941 28039 28941 28098 28941 28067 28942 28069 28942 28092 28942 28092 28943 28069 28943 28029 28943 28092 28944 28029 28944 28030 28944 28030 28945 28029 28945 28032 28945 28030 28946 28032 28946 28031 28946 28031 28947 28032 28947 28033 28947 28031 28948 28033 28948 28093 28948 28093 28949 28033 28949 28034 28949 28093 28950 28034 28950 28035 28950 28035 28951 28034 28951 28036 28951 28035 28952 28036 28952 28094 28952 28094 28953 28036 28953 28037 28953 28094 28954 28037 28954 28038 28954 28038 28955 28037 28955 28028 28955 28038 28956 28028 28956 28097 28956 28097 28957 28028 28957 28098 28957 28039 28958 28040 28958 28098 28958 28098 28959 28040 28959 28041 28959 28098 28960 28041 28960 28042 28960 28042 28961 28041 28961 28043 28961 28042 28962 28043 28962 28100 28962 28100 28963 28043 28963 28044 28963 28100 28964 28044 28964 28071 28964 28071 28965 28044 28965 28046 28965 28071 28965 28046 28965 28045 28965 28045 28966 28046 28966 28047 28966 28045 28966 28047 28966 28072 28966 28072 28967 28047 28967 28048 28967 28072 28968 28048 28968 28049 28968 28049 28969 28048 28969 28050 28969 28049 28970 28050 28970 28075 28970 28075 28971 28050 28971 28051 28971 28075 28972 28051 28972 28014 28972 28014 28973 28051 28973 28052 28973 28014 28974 28052 28974 28015 28974 28053 28975 28055 28975 28054 28975 28054 28976 28055 28976 28056 28976 28054 28977 28056 28977 28057 28977 28057 28978 28056 28978 28058 28978 28057 28979 28058 28979 28085 28979 28085 28980 28058 28980 28059 28980 28085 28981 28059 28981 28086 28981 28086 28982 28059 28982 28060 28982 28086 28983 28060 28983 28062 28983 28062 28984 28060 28984 28061 28984 28062 28985 28061 28985 28089 28985 28089 28986 28061 28986 28063 28986 28089 28987 28063 28987 28090 28987 28090 28988 28063 28988 28064 28988 28090 28989 28064 28989 28065 28989 28065 28990 28064 28990 28066 28990 28065 28991 28066 28991 28091 28991 28091 28992 28066 28992 28012 28992 28091 28993 28012 28993 28067 28993 28067 28994 28012 28994 28068 28994 28067 28995 28068 28995 28069 28995 28100 28996 28071 28996 28070 28996 28070 960 28071 960 28045 960 28070 28997 28045 28997 28120 28997 28120 28998 28045 28998 28072 28998 28120 960 28072 960 28073 960 28073 28999 28072 28999 28049 28999 28073 960 28049 960 28074 960 28074 29000 28049 29000 28075 29000 28074 29001 28075 29001 28076 29001 28076 29002 28075 29002 28014 29002 28076 29003 28014 29003 28123 29003 28123 29004 28014 29004 28016 29004 28123 960 28016 960 28126 960 28126 960 28016 960 28019 960 28126 960 28019 960 28077 960 28077 960 28019 960 28078 960 28077 29005 28078 29005 28128 29005 28128 960 28078 960 28021 960 28128 960 28021 960 28079 960 28079 29006 28021 29006 28080 29006 28079 29007 28080 29007 28130 29007 28130 960 28080 960 28024 960 28130 960 28024 960 28082 960 28082 960 28024 960 28081 960 28082 960 28081 960 28083 960 28083 960 28081 960 28026 960 28083 960 28026 960 28132 960 28132 960 28026 960 28054 960 28132 29008 28054 29008 28084 29008 28084 960 28054 960 28057 960 28084 960 28057 960 28134 960 28134 960 28057 960 28085 960 28134 29009 28085 29009 28135 29009 28135 960 28085 960 28086 960 28135 29010 28086 29010 28087 29010 28087 960 28086 960 28062 960 28087 29011 28062 29011 28088 29011 28088 960 28062 960 28089 960 28088 29012 28089 29012 28102 29012 28102 960 28089 960 28090 960 28102 29013 28090 29013 28103 29013 28103 960 28090 960 28065 960 28103 960 28065 960 28104 960 28104 29014 28065 29014 28091 29014 28104 960 28091 960 28105 960 28105 29015 28091 29015 28067 29015 28105 960 28067 960 28106 960 28106 29016 28067 29016 28092 29016 28106 960 28092 960 28108 960 28108 29017 28092 29017 28030 29017 28108 960 28030 960 28110 960 28110 960 28030 960 28031 960 28110 960 28031 960 28111 960 28111 29018 28031 29018 28093 29018 28111 960 28093 960 28112 960 28112 960 28093 960 28035 960 28112 960 28035 960 28114 960 28114 29019 28035 29019 28094 29019 28114 960 28094 960 28095 960 28095 960 28094 960 28038 960 28095 960 28038 960 28096 960 28096 960 28038 960 28097 960 28096 960 28097 960 28117 960 28117 29020 28097 29020 28098 29020 28117 29021 28098 29021 28099 29021 28099 960 28098 960 28042 960 28099 960 28042 960 28118 960 28118 960 28042 960 28100 960 28118 960 28100 960 28070 960 28151 29022 28087 29022 28101 29022 28101 29023 28087 29023 28088 29023 28101 29024 28088 29024 28150 29024 28150 29025 28088 29025 28102 29025 28150 29025 28102 29025 28149 29025 28149 29026 28102 29026 28103 29026 28149 29026 28103 29026 28148 29026 28148 29027 28103 29027 28104 29027 28148 29028 28104 29028 28147 29028 28147 29029 28104 29029 28105 29029 28147 29030 28105 29030 28146 29030 28146 29031 28105 29031 28106 29031 28146 29032 28106 29032 28107 29032 28107 29033 28106 29033 28108 29033 28107 29034 28108 29034 28144 29034 28144 29035 28108 29035 28110 29035 28144 29036 28110 29036 28109 29036 28109 29037 28110 29037 28111 29037 28109 29038 28111 29038 28142 29038 28142 29039 28111 29039 28112 29039 28142 29040 28112 29040 28113 29040 28113 29041 28112 29041 28114 29041 28113 29041 28114 29041 28115 29041 28115 29042 28114 29042 28095 29042 28115 29043 28095 29043 28140 29043 28140 29044 28095 29044 28096 29044 28140 29045 28096 29045 28116 29045 28116 29046 28096 29046 28117 29046 28116 29047 28117 29047 28139 29047 28139 29048 28117 29048 28099 29048 28139 29049 28099 29049 28138 29049 28138 29050 28099 29050 28118 29050 28138 29051 28118 29051 28119 29051 28119 29052 28118 29052 28070 29052 28119 29053 28070 29053 28167 29053 28167 29054 28070 29054 28120 29054 28167 29055 28120 29055 28166 29055 28166 29056 28120 29056 28073 29056 28166 29057 28073 29057 28121 29057 28121 29058 28073 29058 28074 29058 28121 29059 28074 29059 28122 29059 28122 29060 28074 29060 28076 29060 28122 29061 28076 29061 28124 29061 28124 29062 28076 29062 28123 29062 28124 29063 28123 29063 28163 29063 28163 29064 28123 29064 28126 29064 28163 29065 28126 29065 28125 29065 28125 29066 28126 29066 28077 29066 28125 29067 28077 29067 28127 29067 28127 29068 28077 29068 28128 29068 28127 29068 28128 29068 28160 29068 28160 29069 28128 29069 28079 29069 28160 29070 28079 29070 28129 29070 28129 29071 28079 29071 28130 29071 28129 29072 28130 29072 28131 29072 28131 29073 28130 29073 28082 29073 28131 29074 28082 29074 28157 29074 28157 29075 28082 29075 28083 29075 28157 29076 28083 29076 28155 29076 28155 29077 28083 29077 28132 29077 28155 29078 28132 29078 28133 29078 28133 29079 28132 29079 28084 29079 28133 29080 28084 29080 28154 29080 28154 29081 28084 29081 28134 29081 28154 29082 28134 29082 28152 29082 28152 29083 28134 29083 28135 29083 28152 29084 28135 29084 28151 29084 28151 29085 28135 29085 28087 29085 27980 590 28136 590 28167 590 28167 590 28136 590 27976 590 28167 29086 27976 29086 28119 29086 28119 590 27976 590 28137 590 28119 590 28137 590 28138 590 28138 590 28137 590 27970 590 28138 29087 27970 29087 28139 29087 28139 590 27970 590 27971 590 28139 590 27971 590 28116 590 28116 590 27971 590 27968 590 28116 29088 27968 29088 28140 29088 28140 590 27968 590 27966 590 28140 590 27966 590 28115 590 28115 590 27966 590 28141 590 28115 29089 28141 29089 28113 29089 28113 590 28141 590 27961 590 28113 29090 27961 29090 28142 29090 28142 590 27961 590 28143 590 28142 590 28143 590 28109 590 28109 590 28143 590 28145 590 28109 29091 28145 29091 28144 29091 28144 590 28145 590 27956 590 28144 29092 27956 29092 28107 29092 28107 29093 27956 29093 27957 29093 28107 29094 27957 29094 28146 29094 28146 29095 27957 29095 27955 29095 28146 590 27955 590 28147 590 28147 29096 27955 29096 27953 29096 28147 590 27953 590 28148 590 28148 29097 27953 29097 27951 29097 28148 590 27951 590 28149 590 28149 590 27951 590 27946 590 28149 590 27946 590 28150 590 28150 590 27946 590 27948 590 28150 590 27948 590 28101 590 28101 590 27948 590 28007 590 28101 590 28007 590 28151 590 28151 590 28007 590 28004 590 28151 29098 28004 29098 28152 29098 28152 590 28004 590 28153 590 28152 29099 28153 29099 28154 29099 28154 590 28153 590 28002 590 28154 590 28002 590 28133 590 28133 29100 28002 29100 27998 29100 28133 29101 27998 29101 28155 29101 28155 590 27998 590 28156 590 28155 590 28156 590 28157 590 28157 29102 28156 29102 28158 29102 28157 590 28158 590 28131 590 28131 590 28158 590 28159 590 28131 590 28159 590 28129 590 28129 590 28159 590 27991 590 28129 590 27991 590 28160 590 28160 590 27991 590 27993 590 28160 29103 27993 29103 28127 29103 28127 590 27993 590 28161 590 28127 29104 28161 29104 28125 29104 28125 590 28161 590 28162 590 28125 29105 28162 29105 28163 29105 28163 590 28162 590 28164 590 28163 29106 28164 29106 28124 29106 28124 590 28164 590 27982 590 28124 590 27982 590 28122 590 28122 29107 27982 29107 28165 29107 28122 590 28165 590 28121 590 28121 29108 28165 29108 27979 29108 28121 29109 27979 29109 28166 29109 28166 29110 27979 29110 27980 29110 28166 29111 27980 29111 28167 29111 28168 29112 28170 29112 28169 29112 28169 29113 28170 29113 28171 29113 28169 29114 28171 29114 28173 29114 28173 29115 28171 29115 28172 29115 28173 29116 28172 29116 28174 29116 28174 29117 28172 29117 28175 29117 28174 29118 28175 29118 28176 29118 28176 29119 28175 29119 28177 29119 28176 29120 28177 29120 28178 29120 28178 29121 28177 29121 28179 29121 28178 29122 28179 29122 28181 29122 28181 29123 28179 29123 28180 29123 28181 29123 28180 29123 28182 29123 28182 29124 28180 29124 28184 29124 28182 29125 28184 29125 28183 29125 28183 29126 28184 29126 28186 29126 28183 29127 28186 29127 28185 29127 28185 29128 28186 29128 28187 29128 28185 29129 28187 29129 28188 29129 28188 29130 28187 29130 28190 29130 28188 29131 28190 29131 28189 29131 28189 29132 28190 29132 28191 29132 28189 29133 28191 29133 28192 29133 28192 29134 28191 29134 28194 29134 28192 29135 28194 29135 28193 29135 28193 29136 28194 29136 28195 29136 28193 29137 28195 29137 28196 29137 28196 29138 28195 29138 28197 29138 28196 29139 28197 29139 28198 29139 28198 29140 28197 29140 28199 29140 28198 29141 28199 29141 28200 29141 28200 29142 28199 29142 28201 29142 28200 29143 28201 29143 28202 29143 28202 29144 28201 29144 28203 29144 28202 29145 28203 29145 28204 29145 28204 29146 28203 29146 28206 29146 28204 29147 28206 29147 28205 29147 28205 29148 28206 29148 28208 29148 28205 29149 28208 29149 28207 29149 28207 29150 28208 29150 28209 29150 28207 29151 28209 29151 28211 29151 28211 29152 28209 29152 28210 29152 28211 29153 28210 29153 28212 29153 28212 29154 28210 29154 28213 29154 28212 29155 28213 29155 28215 29155 28215 29156 28213 29156 28214 29156 28215 29157 28214 29157 28217 29157 28217 29158 28214 29158 28216 29158 28217 29159 28216 29159 28219 29159 28219 29160 28216 29160 28218 29160 28219 29161 28218 29161 28220 29161 28220 29162 28218 29162 28221 29162 28220 29163 28221 29163 28222 29163 28222 29164 28221 29164 28223 29164 28222 29165 28223 29165 28224 29165 28224 29166 28223 29166 28226 29166 28224 29167 28226 29167 28225 29167 28225 29168 28226 29168 28227 29168 28225 29169 28227 29169 28228 29169 28228 29170 28227 29170 28230 29170 28228 29171 28230 29171 28229 29171 28229 29172 28230 29172 28231 29172 28229 29173 28231 29173 28232 29173 28232 29174 28231 29174 28233 29174 28232 29175 28233 29175 28234 29175 28234 29176 28233 29176 28236 29176 28234 29177 28236 29177 28235 29177 28235 29178 28236 29178 28237 29178 28235 29179 28237 29179 28238 29179 28238 29180 28237 29180 28239 29180 28238 29181 28239 29181 28240 29181 28240 29182 28239 29182 28242 29182 28240 29183 28242 29183 28241 29183 28241 29184 28242 29184 28243 29184 28241 29185 28243 29185 28244 29185 28244 29186 28243 29186 28245 29186 28244 29187 28245 29187 28168 29187 28168 29188 28245 29188 28170 29188 28319 29189 28321 29189 28246 29189 28246 29190 28321 29190 28247 29190 28246 29191 28247 29191 28248 29191 28248 29192 28247 29192 28249 29192 28248 29193 28249 29193 28250 29193 28250 29194 28249 29194 28251 29194 28250 29195 28251 29195 28253 29195 28253 29196 28251 29196 28252 29196 28253 29197 28252 29197 28254 29197 28254 29198 28252 29198 28256 29198 28254 29199 28256 29199 28255 29199 28255 29200 28256 29200 28257 29200 28255 29201 28257 29201 28259 29201 28259 29202 28257 29202 28258 29202 28259 29203 28258 29203 28261 29203 28261 29204 28258 29204 28260 29204 28261 29205 28260 29205 28262 29205 28262 29206 28260 29206 28264 29206 28262 29207 28264 29207 28263 29207 28263 29208 28264 29208 28265 29208 28263 29209 28265 29209 28266 29209 28266 29210 28265 29210 28267 29210 28266 29211 28267 29211 28268 29211 28268 29212 28267 29212 28269 29212 28268 29213 28269 29213 28271 29213 28271 29214 28269 29214 28270 29214 28271 29214 28270 29214 28272 29214 28272 29215 28270 29215 28273 29215 28272 29216 28273 29216 28274 29216 28274 29217 28273 29217 28275 29217 28274 29217 28275 29217 28276 29217 28276 29218 28275 29218 28277 29218 28276 29219 28277 29219 28278 29219 28278 29220 28277 29220 28280 29220 28278 29221 28280 29221 28279 29221 28279 29222 28280 29222 28281 29222 28279 29222 28281 29222 28282 29222 28282 29223 28281 29223 28283 29223 28282 29224 28283 29224 28284 29224 28284 29225 28283 29225 28285 29225 28284 29226 28285 29226 28286 29226 28286 29227 28285 29227 28287 29227 28286 29228 28287 29228 28289 29228 28289 29229 28287 29229 28288 29229 28289 29230 28288 29230 28290 29230 28290 29231 28288 29231 28292 29231 28290 29232 28292 29232 28291 29232 28291 29233 28292 29233 28293 29233 28291 29234 28293 29234 28295 29234 28295 29235 28293 29235 28294 29235 28295 29236 28294 29236 28296 29236 28296 29237 28294 29237 28297 29237 28296 29238 28297 29238 28298 29238 28298 29239 28297 29239 28299 29239 28298 29240 28299 29240 28300 29240 28300 29241 28299 29241 28301 29241 28300 29242 28301 29242 28302 29242 28302 29243 28301 29243 28303 29243 28302 29244 28303 29244 28304 29244 28304 29245 28303 29245 28306 29245 28304 29246 28306 29246 28305 29246 28305 29247 28306 29247 28307 29247 28305 29248 28307 29248 28308 29248 28308 29249 28307 29249 28310 29249 28308 29249 28310 29249 28309 29249 28309 29250 28310 29250 28311 29250 28309 29251 28311 29251 28312 29251 28312 29252 28311 29252 28314 29252 28312 29253 28314 29253 28313 29253 28313 29254 28314 29254 28315 29254 28313 29255 28315 29255 28316 29255 28316 29256 28315 29256 28317 29256 28316 29257 28317 29257 28318 29257 28318 29258 28317 29258 28320 29258 28318 29259 28320 29259 28319 29259 28319 29260 28320 29260 28321 29260 28852 29261 28322 29261 28323 29261 28852 29262 28323 29262 28324 29262 28331 29263 28325 29263 28852 29263 28852 29264 28325 29264 28326 29264 28852 29265 28326 29265 28322 29265 28327 29266 28328 29266 28330 29266 28330 29267 28328 29267 28329 29267 28330 29268 28329 29268 28331 29268 28331 29269 28329 29269 28332 29269 28331 29270 28332 29270 28325 29270 28323 29271 28333 29271 28324 29271 28324 29272 28333 29272 28334 29272 28324 29273 28334 29273 28335 29273 28335 29274 28334 29274 28336 29274 28335 29274 28336 29274 28861 29274 28861 29275 28336 29275 28337 29275 28861 29276 28337 29276 28853 29276 28853 29277 28337 29277 28338 29277 28853 29278 28338 29278 28854 29278 28854 29279 28338 29279 28340 29279 28854 29280 28340 29280 28339 29280 28339 29281 28340 29281 28341 29281 28339 29281 28341 29281 28863 29281 28863 29282 28341 29282 28342 29282 28863 29283 28342 29283 28864 29283 28864 29284 28342 29284 28343 29284 28864 29284 28343 29284 28865 29284 28865 29285 28343 29285 28344 29285 28865 29286 28344 29286 28345 29286 28345 29287 28344 29287 28346 29287 28345 29288 28346 29288 28347 29288 28347 29289 28346 29289 28349 29289 28347 29289 28349 29289 28348 29289 28348 29290 28349 29290 28350 29290 28348 29291 28350 29291 28858 29291 28858 29292 28350 29292 28351 29292 28858 29293 28351 29293 28327 29293 28327 29294 28351 29294 28352 29294 28327 29295 28352 29295 28328 29295 28353 29296 28810 29296 28354 29296 28354 29297 28810 29297 28802 29297 28354 29298 28802 29298 28369 29298 28358 29299 28355 29299 28356 29299 28356 29300 28355 29300 28357 29300 28356 29301 28357 29301 28353 29301 28353 29302 28357 29302 28811 29302 28353 29303 28811 29303 28810 29303 28363 29304 28359 29304 28358 29304 28358 29305 28359 29305 28813 29305 28358 29306 28813 29306 28355 29306 28360 29307 28808 29307 28361 29307 28361 29308 28808 29308 28362 29308 28361 29309 28362 29309 28363 29309 28363 29310 28362 29310 28809 29310 28363 29311 28809 29311 28359 29311 28364 29312 28901 29312 28360 29312 28360 29313 28901 29313 28807 29313 28360 29314 28807 29314 28808 29314 28365 13164 28896 13164 28364 13164 28364 29315 28896 29316 28898 29317 28364 29318 28898 29318 28901 29318 28372 29319 28894 29319 28365 29319 28365 13178 28894 13178 28366 13178 28365 13181 28366 13181 28896 13181 28802 29320 28367 29321 28369 29322 28369 29323 28367 29323 28368 29323 28369 29323 28368 29323 28370 29323 28370 29324 28368 29324 28371 29324 28370 29325 28371 29325 28372 29325 28372 29326 28371 29326 28893 29326 28372 29327 28893 29327 28894 29327 28373 29328 28510 29328 28374 29328 28374 29329 28510 29329 28375 29329 28374 29330 28375 29330 28617 29330 28617 29331 28375 29331 28376 29331 28617 29332 28376 29332 28378 29332 28378 29333 28376 29333 28377 29333 28378 29334 28377 29334 28605 29334 28605 29335 28377 29335 28379 29335 28605 29336 28379 29336 28606 29336 28606 29337 28379 29337 28381 29337 28606 29338 28381 29338 28380 29338 28380 29339 28381 29339 28383 29339 28380 29340 28383 29340 28382 29340 28382 29341 28383 29341 28481 29341 28382 29342 28481 29342 28608 29342 28608 29343 28481 29343 28541 29343 28867 29344 28384 29344 28483 29344 28483 29345 28384 29345 28611 29345 28483 29346 28611 29346 28480 29346 28480 29347 28611 29347 28385 29347 28480 29348 28385 29348 28386 29348 28386 29349 28385 29349 28610 29349 28386 29350 28610 29350 28541 29350 28541 29351 28610 29351 28609 29351 28541 29352 28609 29352 28608 29352 28387 29353 28388 29353 28389 29353 28475 29354 28581 29354 28477 29354 28390 29355 28391 29355 28457 29355 28392 29356 28395 29356 28393 29356 28393 29357 28395 29357 28406 29357 28393 29358 28406 29358 28904 29358 28392 29359 28394 29359 28395 29359 28395 29360 28394 29360 28396 29360 28395 29361 28396 29361 28397 29361 28521 29362 28399 29362 28398 29362 28398 29363 28399 29363 28400 29363 28398 29364 28400 29364 28401 29364 28401 29365 28402 29365 28398 29365 28398 29366 28402 29366 28403 29366 28398 29367 28403 29367 28404 29367 28405 29368 28407 29368 28406 29368 28406 29369 28407 29369 28905 29369 28406 29370 28905 29370 28904 29370 28408 29371 28409 29371 28405 29371 28405 29372 28409 29372 28891 29372 28405 29373 28891 29373 28407 29373 28411 29374 28895 29374 28408 29374 28408 29375 28895 29375 28892 29375 28408 29376 28892 29376 28409 29376 28425 29377 28899 29377 28410 29377 28410 29378 28899 29378 28897 29378 28410 29379 28897 29379 28411 29379 28411 29380 28897 29380 28412 29380 28411 29381 28412 29381 28895 29381 28413 29382 28419 29382 28422 29382 28414 29383 28415 29383 28532 29383 28414 29384 28532 29384 28418 29384 28426 29385 28416 29385 28532 29385 28532 29386 28416 29386 28417 29386 28532 29387 28417 29387 28418 29387 28419 29388 28420 29388 28422 29388 28422 29389 28420 29389 28421 29389 28422 29390 28421 29390 28425 29390 28425 29391 28421 29391 28423 29391 28425 29392 28423 29392 28803 29392 28803 29393 28424 29393 28425 29393 28425 29394 28424 29394 28900 29394 28425 29395 28900 29395 28899 29395 28431 29396 28427 29396 28426 29396 28426 29397 28427 29397 28428 29397 28426 29398 28428 29398 28416 29398 28434 23081 28429 23081 28555 23081 28555 23082 28429 23082 28430 23082 28555 29399 28430 29399 28557 29399 28557 29400 28430 29400 28431 29400 28557 29401 28431 29401 28558 29401 28558 29402 28431 29402 28426 29402 28403 29403 28432 29403 28404 29403 28404 29404 28432 29404 28433 29404 28404 29405 28433 29405 28434 29405 28434 29406 28433 29406 28435 29406 28434 29407 28435 29407 28429 29407 28436 29408 28437 29408 28438 29408 28438 29409 28437 29409 28450 29409 28438 29410 28450 29410 28842 29410 28842 29411 28450 29411 28449 29411 28436 29412 28439 29412 28437 29412 28437 29413 28439 29413 28440 29413 28437 29414 28440 29414 28441 29414 28531 29415 28443 29415 28442 29415 28442 29416 28443 29416 28444 29416 28442 29417 28444 29417 28445 29417 28445 29418 28446 29418 28442 29418 28442 29419 28446 29419 28447 29419 28442 29420 28447 29420 28448 29420 28449 29421 28450 29422 28843 29423 28843 29424 28450 29424 28451 29424 28843 29425 28451 29425 28845 29425 28845 29426 28451 29426 28836 29426 28836 29427 28451 29427 28452 29427 28836 29428 28452 29428 28453 29428 28453 29429 28452 29429 28390 29429 28390 29430 28452 29430 28454 29430 28390 29431 28454 29431 28391 29431 28470 29432 28455 29432 28456 29432 28456 29433 28455 29433 28832 29433 28456 29434 28832 29434 28457 29434 28457 29435 28832 29435 28458 29435 28457 29436 28458 29436 28390 29436 28459 29437 28460 29437 28512 29437 28461 29438 28462 29438 28463 29438 28461 29439 28463 29439 28466 29439 28547 29440 28464 29440 28463 29440 28463 29441 28464 29441 28465 29441 28463 29442 28465 29442 28466 29442 28460 29443 28467 29443 28512 29443 28512 29444 28467 29444 28468 29444 28512 29445 28468 29445 28456 29445 28456 29446 28468 29446 28469 29446 28456 29447 28469 29447 28470 29447 28473 29448 28471 29448 28547 29448 28547 29449 28471 29449 28472 29449 28547 29450 28472 29450 28464 29450 28547 29451 28545 29451 28473 29451 28473 29452 28545 29452 28543 29452 28473 29453 28543 29453 28474 29453 28474 29454 28543 29454 28475 29454 28475 29455 28543 29455 28542 29455 28475 29456 28542 29456 28581 29456 28447 29457 28476 29457 28448 29457 28448 29458 28476 29458 28478 29458 28448 22979 28478 22979 28477 22979 28477 22980 28478 22980 28479 22980 28477 29459 28479 29459 28475 29459 28483 29460 28480 29460 28540 29460 28540 29461 28480 29461 28386 29461 28540 29462 28386 29462 28541 29462 28481 29463 28383 29463 28482 29463 28482 29464 28383 29464 28381 29464 28482 29465 28381 29465 28379 29465 28375 29466 28566 29467 28376 29468 28376 29469 28566 29469 28482 29469 28376 29470 28482 29470 28377 29470 28377 29471 28482 29471 28379 29471 28483 29472 28540 29472 28867 29472 28867 29473 28540 29473 28484 29473 28867 29474 28484 29474 28868 29474 28868 29475 28484 29475 28486 29475 28868 29476 28486 29476 28485 29476 28485 29477 28486 29477 28871 29477 28871 29478 28486 29478 28487 29478 28871 29479 28487 29479 28488 29479 28388 29480 28387 29480 28487 29480 28487 29481 28387 29481 28746 29481 28487 29482 28746 29482 28488 29482 28489 29483 28860 29483 28500 29483 28500 29484 28860 29484 28749 29484 28500 29485 28749 29485 28389 29485 28389 29486 28749 29486 28490 29486 28389 29487 28490 29487 28387 29487 28522 29488 28497 29488 28491 29488 28493 29489 28492 29489 28523 29489 28493 29490 28523 29490 28496 29490 28502 29491 28494 29491 28523 29491 28523 29492 28494 29492 28495 29492 28523 29493 28495 29493 28496 29493 28497 29494 28498 29494 28491 29494 28491 29495 28498 29495 28499 29495 28491 29496 28499 29496 28500 29496 28500 29497 28499 29497 28501 29497 28500 29498 28501 29498 28489 29498 28509 29499 28503 29499 28502 29499 28502 29500 28503 29501 28504 29502 28502 29503 28504 29503 28494 29503 28505 29504 28506 29504 28507 29504 28507 29505 28506 29505 28508 29505 28507 29506 28508 29506 28570 29506 28570 29507 28508 29507 28509 29507 28570 29508 28509 29508 28571 29508 28571 29509 28509 29509 28502 29509 28375 29510 28510 29510 28566 29510 28566 29511 28510 29511 28373 29511 28566 29512 28373 29512 28505 29512 28505 29513 28373 29513 28511 29513 28505 29514 28511 29514 28506 29514 28462 29515 28459 29515 28463 29515 28463 29516 28459 29516 28512 29516 28463 29517 28512 29517 28549 29517 28549 23127 28512 23127 28513 23127 28549 29518 28513 29518 28514 29518 28514 29519 28513 29519 28515 29519 28514 29520 28515 29520 28517 29520 28517 29521 28515 29521 28516 29521 28517 29522 28516 29522 28519 29522 28519 29523 28516 29523 28518 29523 28519 29524 28518 29524 28553 29524 28553 29525 28518 29525 28520 29525 28553 29526 28520 29526 28398 29526 28398 23137 28520 23137 28395 23137 28398 29527 28395 29527 28521 29527 28521 29528 28395 29528 28397 29528 28492 29529 28522 29529 28523 29529 28523 29530 28522 29530 28491 29530 28523 29531 28491 29531 28573 29531 28573 29532 28491 29532 28524 29532 28573 29533 28524 29533 28525 29533 28525 29534 28524 29534 28526 29534 28525 29535 28526 29535 28575 29535 28575 29536 28526 29536 28527 29536 28575 29537 28527 29537 28578 29537 28578 23101 28527 23101 28528 23101 28578 29538 28528 29538 28529 29538 28529 29539 28528 29539 28530 29539 28529 29540 28530 29540 28442 29540 28442 29541 28530 29541 28437 29541 28442 29542 28437 29542 28531 29542 28531 29543 28437 29543 28441 29543 28415 29544 28413 29544 28532 29544 28532 29545 28413 29545 28422 29545 28532 29546 28422 29546 28534 29546 28534 29547 28422 29547 28533 29547 28534 29548 28533 29548 28561 29548 28561 29549 28533 29549 28535 29549 28561 29550 28535 29550 28562 29550 28562 29551 28535 29551 28536 29551 28562 29552 28536 29552 28537 29552 28537 29553 28536 29553 28538 29553 28537 29554 28538 29554 28564 29554 28564 29555 28538 29555 28539 29555 28564 29556 28539 29556 28482 29556 28482 23121 28539 23121 28540 23121 28482 29557 28540 29557 28481 29557 28481 29558 28540 29558 28541 29558 28581 960 28542 960 28544 960 28544 29559 28542 29559 28543 29559 28544 29560 28543 29560 28639 29560 28639 960 28543 960 28545 960 28639 29561 28545 29561 28546 29561 28546 960 28545 960 28547 960 28546 960 28547 960 28647 960 28647 960 28547 960 28463 960 28647 960 28463 960 28548 960 28548 29562 28463 29562 28549 29562 28548 960 28549 960 28550 960 28550 960 28549 960 28514 960 28550 960 28514 960 28679 960 28679 960 28514 960 28517 960 28679 960 28517 960 28551 960 28551 960 28517 960 28519 960 28551 960 28519 960 28552 960 28552 960 28519 960 28553 960 28552 29563 28553 29563 28664 29563 28664 960 28553 960 28398 960 28664 960 28398 960 28662 960 28662 960 28398 960 28404 960 28662 960 28404 960 28583 960 28583 960 28404 960 28434 960 28583 960 28434 960 28554 960 28554 960 28434 960 28555 960 28554 960 28555 960 28556 960 28556 29564 28555 29564 28557 29564 28556 29565 28557 29565 28588 29565 28588 960 28557 960 28558 960 28588 29566 28558 29566 28559 29566 28559 960 28558 960 28426 960 28559 960 28426 960 28670 960 28670 960 28426 960 28532 960 28670 960 28532 960 28560 960 28560 960 28532 960 28534 960 28560 29567 28534 29567 28671 29567 28671 960 28534 960 28561 960 28671 960 28561 960 28692 960 28692 960 28561 960 28562 960 28692 960 28562 960 28563 960 28563 960 28562 960 28537 960 28563 29568 28537 29568 28689 29568 28689 960 28537 960 28564 960 28689 29569 28564 29569 28607 29569 28607 960 28564 960 28482 960 28607 960 28482 960 28616 960 28616 960 28482 960 28566 960 28616 960 28566 960 28565 960 28565 29570 28566 29570 28505 29570 28565 960 28505 960 28567 960 28567 960 28505 960 28507 960 28567 960 28507 960 28568 960 28568 960 28507 960 28570 960 28568 960 28570 960 28569 960 28569 29571 28570 29571 28571 29571 28569 29572 28571 29572 28572 29572 28572 29573 28571 29573 28502 29573 28572 960 28502 960 28626 960 28626 960 28502 960 28523 960 28626 29574 28523 29574 28686 29574 28686 29575 28523 29575 28573 29575 28686 960 28573 960 28687 960 28687 960 28573 960 28525 960 28687 960 28525 960 28574 960 28574 29576 28525 29576 28575 29576 28574 960 28575 960 28576 960 28576 29577 28575 29577 28578 29577 28576 960 28578 960 28577 960 28577 960 28578 960 28529 960 28577 960 28529 960 28644 960 28644 960 28529 960 28442 960 28644 960 28442 960 28579 960 28579 29578 28442 29578 28448 29578 28579 960 28448 960 28580 960 28580 29579 28448 29579 28477 29579 28580 29580 28477 29580 28544 29580 28544 960 28477 960 28581 960 28582 29581 28696 29581 28633 29581 28662 29582 28583 29582 28584 29582 28584 29583 28583 29583 28554 29583 28584 29584 28554 29584 28585 29584 28585 29585 28554 29585 28556 29585 28585 29586 28556 29586 28586 29586 28586 29587 28556 29587 28588 29587 28586 29588 28588 29588 28587 29588 28587 29589 28588 29589 28559 29589 28587 29590 28559 29590 28589 29590 28595 29591 28590 29591 28670 29591 28597 29592 28599 29592 28591 29592 28591 29593 28599 29593 28593 29593 28591 29594 28593 29594 28592 29594 28592 29595 28593 29595 28594 29595 28595 29596 28670 29596 28596 29596 28597 29597 28598 29597 28599 29597 28599 29598 28598 29598 28600 29598 28599 29599 28600 29599 28601 29599 28590 29600 28602 29600 28670 29600 28670 29601 28602 29601 28603 29601 28670 29602 28603 29602 28559 29602 28559 29603 28603 29603 28604 29603 28559 29604 28604 29604 28589 29604 28606 29605 28607 29605 28605 29605 28605 29606 28607 29606 28378 29606 28606 29607 28380 29607 28607 29607 28607 29608 28380 29608 28382 29608 28607 29609 28382 29609 28608 29609 28609 29610 28610 29610 28872 29610 28872 29611 28610 29611 28385 29611 28872 29612 28385 29612 28866 29612 28866 29613 28385 29613 28611 29613 28866 29614 28611 29614 28384 29614 28569 29615 28612 29615 28568 29615 28568 29616 28612 29616 28613 29616 28568 29617 28613 29617 28567 29617 28567 29618 28613 29618 28614 29618 28567 29619 28614 29619 28565 29619 28565 29620 28614 29620 28615 29620 28565 29621 28615 29621 28616 29621 28616 29622 28615 29622 28374 29622 28616 29623 28374 29623 28607 29623 28607 29624 28374 29624 28617 29624 28607 29625 28617 29625 28378 29625 28572 29626 28629 29626 28569 29626 28569 29627 28629 29627 28618 29627 28569 29628 28618 29628 28612 29628 28859 29629 28851 29629 28619 29629 28619 29630 28620 29630 28859 29630 28859 29631 28620 29631 28621 29631 28859 29632 28621 29632 28622 29632 28685 29633 28623 29633 28626 29633 28626 29634 28623 29634 28624 29634 28624 29635 28625 29635 28626 29635 28626 29636 28625 29636 28627 29636 28626 29637 28627 29637 28572 29637 28572 29638 28627 29638 28628 29638 28572 29639 28628 29639 28629 29639 28683 29640 28630 29640 28708 29640 28708 29641 28630 29641 28631 29641 28708 29642 28631 29642 28700 29642 28700 29643 28631 29643 28632 29643 28700 29644 28632 29644 28633 29644 28633 29645 28632 29646 28634 29647 28633 29648 28634 29649 28582 29650 28682 29651 28577 29651 28635 29651 28635 29652 28577 29652 28644 29652 28635 29653 28644 29653 28636 29653 28636 29654 28644 29654 28637 29654 28546 29655 28638 29655 28639 29655 28639 29656 28638 29656 28640 29656 28639 29657 28640 29657 28544 29657 28544 29658 28640 29658 28641 29658 28544 29659 28641 29659 28580 29659 28580 29660 28641 29660 28642 29660 28580 29661 28642 29661 28579 29661 28579 29662 28642 29662 28643 29662 28579 29663 28643 29663 28644 29663 28644 29664 28643 29664 28645 29664 28644 29665 28645 29665 28637 29665 28653 29666 28646 29666 28647 29666 28647 29667 28646 29667 28648 29667 28647 29668 28648 29668 28546 29668 28546 29669 28648 29669 28649 29669 28546 29670 28649 29670 28638 29670 28677 29671 28650 29671 28548 29671 28548 29672 28650 29672 28651 29672 28548 29673 28651 29673 28647 29673 28647 29674 28651 29674 28652 29674 28647 29675 28652 29675 28653 29675 28716 29676 28655 29677 28654 29678 28654 29679 28655 29679 28656 29679 28654 29680 28656 29680 28913 29680 28913 29681 28656 29681 28657 29681 28913 29682 28657 29682 28658 29682 28658 29683 28657 29683 28676 29683 28658 29684 28676 29684 28915 29684 28666 29685 28667 29685 28903 29685 28659 29686 28672 29686 28664 29686 28659 29687 28664 29687 28660 29687 28584 29688 28661 29688 28662 29688 28662 29689 28661 29689 28663 29689 28662 29690 28663 29690 28664 29690 28664 29691 28663 29691 28665 29691 28664 29692 28665 29692 28660 29692 28666 29693 28903 29693 28672 29693 28667 29694 28668 29694 28903 29694 28903 29695 28668 29695 28669 29695 28903 29696 28669 29696 28906 29696 28601 29697 28596 29697 28599 29697 28599 29698 28596 29698 28670 29698 28599 29699 28670 29699 28806 29699 28806 29700 28670 29700 28560 29700 28806 29701 28560 29701 28762 29701 28762 29702 28560 29702 28671 29702 28762 29703 28671 29703 28764 29703 28672 29704 28903 29704 28664 29704 28664 29705 28903 29705 28902 29705 28664 29706 28902 29706 28552 29706 28673 29707 28551 29707 28674 29707 28674 29708 28551 29708 28552 29708 28674 29709 28552 29709 28675 29709 28675 29710 28552 29710 28902 29710 28676 29711 28677 29711 28915 29711 28915 29712 28677 29712 28548 29712 28915 29713 28548 29713 28916 29713 28916 29714 28548 29714 28550 29714 28916 29715 28550 29715 28678 29715 28678 29716 28550 29716 28679 29716 28678 29717 28679 29717 28680 29717 28680 29718 28679 29718 28551 29718 28680 29719 28551 29719 28681 29719 28681 29720 28551 29721 28673 29722 28682 29723 28683 29723 28577 29723 28577 29724 28683 29724 28708 29724 28577 29725 28708 29725 28576 29725 28576 29726 28708 29726 28684 29726 28576 29727 28684 29727 28574 29727 28848 29728 28687 29728 28713 29728 28713 29729 28687 29729 28574 29729 28713 29730 28574 29730 28711 29730 28711 29731 28574 29731 28684 29731 28622 29732 28685 29732 28859 29732 28859 29733 28685 29733 28626 29733 28859 29734 28626 29734 28857 29734 28857 29735 28626 29735 28686 29735 28857 29736 28686 29736 28856 29736 28856 29737 28686 29737 28687 29737 28856 29738 28687 29738 28850 29738 28850 29739 28687 29739 28848 29739 28688 29740 28689 29740 28889 29740 28889 29741 28689 29741 28607 29741 28889 29742 28607 29742 28872 29742 28872 29743 28607 29743 28608 29743 28872 29744 28608 29744 28609 29744 28688 29745 28690 29745 28689 29745 28689 29746 28690 29746 28695 29746 28689 29747 28695 29747 28563 29747 28563 29748 28695 29748 28691 29748 28563 29749 28691 29749 28692 29749 28692 29750 28691 29750 28693 29750 28692 29751 28693 29751 28671 29751 28671 29752 28693 29752 28694 29752 28671 29753 28694 29753 28764 29753 28905 29754 28407 29754 28890 29754 28693 29755 28691 29755 28695 29755 28790 960 28876 960 28862 960 28696 960 28844 960 28697 960 28697 29756 28698 29756 28696 29756 28696 29757 28698 29757 28699 29757 28696 960 28699 960 28633 960 28633 960 28699 960 28700 960 28800 29758 28705 29758 28844 29758 28844 960 28705 960 28701 960 28844 960 28701 960 28697 960 28847 960 28702 960 28849 960 28849 960 28702 960 28703 960 28849 960 28703 960 28800 960 28800 960 28703 960 28704 960 28800 960 28704 960 28705 960 28699 960 28706 960 28700 960 28700 29759 28706 29759 28707 29759 28700 29760 28707 29760 28708 29760 28708 960 28707 960 28709 960 28708 29761 28709 29761 28684 29761 28684 960 28709 960 28710 960 28684 29762 28710 29762 28711 29762 28711 29763 28710 29763 28712 29763 28711 29764 28712 29764 28713 29764 28713 960 28712 960 28714 960 28713 29765 28714 29765 28848 29765 28848 29766 28714 29766 28715 29766 28470 960 28716 960 28455 960 28455 960 28716 960 28840 960 28455 960 28840 960 28832 960 28913 29767 28912 29767 28730 29767 28911 960 28717 960 28718 960 28718 29768 28717 29768 28719 29768 28718 29769 28719 29769 28914 29769 28720 29770 28721 29770 28725 29770 28725 960 28721 960 28722 960 28722 960 28721 960 28723 960 28723 960 28721 960 28724 960 28723 960 28724 960 28738 960 28722 960 28726 960 28725 960 28725 29771 28726 29771 28727 29771 28725 29772 28727 29772 28825 29772 28825 29773 28727 29773 28728 29773 28825 29774 28728 29774 28911 29774 28911 29775 28728 29775 28729 29775 28911 960 28729 960 28717 960 28913 960 28730 960 28654 960 28654 29776 28730 29776 28731 29776 28654 29777 28731 29777 28716 29777 28716 29778 28731 29778 28732 29778 28716 29779 28732 29779 28840 29779 28840 29780 28732 29780 28733 29780 28840 960 28733 960 28734 960 28735 960 28736 960 28770 960 28724 29781 28737 29781 28738 29781 28738 960 28737 960 28735 960 28738 29782 28735 29782 28739 29782 28739 960 28735 960 28770 960 28742 960 28740 960 28887 960 28887 29783 28740 29783 28741 29783 28887 29784 28741 29784 28886 29784 28742 960 28887 960 28743 960 28743 960 28887 960 28744 960 28743 960 28744 960 28870 960 28871 960 28488 960 28869 960 28869 29785 28488 29785 28746 29785 28869 29786 28746 29786 28745 29786 28745 29787 28746 29787 28747 29787 28746 960 28387 960 28747 960 28747 960 28387 960 28490 960 28747 960 28490 960 28748 960 28748 29788 28490 29788 28749 29788 28748 29789 28749 29789 28750 29789 28750 960 28749 960 28862 960 28750 29790 28862 29790 28874 29790 28759 29791 28785 29791 28751 29791 28751 29792 28785 29792 28752 29792 28805 960 28753 960 28812 960 28753 960 28754 960 28812 960 28812 29793 28754 29793 28755 29793 28812 960 28755 960 28785 960 28785 29794 28755 29794 28756 29794 28785 29795 28756 29795 28752 29795 28757 29796 28873 29796 28888 29796 28751 29797 28758 29797 28759 29797 28759 29798 28758 29798 28760 29798 28759 960 28760 960 28888 960 28888 29799 28760 29799 28761 29799 28888 29800 28761 29800 28757 29800 28804 960 28762 960 28763 960 28763 960 28762 960 28764 960 28763 960 28764 960 28765 960 28766 29801 28767 29801 28690 29801 28690 960 28767 960 28695 960 28767 29802 28768 29802 28695 29802 28695 29803 28768 29803 28769 29803 28695 29804 28769 29804 28765 29804 28771 960 28840 960 28736 960 28736 29805 28840 29805 28734 29805 28736 29806 28734 29806 28770 29806 28771 960 28772 960 28840 960 28840 29807 28772 29807 28773 29807 28840 20790 28773 20790 28846 20790 28846 960 28773 960 28795 960 28774 29808 28775 29808 28776 29808 28776 960 28777 960 28774 960 28774 960 28777 960 28778 960 28774 29809 28778 29809 28725 29809 28725 960 28778 960 28779 960 28725 29810 28779 29810 28720 29810 28780 960 28781 960 28785 960 28785 29811 28781 29811 28782 29811 28884 960 28783 960 28759 960 28759 29812 28783 29812 28784 29812 28759 29813 28784 29813 28785 29813 28785 960 28784 960 28786 960 28785 960 28786 960 28780 960 28794 29814 28787 29814 28855 29814 28855 29815 28787 29815 28788 29815 28855 20882 28788 20882 28862 20882 28862 29816 28788 29816 28789 29816 28862 29817 28789 29817 28790 29817 28800 960 28791 960 28849 960 28849 960 28791 960 28792 960 28849 960 28792 960 28855 960 28855 960 28792 960 28793 960 28855 960 28793 960 28794 960 28795 29818 28796 29818 28846 29818 28846 29819 28796 29819 28797 29819 28846 29820 28797 29820 28844 29820 28844 29821 28797 29821 28798 29821 28844 29822 28798 29822 28800 29822 28800 29823 28798 29823 28799 29823 28800 29824 28799 29824 28791 29824 28782 29825 28801 29825 28810 29825 28810 960 28801 960 28775 960 28810 960 28775 960 28802 960 28802 960 28775 960 28774 960 28802 960 28774 960 28367 960 28367 960 28774 960 28368 960 28890 960 28893 960 28815 960 28815 29826 28893 29826 28371 29826 28815 29827 28371 29827 28368 29827 28807 29828 28901 29828 28424 29828 28424 29829 28803 29829 28594 29829 28804 960 28805 960 28762 960 28762 960 28805 960 28812 960 28762 960 28812 960 28806 960 28806 29830 28812 29830 28359 29830 28806 29831 28359 29831 28809 29831 28807 29832 28424 29832 28808 29832 28808 29833 28424 29833 28594 29833 28808 960 28594 960 28362 960 28362 29834 28594 29834 28593 29834 28362 960 28593 960 28809 960 28809 29835 28593 29835 28599 29835 28809 960 28599 960 28806 960 28810 960 28811 960 28782 960 28782 960 28811 960 28357 960 28782 29836 28357 29836 28785 29836 28785 29837 28357 29837 28355 29837 28785 29838 28355 29838 28812 29838 28812 29839 28355 29839 28813 29839 28812 29840 28813 29840 28359 29840 28674 960 28675 960 28909 960 28814 960 28816 960 28815 960 28815 29841 28816 29841 28817 29841 28815 960 28817 960 28890 960 28890 960 28817 960 28818 960 28818 29842 28819 29842 28890 29842 28890 960 28819 960 28820 960 28890 960 28820 960 28907 960 28910 29843 28821 29843 28825 29843 28909 960 28675 960 28822 960 28822 29844 28675 29844 28902 29844 28822 960 28902 960 28908 960 28368 960 28774 960 28815 960 28815 29845 28774 29845 28823 29845 28815 29846 28823 29846 28814 29846 28821 29847 28824 29847 28825 29847 28825 960 28824 960 28826 960 28825 29848 28826 29848 28725 29848 28725 29849 28826 29849 28827 29849 28827 29850 28828 29850 28725 29850 28725 29851 28828 29851 28829 29851 28725 29852 28829 29852 28774 29852 28774 29853 28829 29853 28830 29853 28774 29854 28830 29854 28823 29854 28941 29855 28944 29855 28840 29855 28840 960 28944 960 28945 960 28840 960 28945 960 28832 960 28832 29856 28945 29856 28831 29856 28832 29857 28831 29857 28458 29857 28458 29858 28831 29858 28833 29858 28458 29859 28833 29859 28390 29859 28833 960 28834 960 28390 960 28390 29860 28834 29860 28835 29860 28390 29861 28835 29861 28453 29861 28453 960 28835 960 28921 960 28453 29862 28921 29862 28836 29862 28836 960 28921 960 28926 960 28836 960 28926 960 28845 960 28845 29863 28926 29863 28929 29863 28845 960 28929 960 28932 960 28933 29864 28837 29864 28846 29864 28846 29865 28837 29865 28935 29865 28935 960 28838 960 28846 960 28846 29866 28838 29866 28839 29866 28846 29867 28839 29867 28840 29867 28840 29868 28839 29868 28841 29868 28840 960 28841 960 28941 960 28842 23472 28449 23472 28696 23472 28696 29869 28449 29869 28843 29869 28696 960 28843 960 28844 960 28844 29870 28843 29870 28845 29870 28844 960 28845 960 28846 960 28846 960 28845 960 28932 960 28846 29871 28932 29871 28933 29871 28715 29872 28847 29872 28848 29872 28848 29873 28847 29873 28849 29873 28848 960 28849 960 28850 960 28850 29874 28849 29874 28855 29874 28850 960 28855 960 28856 960 28324 960 28851 960 28852 960 28852 960 28851 960 28331 960 28853 960 28854 960 28862 960 28865 960 28345 960 28855 960 28855 29875 28345 29875 28347 29875 28855 29876 28347 29876 28856 29876 28856 29877 28347 29877 28348 29877 28856 960 28348 960 28857 960 28857 960 28348 960 28858 960 28857 29878 28858 29878 28859 29878 28859 960 28858 960 28327 960 28859 29879 28327 29879 28851 29879 28851 29880 28327 29880 28330 29880 28851 29881 28330 29881 28331 29881 28489 960 28851 960 28860 960 28860 960 28851 960 28324 960 28860 29882 28324 29882 28749 29882 28749 29883 28324 29883 28335 29883 28749 29884 28335 29884 28862 29884 28862 29885 28335 29885 28861 29885 28862 960 28861 960 28853 960 28854 29886 28339 29886 28862 29886 28862 29887 28339 29887 28863 29887 28862 20814 28863 20814 28855 20814 28855 29888 28863 29888 28864 29888 28855 29889 28864 29889 28865 29889 28866 960 28384 960 28744 960 28744 29890 28384 29890 28867 29890 28744 29891 28867 29891 28868 29891 28869 29892 28870 29892 28871 29892 28871 960 28870 960 28744 960 28871 29893 28744 29893 28485 29893 28485 960 28744 960 28868 960 28866 960 28744 960 28872 960 28872 29894 28744 29894 28887 29894 28872 960 28887 960 28889 960 28688 960 28888 960 28690 960 28690 29895 28888 29895 28873 29895 28690 29896 28873 29896 28766 29896 28874 29897 28862 29897 28875 29897 28875 29898 28862 29898 28876 29898 28875 29899 28876 29899 28878 29899 28878 960 28876 960 28877 960 28878 960 28877 960 28879 960 28879 29900 28877 29900 28880 29900 28879 960 28880 960 28881 960 28881 960 28880 960 28882 960 28881 29901 28882 29901 28883 29901 28883 29902 28882 29902 28884 29902 28883 960 28884 960 28885 960 28885 29903 28884 29903 28759 29903 28885 960 28759 960 28886 960 28886 960 28759 960 28888 960 28886 960 28888 960 28887 960 28887 960 28888 960 28688 960 28887 29904 28688 29904 28889 29904 28765 29905 28764 29905 28695 29905 28695 29906 28764 29906 28694 29906 28695 960 28694 960 28693 960 28407 29907 28891 29907 28890 29907 28890 960 28891 960 28409 960 28890 960 28409 960 28893 960 28893 29908 28409 29908 28892 29908 28893 960 28892 960 28894 960 28894 29909 28892 29909 28895 29909 28894 960 28895 960 28366 960 28366 960 28895 960 28412 960 28366 29910 28412 29910 28896 29910 28896 29911 28412 29911 28897 29911 28896 29912 28897 29912 28898 29912 28898 960 28897 960 28899 960 28898 960 28899 960 28901 960 28901 960 28899 960 28900 960 28901 29913 28900 29913 28424 29913 28902 29914 28903 29914 28906 29914 28904 960 28905 960 28906 960 28906 960 28905 960 28890 960 28906 29915 28890 29915 28902 29915 28902 29916 28890 29916 28907 29916 28902 29917 28907 29917 28908 29917 28909 960 28910 960 28674 960 28674 29918 28910 29918 28825 29918 28674 960 28825 960 28673 960 28673 29919 28825 29919 28911 29919 28673 960 28911 960 28681 960 28681 29920 28911 29920 28718 29920 28912 29921 28913 29921 28914 29921 28914 29922 28913 29922 28658 29922 28914 960 28658 960 28718 960 28718 29923 28658 29923 28915 29923 28718 29924 28915 29924 28916 29924 28916 960 28678 960 28718 960 28718 29925 28678 29925 28680 29925 28718 960 28680 960 28681 960 28921 29926 28917 29926 28926 29926 28926 29927 28917 29927 28918 29927 28926 29928 28918 29928 28925 29928 28834 29929 28919 29929 28835 29929 28835 29930 28919 29930 28920 29930 28835 29931 28920 29931 28921 29931 28921 29932 28920 29932 28922 29932 28921 29933 28922 29933 28917 29933 28833 29934 28923 29934 28834 29934 28834 29935 28923 29935 28924 29935 28834 29936 28924 29936 28919 29936 28925 29937 28927 29938 28926 29939 28926 29940 28927 29940 28928 29940 28926 29941 28928 29941 28929 29941 28929 29942 28928 29942 28930 29942 28929 29943 28930 29943 28932 29943 28932 29944 28930 29944 28931 29944 28932 29944 28931 29944 28933 29944 28933 29945 28931 29945 28934 29945 28933 29946 28934 29946 28837 29946 28837 29947 28934 29947 28936 29947 28837 29948 28936 29948 28935 29948 28935 29949 28936 29949 28937 29949 28935 29950 28937 29950 28838 29950 28838 29951 28937 29951 28938 29951 28838 29951 28938 29951 28839 29951 28839 29952 28938 29952 28939 29952 28839 29953 28939 29953 28841 29953 28841 29277 28939 29277 28940 29277 28841 29278 28940 29278 28941 29278 28941 29954 28940 29954 28942 29954 28941 29955 28942 29955 28944 29955 28944 29956 28942 29956 28943 29956 28944 29957 28943 29957 28945 29957 28945 29282 28943 29282 28946 29282 28945 29283 28946 29283 28831 29283 28831 29958 28946 29958 28947 29958 28831 29959 28947 29959 28833 29959 28833 29960 28947 29960 28948 29960 28833 29961 28948 29961 28923 29961 28949 960 29037 960 29045 960 29045 29962 29037 29962 29039 29962 29045 960 29039 960 28950 960 28950 960 29039 960 28952 960 28950 29963 28952 29963 28951 29963 28951 29964 28952 29964 29042 29964 28953 960 28954 960 29051 960 29051 960 28954 960 29050 960 29051 29965 29053 29965 28953 29965 28953 960 29053 960 28955 960 28953 960 28955 960 29056 960 29056 960 28955 960 29055 960 28964 29966 29103 29966 29020 29966 29020 29967 29103 29967 28956 29967 29031 29968 28957 29968 28958 29968 28958 29969 28959 29969 29031 29969 29031 29970 28959 29970 29049 29970 29031 29971 29049 29971 29032 29971 29049 29972 29086 29972 29032 29972 29032 29973 29086 29973 29074 29973 29032 29974 29074 29974 29034 29974 29074 29975 29080 29975 29034 29975 29034 29976 29080 29976 28960 29976 29034 29977 28960 29977 29035 29977 29035 29978 28960 29978 28961 29978 29035 29979 28961 29979 28963 29979 28961 29980 29059 29980 28963 29980 28963 29981 29059 29981 28962 29981 28963 29982 28962 29982 28964 29982 28964 29983 28962 29983 29102 29983 28964 29984 29102 29984 29103 29984 29036 29985 28966 29985 28965 29985 28965 29986 28966 29986 29029 29986 29019 29987 28967 29987 28968 29987 28968 29988 28967 29988 29098 29988 29098 29989 29095 29989 28968 29989 28968 29990 29095 29990 29094 29990 28968 29991 29094 29991 28969 29991 29094 29992 28970 29992 28969 29992 28969 29993 28970 29993 28971 29993 28969 29994 28971 29994 29024 29994 29024 29995 28971 29995 28972 29995 29024 29996 28972 29996 29025 29996 28972 29997 28973 29997 29025 29997 29025 29998 28973 29998 29090 29998 29025 29999 29090 29999 28974 29999 29090 30000 29089 30000 28974 30000 28974 30001 29089 30001 29087 30001 28974 30002 29087 30002 29029 30002 29029 30003 29087 30003 28975 30003 29029 30004 28975 30004 28965 30004 28956 21191 29050 21191 29020 21191 29020 30005 29050 30005 28954 30005 29020 30006 28954 30006 29019 30006 29019 21191 28954 21191 28967 21191 28976 30007 29007 30007 28977 30007 28978 30008 28981 30008 28985 30008 29000 30009 28979 30009 28980 30009 28985 30010 28981 30010 29030 30010 29030 30011 28981 30011 28982 30011 29030 30012 28982 30012 29016 30012 28983 30013 28984 30013 28985 30013 28985 30014 28984 30014 28986 30014 28985 30015 28986 30015 28978 30015 28990 30016 28992 30016 29033 30016 29033 30017 28992 30017 28987 30017 29033 30018 28987 30018 28983 30018 28983 30019 28987 30019 28988 30019 28983 30020 28988 30020 28984 30020 28996 30021 28989 30021 28990 30021 28990 30022 28989 30022 28991 30022 28990 30023 28991 30023 28992 30023 28977 30024 29007 30024 28993 30024 29007 30025 28994 30026 29021 30027 29021 30028 28994 30028 28995 30028 29021 30029 28995 30029 28996 30029 28996 30030 28995 30030 28997 30030 28996 30031 28997 30032 28989 30033 28998 30034 29006 30034 28977 30034 28977 30035 29006 30035 28999 30035 28977 30036 28999 30036 28976 30036 28980 30037 29001 30037 29000 30037 29000 30038 29001 30038 29002 30038 29000 30039 29002 30039 29003 30039 29003 30040 29002 30040 29004 30040 29003 30041 29004 30041 28998 30041 28998 30042 29004 30042 29005 30042 28998 30043 29005 30043 29006 30043 29007 30044 29021 30044 28993 30044 28993 30045 29021 30045 29018 30045 28993 30046 29018 30046 29008 30046 29008 30047 29018 30047 29022 30047 29008 30047 29022 30047 29009 30047 29009 30048 29022 30048 29023 30048 29009 30049 29023 30049 29010 30049 29010 30050 29023 30050 29011 30050 29011 30051 29023 30051 29026 30051 29011 30052 29026 30052 29012 30052 29012 30053 29026 30053 29027 30053 29012 30054 29027 30054 29013 30054 29013 30055 29027 30055 29028 30055 29013 30056 29028 30056 29014 30056 29014 30057 29028 30057 29030 30057 29014 30058 29030 30058 29015 30058 29015 30059 29030 30059 29016 30059 29015 30060 29016 30060 28979 30060 28979 50 29016 50 29017 50 28979 30061 29017 30061 28980 30061 29022 960 29018 960 29019 960 29019 30062 29018 30062 29020 30062 28990 960 28964 960 28996 960 28996 960 28964 960 29020 960 28996 30063 29020 30063 29021 30063 29021 30064 29020 30064 29018 30064 29019 960 28968 960 29022 960 29022 30065 28968 30065 28969 30065 29022 30066 28969 30066 29023 30066 29023 30067 28969 30067 29024 30067 29023 30068 29024 30068 29026 30068 29033 960 29035 960 28990 960 28990 30069 29035 30069 28963 30069 28990 30070 28963 30070 28964 30070 29024 960 29025 960 29026 960 29026 960 29025 960 28974 960 29026 960 28974 960 29027 960 29027 30071 28974 30071 29029 30071 29027 960 29029 960 29028 960 29028 960 29029 960 28966 960 29028 30072 28966 30072 29030 30072 29030 30073 28966 30073 28957 30073 29030 960 28957 960 28985 960 28985 30074 28957 30074 29031 30074 28985 960 29031 960 28983 960 28983 30075 29031 30075 29032 30075 28983 960 29032 960 29033 960 29033 30076 29032 30076 29034 30076 29033 30077 29034 30077 29035 30077 29036 21214 29037 21214 28966 21214 28966 21216 29037 21216 28949 21216 28966 30078 28949 30078 28957 30078 28957 21214 28949 21214 28958 21214 29037 30079 29036 30079 28965 30079 29039 30080 29037 30080 29038 30080 29038 30081 29040 30081 29039 30081 29039 30082 29040 30082 29041 30082 29039 30083 29041 30083 28952 30083 28959 30084 28958 30084 28949 30084 29041 30085 29788 30085 28952 30085 28952 30086 29788 30086 29043 30086 28952 30087 29043 30087 29042 30087 29042 30088 29043 30088 29044 30088 29042 30089 29044 30089 28951 30089 28951 30090 29044 30090 29608 30090 28951 30091 29608 30091 28950 30091 28950 30092 29608 30092 29046 30092 28950 30093 29046 30093 29045 30093 29045 30094 29046 30094 29047 30094 29045 30095 29047 30095 28949 30095 28949 30096 29047 30096 29048 30096 28949 30097 29048 30097 28959 30097 28959 30098 29048 30098 29049 30098 29051 30099 29050 30099 29101 30099 29101 30100 29050 30100 28956 30100 29101 30101 28956 30101 29103 30101 29101 30102 29604 30102 29051 30102 29051 30103 29604 30103 29052 30103 29051 30104 29052 30104 29053 30104 29052 30105 29603 30105 29053 30105 29053 30106 29603 30106 29606 30106 29053 30107 29606 30107 28955 30107 28955 30108 29606 30108 29054 30108 28955 30109 29054 30109 29055 30109 29055 30110 29054 30110 29057 30110 29055 30111 29057 30111 29056 30111 29056 30112 29057 30112 29605 30112 29056 30113 29605 30113 28953 30113 28953 30114 29605 30114 29058 30114 28953 30115 29058 30115 28954 30115 28954 30116 29058 30116 29097 30116 28954 30117 29097 30117 28967 30117 29085 30118 29060 30118 29059 30118 29059 30119 29060 30119 29061 30119 29059 30120 29061 30120 29099 30120 29099 30121 29061 30122 29062 30123 29099 30124 29062 30124 29063 30124 29063 30125 29064 30125 29099 30125 29099 30126 29064 30126 29065 30126 29099 30127 29065 30127 29068 30127 29068 30128 29065 30128 29066 30128 29066 30129 29067 30129 29068 30129 29068 30130 29067 30130 29069 30130 29068 30131 29069 30131 29609 30131 29069 30132 29070 30132 29609 30132 29609 30133 29070 30133 29071 30133 29609 30134 29071 30134 29072 30134 29072 30135 29073 30135 29609 30135 29609 30136 29073 30136 29075 30136 29609 30137 29075 30137 29074 30137 29074 30138 29075 30139 29076 30140 29076 30141 29077 30141 29074 30141 29074 30142 29077 30142 29078 30142 29074 30143 29078 30143 29080 30143 29078 30144 29079 30144 29080 30144 29080 30145 29079 30145 29081 30145 29080 30146 29081 30146 28960 30146 28960 30147 29081 30147 29082 30147 28960 30148 29082 30148 28961 30148 28961 30149 29082 30149 29083 30149 28961 30150 29083 30150 29059 30150 29059 30151 29083 30151 29084 30151 29059 30152 29084 30152 29085 30152 29049 30153 29048 30153 29086 30153 29086 30154 29048 30154 29611 30154 29086 30155 29611 30155 29074 30155 29074 30156 29611 30156 29610 30156 29074 30157 29610 30158 29609 30159 29037 30160 28965 30160 29038 30160 29038 30161 28965 30161 28975 30161 29038 30162 28975 30162 29088 30162 29088 30163 28975 30163 29087 30163 29088 30164 29087 30164 29607 30164 29607 30165 29087 30165 29089 30165 29607 30166 29089 30166 29091 30166 29089 30167 29090 30167 29091 30167 29091 30168 29090 30168 28973 30168 29091 30169 28973 30169 29092 30169 28973 30170 28972 30170 29092 30170 29092 30171 28972 30172 28971 30173 29092 30174 28971 30174 29093 30174 29093 30175 28971 30175 28970 30175 29093 30176 28970 30176 29096 30176 28970 30177 29094 30177 29096 30177 29096 30178 29094 30178 29095 30178 29096 30179 29095 30179 29097 30179 29097 30180 29095 30180 29098 30180 29097 30181 29098 30181 28967 30181 29099 30182 29628 30182 29059 30182 29059 30183 29628 30183 29100 30183 29059 30184 29100 30184 28962 30184 28962 30185 29100 30185 29101 30185 28962 30186 29101 30186 29102 30186 29102 30187 29101 30187 29103 30187 29501 30188 29500 30188 29104 30188 29104 24495 29500 24495 29496 24495 29104 24495 29496 24495 29725 24495 29725 24522 29496 24522 29495 24522 29725 30189 29495 30189 29105 30189 29105 30190 29495 30190 29106 30190 29105 30191 29106 30191 29107 30191 29107 30192 29106 30192 29494 30192 29107 30193 29494 30193 29721 30193 29721 30194 29494 30194 29493 30194 29721 30195 29493 30195 29727 30195 29727 30196 29493 30196 29108 30196 29727 30197 29108 30197 29728 30197 29728 30198 29108 30198 29109 30198 29728 30198 29109 30198 29730 30198 29730 30199 29109 30199 29110 30199 29730 30200 29110 30200 29111 30200 29111 24478 29110 24478 29112 24478 29111 24477 29112 24477 29113 24477 29113 24406 29112 24406 29114 24406 29113 24406 29114 24406 29115 24406 29115 24525 29114 24525 29499 24525 29115 24525 29499 24525 29720 24525 29720 30201 29499 30201 29497 30201 29720 30202 29497 30202 29116 30202 29116 24433 29497 24433 29117 24433 29116 24433 29117 24433 29118 24433 29118 30203 29117 30203 29502 30203 29118 30204 29502 30204 29119 30204 29119 30205 29502 30205 29501 30205 29119 30206 29501 30206 29104 30206 29120 30207 29134 30207 29619 30207 29120 30208 29619 30208 29399 30208 29399 30209 29619 30209 29618 30209 29399 30210 29618 30210 29393 30210 29393 30211 29618 30211 29617 30211 29393 30212 29617 30212 29121 30212 29121 30213 29617 30213 29122 30213 29121 30214 29122 30214 29394 30214 29394 24556 29122 24556 29123 24556 29394 24556 29123 24556 29124 24556 29124 30215 29123 30215 29125 30215 29124 30216 29125 30216 29396 30216 29396 30217 29125 30217 29625 30217 29396 30218 29625 30218 29397 30218 29625 30219 29624 30219 29397 30219 29397 30220 29624 30220 29623 30220 29397 30221 29623 30221 29126 30221 29126 30222 29623 30222 29127 30222 29126 30223 29127 30223 29389 30223 29389 30224 29127 30224 29128 30224 29128 30225 29127 30225 29129 30225 29128 30226 29129 30226 29130 30226 29130 30203 29129 30203 29131 30203 29130 30204 29131 30204 29391 30204 29391 30227 29131 30227 29626 30227 29391 30228 29626 30228 29392 30228 29626 30229 29132 30229 29392 30229 29392 24464 29132 24464 29615 24464 29392 24464 29615 24464 29387 24464 29387 30230 29615 30230 29133 30230 29387 30231 29133 30231 29388 30231 29388 24479 29133 24479 29614 24479 29120 30232 29135 30232 29134 30232 29134 30233 29135 30233 29136 30233 29134 30234 29136 30234 29621 30234 29621 30235 29136 30235 29137 30235 29621 30236 29137 30236 29614 30236 29614 30237 29137 30237 29362 30237 29614 24406 29362 24406 29388 24406 29143 30238 29404 30238 29637 30238 29637 30239 29404 30239 29138 30239 29152 30240 29139 30240 29405 30240 29405 30241 29139 30241 29140 30241 29140 30242 29139 30242 29636 30242 29140 30243 29636 30243 29141 30243 29141 24396 29636 24396 29630 24396 29141 24396 29630 24396 29142 24396 29142 30244 29630 30244 29629 30244 29142 30245 29629 30245 29403 30245 29403 30217 29629 30217 29640 30217 29403 30246 29640 30246 29138 30246 29138 30247 29640 30247 29639 30247 29138 30248 29639 30248 29637 30248 29143 30249 29637 30249 29144 30249 29144 30250 29637 30250 29145 30250 29144 30251 29145 30251 29554 30251 29554 30252 29145 30252 29146 30252 29554 30253 29146 30253 29415 30253 29146 30254 29602 30254 29415 30254 29415 30255 29602 30255 29147 30255 29415 30256 29147 30256 29149 30256 29147 30229 29648 30229 29149 30229 29149 30257 29648 30257 29148 30257 29149 30258 29148 30258 29150 30258 29150 24382 29148 24382 29647 24382 29150 24381 29647 24381 29151 24381 29151 30259 29647 30259 29645 30259 29405 30260 29408 30260 29152 30260 29152 30261 29408 30261 29410 30261 29152 24374 29410 24374 29153 24374 29153 30262 29410 30262 29411 30262 29153 30263 29411 30263 29643 30263 29643 30264 29411 30264 29154 30264 29643 30265 29154 30265 29644 30265 29644 30266 29154 30266 29413 30266 29644 30267 29413 30267 29645 30267 29645 30268 29413 30268 29414 30268 29645 30269 29414 30269 29151 30269 29155 24562 29417 24562 29157 24562 29157 24429 29417 24429 29156 24429 29157 30270 29156 30270 29158 30270 29158 24394 29156 24394 29416 24394 29158 24395 29416 24395 29159 24395 29159 24555 29416 24555 29160 24555 29159 24556 29160 24556 29652 24556 29652 30242 29160 30242 29161 30242 29652 30271 29161 30271 29162 30271 29162 30272 29161 30272 29163 30272 29162 30273 29163 30273 29649 30273 29649 30274 29163 30274 29172 30274 29649 30275 29172 30275 29653 30275 29168 30276 29164 30277 29167 30278 29167 30279 29164 30279 29165 30279 29167 30280 29165 30280 29155 30280 29155 30281 29165 30281 29166 30281 29155 24562 29166 24562 29417 24562 29167 30282 29661 30282 29168 30282 29168 24566 29661 24566 29169 24566 29168 24567 29169 24567 29420 24567 29420 24564 29169 24564 29658 24564 29420 24565 29658 24565 29170 24565 29170 30283 29658 30283 29657 30283 29170 30284 29657 30284 29171 30284 29171 24382 29657 24382 29656 24382 29171 24381 29656 24381 29422 24381 29422 24406 29656 24406 29655 24406 29422 30285 29655 30285 29175 30285 29175 30286 29655 30286 29654 30286 29653 30287 29172 30287 29173 30287 29173 30288 29172 30288 29174 30288 29173 30289 29174 30289 29654 30289 29654 30290 29174 30290 29419 30290 29654 24544 29419 24544 29175 24544 29186 30281 29176 30281 29177 30281 29177 30291 29176 30291 29184 30291 29192 30292 29178 30292 29179 30292 29192 30293 29179 30293 29180 30293 29180 24423 29179 24423 29181 24423 29180 24424 29181 24424 29182 24424 29182 30294 29181 30294 29183 30294 29182 30295 29183 30295 29423 30295 29423 30296 29183 30296 29185 30296 29423 30297 29185 30297 29184 30297 29184 30298 29185 30298 29695 30298 29184 30299 29695 30299 29177 30299 29186 30300 29177 30300 29429 30300 29429 30301 29177 30301 29669 30301 29429 30251 29669 30251 29187 30251 29187 30302 29669 30302 29188 30302 29187 30303 29188 30303 29430 30303 29188 30254 29666 30254 29430 30254 29430 30304 29666 30304 29664 30304 29430 30305 29664 30305 29191 30305 29664 30306 29189 30306 29191 30306 29191 24526 29189 24526 29190 24526 29191 24464 29190 24464 29548 24464 29548 24525 29190 24525 29197 24525 29192 30307 29427 30308 29178 30309 29178 30310 29427 30310 29193 30310 29178 24449 29193 24449 29662 24449 29662 30311 29193 30311 29426 30311 29662 30311 29426 30311 29194 30311 29194 30262 29426 30262 29425 30262 29194 30312 29425 30312 29671 30312 29671 30313 29425 30313 29195 30313 29671 30314 29195 30314 29672 30314 29672 30315 29195 30315 29550 30315 29672 30316 29550 30316 29673 30316 29673 30317 29550 30318 29196 30319 29673 30320 29196 30320 29197 30320 29197 24505 29196 24505 29198 24505 29197 24525 29198 24525 29548 24525 29541 30321 29199 30321 29200 30321 29541 30322 29200 30322 29538 30322 29538 30323 29200 30323 29674 30323 29538 30324 29674 30324 29536 30324 29536 30325 29674 30325 29781 30325 29536 30326 29781 30327 29201 30328 29201 30329 29781 30329 29681 30329 29201 30330 29681 30330 29202 30330 29202 24489 29681 24489 29682 24489 29202 30331 29682 30331 29437 30331 29437 30332 29682 30332 29203 30332 29437 24491 29203 24491 29438 24491 29438 30333 29203 30333 29204 30333 29438 30334 29204 30334 29205 30334 29204 30335 29700 30335 29205 30335 29205 30336 29700 30336 29702 30336 29205 30337 29702 30337 29206 30337 29206 30338 29702 30338 29703 30338 29206 30339 29703 30339 29439 30339 29439 30340 29703 30340 29207 30340 29207 30341 29703 30341 29704 30341 29207 30342 29704 30342 29433 30342 29433 24498 29704 24498 29208 24498 29433 24503 29208 24503 29209 24503 29209 30343 29208 30343 29691 30343 29209 30344 29691 30344 29210 30344 29691 30345 29601 30345 29210 30345 29210 24482 29601 24482 29680 24482 29210 30346 29680 30346 29435 30346 29435 24525 29680 24525 29678 24525 29541 30347 29444 30347 29199 30347 29199 30348 29444 30348 29443 30348 29199 30349 29443 30349 29675 30349 29675 24477 29443 24477 29211 24477 29675 24477 29211 24477 29676 24477 29676 24524 29211 24524 29441 24524 29676 30350 29441 30350 29678 30350 29678 30351 29441 30351 29440 30351 29678 24525 29440 24525 29435 24525 29769 30352 29212 30352 29770 30352 29770 15488 29212 15488 29455 15488 29770 15489 29455 15489 29213 15489 29215 30353 29450 30353 29768 30353 29768 30354 29450 30354 29214 30354 29768 30355 29214 30355 29769 30355 29769 30356 29214 30356 29457 30356 29769 30357 29457 30357 29212 30357 29768 30358 29774 30358 29215 30358 29215 15496 29774 15496 29216 15496 29215 15497 29216 15497 29217 15497 29217 30359 29216 30359 29218 30359 29217 30360 29218 30360 29449 30360 29449 30361 29218 30361 29219 30361 29449 30362 29219 30362 29220 30362 29220 30363 29219 30363 29687 30363 29220 30364 29687 30364 29221 30364 29221 15504 29687 15504 29690 15504 29221 15487 29690 15487 29445 15487 29222 960 29924 960 29223 960 29223 30365 29924 30365 29922 30365 29223 30366 29922 30366 29224 30366 29224 30367 29922 30367 29921 30367 29224 960 29921 960 29963 960 29963 960 29921 960 29225 960 29963 960 29225 960 29956 960 29956 960 29225 960 29919 960 29977 960 29240 960 29241 960 29977 960 29241 960 29228 960 29241 960 29226 960 29228 960 29228 30368 29226 30368 29227 30368 29228 960 29227 960 29971 960 29971 30369 29227 30369 29253 30369 29971 960 29253 960 29252 960 29229 30370 29230 30370 29659 30370 29659 30371 29230 30371 29231 30371 29659 30372 29231 30372 29233 30372 29231 30373 29232 30373 29233 30373 29233 30374 29232 30374 29234 30374 29233 30375 29234 30375 29236 30375 29234 30376 29235 30376 29236 30376 29236 30377 29235 30377 29889 30377 29236 30378 29889 30378 29237 30378 29237 30379 29889 30379 29887 30379 29237 30380 29887 30380 29239 30380 29239 30381 29887 30381 29238 30381 29239 30382 29238 30382 29767 30382 29767 30383 29238 30383 29241 30383 29462 30384 29766 30384 29463 30384 29463 30385 29766 30385 29767 30385 29463 30386 29767 30386 29240 30386 29240 30387 29767 30387 29241 30387 29758 30388 29472 30388 29242 30388 29244 24650 29243 24650 29245 24650 29244 30389 29245 30389 29474 30389 29474 30390 29245 30390 29759 30390 29474 30391 29759 30391 29242 30391 29242 30392 29759 30393 29246 30394 29242 24653 29246 24653 29758 24653 29472 30395 29758 30395 29470 30395 29470 30396 29758 30396 29247 30396 29470 30397 29247 30397 29468 30397 29468 30398 29247 30398 29248 30398 29468 30399 29248 30399 29467 30399 29467 30400 29248 30400 29249 30400 29467 30401 29249 30401 29250 30401 29249 30402 29764 30402 29250 30402 29250 30403 29764 30403 29765 30403 29250 30404 29765 30404 29251 30404 29251 24649 29765 24649 29766 24649 29251 30405 29766 30405 29462 30405 29473 15166 29252 15166 29253 15166 29243 30406 29244 30406 29598 30406 29598 30407 29244 30407 29473 30407 29598 30408 29473 30408 29599 30408 29599 30409 29473 30409 29253 30409 29599 30410 29253 30410 29597 30410 29597 30411 29253 30411 29884 30411 29597 30412 29884 30412 29254 30412 29884 30413 29255 30413 29254 30413 29254 30414 29255 30414 29256 30414 29254 30415 29256 30415 29646 30415 29646 30416 29256 30416 29882 30416 29646 30417 29882 30417 29257 30417 29257 30418 29882 30418 29642 30418 29642 30419 29882 30419 29881 30419 29642 30420 29881 30420 29633 30420 29924 30421 29258 30421 29925 30421 29925 30422 29258 30422 29633 30422 29925 30423 29633 30423 29259 30423 29259 30424 29633 30424 29881 30424 29260 30425 29634 30425 29409 30425 29409 30426 29634 30426 29258 30426 29409 30427 29258 30427 29222 30427 29222 30428 29258 30428 29924 30428 29634 30429 29260 30429 29267 30429 29261 15190 29398 15190 29622 15190 29622 15189 29398 15189 29612 15189 29261 30430 29622 30430 29262 30430 29262 30431 29622 30431 29263 30431 29262 30432 29263 30432 29479 30432 29263 30433 29752 30433 29479 30433 29479 30434 29752 30434 29264 30434 29479 30435 29264 30435 29565 30435 29565 30436 29264 30436 29750 30436 29565 30437 29750 30437 29265 30437 29265 30438 29750 30438 29741 30438 29265 30438 29741 30438 29266 30438 29266 30439 29741 30440 29477 30441 29477 30442 29741 30442 29632 30442 29477 30443 29632 30443 29267 30443 29267 30444 29632 30444 29635 30444 29267 30445 29635 30445 29634 30445 29955 960 29280 960 29988 960 29988 960 29280 960 29911 960 29988 30446 29911 30446 29268 30446 29268 960 29911 960 29269 960 29268 30447 29269 30447 29948 30447 29948 960 29269 960 29910 960 29948 960 29910 960 29949 960 29613 22431 29919 22431 29918 22431 29613 30448 29918 30448 29620 30448 29620 30449 29918 30449 29270 30449 29620 30450 29270 30450 29271 30450 29271 30451 29270 30451 29272 30451 29271 30452 29272 30452 29273 30452 29273 30453 29272 30453 29916 30453 29273 30454 29916 30454 29739 30454 29739 30455 29916 30455 29274 30455 29739 30456 29274 30456 29277 30456 29280 30457 29275 30457 29276 30457 29276 30458 29275 30458 29277 30458 29276 30459 29277 30459 29914 30459 29914 30460 29277 30460 29274 30460 29278 30461 29279 30461 29482 30461 29482 30462 29279 30462 29275 30462 29482 30463 29275 30463 29955 30463 29955 30464 29275 30464 29280 30464 29279 15235 29278 15235 29480 15235 29281 15236 29735 15236 29282 15236 29281 15236 29282 15236 29489 15236 29489 30465 29282 30465 29734 30465 29489 30466 29734 30466 29491 30466 29491 15241 29734 15241 29284 15241 29491 15242 29284 15242 29283 15242 29283 30467 29284 30467 29285 30467 29283 30468 29285 30468 29485 30468 29485 30469 29285 30469 29286 30469 29485 30470 29286 30470 29484 30470 29484 25033 29286 25033 29287 25033 29484 25034 29287 25034 29288 25034 29288 30471 29287 30472 29738 30473 29288 30474 29738 30474 29480 30474 29480 30475 29738 30475 29289 30475 29480 15250 29289 15250 29279 15250 30000 30476 29295 30476 29290 30476 29290 30477 29295 30477 29906 30477 29290 30478 29906 30478 29291 30478 29291 30479 29906 30479 29904 30479 29291 30480 29904 30480 30007 30480 30007 30481 29904 30481 29903 30481 29736 30482 29910 30482 29722 30482 29722 30483 29910 30483 29292 30483 29722 30484 29292 30484 29723 30484 29292 30485 29293 30485 29723 30485 29723 30486 29293 30486 29294 30486 29723 30487 29294 30487 29299 30487 29295 30488 29297 30488 29296 30488 29296 30489 29297 30489 29298 30489 29296 30490 29298 30490 29907 30490 29907 30491 29298 30491 29724 30491 29907 30492 29724 30492 29908 30492 29908 30493 29724 30493 29299 30493 29908 30494 29299 30494 29909 30494 29909 30495 29299 30495 29294 30495 29300 30496 29716 30496 29301 30496 29301 30497 29716 30497 29297 30497 29301 30498 29297 30498 30000 30498 30000 30499 29297 30499 29295 30499 29709 30500 29510 30500 29307 30500 29303 30501 29515 30501 29707 30501 29707 24573 29515 24573 29302 24573 29303 30502 29707 30502 29304 30502 29304 30503 29707 30503 29306 30503 29304 30504 29306 30505 29305 30506 29305 30507 29306 30507 29705 30507 29305 30508 29705 30508 29307 30508 29307 30509 29705 30509 29712 30509 29307 24581 29712 24581 29709 24581 29510 30510 29709 30510 29308 30510 29308 30511 29709 30511 29309 30511 29308 30512 29309 30512 29512 30512 29512 30513 29309 30513 29310 30513 29512 30514 29310 30514 29311 30514 29311 24589 29310 24589 29716 24589 29311 24589 29716 24589 29300 24589 29895 30515 29312 30515 29896 30515 29896 30516 29312 30516 29313 30516 29896 30517 29313 30517 29897 30517 29897 30518 29313 30518 29314 30518 29897 30519 29314 30519 29899 30519 29899 30520 29314 30520 29701 30520 29899 30521 29701 30521 29900 30521 29900 30522 29701 30522 29699 30522 29900 30523 29699 30523 29315 30523 29315 30524 29699 30524 29698 30524 29315 30525 29698 30525 29901 30525 29901 30526 29698 30526 29316 30526 29901 30527 29316 30527 29902 30527 29902 30528 29316 30528 29317 30528 29902 30529 29317 30529 29903 30529 30007 15288 29903 15288 29318 15288 29318 30530 29903 30530 29317 30530 29318 30531 29317 30531 29515 30531 29515 30532 29317 30532 29302 30532 29683 30533 29319 30533 29434 30533 29321 15448 29320 15448 29696 15448 29696 15449 29320 15449 29697 15449 29321 30534 29696 30534 29322 30534 29322 30535 29696 30535 29323 30535 29322 30536 29323 30536 29518 30536 29323 30537 29694 30537 29518 30537 29518 30538 29694 30538 29693 30538 29518 30539 29693 30539 29526 30539 29526 30540 29693 30540 29804 30540 29526 30541 29804 30541 29324 30541 29324 30542 29804 30542 29692 30542 29324 30543 29692 30543 29325 30543 29325 30544 29692 30544 29432 30544 29432 30544 29692 30544 29685 30544 29432 30545 29685 30545 29434 30545 29434 30545 29685 30545 29684 30545 29434 24628 29684 24628 29683 24628 29531 30546 29326 30546 29327 30546 29327 30547 29326 30548 29328 30549 29327 30550 29799 30550 29531 30550 29531 15514 29799 15514 29778 15514 29531 15515 29778 15515 29329 15515 29329 15516 29778 15516 29779 15516 29329 15517 29779 15517 29330 15517 29330 15518 29779 15518 29780 15518 29330 15519 29780 15519 29532 15519 29532 15520 29780 15520 29331 15520 29532 15521 29331 15521 29534 15521 29534 22196 29331 22196 29333 22196 29333 30551 29331 30551 29332 30551 29333 30552 29332 30552 29483 30552 29332 30553 29334 30553 29483 30553 29483 30554 29334 30554 29335 30554 29483 15535 29335 15535 29336 15535 29336 15505 29335 15505 29733 15505 29336 15505 29733 15505 29486 15505 29486 15506 29733 15506 29731 15506 29486 15506 29731 15506 29337 15506 29337 15507 29731 15507 29338 15507 29337 15508 29338 15508 29490 15508 29490 15509 29338 15509 29732 15509 29490 15510 29732 15510 29339 15510 29339 15511 29732 15511 29328 15511 29339 15511 29328 15511 29340 15511 29340 30555 29328 30555 29326 30555 29775 30556 29773 30556 29451 30556 29451 30557 29773 30557 29456 30557 29456 15554 29773 15554 29341 15554 29456 15555 29341 15555 29454 15555 29454 15556 29341 15556 29772 15556 29454 15557 29772 15557 29453 15557 29453 15558 29772 15558 29771 15558 29453 15558 29771 15558 29452 15558 29452 30558 29771 30558 29342 30558 29342 30559 29771 30560 29595 30561 29342 30562 29595 30562 29344 30562 29595 30563 29594 30563 29344 30563 29344 15561 29594 15561 29343 15561 29344 15562 29343 15562 29345 15562 29345 15563 29343 15563 29347 15563 29345 15564 29347 15564 29346 15564 29346 30564 29347 30564 29348 30564 29348 30565 29347 30565 29349 30565 29348 30566 29349 30566 29350 30566 29350 15509 29349 15509 29352 15509 29350 15510 29352 15510 29549 15510 29549 30567 29352 30567 29351 30567 29351 30568 29352 30568 29353 30568 29351 30569 29353 30569 29356 30569 29353 30570 29354 30570 29356 30570 29356 30571 29354 30571 29355 30571 29356 30572 29355 30572 29357 30572 29357 15550 29355 15550 29775 15550 29357 15550 29775 15550 29358 15550 29358 30573 29775 30573 29451 30573 29582 590 29464 590 29465 590 29300 30574 29301 30574 29359 30574 29996 590 29481 590 29360 590 29475 30575 29361 30575 29407 30575 29362 30576 29137 30576 29478 30576 29574 30577 29363 30577 29366 30577 29364 590 29365 590 29390 590 29364 30578 29390 30578 29366 30578 29372 30579 29367 30579 29368 30579 29556 590 29369 590 29370 590 29370 590 29369 590 29375 590 29368 590 29371 590 29372 590 29372 590 29371 590 29373 590 29372 590 29373 590 29369 590 29369 30580 29373 30580 29374 30580 29369 30581 29374 30581 29375 30581 29442 30582 29544 30582 29376 30582 29377 30583 29378 30583 29552 30583 29559 30584 29385 30584 29381 30584 29546 590 29560 590 29379 590 29379 590 29560 590 29380 590 29381 30585 29382 30585 29559 30585 29559 590 29382 590 29383 590 29559 590 29383 590 29560 590 29560 30586 29383 30586 29384 30586 29560 30587 29384 30587 29380 30587 29559 30588 29533 30588 29385 30588 29385 590 29533 590 29390 590 29385 590 29390 590 29386 590 29386 590 29390 590 29365 590 29392 30589 29387 30589 29390 30589 29390 590 29387 590 29478 590 29478 590 29387 590 29388 590 29478 30590 29388 30590 29362 30590 29389 590 29128 590 29533 590 29533 590 29128 590 29130 590 29533 30591 29130 30591 29390 30591 29390 590 29130 590 29391 590 29390 30592 29391 30592 29392 30592 29481 30593 29393 30593 29121 30593 29121 590 29394 590 29481 590 29481 30594 29394 30594 29124 30594 29481 30595 29124 30595 29395 30595 29124 590 29396 590 29395 590 29395 30596 29396 30596 29397 30596 29395 30597 29397 30597 29533 30597 29533 590 29397 590 29126 590 29533 30598 29126 30598 29389 30598 29481 30599 29996 30599 29393 30599 29393 590 29996 590 29994 590 29393 590 29994 590 29399 590 29137 590 29136 590 29261 590 29261 30600 29136 30600 29398 30600 29399 590 29994 590 29120 590 29120 590 29994 590 29400 590 29120 27725 29400 27725 29135 27725 29135 30601 29400 30601 29401 30601 29135 590 29401 590 29136 590 29136 30602 29401 30602 29402 30602 29136 590 29402 590 29398 590 29140 30603 29141 30603 29406 30603 29406 590 29141 590 29142 590 29406 590 29142 590 29574 590 29574 590 29142 590 29403 590 29403 590 29138 590 29574 590 29574 30604 29138 30604 29404 30604 29574 30605 29404 30605 29555 30605 29555 590 29404 590 29143 590 29555 590 29143 590 29144 590 29267 590 29408 590 29405 590 29140 590 29406 590 29405 590 29405 30606 29406 30606 29477 30606 29405 590 29477 590 29267 590 29407 30607 29361 30607 30048 30607 29267 30608 29260 30608 29408 30608 29408 30609 29260 30609 29409 30609 29408 30610 29409 30610 29410 30610 29410 590 29409 590 29412 590 29410 590 29412 590 29411 590 29411 30611 29412 30611 30049 30611 29411 30612 30049 30612 29154 30612 29154 590 30049 590 30048 590 29154 30613 30048 30613 29413 30613 29413 30614 30048 30614 29361 30614 29413 30615 29361 30615 29414 30615 29471 30616 29150 30616 29361 30616 29361 30617 29150 30617 29151 30617 29361 30618 29151 30618 29414 30618 29554 30619 29415 30619 29471 30619 29471 590 29415 590 29149 590 29471 590 29149 590 29150 590 29172 30620 29163 30620 29465 30620 29465 590 29163 590 29161 590 29161 590 29160 590 29465 590 29465 30621 29160 30621 29416 30621 29465 30622 29416 30622 29578 30622 29578 590 29416 590 29156 590 29156 590 29417 590 29578 590 29578 30623 29417 30623 29166 30623 29578 30624 29166 30624 29418 30624 29418 30625 29166 30625 29165 30625 29418 590 29165 590 29164 590 29174 30626 29466 30626 29419 30626 29419 30627 29466 30627 29461 30627 29168 30628 29420 30628 29458 30628 29458 590 29420 590 29170 590 29458 590 29170 590 30040 590 30040 590 29170 590 29171 590 30040 590 29171 590 29421 590 29421 30629 29171 30629 29422 30629 29421 590 29422 590 29461 590 29461 30630 29422 30630 29175 30630 29461 30631 29175 30631 29419 30631 29184 590 29321 590 29423 590 29423 30632 29321 30632 29322 30632 29423 590 29322 590 29182 590 29182 590 29322 590 29521 590 29182 590 29521 590 29180 590 29428 590 29424 590 29176 590 29184 590 29176 590 29321 590 29321 590 29176 590 29424 590 29321 30633 29424 30633 29320 30633 29320 30634 29424 30634 29824 30634 29551 30635 29425 30635 29426 30635 29551 30636 29426 30636 29552 30636 29426 590 29193 590 29552 590 29552 590 29193 590 29427 590 29552 30637 29427 30637 29521 30637 29521 30638 29427 30638 29192 30638 29521 590 29192 590 29180 590 29191 590 29548 590 29447 590 29447 30639 29548 30639 29448 30639 29176 590 29186 590 29428 590 29428 30640 29186 30640 29429 30640 29428 590 29429 590 30030 590 30030 590 29429 590 29187 590 30030 590 29187 590 29447 590 29447 590 29187 590 29430 590 29447 590 29430 590 29191 590 29319 590 29431 590 30018 590 29562 30641 29432 30641 29435 30641 29319 30642 30018 30642 29434 30642 30019 30643 29207 30643 30018 30643 30018 30644 29207 30644 29433 30644 30018 590 29433 590 29434 590 29434 590 29433 590 29209 590 29434 30645 29209 30645 29432 30645 29432 590 29209 590 29210 590 29432 590 29210 590 29435 590 29201 590 29202 590 29535 590 29535 590 29202 590 29437 590 29535 30646 29437 30646 29436 30646 29437 590 29438 590 29436 590 29436 30647 29438 30647 29205 30647 29436 30648 29205 30648 30020 30648 30020 30649 29205 30649 29206 30649 30020 30650 29206 30650 30019 30650 30019 30651 29206 30651 29439 30651 30019 30652 29439 30652 29207 30652 29435 590 29440 590 29562 590 29562 30653 29440 30653 29441 30653 29562 590 29441 590 29442 590 29441 30654 29211 30655 29442 30656 29442 30657 29211 30657 29443 30657 29442 30658 29443 30658 29545 30658 29545 590 29443 590 29444 590 29545 30659 29444 30659 29541 30659 29445 590 30028 590 29446 590 29446 590 30029 590 29445 590 29445 30660 30029 30660 29447 30660 29445 590 29447 590 29221 590 29448 30661 29351 30661 29356 30661 29217 590 29449 590 29357 590 29221 590 29447 590 29220 590 29220 30662 29447 30662 29448 30662 29220 590 29448 590 29449 590 29449 30663 29448 30663 29356 30663 29449 30664 29356 30664 29357 30664 29217 590 29357 590 29215 590 29215 30665 29357 30665 29358 30665 29215 590 29358 590 29450 590 29450 30666 29358 30666 29451 30666 29450 30667 29451 30667 29214 30667 29452 27790 29578 27790 29453 27790 29453 590 29578 590 29418 590 29453 590 29418 590 29454 590 29454 590 29418 590 29456 590 29455 30668 29212 30668 29418 30668 29451 590 29456 590 29214 590 29214 590 29456 590 29418 590 29214 30669 29418 30669 29457 30669 29457 30670 29418 30670 29212 30670 29164 590 29168 590 29418 590 29418 30671 29168 30671 29458 30671 29418 590 29458 590 29455 590 29455 30672 29458 30672 29459 30672 29455 30673 29459 30673 29460 30673 29467 590 29250 590 29466 590 29466 590 29250 590 29251 590 29466 30674 29251 30674 29461 30674 29461 30675 29251 30675 29462 30675 29461 590 29462 590 29463 590 29591 590 29592 590 29471 590 29464 590 29584 590 29465 590 29465 590 29584 590 29466 590 29465 30676 29466 30676 29172 30676 29172 30677 29466 30677 29174 30677 29590 30678 29469 30678 29470 30678 29584 30679 29586 30679 29466 30679 29466 590 29586 590 29588 590 29466 590 29588 590 29467 590 29467 30680 29588 30680 29590 30680 29467 30681 29590 30681 29468 30681 29468 590 29590 590 29470 590 29469 30682 29591 30682 29470 30682 29470 30683 29591 30683 29471 30683 29470 590 29471 590 29472 590 29472 590 29471 590 29242 590 29476 590 29473 590 29244 590 29242 590 29471 590 29474 590 29474 590 29471 590 29361 590 29474 590 29361 590 29244 590 29244 590 29361 590 29475 590 29244 30684 29475 30684 29476 30684 29565 30685 29265 30685 29406 30685 29406 590 29265 590 29266 590 29406 30686 29266 30686 29477 30686 29479 590 29565 590 29478 590 29137 30687 29261 30687 29478 30687 29478 590 29261 590 29262 590 29478 30688 29262 30688 29479 30688 29395 590 29288 590 29481 590 29481 30689 29288 30689 29480 30689 29481 30690 29480 30690 29360 30690 29360 30691 29480 30691 29278 30691 29360 590 29278 590 29954 590 29954 30692 29278 30692 29482 30692 29483 590 29485 590 29395 590 29395 30693 29485 30693 29484 30693 29395 30694 29484 30694 29288 30694 29483 590 29336 590 29485 590 29485 590 29336 590 29486 590 29485 30695 29486 30695 29283 30695 29283 30696 29486 30696 29337 30696 29489 590 29488 590 29281 590 29281 590 29488 590 29950 590 29340 30697 29487 30697 29339 30697 29339 590 29487 590 29488 590 29339 590 29488 590 29490 590 29490 30698 29488 30698 29489 30698 29490 590 29489 590 29337 590 29337 30699 29489 30699 29491 30699 29337 590 29491 590 29283 590 29488 590 29493 590 29492 590 29492 30700 29493 30700 29494 30700 29492 30701 29494 30701 30004 30701 30004 590 29494 590 29106 590 30004 30702 29106 30702 29505 30702 29505 30703 29106 30703 29495 30703 29505 30704 29495 30704 29496 30704 29117 590 29497 590 29498 590 29498 590 29497 590 29499 590 29498 590 29499 590 29487 590 29487 590 29499 590 29114 590 29487 30705 29114 30705 29112 30705 29496 30706 29500 30706 29505 30706 29505 30707 29500 30707 29501 30707 29505 30708 29501 30708 29498 30708 29498 590 29501 590 29502 590 29498 30709 29502 30709 29117 30709 29112 590 29110 590 29487 590 29487 590 29110 590 29109 590 29487 590 29109 590 29488 590 29488 30710 29109 30710 29108 30710 29488 30711 29108 30711 29493 30711 29511 590 29359 590 29503 590 29503 30712 29359 30712 29505 30712 29561 590 29504 590 29498 590 29498 590 29504 590 29506 590 29498 30713 29506 30713 29505 30713 29505 30714 29506 30714 29507 30714 29505 30715 29507 30715 29503 30715 29509 590 29508 590 29307 590 29307 590 29508 590 29305 590 29535 30716 29304 30716 29305 30716 29307 590 29510 590 29509 590 29509 30717 29510 30717 29308 30717 29509 590 29308 590 29511 590 29511 30718 29308 30718 29512 30718 29511 590 29512 590 29359 590 29359 590 29512 590 29311 590 29359 590 29311 590 29300 590 29537 590 29535 590 29513 590 29513 590 29535 590 29305 590 29513 590 29305 590 29514 590 29514 590 29305 590 29508 590 30009 590 29318 590 29515 590 29304 590 29535 590 29303 590 29303 590 29535 590 29436 590 29303 30719 29436 30719 29515 30719 29515 30720 29436 30720 29516 30720 29515 30721 29516 30721 30009 30721 29518 30722 29517 30722 29519 30722 29518 30723 29519 30723 29322 30723 29322 590 29519 590 29520 590 29322 30724 29520 30724 29521 30724 29521 30725 29520 30725 29522 30725 29521 30726 29522 30726 29563 30726 29523 590 29524 590 29562 590 29517 590 29518 590 29525 590 29525 590 29518 590 29526 590 29525 30727 29526 30727 29527 30727 29526 590 29324 590 29527 590 29527 30728 29324 30728 29325 30728 29527 590 29325 590 29528 590 29528 30729 29325 30729 29432 30729 29528 590 29432 590 29529 590 29529 590 29432 590 29562 590 29529 30730 29562 30730 29530 30730 29530 590 29562 590 29524 590 29326 590 29531 590 29559 590 29559 590 29531 590 29329 590 29559 590 29329 590 29533 590 29533 30731 29329 30731 29330 30731 29330 590 29532 590 29533 590 29533 30732 29532 30732 29534 30732 29533 30733 29534 30733 29395 30733 29395 30734 29534 30734 29333 30734 29395 30735 29333 30735 29483 30735 29201 590 29535 590 29536 590 29536 30736 29535 30736 29537 30736 29536 590 29537 590 29538 590 29538 30737 29537 30737 29539 30737 29538 590 29539 590 29541 590 29541 590 29539 590 29540 590 29541 30738 29540 30738 29545 30738 29545 590 29540 590 29542 590 29545 30739 29542 30739 29543 30739 29544 30740 29442 30740 29546 30740 29546 590 29442 590 29545 590 29546 590 29545 590 29560 590 29560 590 29545 590 29543 590 29560 590 29543 590 29547 590 29342 590 29344 590 29372 590 29548 590 29198 590 29448 590 29448 30741 29198 30741 29196 30741 29448 590 29196 590 29351 590 29351 30742 29196 30742 29550 30742 29351 590 29550 590 29549 590 29549 30743 29550 30743 29195 30743 29549 590 29195 590 29350 590 29350 30744 29195 30744 29425 30744 29350 590 29425 590 29348 590 29348 590 29425 590 29551 590 29348 590 29551 590 29346 590 29346 590 29551 590 29345 590 29344 590 29345 590 29372 590 29372 590 29345 590 29551 590 29372 30745 29551 30745 29367 30745 29367 590 29551 590 29552 590 29367 590 29552 590 29553 590 29553 30746 29552 30746 29378 30746 29592 590 29593 590 29471 590 29471 590 29593 590 29555 590 29471 590 29555 590 29554 590 29554 590 29555 590 29144 590 29593 590 29579 590 29555 590 29555 590 29579 590 29581 590 29555 590 29581 590 29557 590 29363 590 29574 590 29556 590 29556 590 29574 590 29555 590 29556 590 29555 590 29369 590 29369 30747 29555 30747 29557 30747 29369 30748 29557 30748 29558 30748 29340 590 29326 590 29487 590 29487 590 29326 590 29559 590 29487 590 29559 590 29498 590 29498 30749 29559 30749 29560 30749 29498 30750 29560 30750 29561 30750 29561 30751 29560 30751 29547 30751 29376 590 29377 590 29442 590 29442 30752 29377 30752 29552 30752 29442 590 29552 590 29562 590 29562 590 29552 590 29521 590 29562 590 29521 590 29523 590 29523 30753 29521 30753 29563 30753 29571 590 29564 590 29390 590 29366 30754 29390 30754 29574 30754 29574 590 29390 590 29564 590 29574 30755 29564 30755 29572 30755 29577 590 29566 590 29406 590 29565 590 29406 590 29478 590 29478 30756 29406 30756 29566 30756 29478 590 29566 590 29567 590 29567 30757 29568 30757 29478 30757 29478 590 29568 590 29569 590 29478 590 29569 590 29390 590 29390 30758 29569 30758 29570 30758 29390 30759 29570 30759 29571 30759 29572 30760 29573 30760 29574 30760 29574 590 29573 590 29575 590 29574 590 29575 590 29406 590 29406 590 29575 590 29576 590 29406 30761 29576 30761 29577 30761 29558 30762 29582 30762 29369 30762 29369 30763 29582 30763 29465 30763 29369 590 29465 590 29372 590 29372 30764 29465 30764 29578 30764 29372 30765 29578 30765 29342 30765 29342 590 29578 590 29452 590 29761 30766 29757 30766 29593 30766 29593 30767 29757 30767 29579 30767 29757 30768 29580 30768 29579 30768 29579 15575 29580 15575 29794 15575 29579 15576 29794 15576 29581 15576 29581 30769 29794 30769 29793 30769 29581 30769 29793 30769 29557 30769 29557 15507 29793 15507 29791 15507 29557 15508 29791 15508 29558 15508 29558 15797 29791 15797 29583 15797 29558 15798 29583 15798 29582 15798 29582 21963 29583 21963 29464 21963 29464 30770 29583 30770 29790 30770 29464 30771 29790 30771 29584 30771 29790 30771 29585 30771 29584 30771 29584 15569 29585 15569 29760 15569 29584 15549 29760 15549 29586 15549 29586 30772 29760 30772 29587 30772 29586 30773 29587 30773 29588 30773 29588 15808 29587 15808 29589 15808 29588 30774 29589 30774 29590 30774 29590 30775 29589 30775 29763 30775 29590 25068 29763 25068 29469 25068 29469 15556 29763 15556 29762 15556 29469 15557 29762 15557 29591 15557 29591 25069 29762 25069 29761 25069 29591 25070 29761 25070 29592 25070 29592 30776 29761 30776 29593 30776 29594 30777 29595 30777 29596 30777 29597 30778 29598 30778 29599 30778 29600 960 29686 960 29823 960 29781 960 29674 960 29786 960 29601 960 29691 960 29679 960 29602 960 29146 960 29795 960 29603 960 29052 960 29798 960 29628 960 29099 960 29742 960 29742 960 29099 960 29068 960 29068 30779 29609 30779 29631 30779 29631 960 29609 960 29638 960 29100 960 29627 960 29101 960 29101 960 29627 960 29777 960 29798 960 29052 960 29777 960 29777 960 29052 960 29604 960 29777 30780 29604 30780 29101 30780 29605 30781 29057 30781 29797 30781 29797 960 29057 960 29054 960 29797 30782 29054 30782 29798 30782 29798 960 29054 960 29606 960 29798 960 29606 960 29603 960 29605 960 29797 960 29058 960 29058 30783 29797 30783 29786 30783 29058 960 29786 960 29097 960 29091 30784 29092 30784 29677 30784 29677 960 29092 960 29093 960 29677 30785 29093 30785 29786 30785 29786 30786 29093 30786 29096 30786 29786 30787 29096 30787 29097 30787 29088 960 29607 960 29663 960 29663 960 29607 960 29091 960 29041 30788 29040 30788 29789 30788 29789 30789 29040 30789 29038 30789 29608 960 29044 960 29792 960 29792 30790 29044 30790 29043 30790 29792 30791 29043 30791 29814 30791 29814 960 29043 960 29788 960 29795 30792 29047 30792 29792 30792 29792 30793 29047 30793 29046 30793 29792 30794 29046 30794 29608 30794 29609 960 29610 960 29638 960 29638 30795 29610 30795 29611 30795 29638 30796 29611 30797 29795 30798 29795 960 29611 960 29048 960 29795 30799 29048 30799 29047 30799 29612 30800 29613 30800 29620 30800 29621 960 29614 960 29263 960 29263 30801 29614 30801 29133 30801 29263 30802 29133 30802 29742 30802 29742 30803 29133 30803 29615 30803 29742 960 29615 960 29132 960 29125 960 29123 960 29616 960 29616 30804 29123 30804 29739 30804 29123 30805 29122 30805 29739 30805 29739 30806 29122 30806 29617 30806 29739 960 29617 960 29273 960 29273 960 29617 960 29618 960 29273 960 29618 960 29271 960 29271 30807 29618 30807 29619 30807 29271 960 29619 960 29620 960 29620 30808 29619 30808 29134 30808 29620 960 29134 960 29612 960 29612 30809 29134 30809 29621 30809 29612 960 29621 960 29622 960 29622 960 29621 960 29263 960 29777 30810 29623 30810 29737 30810 29737 26209 29623 26209 29624 26209 29737 960 29624 960 29616 960 29616 30811 29624 30811 29625 30811 29616 30812 29625 30812 29125 30812 29132 960 29626 960 29742 960 29742 30813 29626 30813 29627 30813 29742 30814 29627 30814 29628 30814 29628 30815 29627 30815 29100 30815 29626 960 29131 960 29627 960 29627 30816 29131 30816 29129 30816 29627 30817 29129 30817 29777 30817 29777 30818 29129 30818 29127 30818 29777 30819 29127 30819 29623 30819 29629 30820 29630 30820 29631 30820 29631 30821 29630 30821 29632 30821 29633 30822 29258 30822 29634 30822 29642 30823 29633 30823 29153 30823 29153 960 29633 960 29634 960 29153 30824 29634 30824 29152 30824 29152 960 29634 960 29635 960 29152 960 29635 960 29139 960 29139 960 29635 960 29632 960 29139 960 29632 960 29636 960 29636 960 29632 960 29630 960 29146 960 29145 960 29795 960 29795 960 29145 960 29637 960 29795 30825 29637 30825 29638 30825 29638 30826 29637 30826 29639 30826 29638 960 29639 960 29631 960 29631 30827 29639 30827 29640 30827 29631 30828 29640 30828 29629 30828 29641 960 29147 960 29756 960 29756 960 29147 960 29602 960 29153 30829 29643 30829 29642 30829 29642 30830 29643 30830 29644 30830 29642 30831 29644 30831 29257 30831 29257 30832 29644 30832 29645 30832 29257 960 29645 960 29646 960 29645 30833 29647 30833 29646 30833 29646 30834 29647 30834 29148 30834 29646 30835 29148 30835 29641 30835 29641 960 29148 960 29648 960 29641 30836 29648 30836 29147 30836 29162 960 29649 960 29650 960 29650 30837 29649 30837 29651 30837 29596 960 29155 960 29157 960 29157 960 29158 960 29596 960 29596 30838 29158 30838 29159 30838 29596 960 29159 960 29650 960 29650 30839 29159 30839 29652 30839 29650 30840 29652 30840 29162 30840 29649 30841 29653 30841 29651 30841 29651 960 29653 960 29173 960 29651 960 29173 960 29239 960 29173 960 29654 960 29239 960 29239 30842 29654 30842 29655 30842 29239 960 29655 960 29237 960 29237 30843 29655 30843 29656 30843 29237 30844 29656 30844 29236 30844 29236 30845 29656 30845 29657 30845 29236 30846 29657 30846 29233 30846 29233 30847 29657 30847 29658 30847 29233 30848 29658 30848 29659 30848 29659 30849 29658 30849 29169 30849 29659 30850 29169 30850 29660 30850 29660 30851 29169 30851 29661 30851 29660 30852 29661 30852 29167 30852 29663 960 29178 960 29662 960 29808 30853 29181 30853 29663 30853 29663 960 29181 960 29179 960 29663 960 29179 960 29178 960 29038 960 29088 960 29789 960 29789 960 29088 960 29663 960 29789 960 29663 960 29194 960 29194 30854 29663 30854 29662 30854 29695 960 29185 960 29808 960 29808 30855 29185 30855 29183 30855 29808 960 29183 960 29181 960 29190 30856 29189 30856 29688 30856 29688 30857 29189 30857 29664 30857 29688 30858 29664 30858 29665 30858 29665 960 29664 960 29666 960 29665 960 29666 960 29667 960 29667 30859 29666 30859 29188 30859 29667 30860 29188 30860 29668 30860 29668 960 29188 960 29669 960 29668 30861 29669 30861 29670 30861 29670 30862 29669 30862 29177 30862 29670 960 29177 960 29815 960 29194 30863 29671 30863 29789 30863 29789 30864 29671 30864 29672 30864 29789 960 29672 960 29776 960 29776 30865 29672 30865 29673 30865 29776 30866 29673 30866 29197 30866 29675 960 29677 960 29199 960 29199 960 29677 960 29786 960 29199 30867 29786 30867 29200 30867 29200 960 29786 960 29674 960 29675 960 29676 960 29677 960 29677 30868 29676 30868 29678 30868 29677 30869 29678 30869 29679 30869 29679 960 29678 960 29680 960 29679 960 29680 960 29601 960 29681 30870 29781 30870 29714 30870 29700 960 29204 960 29706 960 29706 960 29204 960 29203 960 29681 960 29714 960 29682 960 29691 960 29208 960 29685 960 29704 960 29683 960 29208 960 29208 30871 29683 30871 29684 30871 29208 960 29684 960 29685 960 29823 960 29686 960 29689 960 29690 960 29687 960 29688 960 29688 30872 29687 30872 29776 30872 29688 30873 29776 30873 29190 30873 29190 30874 29776 30874 29197 30874 29686 960 29690 960 29689 960 29689 960 29690 960 29688 960 29689 30875 29688 30875 29820 30875 29820 30876 29688 30876 29665 30876 29691 30877 29685 30877 29679 30877 29679 30878 29685 30878 29692 30878 29679 960 29692 960 29804 960 29804 30879 29693 30879 29808 30879 29693 30880 29694 30880 29808 30880 29808 30881 29694 30881 29323 30881 29808 30882 29323 30882 29695 30882 29695 30883 29323 30883 29696 30883 29695 960 29696 960 29177 960 29177 30884 29696 30884 29697 30884 29177 30885 29697 30885 29815 30885 29316 960 29698 960 29706 960 29706 30886 29698 30886 29699 30886 29706 960 29699 960 29700 960 29700 30887 29699 30887 29701 30887 29700 960 29701 960 29702 960 29702 960 29701 960 29314 960 29702 960 29314 960 29703 960 29703 30888 29314 30888 29313 30888 29703 960 29313 960 29704 960 29704 30889 29313 30889 29312 30889 29704 960 29312 960 29683 960 29705 960 29306 960 29714 960 29714 30890 29306 30890 29706 30890 29714 30891 29706 30891 29682 30891 29682 960 29706 960 29203 960 29317 30892 29316 30892 29302 30892 29302 960 29316 960 29706 960 29302 30893 29706 30893 29707 30893 29707 30894 29706 30894 29306 30894 29708 960 29709 960 29710 960 29710 30895 29709 30895 29712 30895 29710 960 29712 960 29711 960 29711 30896 29712 30896 29705 30896 29711 960 29705 960 29713 960 29713 960 29705 960 29714 960 29713 960 29714 960 29715 960 29310 960 29298 960 29716 960 29716 30897 29298 30897 29297 30897 29717 960 29726 960 29718 960 29718 30898 29726 30898 29298 30898 29718 960 29298 960 29719 960 29719 30899 29298 30899 29310 30899 29719 960 29310 960 29708 960 29708 960 29310 960 29309 960 29708 30900 29309 30900 29709 30900 29113 960 29115 960 29729 960 29729 960 29115 960 29720 960 29729 30901 29720 30901 29726 30901 29726 30902 29720 30902 29116 30902 29726 960 29116 960 29118 960 29727 30903 29722 30903 29721 30903 29721 30904 29722 30904 29723 30904 29721 30905 29723 30905 29107 30905 29107 30906 29723 30906 29299 30906 29107 30907 29299 30907 29105 30907 29105 960 29299 960 29724 960 29105 960 29724 960 29725 960 29725 30908 29724 30908 29298 30908 29725 960 29298 960 29104 960 29104 960 29298 960 29726 960 29104 960 29726 960 29119 960 29119 960 29726 960 29118 960 29727 960 29728 960 29722 960 29722 30909 29728 30909 29730 30909 29722 960 29730 960 29729 960 29729 960 29730 960 29111 960 29729 30910 29111 30910 29113 30910 29338 30911 29731 30911 29722 30911 29286 960 29285 960 29737 960 29737 960 29285 960 29335 960 29799 30912 29327 30912 29729 30912 29729 960 29327 960 29328 960 29729 30913 29328 30913 29722 30913 29722 30914 29328 30914 29732 30914 29722 30915 29732 30915 29338 30915 29284 30916 29731 30916 29285 30916 29285 30917 29731 30917 29733 30917 29285 30918 29733 30918 29335 30918 29284 960 29734 960 29731 960 29731 30919 29734 30919 29282 30919 29731 30920 29282 30920 29722 30920 29722 30921 29282 30921 29735 30921 29722 960 29735 960 29736 960 29286 30922 29737 30922 29287 30922 29287 30923 29737 30923 29616 30923 29287 960 29616 960 29738 960 29738 30924 29616 30924 29289 30924 29289 960 29616 960 29739 960 29289 960 29739 960 29279 960 29279 960 29739 960 29277 960 29279 960 29277 960 29275 960 29751 30925 29740 30925 29750 30925 29750 30926 29740 30926 29741 30926 29631 30927 29749 30927 29743 30927 29068 30928 29631 30928 29742 30928 29742 30929 29631 30929 29743 30929 29742 30930 29743 30930 29744 30930 29740 30931 29745 30931 29741 30931 29741 30932 29745 30932 29746 30932 29741 960 29746 960 29632 960 29632 30933 29746 30933 29747 30933 29632 30934 29747 30934 29631 30934 29631 960 29747 960 29748 960 29631 960 29748 960 29749 960 29750 960 29264 960 29751 960 29751 960 29264 960 29752 960 29751 960 29752 960 29753 960 29753 30935 29752 30935 29263 30935 29753 960 29263 960 29754 960 29754 960 29263 960 29742 960 29754 960 29742 960 29755 960 29755 960 29742 960 29744 960 29641 960 29759 960 29646 960 29646 30936 29759 30936 29245 30936 29646 30937 29245 30937 29243 30937 29598 960 29597 960 29243 960 29243 960 29597 960 29254 960 29243 960 29254 960 29646 960 29756 30938 29757 30938 29761 30938 29761 960 29247 960 29756 960 29756 30939 29247 30939 29758 30939 29756 960 29758 960 29641 960 29641 30940 29758 30940 29246 30940 29641 30941 29246 30941 29759 30941 29585 960 29650 960 29760 960 29760 30942 29650 30942 29651 30942 29760 30943 29651 30943 29587 30943 29587 960 29651 960 29589 960 29761 960 29762 960 29247 960 29247 30944 29762 30944 29763 30944 29247 30945 29763 30945 29248 30945 29248 30946 29763 30946 29589 30946 29248 960 29589 960 29249 960 29249 30947 29589 30947 29651 30947 29249 960 29651 960 29764 960 29764 960 29651 960 29765 960 29765 960 29651 960 29766 960 29766 960 29651 960 29239 960 29766 30948 29239 30948 29767 30948 29768 30949 29769 30949 29660 30949 29660 960 29769 960 29770 960 29660 30950 29770 30950 29659 30950 29659 30951 29770 30951 29213 30951 29659 960 29213 960 29229 960 29595 30952 29771 30952 29596 30952 29596 960 29771 960 29660 960 29596 30953 29660 30953 29155 30953 29155 30954 29660 30954 29167 30954 29771 960 29772 960 29660 960 29660 30955 29772 30955 29341 30955 29660 960 29341 960 29768 960 29768 30956 29341 30956 29773 30956 29768 30957 29773 30957 29774 30957 29774 30958 29773 30958 29775 30958 29774 30959 29775 30959 29216 30959 29216 30960 29775 30960 29355 30960 29216 30961 29355 30961 29218 30961 29218 960 29355 960 29776 960 29218 30962 29776 30962 29219 30962 29219 960 29776 960 29687 960 29335 30963 29334 30963 29737 30963 29737 30964 29334 30964 29332 30964 29737 960 29332 960 29777 960 29777 30965 29332 30965 29331 30965 29778 30966 29798 30966 29779 30966 29779 30967 29798 30967 29777 30967 29779 960 29777 960 29780 960 29780 960 29777 960 29331 960 29781 960 29786 960 29714 960 29714 960 29786 960 29782 960 29714 960 29782 960 29715 960 29796 960 29783 960 29797 960 29783 960 29784 960 29797 960 29797 30968 29784 30968 29785 30968 29797 30969 29785 30969 29786 30969 29786 30970 29785 30970 29787 30970 29786 960 29787 960 29782 960 29347 30971 29343 30971 29814 30971 29355 960 29354 960 29776 960 29776 30972 29354 30972 29353 30972 29776 960 29353 960 29789 960 29789 30973 29353 30973 29352 30973 29789 30974 29352 30974 29349 30974 29788 960 29041 960 29814 960 29814 960 29041 960 29789 960 29814 960 29789 960 29347 960 29347 30975 29789 30975 29349 30975 29790 960 29583 960 29792 960 29602 960 29795 960 29756 960 29756 30976 29795 30976 29580 30976 29756 960 29580 960 29757 960 29583 960 29791 960 29792 960 29792 30977 29791 30977 29793 30977 29792 30978 29793 30978 29795 30978 29795 960 29793 960 29794 960 29795 960 29794 960 29580 960 29717 960 29796 960 29726 960 29726 30979 29796 30979 29797 30979 29726 960 29797 960 29729 960 29729 960 29797 960 29798 960 29729 960 29798 960 29799 960 29799 960 29798 960 29778 960 29801 960 29800 960 29663 960 29091 960 29677 960 29663 960 29663 30980 29677 30980 29813 30980 29663 30981 29813 30981 29801 30981 29808 30982 29802 30982 29803 30982 29804 960 29808 960 29679 960 29679 30983 29808 30983 29803 30983 29679 960 29803 960 29805 960 29800 960 29806 960 29663 960 29663 30984 29806 30984 29807 30984 29663 30985 29807 30985 29808 30985 29808 960 29807 960 29809 960 29808 30986 29809 30986 29802 30986 29805 30987 29810 30987 29679 30987 29679 29815 29810 29815 29811 29815 29679 30988 29811 30988 29677 30988 29677 960 29811 960 29812 960 29677 30989 29812 30989 29813 30989 29343 960 29594 960 29814 960 29814 960 29594 960 29596 960 29814 960 29596 960 29792 960 29792 960 29596 960 29650 960 29792 30990 29650 30990 29790 30990 29790 30991 29650 30991 29585 30991 29815 30992 29892 30992 29816 30992 29815 30993 29816 30993 29670 30993 29670 30994 29816 30994 29817 30994 29670 30995 29817 30995 29668 30995 29668 30996 29817 30996 29818 30996 29668 30997 29818 30997 29667 30997 29667 30998 29818 30998 29819 30998 29667 30999 29819 30999 29665 30999 29665 31000 29819 31000 29890 31000 29665 31001 29890 31001 29820 31001 29820 31002 29890 31002 29821 31002 29820 31003 29821 31003 29689 31003 29689 31004 29821 31004 29822 31004 29689 31005 29822 31005 29823 31005 29823 31006 29822 31006 29927 31006 29823 31007 29927 31007 29600 31007 30024 15464 29892 15464 29824 15464 29824 31008 29892 31008 29815 31008 29824 31009 29815 31009 29320 31009 29320 15467 29815 15467 29697 15467 29892 960 30024 960 29825 960 29825 31010 30024 31010 29939 31010 29826 31011 29895 31011 29827 31011 29827 31012 29895 31012 29894 31012 29827 960 29894 960 29939 960 29939 31013 29894 31013 29828 31013 29939 31014 29828 31014 29825 31014 29829 31015 29830 31015 29880 31015 29880 590 29830 590 29893 590 29880 31016 29893 31016 29831 31016 29831 590 29893 590 30054 590 29831 31017 30054 31017 29832 31017 29832 31018 30054 31018 29833 31018 29832 31019 29833 31019 29834 31019 29834 590 29833 590 29898 590 29834 31020 29898 31020 29835 31020 29835 31021 29898 31021 29836 31021 29835 590 29836 590 29837 590 29837 31022 29836 31022 29838 31022 29837 590 29838 590 29839 590 29839 31023 29838 31023 29905 31023 29839 590 29905 590 29840 590 29840 590 29905 590 29841 590 29840 590 29841 590 29842 590 29842 31024 29841 31024 30076 31024 29842 590 30076 590 29843 590 29843 590 30076 590 30074 590 29843 590 30074 590 29844 590 29844 590 30074 590 29845 590 29844 590 29845 590 29846 590 29846 590 29845 590 30072 590 29846 590 30072 590 29847 590 29847 590 30072 590 29849 590 29847 590 29849 590 29848 590 29848 590 29849 590 29912 590 29848 590 29912 590 29850 590 29850 31025 29912 31025 29913 31025 29850 590 29913 590 29851 590 29851 590 29913 590 29915 590 29851 590 29915 590 29852 590 29852 590 29915 590 30068 590 29852 590 30068 590 29853 590 29853 590 30068 590 29917 590 29853 31026 29917 31026 29854 31026 29854 590 29917 590 29855 590 29854 590 29855 590 29856 590 29856 590 29855 590 29920 590 29856 590 29920 590 29857 590 29857 590 29920 590 29923 590 29857 590 29923 590 29858 590 29858 590 29923 590 29859 590 29858 31027 29859 31027 29860 31027 29860 590 29859 590 30064 590 29860 31028 30064 31028 29861 31028 29861 31029 30064 31029 29883 31029 29861 31030 29883 31030 29862 31030 29862 31031 29883 31031 29863 31031 29862 590 29863 590 29864 590 29864 31032 29863 31032 29885 31032 29864 590 29885 590 29865 590 29865 31033 29885 31033 30061 31033 29865 590 30061 590 29866 590 29866 590 30061 590 29886 590 29866 31034 29886 31034 29867 31034 29867 31035 29886 31035 29888 31035 29867 590 29888 590 29868 590 29868 590 29888 590 29869 590 29868 590 29869 590 29870 590 29870 590 29869 590 30059 590 29870 590 30059 590 29871 590 29871 590 30059 590 29872 590 29871 31036 29872 31036 29873 31036 29873 31037 29872 31037 29874 31037 29873 590 29874 590 29875 590 29875 590 29874 590 29877 590 29875 590 29877 590 29876 590 29876 590 29877 590 30056 590 29876 590 30056 590 29878 590 29878 590 30056 590 29891 590 29878 31038 29891 31038 29879 31038 29879 31039 29891 31039 29829 31039 29879 590 29829 590 29880 590 30064 31040 29859 31040 29259 31040 29259 31041 29881 31041 30064 31041 30064 31042 29881 31042 29882 31042 30064 31043 29882 31043 29883 31043 29882 31044 29256 31044 29883 31044 29883 31045 29256 31045 29255 31045 29883 31046 29255 31046 29863 31046 29255 31047 29884 31047 29863 31047 29863 31048 29884 31048 29253 31048 29863 31049 29253 31049 29885 31049 29253 31050 29227 31050 29885 31050 29885 31051 29227 31051 29226 31051 29885 31052 29226 31052 30061 31052 30061 31053 29226 31053 29241 31053 30061 31054 29241 31054 29886 31054 29886 31055 29241 31055 29238 31055 29886 31056 29238 31056 29888 31056 29888 31057 29238 31057 29887 31057 29887 31058 29889 31058 29888 31058 29888 31059 29889 31059 29235 31059 29888 31060 29235 31060 29869 31060 29235 31061 29234 31061 29869 31061 29869 31062 29234 31062 29232 31062 29869 31063 29232 31063 30059 31063 29232 31064 29231 31064 30059 31064 30059 31065 29231 31065 29230 31065 30059 31066 29230 31066 29872 31066 29230 31067 29931 31067 29872 31067 29872 31068 29931 31068 29928 31068 29872 31068 29928 31068 29874 31068 29874 31069 29928 31069 29927 31069 29874 31070 29927 31070 29877 31070 29927 31071 29822 31071 29877 31071 29877 31072 29822 31072 29821 31072 29877 31073 29821 31073 30056 31073 29821 31074 29890 31074 30056 31074 30056 31075 29890 31075 29819 31075 30056 31076 29819 31076 29891 31076 29819 31077 29818 31077 29891 31077 29891 31078 29818 31078 29817 31078 29891 31079 29817 31079 29829 31079 29817 31080 29816 31080 29829 31080 29829 31081 29816 31081 29892 31081 29829 31082 29892 31082 29830 31082 29892 21919 29825 21919 29830 21919 29830 31083 29825 31083 29828 31083 29830 31084 29828 31084 29893 31084 29893 31085 29828 31085 29894 31085 29893 31085 29894 31085 30054 31085 30054 31086 29894 31086 29895 31086 30054 31087 29895 31087 29833 31087 29895 31088 29896 31088 29833 31088 29833 31089 29896 31089 29897 31089 29833 31090 29897 31090 29898 31090 29897 31091 29899 31091 29898 31091 29898 31092 29899 31092 29900 31092 29898 31093 29900 31093 29836 31093 29900 31094 29315 31094 29836 31094 29836 31095 29315 31095 29901 31095 29836 31096 29901 31096 29838 31096 29901 31097 29902 31097 29838 31097 29838 31098 29902 31098 29903 31098 29838 31099 29903 31099 29905 31099 29903 31100 29904 31100 29905 31100 29905 31101 29904 31101 29906 31101 29905 31102 29906 31102 29841 31102 29841 31103 29906 31103 29295 31103 29841 31104 29295 31104 30076 31104 30076 31105 29295 31105 29296 31105 30076 31106 29296 31106 30074 31106 30074 31107 29296 31107 29907 31107 29907 31108 29908 31108 30074 31108 30074 31109 29908 31109 29909 31109 30074 31110 29909 31110 29845 31110 29909 31111 29294 31111 29845 31111 29845 31112 29294 31112 29293 31112 29845 31113 29293 31113 30072 31113 29293 31114 29292 31114 30072 31114 30072 31115 29292 31115 29910 31115 30072 31116 29910 31116 29849 31116 29910 31117 29269 31117 29849 31117 29849 31118 29269 31118 29911 31118 29849 31118 29911 31118 29912 31118 29912 31119 29911 31119 29280 31119 29912 31120 29280 31120 29913 31120 29280 31121 29276 31122 29913 31123 29913 31124 29276 31124 29914 31124 29913 31125 29914 31125 29915 31125 29914 31126 29274 31126 29915 31126 29915 31127 29274 31127 29916 31127 29915 31128 29916 31128 30068 31128 29916 31129 29272 31129 30068 31129 30068 31130 29272 31130 29270 31130 30068 31131 29270 31131 29917 31131 29270 31132 29918 31132 29917 31132 29917 31133 29918 31133 29919 31133 29917 31134 29919 31134 29855 31134 29919 21866 29225 21866 29855 21866 29855 31135 29225 31135 29921 31135 29855 31136 29921 31136 29920 31136 29920 31137 29921 31137 29922 31137 29920 31138 29922 31138 29923 31138 29923 31139 29922 31139 29924 31139 29923 31140 29924 31140 29859 31140 29859 31141 29924 31141 29925 31141 29859 31142 29925 31142 29259 31142 29926 960 29927 960 29982 960 29982 960 29927 960 29928 960 29982 31143 29928 31143 29929 31143 29929 31144 29928 31144 29931 31144 29929 31145 29931 31145 29930 31145 29930 960 29931 960 29230 960 30023 31146 29932 31147 29933 31148 30002 31149 29934 31149 30003 31149 29973 31150 29935 31150 29974 31150 29960 31151 29936 31151 29967 31151 30007 31152 29318 31152 30009 31152 30016 31153 29937 31153 30017 31153 30024 31154 29824 31154 29424 31154 29933 31155 29938 31155 30025 31155 29940 31156 29827 31156 29939 31156 30018 31157 29431 31157 29826 31157 29827 31158 29940 31158 29826 31158 29945 31159 29290 31159 29941 31159 29941 31160 29290 31160 29291 31160 29941 31161 29291 31161 30008 31161 29944 31162 29942 31162 29943 31162 30001 31163 30000 31163 29943 31163 29943 31164 30000 31164 29290 31164 29943 31165 29290 31165 29944 31165 29944 31166 29290 31166 29945 31166 29944 31167 29945 31167 29946 31167 29992 31168 29268 31168 29947 31168 29947 31169 29268 31169 29948 31169 29947 31170 29948 31170 29998 31170 29998 31171 29948 31172 29949 31173 29998 31174 29949 31174 29950 31174 29991 31175 29951 31175 29990 31175 29952 31176 30052 31177 29953 31178 29954 31179 29482 31179 29955 31179 29956 31180 29402 31180 29401 31180 29964 31181 29963 31181 29957 31181 29957 31182 29963 31182 29956 31182 29962 31183 29958 31183 29959 31183 29960 31184 29223 31184 29961 31184 29961 31185 29223 31185 29224 31185 29961 31186 29224 31186 29959 31186 29959 31187 29224 31187 29963 31187 29959 31188 29963 31189 29962 31190 29962 31191 29963 31191 29964 31191 29962 31192 29964 31192 29965 31192 29967 31193 29966 31193 29968 31193 29960 31194 29967 31194 29223 31194 29223 31195 29967 31195 29968 31195 29223 31196 29968 31196 29222 31196 29222 31197 29968 31197 29969 31197 29222 31198 29969 31198 29409 31198 30045 31199 29970 31199 30044 31199 29252 31200 30044 31200 29971 31200 29971 31201 30044 31201 29972 31201 29971 31202 29972 31202 29228 31202 29228 31203 29972 31203 29973 31203 29974 31204 29975 31204 29976 31204 29461 31205 29463 31205 29240 31205 29973 31206 29974 31206 29228 31206 29228 31207 29974 31207 29976 31207 29228 31208 29976 31208 29977 31208 29977 31209 29976 31209 29978 31209 29977 31210 29978 31210 29240 31210 29240 31211 29978 31211 30037 31211 29240 31212 30037 31212 29461 31212 29930 31213 29460 31213 29459 31213 29985 31214 29929 31214 30038 31214 30038 31215 29929 31215 29930 31215 29979 31216 29980 31216 29984 31216 29981 31217 29926 31217 29983 31217 29983 31218 29926 31218 29982 31218 29983 31219 29982 31219 29984 31219 29984 31220 29982 31220 29929 31220 29984 31221 29929 31221 29979 31221 29979 31222 29929 31223 29985 31224 29979 31225 29985 31225 29986 31225 29956 31226 29401 31226 29957 31226 29957 31227 29401 31227 29400 31227 29957 31228 29400 31228 29995 31228 29987 31229 29997 31229 29953 31229 29953 31230 29997 31230 29954 31230 29953 31231 29954 31232 29952 31233 29952 31234 29954 31234 29955 31234 29952 31235 29955 31235 29989 31235 29989 31236 29955 31236 29988 31236 29989 31237 29988 31237 29990 31237 29990 31238 29988 31238 29268 31238 29990 31239 29268 31239 29991 31239 29991 31240 29268 31240 29992 31240 29991 31241 29992 31241 29993 31241 29400 31242 29994 31242 29995 31242 29995 31243 29994 31243 29996 31243 29995 31244 29996 31244 29997 31244 29997 31245 29996 31245 29360 31245 29997 31246 29360 31246 29954 31246 29950 31247 29488 31247 29998 31247 29998 31248 29488 31248 29492 31248 29998 31249 29492 31249 29999 31249 29999 31250 29492 31250 30004 31250 29301 31251 30000 31251 29359 31251 29359 31252 30000 31252 30001 31252 29359 31253 30001 31253 29505 31253 29505 31254 30001 31254 30002 31254 29505 31255 30002 31255 30004 31255 30004 31256 30002 31256 30003 31256 30004 31257 30003 31257 29999 31257 29999 31258 30003 31258 30005 31258 30011 31259 30006 31259 30010 31259 30012 31260 29516 31260 29436 31260 30012 31261 29436 31261 30021 31261 29291 31262 30007 31262 30008 31262 30008 31263 30007 31263 30009 31263 30008 31264 30009 31264 30010 31264 30010 31265 30009 31265 29516 31265 30010 31266 29516 31266 30011 31266 30011 31267 29516 31267 30012 31267 30011 31268 30012 31269 30013 31270 30017 31271 30014 31271 30015 31271 29940 31272 30016 31272 29826 31272 29826 31273 30016 31273 30017 31273 29826 31274 30017 31274 30018 31274 30018 31275 30017 31275 30015 31275 30018 31276 30015 31276 30019 31276 30019 31277 30015 31277 30021 31277 30019 31278 30021 31278 30020 31278 30020 31279 30021 31279 29436 31279 29428 31280 30022 31280 30023 31280 29428 31281 30023 31281 29424 31281 29424 31282 30023 31282 29933 31282 29424 31283 29933 31283 30024 31283 30024 31284 29933 31284 30025 31284 30024 31285 30025 31285 29939 31285 29939 31286 30025 31286 30026 31286 29939 31287 30026 31287 29940 31287 30032 31288 30027 31288 30031 31288 30028 31289 29926 31289 29446 31289 29446 31290 29926 31290 29981 31290 29446 31291 29981 31291 30029 31291 30029 31292 29981 31292 30033 31292 29428 31293 30030 31293 30022 31293 30022 31294 30030 31294 29447 31294 30022 31295 29447 31295 30031 31295 30031 31296 29447 31296 30029 31296 30031 31297 30029 31298 30032 31299 30032 31300 30029 31300 30033 31300 30032 31301 30033 31301 30034 31301 30035 31302 30036 31303 30039 31304 30041 31305 30040 31305 30037 31305 30037 31306 30040 31306 29421 31306 30037 31307 29421 31307 29461 31307 29930 31308 29459 31308 30038 31308 30038 31309 29459 31309 29458 31309 30038 31310 29458 31310 30039 31310 30039 31311 29458 31311 30040 31311 30039 31312 30040 31312 30035 31312 30035 31313 30040 31313 30041 31313 30035 31314 30041 31314 30042 31314 29476 31315 29475 31315 30046 31315 30046 31316 29475 31316 29407 31316 30046 31317 29407 31317 30043 31317 29252 31318 29473 31318 30044 31318 30044 31319 29473 31319 29476 31319 30044 31320 29476 31320 30045 31320 30045 31321 29476 31321 30046 31321 30045 31322 30046 31322 30047 31322 29407 31323 30048 31323 30043 31323 30043 31324 30048 31324 30049 31324 30043 31325 30049 31325 29969 31325 29969 31326 30049 31326 29412 31326 29969 31327 29412 31327 29409 31327 30050 31328 30052 31328 30051 31328 30051 31329 30052 31329 29952 31329 30051 31330 29952 31330 30053 31330 30054 31331 30055 31331 29893 31331 29893 31332 30055 31332 30141 31332 29893 31333 30141 31333 29830 31333 29830 22660 30141 22660 30139 22660 29830 22661 30139 22661 29829 22661 29829 31334 30139 31334 30138 31334 29829 31335 30138 31335 29891 31335 29891 22664 30138 22664 30174 22664 29891 31336 30174 31336 30056 31336 30056 31337 30174 31337 30057 31337 30056 31337 30057 31337 29877 31337 29877 31338 30057 31338 30172 31338 29877 31339 30172 31339 29874 31339 29874 31340 30172 31340 30058 31340 29874 31341 30058 31341 29872 31341 29872 31342 30058 31342 30169 31342 29872 31343 30169 31343 30059 31343 30059 31344 30169 31344 30167 31344 30059 31345 30167 31345 29869 31345 29869 31346 30167 31346 30166 31346 29869 31347 30166 31347 29888 31347 29888 31348 30166 31348 30164 31348 29888 31349 30164 31349 29886 31349 29886 31350 30164 31350 30060 31350 29886 31351 30060 31351 30061 31351 30061 31352 30060 31352 30062 31352 30061 31353 30062 31353 29885 31353 29885 31354 30062 31354 30163 31354 29885 31354 30163 31354 29863 31354 29863 31355 30163 31355 30063 31355 29863 31355 30063 31355 29883 31355 29883 31356 30063 31356 30161 31356 29883 31357 30161 31357 30064 31357 30064 31358 30161 31358 30065 31358 30064 31359 30065 31359 29859 31359 29859 31360 30065 31360 30159 31360 29859 31361 30159 31361 29923 31361 29923 31362 30159 31362 30158 31362 29923 31363 30158 31363 29920 31363 29920 31364 30158 31364 30066 31364 29920 31365 30066 31365 29855 31365 29855 22625 30066 22625 30067 22625 29855 22626 30067 22626 29917 22626 29917 31366 30067 31366 30069 31366 29917 31367 30069 31367 30068 31367 30068 22629 30069 22629 30154 22629 30068 31368 30154 31368 29915 31368 29915 31369 30154 31369 30070 31369 29915 31369 30070 31369 29913 31369 29913 31370 30070 31370 30153 31370 29913 31371 30153 31371 29912 31371 29912 31372 30153 31372 30151 31372 29912 31373 30151 31373 29849 31373 29849 31374 30151 31374 30071 31374 29849 31375 30071 31375 30072 31375 30072 31376 30071 31376 30149 31376 30072 31377 30149 31377 29845 31377 29845 31378 30149 31378 30073 31378 29845 31379 30073 31379 30074 31379 30074 31380 30073 31380 30075 31380 30074 31381 30075 31381 30076 31381 30076 31382 30075 31382 30147 31382 30076 31383 30147 31383 29841 31383 29841 31384 30147 31384 30146 31384 29841 31385 30146 31385 29905 31385 29905 31386 30146 31386 30077 31386 29905 31386 30077 31386 29838 31386 29838 31387 30077 31387 30078 31387 29838 31388 30078 31388 29836 31388 29836 31389 30078 31389 30145 31389 29836 31390 30145 31390 29898 31390 29898 31391 30145 31391 30144 31391 29898 31392 30144 31392 29833 31392 29833 31393 30144 31393 30143 31393 29833 31394 30143 31394 30054 31394 30054 31395 30143 31395 30055 31395 30136 31396 30079 31396 30080 31396 30080 31397 30079 31397 30081 31397 30080 31398 30081 31398 30082 31398 30082 31399 30081 31399 30142 31399 30082 31399 30142 31399 30083 31399 30083 31400 30142 31400 30085 31400 30083 31401 30085 31401 30084 31401 30084 31402 30085 31402 30086 31402 30084 31402 30086 31402 30087 31402 30087 31403 30086 31403 30088 31403 30087 31404 30088 31404 30089 31404 30089 31405 30088 31405 30090 31405 30089 31406 30090 31406 30091 31406 30091 31407 30090 31407 30148 31407 30091 31408 30148 31408 30092 31408 30092 31409 30148 31409 30093 31409 30092 31410 30093 31410 30094 31410 30094 31411 30093 31411 30095 31411 30094 31412 30095 31412 30096 31412 30096 31413 30095 31413 30097 31413 30096 31414 30097 31414 30098 31414 30098 31415 30097 31415 30099 31415 30098 31416 30099 31416 30100 31416 30100 31417 30099 31417 30150 31417 30100 31418 30150 31418 30101 31418 30101 31419 30150 31419 30102 31419 30101 31419 30102 31419 30103 31419 30103 31420 30102 31420 30152 31420 30103 31421 30152 31421 30104 31421 30104 31422 30152 31422 30106 31422 30104 31423 30106 31423 30105 31423 30105 31424 30106 31424 30155 31424 30105 31425 30155 31425 30107 31425 30107 31426 30155 31426 30109 31426 30107 31427 30109 31427 30108 31427 30108 31428 30109 31428 30156 31428 30108 31429 30156 31429 30110 31429 30110 31430 30156 31430 30157 31430 30110 31431 30157 31431 30112 31431 30112 31432 30157 31432 30111 31432 30112 31433 30111 31433 30113 31433 30113 31434 30111 31434 30160 31434 30113 31435 30160 31435 30115 31435 30115 31436 30160 31436 30114 31436 30115 31437 30114 31437 30117 31437 30117 31438 30114 31438 30116 31438 30117 31439 30116 31439 30118 31439 30118 31440 30116 31440 30162 31440 30118 31441 30162 31441 30119 31441 30119 31442 30162 31442 30120 31442 30119 31443 30120 31443 30121 31443 30121 31444 30120 31444 30123 31444 30121 31445 30123 31445 30122 31445 30122 31446 30123 31446 30124 31446 30122 31447 30124 31447 30125 31447 30125 31448 30124 31448 30165 31448 30125 31449 30165 31449 30126 31449 30126 31450 30165 31450 30168 31450 30126 31451 30168 31451 30127 31451 30127 31452 30168 31452 30170 31452 30127 31453 30170 31453 30128 31453 30128 31454 30170 31454 30171 31454 30128 31455 30171 31455 30129 31455 30129 31456 30171 31456 30130 31456 30129 31457 30130 31457 30131 31457 30131 31458 30130 31458 30173 31458 30131 31459 30173 31459 30132 31459 30132 31460 30173 31460 30137 31460 30132 31461 30137 31461 30133 31461 30133 31462 30137 31462 30140 31462 30133 31463 30140 31463 30134 31463 30134 31464 30140 31464 30135 31464 30134 31465 30135 31465 30136 31465 30136 31466 30135 31466 30079 31466 30137 590 30173 590 30138 590 30137 31467 30138 31467 30140 31467 30140 590 30138 590 30139 590 30140 590 30139 590 30135 590 30135 590 30139 590 30141 590 30135 590 30141 590 30079 590 30079 31468 30141 31468 30055 31468 30079 31469 30055 31469 30081 31469 30081 590 30055 590 30143 590 30081 590 30143 590 30142 590 30142 590 30143 590 30144 590 30142 31470 30144 31470 30085 31470 30085 590 30144 590 30145 590 30085 31471 30145 31471 30086 31471 30086 590 30145 590 30078 590 30086 590 30078 590 30088 590 30088 590 30078 590 30077 590 30088 590 30077 590 30090 590 30090 31472 30077 31472 30146 31472 30090 31473 30146 31473 30148 31473 30148 31474 30146 31474 30147 31474 30148 590 30147 590 30093 590 30093 31475 30147 31475 30075 31475 30093 590 30075 590 30095 590 30095 31476 30075 31476 30073 31476 30095 31477 30073 31477 30097 31477 30097 590 30073 590 30149 590 30097 31478 30149 31478 30099 31478 30099 590 30149 590 30071 590 30099 590 30071 590 30150 590 30150 590 30071 590 30151 590 30150 590 30151 590 30102 590 30102 31479 30151 31479 30153 31479 30102 590 30153 590 30152 590 30152 31480 30153 31480 30070 31480 30152 590 30070 590 30106 590 30106 590 30070 590 30154 590 30106 590 30154 590 30155 590 30155 31481 30154 31481 30069 31481 30155 590 30069 590 30109 590 30109 590 30069 590 30067 590 30109 590 30067 590 30156 590 30156 31482 30067 31482 30066 31482 30156 31483 30066 31483 30157 31483 30066 31484 30158 31484 30157 31484 30157 590 30158 590 30159 590 30157 31485 30159 31485 30111 31485 30111 590 30159 590 30065 590 30111 31486 30065 31486 30160 31486 30160 590 30065 590 30161 590 30160 31487 30161 31487 30114 31487 30114 590 30161 590 30063 590 30114 590 30063 590 30116 590 30116 31488 30063 31488 30163 31488 30116 31489 30163 31489 30162 31489 30162 31490 30163 31490 30062 31490 30162 590 30062 590 30120 590 30120 590 30062 590 30060 590 30120 590 30060 590 30123 590 30123 590 30060 590 30164 590 30123 31491 30164 31491 30124 31491 30124 590 30164 590 30166 590 30124 590 30166 590 30165 590 30165 590 30166 590 30167 590 30165 590 30167 590 30168 590 30168 590 30167 590 30169 590 30168 590 30169 590 30170 590 30170 590 30169 590 30058 590 30170 590 30058 590 30171 590 30171 590 30058 590 30172 590 30171 590 30172 590 30130 590 30130 31492 30172 31492 30057 31492 30130 590 30057 590 30173 590 30173 31493 30057 31493 30174 31493 30173 590 30174 590 30138 590 30187 31494 30176 31494 30175 31494 30175 31495 30176 31495 30177 31495 30175 31496 30177 31496 30178 31496 30178 31497 30177 31497 30179 31497 30178 31498 30179 31498 30263 31498 30263 31499 30179 31499 30180 31499 30263 31500 30180 31500 30181 31500 30181 31501 30180 31501 30223 31501 30181 31502 30223 31502 30182 31502 30182 31503 30223 31503 30221 31503 30182 31504 30221 31504 30239 31504 30239 31505 30221 31505 30183 31505 30239 31506 30183 31506 30240 31506 30240 31507 30183 31507 30184 31507 30240 31508 30184 31508 30260 31508 30260 31509 30184 31509 30213 31509 30260 31510 30213 31510 30261 31510 30261 31511 30213 31511 30205 31511 30261 31512 30205 31512 30268 31512 30268 31513 30205 31513 30185 31513 30268 31514 30185 31514 30186 31514 30186 31515 30185 31515 30204 31515 30186 31516 30204 31516 30187 31516 30187 31517 30204 31517 30176 31517 30225 31518 30206 31518 30264 31518 30264 31519 30206 31519 30236 31519 30189 31520 30256 31520 30188 31520 30188 31521 30256 31521 30203 31521 30189 31522 30188 31522 30190 31522 30189 31523 30190 31523 30269 31523 30269 31524 30190 31524 30191 31524 30269 31525 30191 31525 30192 31525 30192 31526 30191 31526 30227 31526 30192 31527 30227 31527 30193 31527 30193 31528 30227 31528 30220 31528 30193 31529 30220 31529 30195 31529 30220 31530 30194 31530 30195 31530 30195 31531 30194 31531 30241 31531 30206 31532 30225 31532 30229 31532 30229 31533 30225 31533 30196 31533 30231 31534 30203 31534 30197 31534 30197 31535 30203 31535 30233 31535 30217 31536 30233 31536 30198 31536 30198 31537 30233 31537 30203 31537 30198 31538 30203 31538 30199 31538 30199 31539 30203 31539 30281 31539 30180 31540 30201 31540 30226 31540 30229 31541 30228 31541 30206 31541 30206 31542 30228 31542 30277 31542 30206 31543 30277 31543 30200 31543 30180 31544 30179 31544 30201 31544 30201 31545 30179 31545 30177 31545 30201 31546 30177 31546 30202 31546 30202 31547 30177 31547 30176 31547 30202 31548 30176 31548 30231 31548 30231 31549 30176 31549 30203 31549 30203 31550 30176 31550 30204 31550 30203 31551 30204 31551 30188 31551 30188 31552 30204 31552 30185 31552 30188 31553 30185 31553 30205 31553 30200 31554 30207 31554 30206 31554 30206 31555 30207 31555 30219 31555 30206 31556 30219 31556 30208 31556 30274 31557 30273 31557 30209 31557 30209 31558 30273 31558 30270 31558 30209 31559 30270 31559 30210 31559 30210 31560 30270 31560 30282 31560 30210 31561 30282 31561 30211 31561 30211 31562 30282 31562 30281 31562 30211 31563 30281 31563 30212 31563 30212 31564 30281 31564 30203 31564 30205 31565 30213 31565 30220 31565 30228 31566 30214 31566 30277 31566 30277 31567 30214 31567 30215 31567 30277 31568 30215 31568 30278 31568 30278 31569 30215 31569 30217 31569 30278 31570 30217 31570 30216 31570 30216 31571 30217 31571 30198 31571 30274 31572 30209 31572 30207 31572 30207 31573 30209 31573 30218 31573 30207 31574 30218 31574 30219 31574 30213 31575 30184 31575 30220 31575 30220 31576 30184 31576 30183 31576 30220 31577 30183 31577 30194 31577 30194 31578 30183 31578 30221 31578 30194 31579 30221 31579 30222 31579 30222 31580 30221 31580 30223 31580 30222 31581 30223 31581 30224 31581 30224 31582 30223 31582 30180 31582 30224 31583 30180 31583 30225 31583 30225 31584 30180 31584 30226 31584 30225 31585 30226 31585 30196 31585 30190 31586 30188 31586 30191 31586 30191 31587 30188 31587 30205 31587 30191 31588 30205 31588 30227 31588 30227 31589 30205 31589 30220 31589 30258 31590 30217 31590 30259 31590 30259 31591 30217 31591 30215 31591 30259 31592 30215 31592 30244 31592 30244 31593 30215 31593 30214 31593 30244 31594 30214 31594 30234 31594 30234 31595 30214 31595 30228 31595 30234 31596 30228 31596 30235 31596 30235 31597 30228 31597 30229 31597 30235 31598 30229 31598 30237 31598 30237 31599 30229 31599 30196 31599 30237 31600 30196 31600 30238 31600 30238 31601 30196 31601 30226 31601 30238 31602 30226 31602 30262 31602 30262 31603 30226 31603 30201 31603 30262 31604 30201 31604 30267 31604 30267 31605 30201 31605 30202 31605 30267 31606 30202 31606 30230 31606 30230 31607 30202 31607 30231 31607 30230 31608 30231 31608 30257 31608 30257 31609 30231 31609 30197 31609 30257 31610 30197 31610 30232 31610 30232 31611 30197 31611 30233 31611 30232 31612 30233 31612 30258 31612 30258 31613 30233 31613 30217 31613 30236 31614 30244 31614 30234 31614 30234 31615 30235 31615 30236 31615 30236 31616 30235 31616 30237 31616 30236 31617 30237 31617 30264 31617 30264 31618 30237 31618 30238 31618 30264 31619 30238 31619 30262 31619 30182 31620 30239 31620 30241 31620 30241 31621 30239 31621 30240 31621 30241 31622 30240 31622 30195 31622 30242 31623 30275 31623 30236 31623 30236 31624 30275 31624 30276 31624 30236 31625 30276 31625 30244 31625 30244 31626 30276 31626 30243 31626 30244 31627 30243 31627 30259 31627 30259 31628 30243 31628 30245 31628 30267 31629 30230 31629 30189 31629 30189 31630 30230 31630 30257 31630 30189 31631 30257 31631 30256 31631 30246 31632 30248 31632 30247 31632 30247 31633 30248 31633 30275 31633 30247 31634 30275 31634 30249 31634 30249 31635 30275 31635 30242 31635 30187 31636 30175 31636 30267 31636 30253 31637 30250 31637 30251 31637 30251 31638 30250 31638 30271 31638 30251 31639 30271 31639 30246 31639 30246 31640 30271 31640 30272 31640 30246 31641 30272 31641 30248 31641 30267 31642 30175 31642 30262 31642 30251 31643 30252 31643 30253 31643 30253 31644 30252 31644 30254 31644 30253 31645 30254 31645 30255 31645 30255 31646 30254 31646 30256 31646 30255 31647 30256 31647 30280 31647 30280 31648 30256 31648 30257 31648 30280 31649 30257 31649 30279 31649 30279 31650 30257 31650 30232 31650 30279 31651 30232 31651 30245 31651 30245 31652 30232 31652 30258 31652 30245 31653 30258 31653 30259 31653 30240 31654 30260 31654 30195 31654 30195 31655 30260 31655 30261 31655 30195 31656 30261 31656 30193 31656 30193 31657 30261 31657 30268 31657 30193 31658 30268 31658 30192 31658 30175 31659 30178 31659 30262 31659 30262 31660 30178 31660 30263 31660 30262 31661 30263 31661 30264 31661 30264 31662 30263 31662 30181 31662 30264 31663 30181 31663 30265 31663 30265 31664 30181 31664 30182 31664 30265 31665 30182 31665 30266 31665 30266 31666 30182 31666 30241 31666 30187 31667 30267 31667 30186 31667 30186 31668 30267 31668 30189 31668 30186 31669 30189 31669 30268 31669 30268 31670 30189 31670 30269 31670 30268 31671 30269 31671 30192 31671 30250 31672 30270 31672 30271 31672 30271 31673 30270 31673 30273 31673 30271 31674 30273 31674 30272 31674 30272 31675 30273 31675 30274 31675 30272 31676 30274 31676 30248 31676 30248 31677 30274 31677 30207 31677 30248 31678 30207 31678 30275 31678 30275 31679 30207 31679 30200 31679 30275 31680 30200 31680 30276 31680 30276 31681 30200 31681 30277 31681 30276 31682 30277 31682 30243 31682 30243 31683 30277 31683 30278 31683 30243 31684 30278 31684 30245 31684 30245 31685 30278 31685 30216 31685 30245 31686 30216 31686 30279 31686 30279 31687 30216 31687 30198 31687 30279 31688 30198 31688 30280 31688 30280 31689 30198 31689 30199 31689 30280 31690 30199 31690 30255 31690 30255 31691 30199 31691 30281 31691 30255 31692 30281 31692 30253 31692 30253 31693 30281 31693 30282 31693 30253 31694 30282 31694 30250 31694 30250 31695 30282 31695 30270 31695 30283 31696 30297 31696 30284 31696 30284 31697 30297 31697 30285 31697 30284 31698 30285 31698 30355 31698 30355 31699 30285 31699 30287 31699 30355 31699 30287 31699 30286 31699 30286 31700 30287 31700 30288 31700 30286 31700 30288 31700 30353 31700 30353 31701 30288 31701 30289 31701 30353 31702 30289 31702 30351 31702 30351 31703 30289 31703 30447 31703 30351 31704 30447 31704 30350 31704 30350 31705 30447 31705 30290 31705 30350 31706 30290 31706 30291 31706 30291 31707 30290 31707 30292 31707 30291 31708 30292 31708 30347 31708 30347 31709 30292 31709 30446 31709 30347 31709 30446 31709 30293 31709 30293 31710 30446 31710 30294 31710 30293 31710 30294 31710 30346 31710 30346 31711 30294 31711 30295 31711 30346 31712 30295 31712 30343 31712 30343 31713 30295 31713 30296 31713 30343 31714 30296 31714 30283 31714 30283 31696 30296 31696 30297 31696 30319 31715 30362 31715 30298 31715 30298 31716 30362 31716 30361 31716 30298 31717 30361 31717 30299 31717 30299 31718 30361 31718 30360 31718 30299 31719 30360 31719 30300 31719 30300 31720 30360 31720 30301 31720 30300 31721 30301 31721 30302 31721 30302 31722 30301 31722 30370 31722 30302 31723 30370 31723 30303 31723 30303 31724 30370 31724 30304 31724 30303 31725 30304 31725 30312 31725 30312 31726 30304 31726 30368 31726 30312 31727 30368 31727 30305 31727 30305 31728 30368 31728 30307 31728 30305 31729 30307 31729 30306 31729 30306 31730 30307 31730 30367 31730 30306 31731 30367 31731 30315 31731 30315 31732 30367 31732 30308 31732 30315 31733 30308 31733 30317 31733 30317 31734 30308 31734 30309 31734 30317 31735 30309 31735 30318 31735 30318 31736 30309 31736 30364 31736 30318 31737 30364 31737 30319 31737 30319 31738 30364 31738 30362 31738 30329 31739 30298 31739 30310 31739 30310 31740 30298 31740 30299 31740 30310 31741 30299 31741 30311 31741 30311 31742 30299 31742 30300 31742 30311 31743 30300 31743 30321 31743 30321 31744 30300 31744 30302 31744 30321 31745 30302 31745 30322 31745 30322 31746 30302 31746 30303 31746 30322 31747 30303 31747 30324 31747 30324 31748 30303 31748 30312 31748 30324 31749 30312 31749 30313 31749 30313 31750 30312 31750 30305 31750 30313 31751 30305 31751 30314 31751 30314 31752 30305 31752 30306 31752 30314 31753 30306 31753 30325 31753 30325 31754 30306 31754 30315 31754 30325 31755 30315 31755 30327 31755 30327 31756 30315 31756 30317 31756 30327 31757 30317 31757 30316 31757 30316 31758 30317 31758 30318 31758 30316 31759 30318 31759 30320 31759 30320 31760 30318 31760 30319 31760 30320 31761 30319 31761 30329 31761 30329 31762 30319 31762 30298 31762 30341 31763 30310 31763 30342 31763 30342 31764 30310 31764 30311 31764 30342 31765 30311 31765 30330 31765 30330 31766 30311 31766 30321 31766 30330 31767 30321 31767 30331 31767 30331 31768 30321 31768 30322 31768 30331 31769 30322 31769 30333 31769 30333 31770 30322 31770 30324 31770 30333 31771 30324 31771 30323 31771 30323 31772 30324 31772 30313 31772 30323 31773 30313 31773 30335 31773 30335 31774 30313 31774 30314 31774 30335 31775 30314 31775 30336 31775 30336 31776 30314 31776 30325 31776 30336 31777 30325 31777 30326 31777 30326 31778 30325 31778 30327 31778 30326 31779 30327 31779 30338 31779 30338 31780 30327 31780 30316 31780 30338 31781 30316 31781 30328 31781 30328 31782 30316 31782 30320 31782 30328 31783 30320 31783 30340 31783 30340 31784 30320 31784 30329 31784 30340 31785 30329 31785 30341 31785 30341 31786 30329 31786 30310 31786 30356 31787 30342 31787 30357 31787 30357 31788 30342 31788 30330 31788 30357 31789 30330 31789 30332 31789 30332 31790 30330 31790 30331 31790 30332 31791 30331 31791 30344 31791 30344 31792 30331 31792 30333 31792 30344 31793 30333 31793 30345 31793 30345 31794 30333 31794 30323 31794 30345 31795 30323 31795 30334 31795 30334 31796 30323 31796 30335 31796 30334 31797 30335 31797 30348 31797 30348 31798 30335 31798 30336 31798 30348 31799 30336 31799 30349 31799 30349 31800 30336 31800 30326 31800 30349 31801 30326 31801 30337 31801 30337 31802 30326 31802 30338 31802 30337 31803 30338 31803 30352 31803 30352 31804 30338 31804 30328 31804 30352 31805 30328 31805 30339 31805 30339 31806 30328 31806 30340 31806 30339 31807 30340 31807 30354 31807 30354 31808 30340 31808 30341 31808 30354 31809 30341 31809 30356 31809 30356 31810 30341 31810 30342 31810 30284 31811 30357 31811 30283 31811 30283 31812 30357 31812 30332 31812 30283 31813 30332 31813 30343 31813 30343 31814 30332 31814 30344 31814 30343 31815 30344 31815 30346 31815 30346 31816 30344 31816 30345 31816 30346 31817 30345 31817 30293 31817 30293 31818 30345 31818 30334 31818 30293 31819 30334 31819 30347 31819 30347 31820 30334 31820 30348 31820 30347 31821 30348 31821 30291 31821 30291 31822 30348 31822 30349 31822 30291 31823 30349 31823 30350 31823 30350 31824 30349 31824 30337 31824 30350 31825 30337 31825 30351 31825 30351 31826 30337 31826 30352 31826 30351 31827 30352 31827 30353 31827 30353 31828 30352 31828 30339 31828 30353 31829 30339 31829 30286 31829 30286 31830 30339 31830 30354 31830 30286 31831 30354 31831 30355 31831 30355 31832 30354 31832 30356 31832 30355 31833 30356 31833 30284 31833 30284 31834 30356 31834 30357 31834 30358 31835 30301 31835 30359 31835 30359 31836 30301 31836 30360 31836 30359 31837 30360 31837 30380 31837 30380 31838 30360 31838 30361 31838 30380 31839 30361 31839 30381 31839 30381 31840 30361 31840 30362 31840 30381 31841 30362 31841 30384 31841 30384 31842 30362 31842 30364 31842 30384 31843 30364 31843 30363 31843 30363 31844 30364 31844 30309 31844 30363 31845 30309 31845 30365 31845 30365 31846 30309 31846 30308 31846 30365 31847 30308 31847 30366 31847 30366 31848 30308 31848 30367 31848 30366 31849 30367 31849 30374 31849 30374 31850 30367 31850 30307 31850 30374 31851 30307 31851 30375 31851 30375 31852 30307 31852 30368 31852 30375 31853 30368 31853 30376 31853 30376 31854 30368 31854 30304 31854 30376 31855 30304 31855 30369 31855 30369 31856 30304 31856 30370 31856 30369 31857 30370 31857 30358 31857 30358 31858 30370 31858 30301 31858 30393 31859 30363 31859 30385 31859 30385 31860 30363 31860 30365 31860 30385 31861 30365 31861 30371 31861 30371 31862 30365 31862 30366 31862 30371 31863 30366 31863 30372 31863 30372 31864 30366 31864 30374 31864 30372 31865 30374 31865 30373 31865 30373 31866 30374 31866 30375 31866 30373 31867 30375 31867 30388 31867 30388 31868 30375 31868 30376 31868 30388 31869 30376 31869 30377 31869 30377 31870 30376 31870 30369 31870 30377 31871 30369 31871 30390 31871 30390 31872 30369 31872 30358 31872 30390 31873 30358 31873 30378 31873 30378 31874 30358 31874 30359 31874 30378 31875 30359 31875 30379 31875 30379 31876 30359 31876 30380 31876 30379 31877 30380 31877 30382 31877 30382 31878 30380 31878 30381 31878 30382 31879 30381 31879 30383 31879 30383 31880 30381 31880 30384 31880 30383 31881 30384 31881 30393 31881 30393 31882 30384 31882 30363 31882 30403 31883 30385 31883 30404 31883 30404 31884 30385 31884 30371 31884 30404 31885 30371 31885 30395 31885 30395 31886 30371 31886 30372 31886 30395 31887 30372 31887 30386 31887 30386 31888 30372 31888 30373 31888 30386 31889 30373 31889 30387 31889 30387 31890 30373 31890 30388 31890 30387 31891 30388 31891 30397 31891 30397 31892 30388 31892 30377 31892 30397 31893 30377 31893 30399 31893 30399 31894 30377 31894 30390 31894 30399 31895 30390 31895 30389 31895 30389 31896 30390 31896 30378 31896 30389 31897 30378 31897 30391 31897 30391 31898 30378 31898 30379 31898 30391 31899 30379 31899 30402 31899 30402 31900 30379 31900 30382 31900 30402 31901 30382 31901 30392 31901 30392 31902 30382 31902 30383 31902 30392 31903 30383 31903 30394 31903 30394 31904 30383 31904 30393 31904 30394 31905 30393 31905 30403 31905 30403 31906 30393 31906 30385 31906 30418 31907 30404 31907 30406 31907 30406 31908 30404 31908 30395 31908 30406 31909 30395 31909 30407 31909 30407 31910 30395 31910 30386 31910 30407 31911 30386 31911 30408 31911 30408 31912 30386 31912 30387 31912 30408 31913 30387 31913 30396 31913 30396 31914 30387 31914 30397 31914 30396 31915 30397 31915 30398 31915 30398 31916 30397 31916 30399 31916 30398 31917 30399 31917 30400 31917 30400 31918 30399 31918 30389 31918 30400 31919 30389 31919 30401 31919 30401 31920 30389 31920 30391 31920 30401 31921 30391 31921 30412 31921 30412 31922 30391 31922 30402 31922 30412 31923 30402 31923 30414 31923 30414 31924 30402 31924 30392 31924 30414 31925 30392 31925 30415 31925 30415 31926 30392 31926 30394 31926 30415 31927 30394 31927 30416 31927 30416 31928 30394 31928 30403 31928 30416 31929 30403 31929 30418 31929 30418 31930 30403 31930 30404 31930 30405 31931 30406 31931 30430 31931 30430 31932 30406 31932 30407 31932 30430 31933 30407 31933 30419 31933 30419 31934 30407 31934 30408 31934 30419 31935 30408 31935 30409 31935 30409 31936 30408 31936 30396 31936 30409 31937 30396 31937 30410 31937 30410 31938 30396 31938 30398 31938 30410 31939 30398 31939 30422 31939 30422 31940 30398 31940 30400 31940 30422 31941 30400 31941 30411 31941 30411 31942 30400 31942 30401 31942 30411 31943 30401 31943 30425 31943 30425 31944 30401 31944 30412 31944 30425 31945 30412 31945 30413 31945 30413 31946 30412 31946 30414 31946 30413 31947 30414 31947 30427 31947 30427 31948 30414 31948 30415 31948 30427 31949 30415 31949 30428 31949 30428 31950 30415 31950 30416 31950 30428 31951 30416 31951 30417 31951 30417 31952 30416 31952 30418 31952 30417 31953 30418 31953 30405 31953 30405 31954 30418 31954 30406 31954 30429 31955 30430 31955 30443 31955 30443 31956 30430 31956 30419 31956 30443 31957 30419 31957 30441 31957 30441 31958 30419 31958 30409 31958 30441 31959 30409 31959 30420 31959 30420 31960 30409 31960 30410 31960 30420 31961 30410 31961 30421 31961 30421 31962 30410 31962 30422 31962 30421 31963 30422 31963 30423 31963 30423 31964 30422 31964 30411 31964 30423 31965 30411 31965 30424 31965 30424 31966 30411 31966 30425 31966 30424 31967 30425 31967 30436 31967 30436 31968 30425 31968 30413 31968 30436 31969 30413 31969 30426 31969 30426 31970 30413 31970 30427 31970 30426 31971 30427 31971 30434 31971 30434 31972 30427 31972 30428 31972 30434 31973 30428 31973 30433 31973 30433 31974 30428 31974 30417 31974 30433 31975 30417 31975 30431 31975 30431 31976 30417 31976 30405 31976 30431 31977 30405 31977 30429 31977 30429 31978 30405 31978 30430 31978 30443 31979 30449 31979 30429 31979 30429 31980 30449 31980 30432 31980 30429 31981 30432 31981 30431 31981 30431 31982 30432 31982 30450 31982 30431 31982 30450 31982 30433 31982 30433 31983 30450 31983 30444 31983 30433 31983 30444 31983 30434 31983 30434 31984 30444 31984 30435 31984 30434 31985 30435 31985 30426 31985 30426 31986 30435 31986 30445 31986 30426 31987 30445 31987 30436 31987 30436 31988 30445 31988 30437 31988 30436 31989 30437 31989 30424 31989 30424 31990 30437 31990 30438 31990 30424 31991 30438 31991 30423 31991 30423 31992 30438 31992 30439 31992 30423 31993 30439 31993 30421 31993 30421 31994 30439 31994 30440 31994 30421 31995 30440 31995 30420 31995 30420 31996 30440 31996 30448 31996 30420 31997 30448 31997 30441 31997 30441 31998 30448 31998 30442 31998 30441 31998 30442 31998 30443 31998 30443 31979 30442 31979 30449 31979 30450 21 30295 21 30444 21 30444 21 30295 21 30294 21 30444 21 30294 21 30435 21 30435 21 30294 21 30446 21 30435 31999 30446 31999 30445 31999 30445 32000 30446 32000 30292 32000 30445 32001 30292 32001 30437 32001 30437 32002 30292 32002 30290 32002 30437 32003 30290 32003 30438 32003 30438 32004 30290 32004 30447 32004 30438 21 30447 21 30439 21 30439 32005 30447 32005 30289 32005 30439 21 30289 21 30440 21 30440 21 30289 21 30288 21 30440 21 30288 21 30448 21 30448 21 30288 21 30287 21 30448 21 30287 21 30442 21 30442 21 30287 21 30285 21 30442 21 30285 21 30449 21 30449 32006 30285 32006 30297 32006 30449 21 30297 21 30432 21 30432 32007 30297 32007 30296 32007 30432 21 30296 21 30450 21 30450 32008 30296 32008 30295 32008 30611 32009 30515 32009 30451 32009 30451 32010 30515 32010 30452 32010 30451 32011 30452 32011 30608 32011 30608 32012 30452 32012 30518 32012 30608 32013 30518 32013 30453 32013 30453 32014 30518 32014 30517 32014 30453 32015 30517 32015 30589 32015 30589 32016 30517 32016 30454 32016 30589 32017 30454 32017 30590 32017 30590 32018 30454 32018 30538 32018 30590 32019 30538 32019 30593 32019 30593 32020 30538 32020 30455 32020 30593 32021 30455 32021 30602 32021 30602 32022 30455 32022 30456 32022 30602 32023 30456 32023 30597 32023 30597 32024 30456 32024 30526 32024 30597 32025 30526 32025 30457 32025 30457 32026 30526 32026 30527 32026 30457 32027 30527 32027 30612 32027 30612 32028 30527 32028 30459 32028 30612 32029 30459 32029 30458 32029 30458 32030 30459 32030 30460 32030 30458 32031 30460 32031 30611 32031 30611 32032 30460 32032 30515 32032 30606 32009 30522 32009 30461 32009 30461 32033 30522 32033 30520 32033 30461 32034 30520 32034 30613 32034 30613 32035 30520 32035 30462 32035 30613 32013 30462 32013 30463 32013 30463 32036 30462 32036 30529 32036 30463 32037 30529 32037 30595 32037 30595 32038 30529 32038 30528 32038 30595 32039 30528 32039 30596 32039 30596 32040 30528 32040 30535 32040 30596 32041 30535 32041 30464 32041 30464 32042 30535 32042 30530 32042 30464 32043 30530 32043 30601 32043 30601 32044 30530 32044 30465 32044 30601 32045 30465 32045 30466 32045 30466 32024 30465 32024 30534 32024 30466 32025 30534 32025 30636 32025 30636 32046 30534 32046 30467 32046 30636 32027 30467 32027 30468 32027 30468 32047 30467 32047 30525 32047 30468 32048 30525 32048 30604 32048 30604 32030 30525 32030 30524 32030 30604 32031 30524 32031 30606 32031 30606 32049 30524 32049 30522 32049 30481 31494 30469 31494 30541 31494 30541 32050 30469 32050 30470 32050 30541 32051 30470 32051 30471 32051 30471 32052 30470 32052 30472 32052 30471 32053 30472 32053 30473 32053 30473 32054 30472 32054 30475 32054 30473 32055 30475 32055 30474 32055 30474 32056 30475 32056 30647 32056 30474 32057 30647 32057 30476 32057 30476 32058 30647 32058 30477 32058 30476 32059 30477 32059 30539 32059 30539 32060 30477 32060 30644 32060 30539 32061 30644 32061 30478 32061 30478 32062 30644 32062 30642 32062 30478 31508 30642 31508 30542 31508 30542 32063 30642 32063 30479 32063 30542 32064 30479 32064 30543 32064 30543 32065 30479 32065 30641 32065 30543 32066 30641 32066 30545 32066 30545 32067 30641 32067 30639 32067 30545 32068 30639 32068 30480 32068 30480 32069 30639 32069 30637 32069 30480 32070 30637 32070 30481 32070 30481 32071 30637 32071 30469 32071 30556 32072 30492 32072 30482 32072 30482 32073 30492 32073 30484 32073 30482 32074 30484 32074 30483 32074 30483 31675 30484 31675 30485 31675 30483 31676 30485 31676 30564 31676 30564 32075 30485 32075 30486 32075 30564 32076 30486 32076 30565 32076 30565 32077 30486 32077 30631 32077 30565 32078 30631 32078 30487 32078 30487 32079 30631 32079 30632 32079 30487 32080 30632 32080 30566 32080 30566 32081 30632 32081 30488 32081 30566 32082 30488 32082 30557 32082 30557 32083 30488 32083 30489 32083 30557 31686 30489 31686 30563 31686 30563 32084 30489 32084 30622 32084 30563 31688 30622 31688 30490 31688 30490 32085 30622 32085 30618 32085 30490 32086 30618 32086 30561 32086 30561 32087 30618 32087 30626 32087 30561 32088 30626 32088 30558 32088 30558 32089 30626 32089 30491 32089 30558 32090 30491 32090 30556 32090 30556 32091 30491 32091 30492 32091 30650 32092 30521 32092 30610 32092 30610 32093 30521 32093 30605 32093 30605 32094 30521 32094 30603 32094 30603 32095 30521 32095 30523 32095 30603 32096 30523 32096 30493 32096 30523 32097 30544 32097 30493 32097 30493 32098 30544 32098 30494 32098 30493 32099 30494 32099 30635 32099 30635 32100 30494 32100 30495 32100 30635 32101 30495 32101 30634 32101 30495 32102 30548 32102 30634 32102 30634 32103 30548 32103 30496 32103 30497 32104 30643 32104 30504 32104 30504 32105 30643 32105 30540 32105 30498 32106 30638 32106 30500 32106 30498 32107 30500 32107 30499 32107 30499 32108 30500 32108 30501 32108 30499 32109 30501 32109 30502 32109 30502 31526 30501 31526 30640 31526 30502 32110 30640 32110 30503 32110 30503 32111 30640 32111 30497 32111 30503 32112 30497 32112 30504 32112 30638 32113 30498 32113 30621 32113 30621 32114 30498 32114 30549 32114 30621 32115 30549 32115 30620 32115 30620 32116 30549 32116 30562 32116 30505 32117 30569 32117 30506 32117 30506 32117 30569 32117 30573 32117 30506 32118 30573 32118 30507 32118 30507 32119 30573 32119 30574 32119 30508 32120 30510 32120 30509 32120 30509 32120 30510 32120 30511 32120 30516 21 30512 21 30513 21 30513 32121 30512 32121 30607 32121 30571 32122 30551 32122 30572 32122 30514 32123 30584 32123 30572 32123 30460 32124 30521 32124 30515 32124 30515 32125 30521 32125 30650 32125 30515 32126 30650 32126 30452 32126 30538 32127 30454 32127 30516 32127 30516 32128 30454 32128 30517 32128 30516 32129 30517 32129 30512 32129 30512 32130 30517 32130 30518 32130 30512 32131 30518 32131 30519 32131 30519 32132 30518 32132 30452 32132 30519 32133 30452 32133 30649 32133 30649 32134 30452 32134 30650 32134 30527 32135 30529 32135 30459 32135 30459 32136 30529 32136 30462 32136 30459 32137 30462 32137 30460 32137 30460 32138 30462 32138 30520 32138 30460 32139 30520 32139 30521 32139 30521 32140 30520 32140 30522 32140 30521 32141 30522 32141 30523 32141 30523 32142 30522 32142 30524 32142 30523 32143 30524 32143 30525 32143 30526 32144 30535 32144 30527 32144 30527 32145 30535 32145 30528 32145 30527 32146 30528 32146 30529 32146 30530 32147 30531 32147 30465 32147 30465 32148 30531 32148 30532 32148 30532 32149 30533 32149 30465 32149 30465 32150 30533 32150 30572 32150 30465 32151 30572 32151 30534 32151 30534 32152 30572 32152 30467 32152 30530 32153 30535 32153 30531 32153 30531 32154 30535 32154 30526 32154 30531 32155 30526 32155 30508 32155 30508 32156 30526 32156 30456 32156 30508 32157 30456 32157 30510 32157 30510 32158 30456 32158 30455 32158 30510 32159 30455 32159 30536 32159 30536 32160 30455 32160 30538 32160 30536 32161 30538 32161 30537 32161 30537 32162 30538 32162 30516 32162 30476 32163 30539 32163 30540 32163 30540 32164 30539 32164 30478 32164 30540 32165 30478 32165 30504 32165 30549 32166 30481 32166 30541 32166 30541 32167 30471 32167 30572 32167 30572 32168 30471 32168 30473 32168 30478 32169 30542 32169 30504 32169 30504 32170 30542 32170 30543 32170 30504 32171 30543 32171 30503 32171 30503 32172 30543 32172 30545 32172 30503 31658 30545 31658 30502 31658 30525 32173 30467 32173 30523 32173 30523 32174 30467 32174 30572 32174 30523 32175 30572 32175 30544 32175 30481 32176 30549 32176 30480 32176 30480 32177 30549 32177 30498 32177 30480 32178 30498 32178 30545 32178 30545 32179 30498 32179 30499 32179 30545 32180 30499 32180 30502 32180 30540 31666 30546 31666 30476 31666 30476 32181 30546 32181 30547 32181 30476 32182 30547 32182 30474 32182 30474 32183 30547 32183 30548 32183 30474 32184 30548 32184 30473 32184 30473 32185 30548 32185 30495 32185 30473 32186 30495 32186 30572 32186 30572 32187 30495 32187 30494 32187 30572 32188 30494 32188 30544 32188 30541 32189 30572 32189 30549 32189 30549 32190 30572 32190 30584 32190 30549 32191 30584 32191 30586 32191 30550 32192 30578 32192 30551 32192 30551 32193 30578 32193 30580 32193 30551 32194 30580 32194 30572 32194 30572 32195 30580 32195 30581 32195 30572 32196 30581 32196 30514 32196 30586 32197 30552 32197 30549 32197 30549 32198 30552 32198 30553 32198 30549 32199 30553 32199 30554 32199 30558 32200 30556 32200 30555 32200 30555 32201 30556 32201 30551 32201 30551 32202 30556 32202 30482 32202 30551 32203 30482 32203 30483 32203 30563 32204 30575 32204 30557 32204 30557 32205 30575 32205 30576 32205 30557 32206 30576 32206 30566 32206 30566 32207 30576 32207 30550 32207 30555 32208 30559 32208 30558 32208 30558 32209 30559 32209 30560 32209 30558 32210 30560 32210 30561 32210 30561 32211 30560 32211 30562 32211 30561 32212 30562 32212 30490 32212 30490 32213 30562 32213 30549 32213 30490 32214 30549 32214 30563 32214 30563 32215 30549 32215 30554 32215 30563 32216 30554 32216 30575 32216 30483 32217 30564 32217 30551 32217 30551 32218 30564 32218 30565 32218 30551 32219 30565 32219 30550 32219 30550 32220 30565 32220 30487 32220 30550 32221 30487 32221 30566 32221 30570 32222 30567 32222 30571 32222 30568 32223 30570 32223 30569 32223 30569 32224 30570 32224 30571 32224 30569 32225 30571 32225 30573 32225 30573 32226 30571 32226 30572 32226 30573 32227 30572 32227 30574 32227 30574 32228 30572 32228 30533 32228 30575 31590 30619 31590 30576 31590 30576 32229 30619 32229 30577 32229 30576 32230 30577 32230 30550 32230 30550 32231 30577 32231 30633 32231 30550 32232 30633 32232 30578 32232 30578 32233 30633 32233 30579 32233 30578 32234 30579 32234 30580 32234 30580 32235 30579 32235 30629 32235 30580 32236 30629 32236 30581 32236 30581 31599 30629 31599 30582 31599 30581 31600 30582 31600 30514 31600 30514 32237 30582 32237 30583 32237 30514 32238 30583 32238 30584 32238 30584 32239 30583 32239 30585 32239 30584 32240 30585 32240 30586 32240 30586 32241 30585 32241 30587 32241 30586 32242 30587 32242 30552 32242 30552 32243 30587 32243 30624 32243 30552 32244 30624 32244 30553 32244 30553 32245 30624 32245 30623 32245 30553 32246 30623 32246 30554 32246 30554 32247 30623 32247 30588 32247 30554 32248 30588 32248 30575 32248 30575 32249 30588 32249 30619 32249 30602 32250 30600 32251 30594 32252 30598 32253 30466 32253 30636 32253 30608 32254 30453 32254 30607 32254 30607 32255 30453 32255 30589 32255 30607 32256 30589 32256 30513 32256 30513 32257 30589 32257 30590 32257 30513 32258 30590 32258 30591 32258 30591 32259 30590 32259 30593 32259 30591 32260 30593 32260 30592 32260 30592 32261 30593 32261 30511 32261 30602 32262 30594 32262 30593 32262 30593 32263 30594 32263 30509 32263 30593 32264 30509 32264 30511 32264 30612 32265 30595 32265 30457 32265 30457 32266 30595 32266 30596 32266 30457 32267 30596 32267 30597 32267 30597 32268 30596 32268 30602 32268 30506 32269 30507 32269 30598 32269 30598 32270 30507 32270 30599 32270 30598 32271 30599 32271 30466 32271 30466 32272 30599 32272 30600 32272 30466 32273 30600 32273 30601 32273 30601 32274 30600 32274 30602 32274 30601 32275 30602 32275 30464 32275 30464 32276 30602 32276 30596 32276 30468 32277 30604 32277 30603 32277 30603 32278 30604 32278 30606 32278 30603 32279 30606 32279 30605 32279 30605 32280 30606 32280 30461 32280 30605 32281 30461 32281 30613 32281 30607 32282 30648 32282 30608 32282 30608 32283 30648 32283 30609 32283 30608 32284 30609 32284 30451 32284 30451 32285 30609 32285 30610 32285 30451 32286 30610 32286 30611 32286 30611 32287 30610 32287 30605 32287 30611 32288 30605 32288 30458 32288 30458 32289 30605 32289 30613 32289 30458 32290 30613 32290 30612 32290 30612 32291 30613 32291 30463 32291 30612 32292 30463 32292 30595 32292 30614 32293 30615 32293 30505 32293 30598 32294 30630 32294 30506 32294 30506 32295 30630 32295 30616 32295 30506 32296 30616 32296 30505 32296 30505 32297 30616 32297 30617 32297 30505 32298 30617 32298 30614 32298 30626 32299 30618 32299 30620 32299 30632 32300 30577 32300 30488 32300 30488 32301 30577 32301 30619 32301 30488 32302 30619 32302 30489 32302 30620 32303 30618 32303 30621 32303 30621 32304 30618 32304 30622 32304 30621 32305 30622 32305 30489 32305 30583 32306 30598 32306 30585 32306 30585 32307 30598 32307 30621 32307 30585 32308 30621 32308 30587 32308 30619 32309 30588 32309 30489 32309 30489 32310 30588 32310 30623 32310 30489 32311 30623 32311 30621 32311 30621 32312 30623 32312 30624 32312 30621 32313 30624 32313 30587 32313 30485 32314 30484 32314 30630 32314 30630 32315 30484 32315 30492 32315 30630 32316 30492 32316 30625 32316 30625 32317 30492 32317 30491 32317 30625 32318 30491 32318 30627 32318 30627 32319 30491 32319 30626 32319 30627 32320 30626 32320 30628 32320 30628 32321 30626 32321 30620 32321 30583 32322 30582 32322 30598 32322 30598 32323 30582 32323 30629 32323 30598 32324 30629 32324 30579 32324 30485 32325 30630 32325 30486 32325 30486 32326 30630 32326 30598 32326 30486 32327 30598 32327 30631 32327 30631 32328 30598 32328 30579 32328 30631 32329 30579 32329 30632 32329 30632 32330 30579 32330 30633 32330 30632 32331 30633 32331 30577 32331 30475 32332 30472 32332 30634 32332 30621 32333 30635 32333 30634 32333 30641 32334 30479 32334 30497 32334 30636 32335 30468 32335 30598 32335 30598 32336 30468 32336 30603 32336 30598 32337 30603 32337 30621 32337 30621 32338 30603 32338 30493 32338 30621 32339 30493 32339 30635 32339 30472 32340 30470 32340 30634 32340 30634 32341 30470 32341 30469 32341 30634 32342 30469 32342 30621 32342 30621 32343 30469 32343 30637 32343 30621 32344 30637 32344 30638 32344 30638 32345 30637 32345 30639 32345 30638 32346 30639 32346 30641 32346 30500 32347 30638 32347 30501 32347 30501 32348 30638 32348 30641 32348 30501 32349 30641 32349 30640 32349 30640 32350 30641 32350 30497 32350 30479 31575 30642 31575 30497 31575 30497 32351 30642 32351 30644 32351 30497 32352 30644 32352 30643 32352 30643 32353 30644 32353 30477 32353 30643 31579 30477 31579 30645 31579 30645 32354 30477 32354 30647 32354 30645 32355 30647 32355 30646 32355 30646 32356 30647 32356 30475 32356 30646 32357 30475 32357 30496 32357 30496 32358 30475 32358 30634 32358 30607 32359 30512 32359 30519 32359 30607 32360 30519 32360 30648 32360 30648 32361 30519 32361 30649 32361 30648 32362 30649 32362 30609 32362 30609 32363 30649 32363 30650 32363 30609 32364 30650 32364 30610 32364 30651 32365 30652 32365 30659 32365 30651 590 30768 590 30652 590 30652 32366 30768 32366 30766 32366 30652 590 30766 590 30689 590 30678 32367 30777 32367 30653 32367 30653 590 30777 590 30658 590 30653 32368 30658 32368 30654 32368 30675 11409 30656 11409 30655 11409 30655 590 30656 590 30670 590 30655 32369 30670 32369 30657 32369 30658 590 30774 590 30654 590 30654 32370 30774 32370 30773 32370 30654 590 30773 590 30659 590 30659 32371 30773 32371 30660 32371 30659 32372 30660 32372 30651 32372 30661 32373 30663 32373 30789 32373 30669 590 30791 590 30662 590 30662 32374 30791 32374 30664 32374 30662 32375 30664 32375 30663 32375 30663 32376 30664 32376 30790 32376 30663 32377 30790 32377 30789 32377 30665 590 30667 590 30666 590 30666 590 30667 590 30795 590 30666 590 30795 590 30669 590 30669 32378 30795 32378 30668 32378 30669 32379 30668 32379 30791 32379 30670 590 30751 590 30657 590 30657 32380 30751 32380 30750 32380 30657 590 30750 590 30671 590 30671 32381 30750 32381 30746 32381 30671 590 30746 590 30665 590 30665 32382 30746 32382 30672 32382 30665 32383 30672 32383 30667 32383 30673 590 30674 590 30675 590 30675 32384 30674 32384 30753 32384 30675 590 30753 590 30656 590 30685 32385 30676 32385 30677 32385 30677 32386 30676 32386 30679 32386 30677 590 30679 590 30678 590 30678 590 30679 590 30680 590 30678 590 30680 590 30777 590 30687 590 30681 590 30682 590 30682 590 30681 590 30757 590 30682 590 30757 590 30673 590 30673 32387 30757 32387 30754 32387 30673 32388 30754 32388 30674 32388 30789 590 30683 590 30661 590 30661 32389 30683 32389 30786 32389 30661 590 30786 590 30684 590 30684 590 30786 590 30785 590 30684 590 30785 590 30685 590 30685 32390 30785 32390 30782 32390 30685 590 30782 590 30676 590 30693 590 30694 590 30686 590 30686 32391 30694 32391 30760 32391 30686 590 30760 590 30687 590 30687 32392 30760 32392 30758 32392 30687 32393 30758 32393 30681 32393 30766 32394 30688 32394 30689 32394 30689 32395 30688 32395 30690 32395 30689 590 30690 590 30692 590 30692 32396 30690 32396 30691 32396 30692 590 30691 590 30693 590 30693 32397 30691 32397 30763 32397 30693 32398 30763 32398 30694 32398 30745 32399 30695 32399 30767 32399 30767 32400 30695 32400 30696 32400 30695 32401 30697 32401 30696 32401 30696 32402 30697 32402 30698 32402 30696 32403 30698 32403 30765 32403 30765 32404 30698 32404 30699 32404 30765 32405 30699 32405 30764 32405 30764 11435 30699 11435 30700 11435 30764 11435 30700 11435 30762 11435 30762 32406 30700 32406 30701 32406 30762 32407 30701 32407 30761 32407 30761 11440 30701 11440 30702 11440 30761 32408 30702 32408 30703 32408 30703 32409 30702 32409 30705 32409 30703 11442 30705 11442 30704 11442 30704 32410 30705 32410 30706 32410 30704 12217 30706 12217 30759 12217 30759 32411 30706 32411 30707 32411 30759 32412 30707 32412 30756 32412 30756 32413 30707 32413 30708 32413 30756 32414 30708 32414 30755 32414 30755 10915 30708 10915 30710 10915 30755 10916 30710 10916 30709 10916 30709 32415 30710 32415 30711 32415 30709 11452 30711 11452 30752 11452 30752 32416 30711 32416 30712 32416 30752 32417 30712 32417 30714 32417 30714 21 30712 21 30713 21 30714 21 30713 21 30715 21 30715 32418 30713 32418 30716 32418 30715 32419 30716 32419 30717 32419 30717 11457 30716 11457 30718 11457 30717 32420 30718 32420 30749 32420 30749 10859 30718 10859 30719 10859 30749 10860 30719 10860 30748 10860 30748 32421 30719 32421 30720 32421 30748 32422 30720 32422 30747 32422 30747 32423 30720 32423 30722 32423 30747 32424 30722 32424 30721 32424 30721 11463 30722 11463 30723 11463 30721 32425 30723 32425 30794 32425 30794 11465 30723 11465 30724 11465 30794 32426 30724 32426 30725 32426 30725 32427 30724 32427 30726 32427 30725 11467 30726 11467 30793 11467 30793 32428 30726 32428 30727 32428 30793 32429 30727 32429 30792 32429 30792 10873 30727 10873 30729 10873 30792 10873 30729 10873 30728 10873 30728 32430 30729 32430 30730 32430 30728 32431 30730 32431 30731 32431 30731 32432 30730 32432 30732 32432 30731 32433 30732 32433 30788 32433 30788 32434 30732 32434 30733 32434 30788 32435 30733 32435 30787 32435 30787 32436 30733 32436 30734 32436 30787 32436 30734 32436 30784 32436 30784 32437 30734 32437 30735 32437 30784 32438 30735 32438 30783 32438 30783 32439 30735 32439 30736 32439 30783 32440 30736 32440 30781 32440 30781 32441 30736 32441 30737 32441 30781 32442 30737 32442 30780 32442 30780 12240 30737 12240 30738 12240 30780 32443 30738 32443 30779 32443 30779 11486 30738 11486 30739 11486 30779 12242 30739 12242 30778 12242 30778 32444 30739 32444 30740 32444 30778 11487 30740 11487 30776 11487 30776 32445 30740 32445 30741 32445 30776 32446 30741 32446 30775 32446 30775 32447 30741 32447 30742 32447 30775 32448 30742 32448 30772 32448 30772 32449 30742 32449 30743 32449 30772 32450 30743 32450 30771 32450 30771 32451 30743 32451 30744 32451 30771 32452 30744 32452 30770 32452 30770 32453 30744 32453 30745 32453 30770 32453 30745 32453 30769 32453 30769 32399 30745 32399 30767 32399 30721 32454 30672 32454 30747 32454 30747 32455 30672 32455 30746 32455 30747 32456 30746 32456 30748 32456 30748 32457 30746 32457 30750 32457 30748 32458 30750 32458 30749 32458 30749 32459 30750 32459 30751 32459 30749 32460 30751 32460 30717 32460 30717 32461 30751 32461 30670 32461 30717 32462 30670 32462 30715 32462 30715 32463 30670 32463 30656 32463 30715 11509 30656 11509 30714 11509 30714 11510 30656 11510 30753 11510 30714 32464 30753 32464 30752 32464 30752 32465 30753 32465 30674 32465 30752 32466 30674 32466 30709 32466 30709 32467 30674 32467 30754 32467 30709 32468 30754 32468 30755 32468 30755 32469 30754 32469 30757 32469 30755 32470 30757 32470 30756 32470 30756 32471 30757 32471 30681 32471 30756 32472 30681 32472 30759 32472 30759 32473 30681 32473 30758 32473 30759 32474 30758 32474 30704 32474 30704 32475 30758 32475 30760 32475 30704 32476 30760 32476 30703 32476 30703 32477 30760 32477 30694 32477 30703 11524 30694 11524 30761 11524 30761 11525 30694 11525 30763 11525 30761 32478 30763 32478 30762 32478 30762 32479 30763 32479 30691 32479 30762 32480 30691 32480 30764 32480 30764 32481 30691 32481 30690 32481 30764 32482 30690 32482 30765 32482 30765 32483 30690 32483 30688 32483 30765 32484 30688 32484 30696 32484 30696 32485 30688 32485 30766 32485 30696 32486 30766 32486 30767 32486 30767 32487 30766 32487 30768 32487 30767 32488 30768 32488 30769 32488 30769 32489 30768 32489 30651 32489 30769 32490 30651 32490 30770 32490 30770 32491 30651 32491 30660 32491 30770 32492 30660 32492 30771 32492 30771 32493 30660 32493 30773 32493 30771 32494 30773 32494 30772 32494 30772 32495 30773 32495 30774 32495 30772 32496 30774 32496 30775 32496 30775 32497 30774 32497 30658 32497 30775 32498 30658 32498 30776 32498 30776 32499 30658 32499 30777 32499 30776 32500 30777 32500 30778 32500 30778 32501 30777 32501 30680 32501 30778 11549 30680 11549 30779 11549 30779 32502 30680 32502 30679 32502 30779 32503 30679 32503 30780 32503 30780 32504 30679 32504 30676 32504 30780 32505 30676 32505 30781 32505 30781 32506 30676 32506 30782 32506 30781 32507 30782 32507 30783 32507 30783 32508 30782 32508 30785 32508 30783 32509 30785 32509 30784 32509 30784 32510 30785 32510 30786 32510 30784 32511 30786 32511 30787 32511 30787 32512 30786 32512 30683 32512 30787 32513 30683 32513 30788 32513 30788 32514 30683 32514 30789 32514 30788 32515 30789 32515 30731 32515 30731 32516 30789 32516 30790 32516 30731 32517 30790 32517 30728 32517 30728 32518 30790 32518 30664 32518 30728 32519 30664 32519 30792 32519 30792 32520 30664 32520 30791 32520 30792 32521 30791 32521 30793 32521 30793 32522 30791 32522 30668 32522 30793 32523 30668 32523 30725 32523 30725 32524 30668 32524 30795 32524 30725 32525 30795 32525 30794 32525 30794 32526 30795 32526 30667 32526 30794 32527 30667 32527 30721 32527 30721 32528 30667 32528 30672 32528 30796 590 30940 590 30797 590 30797 32529 30940 32529 30813 32529 30797 32530 30813 32530 30798 32530 30803 32531 30910 32531 30799 32531 30799 32532 30910 32532 30800 32532 30799 590 30800 590 30796 590 30796 32533 30800 32533 30801 32533 30796 32534 30801 32534 30940 32534 30842 12690 30913 12690 30802 12690 30802 12689 30913 12689 30912 12689 30802 590 30912 590 30803 590 30803 32535 30912 32535 30804 32535 30803 12684 30804 12684 30910 12684 30805 590 30931 590 30806 590 30806 32536 30931 32536 30807 32536 30806 32537 30807 32537 30833 32537 30817 590 30808 590 30926 590 30822 32538 30824 32538 30808 32538 30808 32539 30824 32539 30809 32539 30808 32540 30809 32540 30926 32540 30828 32541 30935 32541 30810 32541 30810 590 30935 590 30811 590 30810 32542 30811 32542 30805 32542 30805 32543 30811 32543 30812 32543 30805 32544 30812 32544 30931 32544 30813 590 30939 590 30798 590 30798 590 30939 590 30815 590 30798 590 30815 590 30814 590 30814 590 30815 590 30825 590 30814 590 30825 590 30826 590 30926 590 30816 590 30817 590 30817 32545 30816 32545 30819 32545 30817 590 30819 590 30818 590 30818 11689 30819 11689 30820 11689 30818 32546 30820 32546 30830 32546 30821 32547 30837 32547 30822 32547 30822 32548 30837 32548 30823 32548 30822 32549 30823 32549 30824 32549 30825 590 30937 590 30826 590 30826 590 30937 590 30827 590 30826 590 30827 590 30828 590 30828 590 30827 590 30936 590 30828 590 30936 590 30935 590 30820 32550 30829 32550 30830 32550 30830 590 30829 590 30922 590 30830 590 30922 590 30831 590 30831 590 30922 590 30921 590 30831 590 30921 590 30832 590 30807 590 30930 590 30833 590 30833 590 30930 590 30835 590 30833 590 30835 590 30834 590 30834 32551 30835 32551 30929 32551 30834 590 30929 590 30821 590 30821 32552 30929 32552 30836 32552 30821 12706 30836 12706 30837 12706 30921 590 30919 590 30832 590 30832 590 30919 590 30839 590 30832 590 30839 590 30838 590 30838 32553 30839 32553 30840 32553 30838 590 30840 590 30841 590 30840 590 30918 590 30841 590 30841 590 30918 590 30916 590 30841 590 30916 590 30842 590 30842 32554 30916 32554 30843 32554 30842 32555 30843 32555 30913 32555 30846 32556 30844 32556 30845 32556 30845 32557 30844 32557 30907 32557 30845 32558 30847 32558 30846 32558 30846 12758 30847 12758 30848 12758 30846 12758 30848 12758 30925 12758 30925 32559 30848 32559 30849 32559 30925 32559 30849 32559 30924 32559 30924 32560 30849 32560 30850 32560 30924 12762 30850 12762 30923 12762 30923 12763 30850 12763 30851 12763 30923 12764 30851 12764 30852 12764 30852 32561 30851 32561 30853 32561 30852 32562 30853 32562 30854 32562 30854 11876 30853 11876 30855 11876 30854 11875 30855 11875 30920 11875 30920 11878 30855 11878 30856 11878 30920 11877 30856 11877 30857 11877 30857 32563 30856 32563 30858 32563 30857 32564 30858 32564 30859 32564 30859 12771 30858 12771 30860 12771 30859 12772 30860 12772 30861 12772 30861 12773 30860 12773 30862 12773 30861 32565 30862 32565 30917 32565 30917 32566 30862 32566 30863 32566 30917 32566 30863 32566 30915 32566 30915 12777 30863 12777 30864 12777 30915 12777 30864 12777 30914 12777 30914 11296 30864 11296 30865 11296 30914 11296 30865 11296 30866 11296 30866 32567 30865 32567 30867 32567 30866 32568 30867 32568 30911 32568 30911 12722 30867 12722 30869 12722 30911 12723 30869 12723 30868 12723 30868 11852 30869 11852 30870 11852 30868 11852 30870 11852 30871 11852 30871 12724 30870 12724 30872 12724 30871 12725 30872 12725 30874 12725 30874 11306 30872 11306 30873 11306 30874 12726 30873 12726 30909 12726 30909 11853 30873 11853 30875 11853 30909 32569 30875 32569 30876 32569 30876 32570 30875 32570 30877 32570 30876 12729 30877 12729 30938 12729 30938 32571 30877 32571 30878 32571 30938 12731 30878 12731 30879 12731 30879 12732 30878 12732 30880 12732 30879 12733 30880 12733 30881 12733 30881 12734 30880 12734 30883 12734 30881 12735 30883 12735 30882 12735 30882 12736 30883 12736 30884 12736 30882 11318 30884 11318 30885 11318 30885 12737 30884 12737 30886 12737 30885 12738 30886 12738 30887 12738 30887 6 30886 6 30889 6 30887 6 30889 6 30888 6 30888 12739 30889 12739 30890 12739 30888 12740 30890 12740 30891 12740 30891 11250 30890 11250 30892 11250 30891 12741 30892 12741 30934 12741 30934 11252 30892 11252 30893 11252 30934 12742 30893 12742 30933 12742 30933 12743 30893 12743 30894 12743 30933 12744 30894 12744 30932 12744 30932 12745 30894 12745 30896 12745 30932 32572 30896 32572 30895 32572 30895 11865 30896 11865 30898 11865 30895 11866 30898 11866 30897 11866 30897 32573 30898 32573 30900 32573 30897 11868 30900 11868 30899 11868 30899 12749 30900 12749 30901 12749 30899 11261 30901 11261 30928 11261 30928 12750 30901 12750 30902 12750 30928 12751 30902 12751 30904 12751 30904 11869 30902 11869 30903 11869 30904 11869 30903 11869 30905 11869 30905 12752 30903 12752 30906 12752 30905 12753 30906 12753 30927 12753 30927 32574 30906 32574 30907 32574 30927 32575 30907 32575 30908 32575 30908 32576 30907 32576 30844 32576 30909 11907 30801 11907 30874 11907 30874 32577 30801 32577 30800 32577 30874 32578 30800 32578 30871 32578 30871 12803 30800 12803 30910 12803 30871 32579 30910 32579 30868 32579 30868 32580 30910 32580 30804 32580 30868 12806 30804 12806 30911 12806 30911 32581 30804 32581 30912 32581 30911 32582 30912 32582 30866 32582 30866 32583 30912 32583 30913 32583 30866 32584 30913 32584 30914 32584 30914 32585 30913 32585 30843 32585 30914 12814 30843 12814 30915 12814 30915 12815 30843 12815 30916 12815 30915 32586 30916 32586 30917 32586 30917 32587 30916 32587 30918 32587 30917 32588 30918 32588 30861 32588 30861 12819 30918 12819 30840 12819 30861 32589 30840 32589 30859 32589 30859 32590 30840 32590 30839 32590 30859 32591 30839 32591 30857 32591 30857 32592 30839 32592 30919 32592 30857 32593 30919 32593 30920 32593 30920 32594 30919 32594 30921 32594 30920 32595 30921 32595 30854 32595 30854 32596 30921 32596 30922 32596 30854 32597 30922 32597 30852 32597 30852 12828 30922 12828 30829 12828 30852 32598 30829 32598 30923 32598 30923 32599 30829 32599 30820 32599 30923 12831 30820 12831 30924 12831 30924 32600 30820 32600 30819 32600 30924 32601 30819 32601 30925 32601 30925 32602 30819 32602 30816 32602 30925 32603 30816 32603 30846 32603 30846 32604 30816 32604 30926 32604 30846 32605 30926 32605 30844 32605 30844 32606 30926 32606 30809 32606 30844 32607 30809 32607 30908 32607 30908 32608 30809 32608 30824 32608 30908 32609 30824 32609 30927 32609 30927 12840 30824 12840 30823 12840 30927 32610 30823 32610 30905 32610 30905 32611 30823 32611 30837 32611 30905 12843 30837 12843 30904 12843 30904 32612 30837 32612 30836 32612 30904 32613 30836 32613 30928 32613 30928 32614 30836 32614 30929 32614 30928 32615 30929 32615 30899 32615 30899 12848 30929 12848 30835 12848 30899 32616 30835 32616 30897 32616 30897 32617 30835 32617 30930 32617 30897 12851 30930 12851 30895 12851 30895 12852 30930 12852 30807 12852 30895 32618 30807 32618 30932 32618 30932 32619 30807 32619 30931 32619 30932 12780 30931 12780 30933 12780 30933 32620 30931 32620 30812 32620 30933 12782 30812 12782 30934 12782 30934 32621 30812 32621 30811 32621 30934 12784 30811 12784 30891 12784 30891 32622 30811 32622 30935 32622 30891 32623 30935 32623 30888 32623 30888 32624 30935 32624 30936 32624 30888 11893 30936 11893 30887 11893 30887 11894 30936 11894 30827 11894 30887 12788 30827 12788 30885 12788 30885 32625 30827 32625 30937 32625 30885 32626 30937 32626 30882 32626 30882 32627 30937 32627 30825 32627 30882 12792 30825 12792 30881 12792 30881 32628 30825 32628 30815 32628 30881 32629 30815 32629 30879 32629 30879 32630 30815 32630 30939 32630 30879 32631 30939 32631 30938 32631 30938 32632 30939 32632 30813 32632 30938 12798 30813 12798 30876 12798 30876 12799 30813 12799 30940 12799 30876 32633 30940 32633 30909 32633 30909 32634 30940 32634 30801 32634 30941 32635 30942 32635 31397 32635 31397 32636 30942 32636 30947 32636 31397 32637 30947 32637 30948 32637 30943 32638 30944 32638 30945 32638 30945 32639 30944 32639 31424 32639 30945 32640 31424 32640 31304 32640 31304 32641 30946 32641 30945 32641 30945 32642 30946 32642 31422 32642 30945 32643 31422 32643 30947 32643 30947 32644 31422 32644 31423 32644 30947 32645 31423 32645 30948 32645 30949 32646 30950 32646 30951 32646 30951 32647 30950 32647 30956 32647 30951 32648 30956 32648 31564 32648 30952 32649 30954 32649 30953 32649 30953 32650 30954 32650 30955 32650 30953 32651 30955 32651 31557 32651 31557 32652 31558 32652 30953 32652 30953 32653 31558 32653 31561 32653 30953 32654 31561 32654 30956 32654 30956 32655 31561 32655 30957 32655 30956 32656 30957 32656 31564 32656 30960 32657 30958 32657 30959 32657 30959 32658 30961 32658 30960 32658 30960 32659 30961 32659 30962 32659 30960 32660 30962 32660 30963 32660 30962 32661 31201 32661 30963 32661 30963 32662 31201 32662 31203 32662 30963 32663 31203 32663 30964 32663 31203 32664 30965 32664 30964 32664 30964 32665 30965 32665 30966 32665 30964 32666 30966 32666 30967 32666 30966 32667 30968 32667 30967 32667 30967 32668 30968 32668 31205 32668 30967 32669 31205 32669 30969 32669 31205 32670 31206 32670 30969 32670 30969 32671 31206 32671 30970 32671 30969 32672 30970 32672 30971 32672 30970 32673 31208 32673 30971 32673 30971 32674 31208 32674 30972 32674 30971 32675 30972 32675 30973 32675 30972 32676 31210 32676 30973 32676 30973 32677 31210 32677 31211 32677 30973 32678 31211 32678 30974 32678 31211 32679 31213 32679 30974 32679 30974 32680 31213 32680 30975 32680 30974 32681 30975 32681 30976 32681 30975 32682 31215 32682 30976 32682 30976 32683 31215 32683 31216 32683 30976 32684 31216 32684 30977 32684 31216 32685 31217 32685 30977 32685 30977 32686 31217 32686 30978 32686 30977 32687 30978 32687 30979 32687 30978 32688 31218 32688 30979 32688 30979 32689 31218 32689 30980 32689 30979 32690 30980 32690 30982 32690 30980 32691 30981 32691 30982 32691 30982 32692 30981 32692 30984 32692 30982 32693 30984 32693 30983 32693 30984 32694 31221 32694 30983 32694 30983 32695 31221 32695 31222 32695 30983 32696 31222 32696 30986 32696 31222 32697 30985 32697 30986 32697 30986 32698 30985 32698 31225 32698 30986 32699 31225 32699 30987 32699 31225 32700 30988 32700 30987 32700 30987 32701 30988 32701 30989 32701 30987 32702 30989 32702 30991 32702 30989 32703 30990 32703 30991 32703 30991 32704 30990 32704 31228 32704 30991 32705 31228 32705 30992 32705 31228 32706 31229 32706 30992 32706 30992 32707 31229 32707 31232 32707 30992 32708 31232 32708 30993 32708 31232 32709 30994 32709 30993 32709 30993 32710 30994 32710 31234 32710 30993 32711 31234 32711 30995 32711 31234 32712 31235 32712 30995 32712 30995 32713 31235 32713 31236 32713 30995 32714 31236 32714 30996 32714 31236 32715 31238 32715 30996 32715 30996 32716 31238 32716 31239 32716 30996 32717 31239 32717 30997 32717 31239 32718 30998 32718 30997 32718 30997 32719 30998 32719 31242 32719 30997 32720 31242 32720 31001 32720 31242 32721 30999 32721 31001 32721 31001 32722 30999 32722 31000 32722 31001 32723 31000 32723 31002 32723 31000 32724 31244 32724 31002 32724 31002 32725 31244 32725 31245 32725 31002 32726 31245 32726 31003 32726 31245 32727 31246 32727 31003 32727 31003 32728 31246 32728 31004 32728 31003 32729 31004 32729 31005 32729 31004 32730 31248 32730 31005 32730 31005 32731 31248 32731 31250 32731 31005 32732 31250 32732 31007 32732 31250 32733 31251 32733 31007 32733 31007 32734 31251 32734 31006 32734 31007 32735 31006 32735 31009 32735 31006 32736 31008 32736 31009 32736 31009 32737 31008 32737 31255 32737 31009 32738 31255 32738 31010 32738 31255 32739 31256 32739 31010 32739 31010 32740 31256 32740 31257 32740 31010 32741 31257 32741 31011 32741 31257 32742 31258 32742 31011 32742 31011 32743 31258 32743 31259 32743 31011 32744 31259 32744 31012 32744 31259 32745 31262 32745 31012 32745 31012 32746 31262 32746 31014 32746 31012 32747 31014 32747 31013 32747 31014 32748 31264 32748 31013 32748 31013 32749 31264 32749 31265 32749 31013 32750 31265 32750 31015 32750 31265 32751 31267 32751 31015 32751 31015 32752 31267 32752 31268 32752 31015 32753 31268 32753 31016 32753 31268 32754 31270 32754 31016 32754 31016 32755 31270 32755 31271 32755 31016 32756 31271 32756 31017 32756 31271 32757 31272 32757 31017 32757 31017 32758 31272 32758 31018 32758 31017 32759 31018 32759 31019 32759 31018 32760 31020 32760 31019 32760 31019 32761 31020 32761 31276 32761 31019 32762 31276 32762 31021 32762 31276 32763 31277 32763 31021 32763 31021 32764 31277 32764 31022 32764 31021 32765 31022 32765 31023 32765 31022 32766 31279 32766 31023 32766 31023 32767 31279 32767 31197 32767 31023 32768 31197 32768 30958 32768 30958 32769 31197 32769 31198 32769 30958 32770 31198 32770 30959 32770 31024 32771 31121 32771 31119 32771 31024 32772 31407 32773 31121 32774 31121 32775 31407 32775 31025 32775 31121 32776 31025 32776 31122 32776 31122 32777 31025 32778 31406 32779 31122 32780 31406 32780 31026 32780 31406 32781 31410 32781 31026 32781 31026 32782 31410 32782 31028 32782 31026 32783 31028 32783 31027 32783 31028 32784 31029 32784 31027 32784 31027 32785 31029 32785 31416 32785 31027 32786 31416 32786 31123 32786 31123 32787 31416 32788 31415 32789 31123 32790 31415 32790 31125 32790 31125 32791 31415 32791 31413 32791 31125 32792 31413 32792 31127 32792 31127 32793 31413 32793 31030 32793 31030 32794 31428 32794 31127 32794 31127 32795 31428 32796 31431 32795 31127 32797 31431 32797 31128 32797 31128 32798 31431 32798 31430 32798 31128 32799 31430 32800 31031 32801 31031 32802 31430 32802 31032 32802 31031 32803 31032 32803 31132 32803 31132 32804 31032 32804 31442 32804 31442 32805 31441 32805 31132 32805 31132 32806 31441 32807 31443 32808 31132 32809 31443 32809 31033 32809 31033 32810 31443 32810 31289 32810 31033 32811 31289 32811 31133 32811 31133 32812 31289 32812 31456 32812 31133 32813 31456 32814 31135 32815 31135 32816 31456 32817 31034 32817 31034 32818 31457 32818 31135 32818 31135 32819 31457 32819 31459 32819 31135 32820 31459 32821 31137 32822 31137 32823 31459 32824 31036 32825 31137 32826 31036 32826 31035 32826 31035 32827 31036 32827 31288 32827 31035 32828 31288 32828 31139 32829 31139 32830 31288 32830 31287 32830 31287 32831 31466 32831 31139 32831 31139 32832 31466 32832 31037 32832 31139 32833 31037 32833 31140 32833 31140 32834 31037 32834 31470 32834 31140 32835 31470 32835 31143 32835 31143 32836 31470 32836 31285 32836 31143 32837 31285 32837 31038 32837 31285 32838 31473 32838 31038 32838 31038 32839 31473 32839 31472 32839 31038 32840 31472 32840 31039 32840 31472 32841 31040 32842 31039 32843 31039 32844 31040 32844 31041 32844 31039 32845 31041 32845 31146 32845 31146 32846 31041 32846 31478 32846 31146 32847 31478 32847 31042 32847 31478 32848 31481 32848 31042 32848 31042 32849 31481 32849 31043 32849 31042 32850 31043 32850 31148 32850 31043 32851 31486 32851 31148 32851 31148 32852 31486 32852 31485 32852 31148 32853 31485 32853 31149 32853 31149 32854 31485 32854 31484 32854 31149 32855 31484 32855 31150 32855 31150 32856 31484 32856 31044 32856 31150 32857 31044 32858 31045 32859 31045 32860 31044 32860 31494 32860 31494 32861 31504 32861 31045 32861 31045 32862 31504 32862 31502 32862 31045 32863 31502 32863 31046 32863 31046 32864 31502 32864 31501 32864 31046 32865 31501 32866 31047 32865 31047 32867 31501 32868 31514 32869 31047 32870 31514 32870 31154 32870 31154 32871 31514 32871 31048 32871 31048 32872 31049 32872 31154 32872 31154 32873 31049 32873 31050 32873 31154 32874 31050 32874 31156 32874 31156 32875 31050 32875 31051 32875 31156 32876 31051 32876 31157 32876 31157 32877 31051 32877 31527 32877 31157 32878 31527 32878 31054 32878 31054 32879 31527 32879 31052 32879 31052 32880 31053 32881 31054 32882 31054 32883 31053 32883 31528 32883 31054 32884 31528 32884 31159 32884 31159 32885 31528 32886 31055 32887 31159 32888 31055 32888 31056 32888 31056 32889 31055 32889 31057 32889 31056 32890 31057 32890 31059 32890 31059 32891 31057 32892 31058 32893 31058 32894 31539 32894 31059 32894 31059 32895 31539 32895 31538 32895 31059 32896 31538 32896 31060 32896 31060 32897 31538 32897 31283 32897 31060 32898 31283 32898 31061 32898 31061 32899 31283 32899 31062 32899 31061 32900 31062 32900 31063 32900 31062 32901 31282 32901 31063 32901 31063 32902 31282 32902 31544 32902 31063 32903 31544 32903 31064 32903 31544 32904 31065 32905 31064 32906 31064 32907 31065 32907 31066 32907 31064 32908 31066 32908 31163 32908 31163 32909 31066 32910 31067 32911 31163 32912 31067 32912 31164 32912 31067 32913 31551 32913 31164 32913 31164 32914 31551 32914 31550 32914 31164 32915 31550 32915 31068 32915 31550 32916 31069 32916 31068 32916 31068 32917 31069 32917 31555 32917 31068 32918 31555 32918 31166 32918 31166 32919 31555 32919 31070 32919 31166 32920 31070 32920 31167 32920 31167 32921 31070 32921 31569 32921 31167 32922 31569 32922 31169 32922 31169 32923 31569 32924 31571 32924 31571 32925 31570 32925 31169 32925 31169 32926 31570 32926 31573 32926 31169 32927 31573 32927 31171 32927 31171 32928 31573 32928 31572 32928 31171 32929 31572 32929 31172 32929 31172 32930 31572 32930 31281 32930 31172 32931 31281 32931 31071 32931 31071 32932 31281 32933 31072 32934 31072 32935 31582 32935 31071 32935 31071 32936 31582 32936 31073 32936 31071 32937 31073 32937 31075 32937 31075 32938 31073 32939 31074 32940 31075 32941 31074 32941 31175 32941 31175 32942 31074 32942 31076 32942 31175 32943 31076 32943 31176 32943 31176 32944 31076 32944 31077 32944 31077 32945 31078 32945 31176 32945 31176 32946 31078 32946 31594 32946 31176 32947 31594 32947 31177 32947 31177 32948 31594 32948 31079 32948 31177 32949 31079 32949 31179 32949 31179 32950 31079 32950 31080 32950 31179 32951 31080 32951 31181 32951 31181 32952 31080 32952 31081 32952 31081 32953 31082 32953 31181 32953 31181 32954 31082 32954 31083 32954 31181 32955 31083 32955 31182 32955 31182 32956 31083 32957 31084 32958 31182 32959 31084 32959 31085 32959 31085 32960 31084 32960 31086 32960 31085 32961 31086 32961 31087 32961 31086 32962 31327 32962 31087 32962 31087 32963 31327 32963 31088 32963 31087 32964 31088 32964 31090 32964 31088 32965 31089 32965 31090 32966 31090 32967 31089 32967 31092 32967 31090 32968 31092 32968 31091 32968 31091 32969 31092 32969 31093 32969 31091 32970 31093 32971 31185 32972 31093 32973 31094 32973 31185 32973 31185 32974 31094 32975 31095 32976 31185 32977 31095 32977 31096 32977 31095 32978 31336 32978 31096 32978 31096 32979 31336 32979 31097 32979 31096 32980 31097 32980 31188 32980 31188 32981 31097 32981 31335 32981 31188 32982 31335 32982 31189 32982 31189 32983 31335 32983 31347 32983 31189 32984 31347 32984 31098 32984 31098 32985 31347 32985 31346 32985 31346 32986 31355 32986 31098 32986 31098 32987 31355 32987 31354 32987 31098 32988 31354 32988 31191 32988 31191 32989 31354 32989 31099 32989 31191 32990 31099 32990 31100 32990 31100 32991 31099 32991 31353 32991 31100 32992 31353 32992 31101 32992 31101 32993 31353 32993 31368 32993 31368 32994 31367 32994 31101 32994 31101 32995 31367 32995 31369 32995 31101 32996 31369 32996 31102 32996 31102 32997 31369 32997 31103 32997 31102 32998 31103 32998 31104 32998 31104 32999 31103 32999 31106 32999 31104 33000 31106 33000 31105 33000 31105 33001 31106 33001 31382 33001 31382 33002 31381 33002 31105 33002 31105 33003 31381 33003 31107 33003 31105 33004 31107 33004 31109 33004 31109 33005 31107 33006 31108 33007 31109 33008 31108 33008 31110 33008 31110 33009 31108 33009 31111 33009 31110 33010 31111 33010 31113 33010 31113 33011 31111 33011 31291 33011 31291 33012 31112 33012 31113 33012 31113 33013 31112 33013 31290 33013 31113 33014 31290 33014 31114 33014 31114 33015 31290 33015 31115 33015 31114 33016 31115 33016 31116 33016 31116 33017 31115 33017 31398 33017 31116 33018 31398 33018 31119 33018 31119 33019 31398 33019 31404 33019 31119 33020 31404 33020 31024 33020 31196 33021 31114 33021 31117 33021 31117 33022 31114 33022 31116 33022 31117 33023 31116 33023 31118 33023 31118 33024 31116 33024 31119 33024 31118 33025 31119 33025 31120 33025 31120 33026 31119 33026 31121 33026 31120 33027 31121 33027 31199 33027 31199 33028 31121 33028 31122 33028 31199 33029 31122 33029 31200 33029 31200 33030 31122 33030 31026 33030 31200 33031 31026 33032 31202 33033 31202 33034 31026 33034 31027 33034 31202 33035 31027 33035 31204 33035 31204 33036 31027 33036 31123 33036 31204 33037 31123 33037 31124 33037 31124 33038 31123 33038 31125 33038 31124 33039 31125 33039 31126 33039 31126 33040 31125 33040 31127 33040 31126 33041 31127 33041 31129 33041 31129 33042 31127 33043 31128 33044 31129 33045 31128 33045 31130 33045 31130 33046 31128 33046 31031 33046 31130 33047 31031 33047 31131 33047 31131 33048 31031 33049 31132 33050 31131 33051 31132 33051 31207 33051 31207 33052 31132 33053 31033 33054 31207 33055 31033 33055 31209 33055 31209 33056 31033 33056 31133 33056 31209 33057 31133 33057 31134 33057 31134 33058 31133 33058 31135 33058 31134 33059 31135 33059 31136 33059 31136 33060 31135 33060 31137 33060 31136 33061 31137 33061 31212 33061 31212 33062 31137 33062 31035 33062 31212 33063 31035 33063 31138 33063 31138 33064 31035 33064 31139 33064 31138 33065 31139 33065 31214 33065 31214 33066 31139 33067 31140 33068 31214 33069 31140 33069 31141 33069 31141 33070 31140 33070 31143 33070 31141 33071 31143 33071 31142 33071 31142 33072 31143 33073 31038 33074 31142 33075 31038 33075 31144 33075 31144 33076 31038 33077 31039 33078 31144 33079 31039 33079 31145 33079 31145 33080 31039 33080 31146 33080 31145 33081 31146 33081 31147 33081 31147 33082 31146 33082 31042 33082 31147 33083 31042 33083 31219 33083 31219 33084 31042 33084 31148 33084 31219 33085 31148 33085 31220 33085 31220 33086 31148 33086 31149 33086 31220 33087 31149 33087 31151 33087 31151 33088 31149 33088 31150 33088 31151 33089 31150 33089 31152 33089 31152 33090 31150 33090 31045 33090 31152 33091 31045 33092 31223 33093 31223 33094 31045 33095 31046 33096 31223 33097 31046 33097 31153 33097 31153 33098 31046 33098 31047 33098 31153 33099 31047 33100 31224 33101 31224 33102 31047 33102 31154 33102 31224 33103 31154 33103 31155 33103 31155 33104 31154 33104 31156 33104 31155 33105 31156 33105 31226 33105 31226 33106 31156 33106 31157 33106 31226 33107 31157 33107 31227 33107 31227 33108 31157 33108 31054 33108 31227 33109 31054 33109 31158 33109 31158 33110 31054 33110 31159 33110 31158 33111 31159 33111 31230 33111 31230 33112 31159 33112 31056 33112 31230 33113 31056 33113 31231 33113 31231 33114 31056 33114 31059 33114 31231 33115 31059 33115 31160 33115 31160 33116 31059 33116 31060 33116 31160 33117 31060 33117 31233 33117 31233 33118 31060 33118 31061 33118 31233 33119 31061 33119 31161 33119 31161 33120 31061 33120 31063 33120 31161 33121 31063 33121 31237 33121 31237 33122 31063 33122 31064 33122 31237 33123 31064 33123 31162 33123 31162 33124 31064 33124 31163 33124 31162 33125 31163 33126 31240 33127 31240 33128 31163 33128 31164 33128 31240 33129 31164 33129 31241 33129 31241 33130 31164 33130 31068 33130 31241 33131 31068 33131 31243 33131 31243 33132 31068 33132 31166 33132 31243 33133 31166 33133 31165 33133 31165 33134 31166 33134 31167 33134 31165 33135 31167 33135 31168 33135 31168 33136 31167 33137 31169 33137 31168 33138 31169 33138 31170 33138 31170 33139 31169 33140 31171 33140 31170 33141 31171 33141 31247 33141 31247 33142 31171 33142 31172 33142 31247 33143 31172 33144 31173 33145 31173 33146 31172 33146 31071 33146 31173 33147 31071 33147 31174 33147 31174 33148 31071 33148 31075 33148 31174 33149 31075 33149 31249 33149 31249 33150 31075 33150 31175 33150 31249 33151 31175 33152 31252 33152 31252 33153 31175 33153 31176 33153 31252 33154 31176 33154 31253 33154 31253 33155 31176 33155 31177 33155 31253 33156 31177 33156 31178 33156 31178 33157 31177 33157 31179 33157 31178 33158 31179 33158 31180 33158 31180 33159 31179 33159 31181 33159 31180 33160 31181 33160 31254 33160 31254 33161 31181 33161 31182 33161 31254 33162 31182 33162 31183 33162 31183 33163 31182 33164 31085 33165 31183 33166 31085 33166 31184 33166 31184 33167 31085 33167 31087 33167 31184 33168 31087 33168 31260 33168 31260 33169 31087 33169 31090 33169 31260 33170 31090 33170 31261 33170 31261 33171 31090 33172 31091 33173 31261 33174 31091 33175 31263 33176 31263 33177 31091 33177 31185 33177 31263 33178 31185 33178 31186 33178 31186 33179 31185 33179 31096 33179 31186 33180 31096 33180 31187 33180 31187 33181 31096 33181 31188 33181 31187 33182 31188 33182 31266 33182 31266 33183 31188 33183 31189 33183 31266 33184 31189 33184 31269 33184 31269 33185 31189 33186 31098 33187 31269 33188 31098 33188 31190 33188 31190 33189 31098 33190 31191 33191 31190 33192 31191 33192 31192 33192 31192 33193 31191 33193 31100 33193 31192 33194 31100 33194 31193 33194 31193 33195 31100 33195 31101 33195 31193 33196 31101 33196 31273 33196 31273 33197 31101 33197 31102 33197 31273 33198 31102 33198 31194 33198 31194 33199 31102 33199 31104 33199 31194 33200 31104 33200 31274 33200 31274 33201 31104 33201 31105 33201 31274 33202 31105 33202 31275 33202 31275 33203 31105 33203 31109 33203 31275 33204 31109 33204 31278 33204 31278 33205 31109 33205 31110 33205 31278 33206 31110 33206 31195 33206 31195 33207 31110 33207 31113 33207 31195 33208 31113 33208 31196 33208 31196 33209 31113 33209 31114 33209 31197 33210 31117 33210 31198 33210 31198 33211 31117 33211 31118 33211 31198 33212 31118 33212 30959 33212 30959 33213 31118 33213 31120 33213 30959 33214 31120 33214 30961 33214 30961 33215 31120 33215 31199 33215 30961 33216 31199 33216 30962 33216 30962 33217 31199 33217 31200 33217 30962 33218 31200 33218 31201 33218 31201 33219 31200 33219 31202 33219 31201 33220 31202 33220 31203 33220 31203 33221 31202 33221 31204 33221 31203 33222 31204 33222 30965 33222 30965 33223 31204 33223 31124 33223 30965 33224 31124 33225 30966 33226 30966 33227 31124 33227 31126 33227 30966 33228 31126 33229 30968 33230 30968 33231 31126 33232 31129 33233 30968 33234 31129 33234 31205 33234 31205 33235 31129 33235 31130 33235 31205 33236 31130 33236 31206 33236 31206 33237 31130 33237 31131 33237 31206 33238 31131 33238 30970 33238 30970 33239 31131 33240 31207 33241 30970 33242 31207 33242 31208 33242 31208 33243 31207 33243 31209 33243 31208 33244 31209 33245 30972 33246 30972 33247 31209 33247 31134 33247 30972 33248 31134 33248 31210 33248 31210 33249 31134 33249 31136 33249 31210 33250 31136 33251 31211 33252 31211 33253 31136 33254 31212 33255 31211 33256 31212 33257 31213 33258 31213 33259 31212 33259 31138 33259 31213 33260 31138 33260 30975 33260 30975 33261 31138 33262 31214 33263 30975 33264 31214 33264 31215 33264 31215 33265 31214 33265 31141 33265 31215 33266 31141 33267 31216 33268 31216 33269 31141 33269 31142 33269 31216 33270 31142 33270 31217 33270 31217 33271 31142 33271 31144 33271 31217 33272 31144 33272 30978 33272 30978 33273 31144 33273 31145 33273 30978 33274 31145 33274 31218 33274 31218 33275 31145 33275 31147 33275 31218 33276 31147 33277 30980 33278 30980 33279 31147 33280 31219 33281 30980 33282 31219 33282 30981 33282 30981 33283 31219 33283 31220 33283 30981 33284 31220 33284 30984 33284 30984 33285 31220 33285 31151 33285 30984 33286 31151 33286 31221 33286 31221 33287 31151 33287 31152 33287 31221 33288 31152 33288 31222 33288 31222 33289 31152 33289 31223 33289 31222 33290 31223 33290 30985 33290 30985 33291 31223 33291 31153 33291 30985 33292 31153 33293 31225 33294 31225 33295 31153 33295 31224 33295 31225 33296 31224 33296 30988 33296 30988 33297 31224 33297 31155 33297 30988 33298 31155 33298 30989 33298 30989 33299 31155 33299 31226 33299 30989 33300 31226 33300 30990 33300 30990 33301 31226 33301 31227 33301 30990 33302 31227 33303 31228 33304 31228 33305 31227 33305 31158 33305 31228 33306 31158 33306 31229 33306 31229 33307 31158 33307 31230 33307 31229 33308 31230 33309 31232 33310 31232 33311 31230 33311 31231 33311 31232 33312 31231 33312 30994 33312 30994 33313 31231 33313 31160 33313 30994 33314 31160 33314 31234 33314 31234 33315 31160 33315 31233 33315 31234 33316 31233 33316 31235 33316 31235 33317 31233 33317 31161 33317 31235 33318 31161 33318 31236 33318 31236 33319 31161 33319 31237 33319 31236 33320 31237 33320 31238 33320 31238 33321 31237 33321 31162 33321 31238 33322 31162 33322 31239 33322 31239 33323 31162 33323 31240 33323 31239 33324 31240 33324 30998 33324 30998 33325 31240 33325 31241 33325 30998 33326 31241 33326 31242 33326 31242 33327 31241 33328 31243 33329 31242 33330 31243 33330 30999 33330 30999 33331 31243 33331 31165 33331 30999 33332 31165 33332 31000 33332 31000 33333 31165 33333 31168 33333 31000 33334 31168 33334 31244 33334 31244 33335 31168 33335 31170 33335 31244 33336 31170 33337 31245 33338 31245 33339 31170 33340 31247 33341 31245 33342 31247 33342 31246 33342 31246 33343 31247 33343 31173 33343 31246 33344 31173 33344 31004 33344 31004 33345 31173 33345 31174 33345 31004 33346 31174 33346 31248 33346 31248 33347 31174 33347 31249 33347 31248 33348 31249 33348 31250 33348 31250 33349 31249 33349 31252 33349 31250 33350 31252 33351 31251 33352 31251 33353 31252 33354 31253 33355 31251 33356 31253 33356 31006 33356 31006 33357 31253 33357 31178 33357 31006 33358 31178 33358 31008 33358 31008 33359 31178 33359 31180 33359 31008 33360 31180 33361 31255 33362 31255 33363 31180 33364 31254 33365 31255 33366 31254 33366 31256 33366 31256 33367 31254 33368 31183 33369 31256 33370 31183 33370 31257 33370 31257 33371 31183 33371 31184 33371 31257 33372 31184 33373 31258 33374 31258 33375 31184 33376 31260 33377 31258 33378 31260 33378 31259 33378 31259 33379 31260 33379 31261 33379 31259 33380 31261 33380 31262 33380 31262 33381 31261 33381 31263 33381 31262 33382 31263 33382 31014 33382 31014 33383 31263 33383 31186 33383 31014 33384 31186 33384 31264 33384 31264 33385 31186 33386 31187 33387 31264 33388 31187 33388 31265 33388 31265 33389 31187 33389 31266 33389 31265 33390 31266 33390 31267 33390 31267 33391 31266 33391 31269 33391 31267 33392 31269 33392 31268 33392 31268 33393 31269 33393 31190 33393 31268 33394 31190 33394 31270 33394 31270 33395 31190 33395 31192 33395 31270 33396 31192 33396 31271 33396 31271 33397 31192 33397 31193 33397 31271 33398 31193 33398 31272 33398 31272 33399 31193 33399 31273 33399 31272 33400 31273 33400 31018 33400 31018 33401 31273 33401 31194 33401 31018 33402 31194 33402 31020 33402 31020 33403 31194 33403 31274 33403 31020 33404 31274 33404 31276 33404 31276 33405 31274 33405 31275 33405 31276 33406 31275 33406 31277 33406 31277 33407 31275 33408 31278 33409 31277 33410 31278 33410 31022 33410 31022 33411 31278 33411 31195 33411 31022 33412 31195 33412 31279 33412 31279 33413 31195 33413 31196 33413 31279 33414 31196 33414 31197 33414 31197 33415 31196 33415 31117 33415 31082 33416 31081 33416 31599 33416 31080 33417 31079 33417 31595 33417 31076 33418 31074 33418 31280 33418 31281 33419 31572 33419 31581 33419 31069 33420 31550 33420 31552 33420 31065 33421 31544 33421 31545 33421 31282 33422 31062 33422 31546 33422 31283 33423 31538 33423 31542 33423 31539 33424 31058 33424 31284 33424 31057 33425 31055 33425 31531 33425 31527 33426 31051 33426 31515 33426 31504 33427 31494 33427 31495 33427 31486 33428 31043 33428 31487 33428 31040 33429 31472 33430 31479 33431 31473 33432 31285 33432 31286 33432 31470 33433 31037 33433 31471 33433 31466 33434 31287 33434 31468 33434 31288 33435 31036 33435 31462 33435 31456 33436 31289 33436 31444 33436 31032 33437 31430 33437 31440 33437 31029 33438 31028 33438 31417 33439 31407 33440 31024 33440 31403 33440 31404 33441 31398 33441 31405 33441 31115 33442 31290 33442 31399 33442 31112 33443 31291 33443 31394 33443 31111 33444 31108 33444 31383 33444 31106 33445 31103 33445 31380 33445 31355 33446 31346 33446 31357 33446 31336 33447 31095 33447 31334 33447 31089 33448 31088 33449 31328 33450 31327 33451 31086 33451 31292 33451 31084 33452 31083 33452 31607 33452 30955 33453 31577 33453 31565 33453 31424 33454 31436 33454 31425 33454 31507 33455 31615 33455 31508 33455 31489 33456 31620 33456 31499 33456 31296 33457 31293 33457 31294 33457 31294 33458 31293 33458 31295 33458 31294 33459 31295 33459 31298 33459 31296 33460 31294 33460 31297 33460 31297 33461 31294 33461 31298 33461 31297 33462 31298 33462 31299 33462 31461 33463 31300 33463 31301 33463 31301 33464 31300 33464 31302 33464 31303 33465 31437 33465 31435 33465 31304 33466 31424 33466 31426 33466 31307 33467 31305 33468 31306 33469 31306 33470 31305 33470 31388 33470 31306 33471 31388 33471 31389 33471 31307 33472 31306 33472 31308 33472 31308 33473 31306 33473 31389 33473 31308 33474 31389 33474 31392 33474 31387 33475 31309 33475 31391 33475 31391 33476 31309 33476 31393 33476 31358 33477 31360 33477 31361 33477 31340 33478 31310 33479 31351 33480 31311 33481 31312 33481 31313 33481 31313 33482 31312 33483 31602 33484 31313 33485 31602 33485 31604 33485 31311 33486 31313 33487 31314 33488 31314 33489 31313 33489 31604 33489 31314 33490 31604 33490 31605 33490 31315 33491 31316 33491 31597 33491 31597 33492 31316 33492 31606 33492 31317 33493 31578 33493 31318 33493 31557 33494 30955 33495 31319 33496 31320 33497 31541 33497 31321 33497 31321 33498 31541 33499 31533 33500 31321 33501 31533 33501 31535 33501 31320 33502 31321 33503 31322 33504 31322 33505 31321 33505 31535 33505 31322 33506 31535 33506 31536 33506 31323 33507 31324 33507 31530 33507 31530 33508 31324 33508 31537 33508 31086 33509 31084 33509 31292 33509 31292 33510 31084 33510 31607 33510 31292 33511 31607 33511 31330 33511 31330 33512 31607 33512 31326 33512 31330 33513 31326 33513 31325 33513 31325 33514 31326 33514 31608 33514 31088 33515 31327 33515 31328 33515 31328 33516 31327 33516 31292 33516 31328 33517 31292 33517 31329 33517 31329 33518 31292 33518 31330 33518 31329 33519 31330 33519 31331 33519 31331 33520 31330 33520 31325 33520 31094 33521 31093 33521 31332 33521 31332 33522 31093 33522 31092 33522 31092 33523 31089 33523 31332 33523 31332 33524 31089 33524 31328 33524 31332 33525 31328 33525 31333 33525 31333 33526 31328 33526 31329 33526 31333 33527 31329 33527 31341 33527 31341 33528 31329 33528 31331 33528 31095 33529 31094 33529 31334 33529 31334 33530 31094 33530 31332 33530 31334 33531 31332 33531 31338 33531 31338 33532 31332 33532 31333 33532 31338 33533 31333 33533 31339 33533 31339 33534 31333 33534 31341 33534 31347 33535 31335 33535 31348 33535 31348 33536 31335 33536 31097 33536 31097 33537 31336 33537 31348 33537 31348 33538 31336 33538 31334 33538 31348 33539 31334 33539 31337 33539 31337 33540 31334 33540 31338 33540 31337 33541 31338 33541 31351 33541 31351 33542 31338 33542 31339 33542 31351 33543 31339 33543 31340 33543 31340 33544 31339 33544 31341 33544 31340 33545 31341 33545 31342 33545 31342 33546 31341 33546 31331 33546 31342 33547 31331 33547 31343 33547 31343 33548 31331 33548 31325 33548 31343 33549 31325 33549 31344 33549 31344 33550 31325 33550 31608 33550 31344 33551 31608 33551 31345 33551 31345 33552 31608 33552 31609 33552 31346 33553 31347 33553 31357 33553 31357 33554 31347 33554 31348 33554 31357 33555 31348 33555 31349 33555 31349 33556 31348 33556 31337 33556 31349 33557 31337 33557 31350 33557 31350 33558 31337 33558 31351 33558 31350 33559 31351 33559 31352 33559 31352 33560 31351 33560 31310 33560 31352 33561 31310 33561 31359 33561 31353 33562 31099 33562 31356 33562 31356 33563 31099 33563 31354 33563 31354 33564 31355 33564 31356 33564 31356 33565 31355 33565 31357 33565 31356 33566 31357 33566 31364 33566 31364 33567 31357 33567 31349 33567 31364 33568 31349 33568 31363 33568 31363 33569 31349 33569 31350 33569 31363 33570 31350 33570 31361 33570 31361 33571 31350 33571 31352 33571 31361 33572 31352 33572 31358 33572 31358 33573 31352 33573 31359 33573 31360 33574 31373 33574 31361 33574 31361 33575 31373 33575 31372 33575 31361 33576 31372 33576 31363 33576 31363 33577 31372 33577 31362 33577 31363 33578 31362 33578 31364 33578 31364 33579 31362 33579 31365 33579 31364 33580 31365 33580 31356 33580 31356 33581 31365 33581 31366 33581 31356 33582 31366 33582 31353 33582 31369 33583 31367 33583 31366 33583 31366 33584 31367 33584 31368 33584 31366 33585 31368 33585 31353 33585 31103 33586 31369 33586 31380 33586 31380 33587 31369 33587 31366 33587 31380 33588 31366 33588 31379 33588 31379 33589 31366 33589 31365 33589 31379 33590 31365 33590 31370 33590 31370 33591 31365 33591 31362 33591 31370 33592 31362 33592 31371 33592 31371 33593 31362 33593 31372 33593 31371 33594 31372 33594 31375 33594 31375 33595 31372 33595 31373 33595 31375 33596 31373 33596 31374 33596 31375 33597 31376 33597 31371 33597 31371 33598 31376 33598 31377 33598 31371 33599 31377 33599 31370 33599 31370 33600 31377 33600 31378 33600 31370 33601 31378 33601 31379 33601 31379 33602 31378 33602 31386 33602 31379 33603 31386 33603 31380 33603 31380 33604 31386 33604 31384 33604 31380 33605 31384 33605 31106 33605 31107 33606 31381 33606 31384 33606 31384 33607 31381 33607 31382 33607 31384 33608 31382 33608 31106 33608 31108 33609 31107 33610 31383 33611 31383 33612 31107 33612 31384 33612 31383 33613 31384 33613 31385 33613 31385 33614 31384 33614 31386 33614 31385 33615 31386 33615 31390 33615 31390 33616 31386 33616 31378 33616 31390 33617 31378 33617 31391 33617 31391 33618 31378 33618 31377 33618 31391 33619 31377 33619 31387 33619 31387 33620 31377 33620 31376 33620 31291 33621 31111 33621 31394 33621 31394 33622 31111 33622 31383 33622 31394 33623 31383 33623 31395 33623 31395 33624 31383 33624 31385 33624 31395 33625 31385 33625 31388 33625 31388 33626 31385 33626 31390 33626 31388 33627 31390 33627 31389 33627 31389 33628 31390 33628 31391 33628 31389 33629 31391 33629 31392 33629 31392 33630 31391 33630 31393 33630 31290 33631 31112 33631 31399 33631 31399 33632 31112 33632 31394 33632 31399 33633 31394 33633 31402 33633 31402 33634 31394 33634 31395 33634 31402 33635 31395 33635 31396 33635 31396 33636 31395 33636 31388 33636 31396 33637 31388 33637 31397 33637 31397 33638 31388 33638 31305 33638 31398 33639 31115 33639 31405 33639 31405 33640 31115 33640 31399 33640 31405 33641 31399 33641 31400 33641 31400 33642 31399 33642 31402 33642 31400 33643 31402 33643 31401 33643 31401 33644 31402 33644 31396 33644 31024 33645 31404 33645 31403 33645 31403 33646 31404 33646 31405 33646 31403 33647 31405 33647 31409 33647 31409 33648 31405 33648 31400 33648 31409 33649 31400 33649 31421 33649 31421 33650 31400 33650 31401 33650 31410 33651 31406 33651 31411 33651 31411 33652 31406 33652 31025 33652 31025 33653 31407 33653 31411 33653 31411 33654 31407 33654 31403 33654 31411 33655 31403 33655 31408 33655 31408 33656 31403 33656 31409 33656 31408 33657 31409 33657 31420 33657 31420 33658 31409 33658 31421 33658 31028 33659 31410 33659 31417 33659 31417 33660 31410 33660 31411 33660 31417 33661 31411 33661 31412 33661 31412 33662 31411 33662 31408 33662 31412 33663 31408 33663 31419 33663 31419 33664 31408 33664 31420 33664 31413 33665 31415 33665 31414 33665 31414 33666 31415 33666 31416 33666 31416 33667 31029 33667 31414 33667 31414 33668 31029 33668 31417 33668 31414 33669 31417 33669 31418 33669 31418 33670 31417 33670 31412 33670 31418 33671 31412 33671 31426 33671 31426 33672 31412 33672 31419 33672 31426 33673 31419 33673 31304 33673 31304 33674 31419 33674 31420 33674 31304 33675 31420 33675 30946 33675 30946 33676 31420 33676 31421 33676 30946 33677 31421 33677 31422 33677 31422 33678 31421 33678 31401 33678 31422 33679 31401 33679 31423 33679 31423 33680 31401 33680 31396 33680 31423 33681 31396 33681 30948 33681 30948 33682 31396 33683 31397 33684 31424 33685 31425 33685 31426 33685 31426 33686 31425 33686 31433 33686 31426 33687 31433 33687 31418 33687 31418 33688 31433 33688 31427 33688 31418 33689 31427 33689 31414 33689 31414 33690 31427 33690 31429 33690 31414 33691 31429 33691 31413 33691 31431 33692 31428 33692 31429 33692 31429 33693 31428 33693 31030 33693 31429 33694 31030 33694 31413 33694 31430 33695 31431 33695 31440 33695 31440 33696 31431 33696 31429 33696 31440 33697 31429 33697 31432 33697 31432 33698 31429 33698 31427 33698 31432 33699 31427 33699 31434 33699 31434 33700 31427 33700 31433 33700 31434 33701 31433 33701 31435 33701 31435 33702 31433 33702 31425 33702 31435 33703 31425 33703 31303 33703 31303 33704 31425 33705 31436 33706 31437 33707 31438 33707 31435 33707 31435 33708 31438 33708 31447 33708 31435 33709 31447 33709 31434 33709 31434 33710 31447 33710 31446 33710 31434 33711 31446 33711 31432 33711 31432 33712 31446 33712 31439 33712 31432 33713 31439 33713 31440 33713 31440 33714 31439 33714 31445 33714 31440 33715 31445 33715 31032 33715 31443 33716 31441 33716 31445 33716 31445 33717 31441 33717 31442 33717 31445 33718 31442 33718 31032 33718 31289 33719 31443 33720 31444 33721 31444 33722 31443 33722 31445 33722 31444 33723 31445 33723 31455 33723 31455 33724 31445 33724 31439 33724 31455 33725 31439 33725 31453 33725 31453 33726 31439 33726 31446 33726 31453 33727 31446 33727 31451 33727 31451 33728 31446 33728 31447 33728 31451 33729 31447 33729 31449 33729 31449 33730 31447 33730 31438 33730 31449 33731 31438 33731 31448 33731 31449 33732 31450 33732 31451 33732 31451 33733 31450 33733 31452 33733 31451 33734 31452 33734 31453 33734 31453 33735 31452 33735 31454 33735 31453 33736 31454 33736 31455 33736 31455 33737 31454 33737 31460 33737 31455 33738 31460 33738 31444 33738 31444 33739 31460 33739 31458 33739 31444 33740 31458 33740 31456 33740 31459 33741 31457 33741 31458 33741 31458 33742 31457 33742 31034 33742 31458 33743 31034 33743 31456 33743 31036 33744 31459 33744 31462 33744 31462 33745 31459 33745 31458 33745 31462 33746 31458 33746 31464 33746 31464 33747 31458 33747 31460 33747 31464 33748 31460 33748 31465 33748 31465 33749 31460 33749 31454 33749 31465 33750 31454 33750 31301 33750 31301 33751 31454 33751 31452 33751 31301 33752 31452 33752 31461 33752 31461 33753 31452 33753 31450 33753 31287 33754 31288 33754 31468 33754 31468 33755 31288 33755 31462 33755 31468 33756 31462 33756 31463 33756 31463 33757 31462 33757 31464 33757 31463 33758 31464 33758 31295 33758 31295 33759 31464 33759 31465 33759 31295 33760 31465 33760 31298 33760 31298 33761 31465 33761 31301 33761 31298 33762 31301 33762 31299 33762 31299 33763 31301 33763 31302 33763 31037 33764 31466 33764 31471 33764 31471 33765 31466 33765 31468 33765 31471 33766 31468 33766 31467 33766 31467 33767 31468 33767 31463 33767 31467 33768 31463 33768 31493 33768 31493 33769 31463 33769 31295 33769 31493 33770 31295 33770 31469 33770 31469 33771 31295 33771 31293 33771 31285 33772 31470 33772 31286 33772 31286 33773 31470 33773 31471 33773 31286 33774 31471 33774 31474 33774 31474 33775 31471 33775 31467 33775 31474 33776 31467 33776 31492 33776 31492 33777 31467 33777 31493 33777 31472 33778 31473 33778 31479 33778 31479 33779 31473 33779 31286 33779 31479 33780 31286 33780 31475 33780 31475 33781 31286 33781 31474 33781 31475 33782 31474 33782 31476 33782 31476 33783 31474 33783 31492 33783 31481 33784 31478 33784 31477 33784 31477 33785 31478 33785 31041 33785 31041 33786 31040 33786 31477 33786 31477 33787 31040 33787 31479 33787 31477 33788 31479 33788 31483 33788 31483 33789 31479 33789 31475 33789 31483 33790 31475 33790 31480 33790 31480 33791 31475 33791 31476 33791 31043 33792 31481 33792 31487 33792 31487 33793 31481 33793 31477 33793 31487 33794 31477 33794 31482 33794 31482 33795 31477 33795 31483 33795 31482 33796 31483 33796 31488 33796 31488 33797 31483 33797 31480 33797 31044 33798 31484 33798 31496 33798 31496 33799 31484 33799 31485 33799 31485 33800 31486 33800 31496 33800 31496 33801 31486 33801 31487 33801 31496 33802 31487 33802 31498 33802 31498 33803 31487 33803 31482 33803 31498 33804 31482 33804 31499 33804 31499 33805 31482 33805 31488 33805 31499 33806 31488 33806 31489 33806 31489 33807 31488 33807 31480 33807 31489 33808 31480 33808 31490 33808 31490 33809 31480 33809 31476 33809 31490 33810 31476 33810 31623 33810 31623 33811 31476 33811 31492 33811 31623 33812 31492 33812 31491 33812 31491 33813 31492 33813 31493 33813 31491 33814 31493 33814 31618 33814 31618 33815 31493 33815 31469 33815 31494 33816 31044 33816 31495 33816 31495 33817 31044 33817 31496 33817 31495 33818 31496 33818 31497 33818 31497 33819 31496 33819 31498 33819 31497 33820 31498 33820 31505 33820 31505 33821 31498 33821 31499 33821 31505 33822 31499 33822 31506 33822 31506 33823 31499 33823 31620 33823 31506 33824 31620 33824 31500 33824 31514 33825 31501 33825 31503 33825 31503 33826 31501 33826 31502 33826 31502 33827 31504 33827 31503 33827 31503 33828 31504 33828 31495 33828 31503 33829 31495 33829 31512 33829 31512 33830 31495 33830 31497 33830 31512 33831 31497 33831 31511 33831 31511 33832 31497 33832 31505 33832 31511 33833 31505 33833 31508 33833 31508 33834 31505 33834 31506 33834 31508 33835 31506 33835 31507 33835 31507 33836 31506 33837 31500 33838 31615 33839 31519 33839 31508 33839 31508 33840 31519 33840 31509 33840 31508 33841 31509 33841 31511 33841 31511 33842 31509 33842 31510 33842 31511 33843 31510 33843 31512 33843 31512 33844 31510 33844 31516 33844 31512 33845 31516 33845 31503 33845 31503 33846 31516 33846 31513 33846 31503 33847 31513 33847 31514 33847 31050 33848 31049 33848 31513 33848 31513 33849 31049 33849 31048 33849 31513 33850 31048 33850 31514 33850 31051 33851 31050 33851 31515 33851 31515 33852 31050 33852 31513 33852 31515 33853 31513 33853 31524 33853 31524 33854 31513 33854 31516 33854 31524 33855 31516 33855 31517 33855 31517 33856 31516 33856 31510 33856 31517 33857 31510 33857 31520 33857 31520 33858 31510 33858 31509 33858 31520 33859 31509 33859 31518 33859 31518 33860 31509 33860 31519 33860 31518 33861 31519 33861 31614 33861 31518 33862 31521 33862 31520 33862 31520 33863 31521 33863 31522 33863 31520 33864 31522 33864 31517 33864 31517 33865 31522 33865 31523 33865 31517 33866 31523 33866 31524 33866 31524 33867 31523 33867 31525 33867 31524 33868 31525 33868 31515 33868 31515 33869 31525 33869 31526 33869 31515 33870 31526 33870 31527 33870 31528 33871 31053 33871 31526 33871 31526 33872 31053 33872 31052 33872 31526 33873 31052 33873 31527 33873 31055 33874 31528 33875 31531 33876 31531 33877 31528 33877 31526 33877 31531 33878 31526 33878 31529 33878 31529 33879 31526 33879 31525 33879 31529 33880 31525 33880 31534 33880 31534 33881 31525 33881 31523 33881 31534 33882 31523 33882 31530 33882 31530 33883 31523 33883 31522 33883 31530 33884 31522 33884 31323 33884 31323 33885 31522 33885 31521 33885 31058 33886 31057 33886 31284 33886 31284 33887 31057 33887 31531 33887 31284 33888 31531 33888 31532 33888 31532 33889 31531 33889 31529 33889 31532 33890 31529 33890 31533 33890 31533 33891 31529 33891 31534 33891 31533 33892 31534 33892 31535 33892 31535 33893 31534 33893 31530 33893 31535 33894 31530 33894 31536 33894 31536 33895 31530 33895 31537 33895 31538 33896 31539 33896 31542 33896 31542 33897 31539 33897 31284 33897 31542 33898 31284 33898 31540 33898 31540 33899 31284 33899 31532 33899 31540 33900 31532 33900 31563 33900 31563 33901 31532 33901 31533 33901 31563 33902 31533 33902 30951 33902 30951 33903 31533 33903 31541 33903 31062 33904 31283 33904 31546 33904 31546 33905 31283 33905 31542 33905 31546 33906 31542 33906 31543 33906 31543 33907 31542 33907 31540 33907 31543 33908 31540 33908 31562 33908 31562 33909 31540 33909 31563 33909 31544 33910 31282 33910 31545 33910 31545 33911 31282 33911 31546 33911 31545 33912 31546 33912 31549 33912 31549 33913 31546 33913 31543 33913 31549 33914 31543 33914 31560 33914 31560 33915 31543 33915 31562 33915 31551 33916 31067 33916 31547 33916 31547 33917 31067 33917 31066 33917 31066 33918 31065 33918 31547 33918 31547 33919 31065 33919 31545 33919 31547 33920 31545 33920 31548 33920 31548 33921 31545 33921 31549 33921 31548 33922 31549 33922 31559 33922 31559 33923 31549 33923 31560 33923 31550 33924 31551 33924 31552 33924 31552 33925 31551 33925 31547 33925 31552 33926 31547 33926 31553 33926 31553 33927 31547 33927 31548 33927 31553 33928 31548 33928 31554 33928 31554 33929 31548 33929 31559 33929 31569 33930 31070 33930 31556 33930 31556 33931 31070 33931 31555 33931 31555 33932 31069 33932 31556 33932 31556 33933 31069 33933 31552 33933 31556 33934 31552 33934 31567 33934 31567 33935 31552 33935 31553 33935 31567 33936 31553 33936 31319 33936 31319 33937 31553 33937 31554 33937 31319 33938 31554 33938 31557 33938 31557 33939 31554 33939 31559 33939 31557 33940 31559 33940 31558 33940 31558 33941 31559 33941 31560 33941 31558 33942 31560 33942 31561 33942 31561 33943 31560 33943 31562 33943 31561 33944 31562 33944 30957 33944 30957 33945 31562 33945 31563 33945 30957 33946 31563 33946 31564 33946 31564 33947 31563 33948 30951 33947 30955 33949 31565 33949 31319 33949 31319 33950 31565 33950 31566 33950 31319 33951 31566 33951 31567 33951 31567 33952 31566 33952 31575 33952 31567 33953 31575 33953 31556 33953 31556 33954 31575 33954 31568 33954 31556 33955 31568 33955 31569 33955 31573 33956 31570 33956 31568 33956 31568 33957 31570 33957 31571 33957 31568 33958 31571 33958 31569 33958 31572 33959 31573 33959 31581 33960 31581 33961 31573 33961 31568 33961 31581 33962 31568 33962 31574 33962 31574 33963 31568 33963 31575 33963 31574 33964 31575 33964 31576 33964 31576 33965 31575 33965 31566 33965 31576 33966 31566 33966 31318 33966 31318 33967 31566 33967 31565 33967 31318 33968 31565 33968 31317 33968 31317 33969 31565 33969 31577 33969 31578 33970 31579 33970 31318 33970 31318 33971 31579 33971 31580 33971 31318 33972 31580 33972 31576 33972 31576 33973 31580 33973 31585 33973 31576 33974 31585 33974 31574 33974 31574 33975 31585 33975 31584 33975 31574 33976 31584 33976 31581 33976 31581 33977 31584 33977 31583 33977 31581 33978 31583 33978 31281 33978 31073 33979 31582 33979 31583 33979 31583 33980 31582 33980 31072 33980 31583 33981 31072 33981 31281 33981 31074 33982 31073 33982 31280 33982 31280 33983 31073 33983 31583 33983 31280 33984 31583 33984 31592 33984 31592 33985 31583 33985 31584 33985 31592 33986 31584 33986 31591 33986 31591 33987 31584 33987 31585 33987 31591 33988 31585 33988 31588 33988 31588 33989 31585 33989 31580 33989 31588 33990 31580 33990 31586 33990 31586 33991 31580 33991 31579 33991 31586 33992 31579 33993 31587 33994 31586 33995 31598 33995 31588 33995 31588 33996 31598 33996 31589 33996 31588 33997 31589 33997 31591 33997 31591 33998 31589 33998 31590 33998 31591 33999 31590 33999 31592 33999 31592 34000 31590 34000 31593 34000 31592 34001 31593 34001 31280 34001 31280 34002 31593 34002 31596 34002 31280 34003 31596 34003 31076 34003 31594 34004 31078 34004 31596 34004 31596 34005 31078 34005 31077 34005 31596 34006 31077 34006 31076 34006 31079 34007 31594 34007 31595 34007 31595 34008 31594 34008 31596 34008 31595 34009 31596 34009 31601 34009 31601 34010 31596 34010 31593 34010 31601 34011 31593 34011 31603 34011 31603 34012 31593 34012 31590 34012 31603 34013 31590 34013 31597 34013 31597 34014 31590 34014 31589 34014 31597 34015 31589 34015 31315 34015 31315 34016 31589 34016 31598 34016 31081 34017 31080 34017 31599 34017 31599 34018 31080 34018 31595 34018 31599 34019 31595 34019 31600 34019 31600 34020 31595 34020 31601 34020 31600 34021 31601 34021 31602 34021 31602 34022 31601 34022 31603 34022 31602 34023 31603 34023 31604 34023 31604 34024 31603 34024 31597 34024 31604 34025 31597 34025 31605 34025 31605 34026 31597 34026 31606 34026 31083 34027 31082 34027 31607 34027 31607 34028 31082 34028 31599 34028 31607 34029 31599 34029 31326 34029 31326 34030 31599 34030 31600 34030 31326 34031 31600 34031 31608 34031 31608 34032 31600 34032 31602 34032 31608 34033 31602 34033 31609 34033 31609 34034 31602 34034 31312 34034 31620 34035 31610 34035 31611 34035 31611 34036 31612 34036 31620 34036 31620 34037 31612 34037 31613 34037 31620 34038 31613 34038 31500 34038 31613 34039 31614 34039 31519 34039 31519 34040 31615 34040 31613 34040 31613 34041 31615 34041 31507 34041 31613 34042 31507 34042 31500 34042 31616 34043 31617 34043 31469 34043 31469 34044 31617 34044 31622 34044 31469 34045 31622 34045 31618 34045 31619 34046 31610 34047 31621 34048 31621 34049 31610 34049 31620 34049 31621 34050 31620 34050 31489 34050 31489 34051 31490 34051 31621 34051 31621 34052 31490 34052 31623 34052 31621 34053 31623 34054 31622 34053 31622 34055 31623 34055 31491 34055 31622 34056 31491 34056 31618 34056 31624 34057 31625 34057 31626 34057 31626 34058 31625 34058 31627 34058 31626 34058 31627 34058 31628 34058 31628 34059 31627 34059 31629 34059 31628 34060 31629 34060 31630 34060 31630 34061 31629 34061 31632 34061 31630 34062 31632 34062 31631 34062 31631 34063 31632 34063 31633 34063 31631 34064 31633 34064 31635 34064 31635 34065 31633 34065 31634 34065 31635 34066 31634 34066 31636 34066 31636 34067 31634 34067 31637 34067 31636 34068 31637 34068 31639 34068 31639 34069 31637 34069 31638 34069 31639 34070 31638 34070 31640 34070 31640 34071 31638 34071 31641 34071 31640 34072 31641 34072 31642 34072 31642 34073 31641 34073 31643 34073 31642 34074 31643 34074 31645 34074 31645 34075 31643 34075 31644 34075 31645 34075 31644 34075 31646 34075 31646 34076 31644 34076 31647 34076 31646 34077 31647 34077 31649 34077 31649 34078 31647 34078 31648 34078 31649 34078 31648 34078 31651 34078 31651 34079 31648 34079 31650 34079 31651 34080 31650 34080 31652 34080 31652 34081 31650 34081 31653 34081 31652 34082 31653 34082 31654 34082 31654 34083 31653 34083 31655 34083 31654 34084 31655 34084 31656 34084 31656 34085 31655 34085 31658 34085 31656 34086 31658 34086 31657 34086 31657 34087 31658 34087 31659 34087 31657 34088 31659 34088 31660 34088 31660 34089 31659 34089 31661 34089 31660 34089 31661 34089 31662 34089 31662 34090 31661 34090 31663 34090 31662 34091 31663 34091 31664 34091 31664 34092 31663 34092 31665 34092 31664 34093 31665 34093 31667 34093 31667 34094 31665 34094 31666 34094 31667 34095 31666 34095 31668 34095 31668 34096 31666 34096 31670 34096 31668 34097 31670 34097 31669 34097 31669 34098 31670 34098 31671 34098 31669 34098 31671 34098 31673 34098 31673 34099 31671 34099 31672 34099 31673 34100 31672 34100 31675 34100 31675 34101 31672 34101 31674 34101 31675 34102 31674 34102 31677 34102 31677 34103 31674 34103 31676 34103 31677 34104 31676 34104 31624 34104 31624 34105 31676 34105 31625 34105 31678 34106 31680 34107 31679 34108 31679 34109 31680 34109 31681 34109 31679 34110 31681 34111 31682 34112 31681 34113 32203 34114 31682 34115 31682 34116 32203 34116 31683 34116 31682 34117 31683 34118 31684 34119 31684 34120 31683 34120 32190 34120 31684 34121 32190 34122 31685 34123 31686 34124 31687 34124 32345 34124 32345 34125 31687 34125 31693 34125 32345 34126 31693 34126 31688 34126 31689 34127 31690 34128 31691 34129 31691 34130 31690 34130 32097 34130 31691 34131 32097 34131 32092 34131 32092 34132 32093 34132 31691 34133 31691 34134 32093 34135 31692 34136 31691 34137 31692 34137 31693 34137 31693 34138 31692 34138 32096 34138 31693 34139 32096 34139 31688 34139 31694 34140 31771 34140 31954 34140 31954 34141 31695 34141 31694 34141 31694 34142 31695 34142 31696 34142 31694 34143 31696 34143 31697 34143 31696 34144 31698 34144 31697 34144 31697 34145 31698 34145 31699 34145 31697 34146 31699 34146 31700 34146 31699 34147 31959 34147 31700 34147 31700 34148 31959 34148 31701 34148 31700 34149 31701 34149 31702 34149 31701 34150 31961 34150 31702 34150 31702 34151 31961 34151 31703 34151 31702 34152 31703 34152 31704 34152 31703 34153 31964 34153 31704 34153 31704 34154 31964 34154 31966 34154 31704 34155 31966 34155 31705 34155 31966 34156 31968 34156 31705 34156 31705 34157 31968 34157 31969 34157 31705 34158 31969 34158 31707 34158 31969 34159 31706 34159 31707 34159 31707 34160 31706 34160 31972 34160 31707 34161 31972 34161 31708 34161 31972 34162 31973 34162 31708 34162 31708 34163 31973 34163 31974 34163 31708 34164 31974 34164 31710 34164 31974 34165 31709 34165 31710 34165 31710 34166 31709 34166 31712 34166 31710 34167 31712 34167 31711 34167 31712 34168 31979 34168 31711 34168 31711 34169 31979 34169 31980 34169 31711 34170 31980 34170 31713 34170 31980 34171 31981 34171 31713 34171 31713 34172 31981 34172 31982 34172 31713 34173 31982 34173 31715 34173 31982 34174 31714 34174 31715 34174 31715 34175 31714 34175 31716 34175 31715 34176 31716 34176 31718 34176 31716 34177 31717 34177 31718 34177 31718 34178 31717 34178 31719 34178 31718 34179 31719 34179 31720 34179 31719 34180 31984 34180 31720 34180 31720 34181 31984 34181 31985 34181 31720 34182 31985 34182 31722 34182 31985 34183 31721 34183 31722 34183 31722 34184 31721 34184 31986 34184 31722 34185 31986 34185 31723 34185 31986 34186 31724 34186 31723 34186 31723 34187 31724 34187 31725 34187 31723 34188 31725 34188 31726 34188 31725 34189 31987 34189 31726 34189 31726 34190 31987 34190 31727 34190 31726 34191 31727 34191 31729 34191 31727 34192 31728 34192 31729 34192 31729 34193 31728 34193 31989 34193 31729 34194 31989 34194 31730 34194 31989 34195 31990 34195 31730 34195 31730 34196 31990 34196 31992 34196 31730 34197 31992 34197 31732 34197 31992 34198 31731 34198 31732 34198 31732 34199 31731 34199 31733 34199 31732 34200 31733 34200 31735 34200 31733 34201 31734 34201 31735 34201 31735 34202 31734 34202 31737 34202 31735 34203 31737 34203 31736 34203 31737 34204 31994 34204 31736 34204 31736 34205 31994 34205 31996 34205 31736 34206 31996 34206 31738 34206 31996 34207 31739 34207 31738 34207 31738 34208 31739 34208 31998 34208 31738 34209 31998 34209 31741 34209 31998 34210 31740 34210 31741 34210 31741 34211 31740 34211 32000 34211 31741 34212 32000 34212 31742 34212 32000 34213 32002 34213 31742 34213 31742 34214 32002 34214 32003 34214 31742 34215 32003 34215 31744 34215 32003 34216 31743 34216 31744 34216 31744 34217 31743 34217 31746 34217 31744 34218 31746 34218 31745 34218 31746 34219 32006 34219 31745 34219 31745 34220 32006 34220 31747 34220 31745 34221 31747 34221 31748 34221 31747 34222 32008 34222 31748 34222 31748 34223 32008 34223 32010 34223 31748 34224 32010 34224 31749 34224 32010 34225 32011 34225 31749 34225 31749 34226 32011 34226 31750 34226 31749 34227 31750 34227 31752 34227 31750 34228 31751 34228 31752 34228 31752 34229 31751 34229 31753 34229 31752 34230 31753 34230 31754 34230 31753 34231 31755 34231 31754 34231 31754 34232 31755 34232 31756 34232 31754 34233 31756 34233 31757 34233 31756 34234 31758 34234 31757 34234 31757 34235 31758 34235 32015 34235 31757 34236 32015 34236 31760 34236 32015 34237 31759 34237 31760 34237 31760 34238 31759 34238 31762 34238 31760 34239 31762 34239 31761 34239 31762 34240 32017 34240 31761 34240 31761 34241 32017 34241 32019 34241 31761 34242 32019 34242 31763 34242 32019 34243 31764 34243 31763 34243 31763 34244 31764 34244 31765 34244 31763 34245 31765 34245 31767 34245 31765 34246 31766 34246 31767 34246 31767 34247 31766 34247 31768 34247 31767 34248 31768 34248 31769 34248 31768 34249 32023 34249 31769 34249 31769 34250 32023 34250 32025 34250 31769 34251 32025 34251 31771 34251 31771 34252 32025 34252 31770 34252 31771 34253 31770 34253 31954 34253 31882 34254 31773 34254 31772 34254 31882 34255 32151 34255 31773 34255 31773 34256 32151 34256 32149 34256 31773 34257 32149 34257 31774 34257 31774 34258 32149 34259 31776 34260 31774 34261 31776 34261 31775 34261 31776 34262 32148 34262 31775 34262 31775 34263 32148 34263 31777 34263 31775 34264 31777 34264 31778 34264 31777 34265 32035 34266 31778 34267 31778 34268 32035 34268 32158 34268 31778 34269 32158 34269 31779 34269 31779 34270 32158 34270 32157 34270 31779 34271 32157 34271 31886 34271 31886 34272 32157 34272 32156 34272 31886 34273 32156 34273 31887 34273 31887 34274 32156 34274 31780 34274 31780 34275 32176 34275 31887 34275 31887 34276 32176 34276 31781 34276 31887 34277 31781 34277 31888 34277 31888 34278 31781 34278 31782 34278 31888 34279 31782 34279 31889 34279 31889 34280 31782 34280 32182 34280 31889 34281 32182 34281 31783 34281 31783 34282 32182 34282 32183 34282 32183 34283 31784 34283 31783 34283 31783 34284 31784 34284 31785 34284 31783 34285 31785 34285 31891 34285 31891 34286 31785 34287 32032 34288 31891 34289 32032 34289 31786 34289 31786 34290 32032 34290 31787 34290 31786 34291 31787 34291 31892 34291 31892 34292 31787 34292 32196 34292 32196 34293 32195 34293 31892 34293 31892 34294 32195 34294 31789 34294 31892 34295 31789 34295 31788 34295 31788 34296 31789 34297 31791 34298 31788 34299 31791 34299 31790 34299 31790 34300 31791 34300 32205 34300 31790 34301 32205 34301 31792 34301 31792 34302 32205 34303 32204 34304 32204 34305 32210 34306 31792 34307 31792 34308 32210 34308 32209 34308 31792 34309 32209 34309 31894 34309 31894 34310 32209 34310 31793 34310 31894 34311 31793 34311 31794 34311 31794 34312 31793 34312 32214 34312 31794 34313 32214 34313 31895 34313 32214 34314 31795 34314 31895 34314 31895 34315 31795 34315 31796 34315 31895 34316 31796 34316 31898 34316 31796 34317 32219 34318 31898 34319 31898 34320 32219 34320 32218 34320 31898 34321 32218 34321 31899 34321 31899 34322 32218 34322 31797 34322 31899 34323 31797 34323 31901 34323 31797 34324 31798 34324 31901 34324 31901 34325 31798 34325 32031 34325 31901 34326 32031 34326 31801 34326 32031 34327 31799 34328 31801 34328 31801 34329 31799 34329 31800 34329 31801 34330 31800 34330 31903 34330 31903 34331 31800 34331 32226 34331 31903 34332 32226 34332 31905 34332 31905 34333 32226 34333 31803 34333 31905 34334 31803 34334 31802 34334 31802 34335 31803 34335 31804 34335 31804 34336 31805 34336 31802 34336 31802 34337 31805 34337 31806 34337 31802 34338 31806 34338 31909 34338 31909 34339 31806 34339 31807 34339 31909 34340 31807 34340 31808 34340 31808 34341 31807 34342 31809 34342 31808 34343 31809 34343 31810 34343 31810 34344 31809 34344 32249 34344 32249 34345 32248 34345 31810 34345 31810 34346 32248 34346 31811 34346 31810 34347 31811 34347 31913 34347 31913 34348 31811 34348 32030 34348 31913 34349 32030 34349 31812 34349 31812 34350 32030 34350 32029 34350 31812 34351 32029 34351 31815 34351 31815 34352 32029 34352 31813 34352 31813 34353 31814 34353 31815 34353 31815 34354 31814 34354 32264 34354 31815 34355 32264 34355 31916 34355 31916 34356 32264 34357 32265 34358 31916 34359 32265 34359 31917 34359 31917 34360 32265 34360 31816 34360 31917 34361 31816 34361 31817 34361 31817 34362 31816 34362 32268 34362 32268 34363 32274 34363 31817 34363 31817 34364 32274 34364 31818 34364 31817 34365 31818 34365 31819 34365 31819 34366 31818 34366 31820 34366 31819 34367 31820 34367 31821 34367 31821 34368 31820 34368 31822 34368 31821 34369 31822 34370 31824 34371 31822 34372 31823 34373 31824 34374 31824 34375 31823 34376 32283 34377 31824 34378 32283 34378 31825 34378 32283 34379 32028 34379 31825 34380 31825 34381 32028 34381 32286 34381 31825 34382 32286 34382 31826 34382 31826 34383 32286 34383 31827 34383 31826 34384 31827 34384 31923 34384 31827 34385 32291 34385 31923 34385 31923 34386 32291 34386 31828 34386 31923 34387 31828 34387 31926 34387 31828 34388 32298 34389 31926 34389 31926 34390 32298 34390 31829 34390 31926 34391 31829 34391 31927 34391 31927 34392 31829 34393 32296 34394 31927 34395 32296 34395 31830 34395 31830 34396 32296 34396 32295 34396 31830 34397 32295 34397 31832 34397 31832 34398 32295 34398 32308 34398 32308 34399 31831 34399 31832 34399 31832 34400 31831 34400 32309 34400 31832 34401 32309 34401 31929 34401 31929 34402 32309 34402 31834 34402 31929 34403 31834 34403 31833 34403 31833 34404 31834 34404 32027 34404 31833 34405 32027 34405 31835 34405 31835 34406 32027 34406 32318 34406 32318 34407 32317 34407 31835 34407 31835 34408 32317 34408 31836 34408 31835 34409 31836 34409 31837 34409 31837 34410 31836 34411 31838 34412 31837 34413 31838 34413 31839 34413 31839 34414 31838 34414 31840 34414 31839 34415 31840 34415 31842 34415 31842 34416 31840 34416 32333 34416 32333 34417 31841 34418 31842 34419 31842 34420 31841 34420 31843 34420 31842 34421 31843 34421 31932 34421 31932 34422 31843 34423 31844 34424 31932 34425 31844 34425 31934 34425 31934 34426 31844 34427 32026 34428 31934 34429 32026 34429 31935 34429 31935 34430 32026 34430 31845 34430 31845 34431 32344 34431 31935 34431 31935 34432 32344 34432 31846 34432 31935 34433 31846 34433 31847 34433 31847 34434 31846 34434 32040 34434 31847 34435 32040 34435 31848 34435 31848 34436 32040 34436 31849 34436 31848 34437 31849 34437 31938 34437 31849 34438 32080 34438 31938 34438 31938 34439 32080 34439 31850 34439 31938 34440 31850 34440 31851 34440 31850 34441 31852 34442 31851 34443 31851 34444 31852 34444 31853 34444 31851 34445 31853 34445 31855 34445 31855 34446 31853 34446 31854 34446 31855 34447 31854 34447 31856 34447 31854 34448 32086 34448 31856 34448 31856 34449 32086 34449 31857 34449 31856 34450 31857 34450 31859 34450 31857 34451 31858 34451 31859 34451 31859 34452 31858 34452 31860 34452 31859 34453 31860 34454 31861 34453 31861 34455 31860 34455 31863 34455 31861 34456 31863 34456 31862 34456 31862 34457 31863 34457 32087 34457 31862 34458 32087 34458 31864 34458 31864 34459 32087 34459 32104 34459 32104 34460 31865 34461 31864 34462 31864 34463 31865 34463 31866 34463 31864 34464 31866 34464 31867 34464 31867 34465 31866 34465 31868 34465 31867 34466 31868 34466 31944 34466 31944 34467 31868 34467 31869 34467 31944 34468 31869 34468 31946 34468 31946 34469 31869 34469 32113 34469 32113 34470 32112 34470 31946 34470 31946 34471 32112 34471 32114 34471 31946 34472 32114 34472 31947 34472 31947 34473 32114 34473 31871 34473 31947 34474 31871 34474 31870 34474 31870 34475 31871 34475 32126 34475 31870 34476 32126 34476 31949 34476 31949 34477 32126 34477 32125 34477 32125 34478 31872 34478 31949 34478 31949 34479 31872 34479 32127 34479 31949 34480 32127 34480 31874 34480 31874 34481 32127 34482 31873 34483 31874 34484 31873 34484 31875 34484 31875 34485 31873 34486 31876 34487 31875 34488 31876 34488 31951 34488 31951 34489 31876 34489 31877 34489 31877 34490 31878 34490 31951 34490 31951 34491 31878 34492 32137 34493 31951 34494 32137 34494 31952 34494 31952 34495 32137 34495 31880 34495 31952 34496 31880 34496 31879 34496 31879 34497 31880 34497 32142 34497 31879 34498 32142 34498 31772 34498 31772 34499 32142 34499 31881 34499 31772 34500 31881 34500 31882 34500 32024 34501 31952 34501 31883 34501 31883 34502 31952 34502 31879 34502 31883 34503 31879 34503 31953 34503 31953 34504 31879 34504 31772 34504 31953 34505 31772 34505 31955 34505 31955 34506 31772 34506 31773 34506 31955 34507 31773 34507 31956 34507 31956 34508 31773 34508 31774 34508 31956 34509 31774 34509 31957 34509 31957 34510 31774 34510 31775 34510 31957 34511 31775 34511 31958 34511 31958 34512 31775 34512 31778 34512 31958 34513 31778 34513 31960 34513 31960 34514 31778 34514 31779 34514 31960 34515 31779 34516 31884 34517 31884 34518 31779 34518 31886 34518 31884 34519 31886 34520 31885 34521 31885 34522 31886 34522 31887 34522 31885 34523 31887 34523 31962 34523 31962 34524 31887 34524 31888 34524 31962 34525 31888 34525 31963 34525 31963 34526 31888 34526 31889 34527 31963 34528 31889 34528 31890 34528 31890 34529 31889 34529 31783 34529 31890 34530 31783 34530 31965 34530 31965 34531 31783 34531 31891 34531 31965 34532 31891 34532 31967 34532 31967 34533 31891 34533 31786 34533 31967 34534 31786 34534 31970 34534 31970 34535 31786 34535 31892 34535 31970 34536 31892 34536 31971 34536 31971 34537 31892 34537 31788 34537 31971 34538 31788 34538 31893 34538 31893 34539 31788 34539 31790 34539 31893 34540 31790 34540 31975 34540 31975 34541 31790 34541 31792 34541 31975 34542 31792 34542 31976 34542 31976 34543 31792 34543 31894 34543 31976 34544 31894 34544 31977 34544 31977 34545 31894 34545 31794 34545 31977 34546 31794 34546 31978 34546 31978 34547 31794 34547 31895 34547 31978 34548 31895 34548 31896 34548 31896 34549 31895 34549 31898 34549 31896 34550 31898 34550 31897 34550 31897 34551 31898 34551 31899 34551 31897 34552 31899 34552 31900 34552 31900 34553 31899 34553 31901 34553 31900 34554 31901 34554 31902 34554 31902 34555 31901 34555 31801 34555 31902 34556 31801 34556 31983 34556 31983 34557 31801 34558 31903 34559 31983 34560 31903 34560 31904 34560 31904 34561 31903 34561 31905 34561 31904 34562 31905 34562 31906 34562 31906 34563 31905 34563 31802 34563 31906 34564 31802 34564 31907 34564 31907 34565 31802 34565 31909 34565 31907 34566 31909 34566 31908 34566 31908 34567 31909 34567 31808 34567 31908 34568 31808 34568 31910 34568 31910 34569 31808 34569 31810 34569 31910 34570 31810 34570 31911 34570 31911 34571 31810 34571 31913 34571 31911 34572 31913 34572 31912 34572 31912 34573 31913 34573 31812 34573 31912 34574 31812 34574 31914 34574 31914 34575 31812 34575 31815 34575 31914 34576 31815 34576 31915 34576 31915 34577 31815 34577 31916 34577 31915 34578 31916 34578 31988 34578 31988 34579 31916 34579 31917 34579 31988 34580 31917 34580 31918 34580 31918 34581 31917 34581 31817 34581 31918 34582 31817 34582 31919 34582 31919 34583 31817 34583 31819 34583 31919 34584 31819 34584 31920 34584 31920 34585 31819 34585 31821 34585 31920 34586 31821 34586 31991 34586 31991 34587 31821 34587 31824 34587 31991 34588 31824 34588 31993 34588 31993 34589 31824 34589 31825 34589 31993 34590 31825 34590 31921 34590 31921 34591 31825 34591 31826 34591 31921 34592 31826 34592 31922 34592 31922 34593 31826 34593 31923 34593 31922 34594 31923 34594 31924 34594 31924 34595 31923 34595 31926 34595 31924 34596 31926 34596 31925 34596 31925 34597 31926 34597 31927 34597 31925 34598 31927 34598 31928 34598 31928 34599 31927 34599 31830 34599 31928 34600 31830 34600 31995 34600 31995 34601 31830 34601 31832 34601 31995 34602 31832 34602 31997 34602 31997 34603 31832 34603 31929 34603 31997 34604 31929 34604 31930 34604 31930 34605 31929 34605 31833 34605 31930 34606 31833 34606 31999 34606 31999 34607 31833 34607 31835 34607 31999 34608 31835 34608 32001 34608 32001 34609 31835 34609 31837 34609 32001 34610 31837 34610 31931 34610 31931 34611 31837 34611 31839 34611 31931 34612 31839 34612 32004 34612 32004 34613 31839 34613 31842 34613 32004 34614 31842 34614 32005 34614 32005 34615 31842 34615 31932 34615 32005 34616 31932 34616 31933 34616 31933 34617 31932 34617 31934 34617 31933 34618 31934 34618 32007 34618 32007 34619 31934 34619 31935 34619 32007 34620 31935 34620 31936 34620 31936 34621 31935 34621 31847 34621 31936 34622 31847 34622 32009 34622 32009 34623 31847 34623 31848 34623 32009 34624 31848 34624 31937 34624 31937 34625 31848 34625 31938 34625 31937 34626 31938 34626 32012 34626 32012 34627 31938 34628 31851 34629 32012 34630 31851 34630 31939 34630 31939 34631 31851 34631 31855 34631 31939 34632 31855 34632 31940 34632 31940 34633 31855 34633 31856 34633 31940 34634 31856 34634 32013 34634 32013 34635 31856 34635 31859 34635 32013 34636 31859 34636 31941 34636 31941 34637 31859 34637 31861 34637 31941 34638 31861 34638 31942 34638 31942 34639 31861 34639 31862 34639 31942 34640 31862 34640 32014 34640 32014 34641 31862 34641 31864 34641 32014 34642 31864 34642 31943 34642 31943 34643 31864 34643 31867 34643 31943 34644 31867 34644 32016 34644 32016 34645 31867 34645 31944 34645 32016 34646 31944 34646 31945 34646 31945 34647 31944 34647 31946 34647 31945 34648 31946 34648 32018 34648 32018 34649 31946 34649 31947 34649 32018 34650 31947 34650 31948 34650 31948 34651 31947 34651 31870 34651 31948 34652 31870 34652 32020 34652 32020 34653 31870 34653 31949 34653 32020 34654 31949 34654 32021 34654 32021 34655 31949 34655 31874 34655 32021 34656 31874 34656 32022 34656 32022 34657 31874 34657 31875 34657 32022 34658 31875 34658 31950 34658 31950 34659 31875 34659 31951 34659 31950 34660 31951 34660 32024 34660 32024 34661 31951 34661 31952 34661 32025 34662 31883 34662 31770 34662 31770 34663 31883 34664 31953 34665 31770 34666 31953 34666 31954 34666 31954 34667 31953 34667 31955 34667 31954 34668 31955 34668 31695 34668 31695 34669 31955 34669 31956 34669 31695 34670 31956 34670 31696 34670 31696 34671 31956 34671 31957 34671 31696 34672 31957 34672 31698 34672 31698 34673 31957 34673 31958 34673 31698 34674 31958 34674 31699 34674 31699 34675 31958 34675 31960 34675 31699 34676 31960 34676 31959 34676 31959 34677 31960 34677 31884 34677 31959 34678 31884 34678 31701 34678 31701 34679 31884 34679 31885 34679 31701 34680 31885 34680 31961 34680 31961 34681 31885 34681 31962 34681 31961 34682 31962 34682 31703 34682 31703 34683 31962 34683 31963 34683 31703 34684 31963 34685 31964 34686 31964 34687 31963 34687 31890 34687 31964 34688 31890 34688 31966 34688 31966 34689 31890 34689 31965 34689 31966 34690 31965 34690 31968 34690 31968 34691 31965 34691 31967 34691 31968 34692 31967 34693 31969 34694 31969 34695 31967 34695 31970 34695 31969 34696 31970 34696 31706 34696 31706 34697 31970 34698 31971 34699 31706 34700 31971 34700 31972 34700 31972 34701 31971 34702 31893 34703 31972 34704 31893 34704 31973 34704 31973 34705 31893 34705 31975 34705 31973 34706 31975 34706 31974 34706 31974 34707 31975 34707 31976 34707 31974 34708 31976 34708 31709 34708 31709 34709 31976 34709 31977 34709 31709 34710 31977 34710 31712 34710 31712 34711 31977 34711 31978 34711 31712 34712 31978 34712 31979 34712 31979 34713 31978 34714 31896 34715 31979 34716 31896 34716 31980 34716 31980 34717 31896 34717 31897 34717 31980 34718 31897 34718 31981 34718 31981 34719 31897 34719 31900 34719 31981 34720 31900 34720 31982 34720 31982 34721 31900 34721 31902 34721 31982 34722 31902 34722 31714 34722 31714 34723 31902 34723 31983 34723 31714 34724 31983 34724 31716 34724 31716 34725 31983 34725 31904 34725 31716 34726 31904 34726 31717 34726 31717 34727 31904 34727 31906 34727 31717 34728 31906 34728 31719 34728 31719 34729 31906 34730 31907 34731 31719 34732 31907 34732 31984 34732 31984 34733 31907 34733 31908 34733 31984 34734 31908 34734 31985 34734 31985 34735 31908 34735 31910 34735 31985 34736 31910 34736 31721 34736 31721 34737 31910 34738 31911 34739 31721 34740 31911 34740 31986 34740 31986 34741 31911 34741 31912 34741 31986 34742 31912 34742 31724 34742 31724 34743 31912 34743 31914 34743 31724 34744 31914 34744 31725 34744 31725 34745 31914 34745 31915 34745 31725 34746 31915 34746 31987 34746 31987 34747 31915 34747 31988 34747 31987 34748 31988 34749 31727 34750 31727 34751 31988 34751 31918 34751 31727 34752 31918 34752 31728 34752 31728 34753 31918 34754 31919 34755 31728 34756 31919 34756 31989 34756 31989 34757 31919 34757 31920 34757 31989 34758 31920 34758 31990 34758 31990 34759 31920 34759 31991 34759 31990 34760 31991 34760 31992 34760 31992 34761 31991 34761 31993 34761 31992 34762 31993 34762 31731 34762 31731 34763 31993 34763 31921 34763 31731 34764 31921 34764 31733 34764 31733 34765 31921 34765 31922 34765 31733 34766 31922 34766 31734 34766 31734 34767 31922 34767 31924 34767 31734 34768 31924 34768 31737 34768 31737 34769 31924 34769 31925 34769 31737 34770 31925 34770 31994 34770 31994 34771 31925 34771 31928 34771 31994 34772 31928 34772 31996 34772 31996 34773 31928 34773 31995 34773 31996 34774 31995 34774 31739 34774 31739 34775 31995 34775 31997 34775 31739 34776 31997 34776 31998 34776 31998 34777 31997 34777 31930 34777 31998 34778 31930 34778 31740 34778 31740 34779 31930 34779 31999 34779 31740 34780 31999 34780 32000 34780 32000 34781 31999 34781 32001 34781 32000 34782 32001 34782 32002 34782 32002 34783 32001 34783 31931 34783 32002 34784 31931 34785 32003 34786 32003 34787 31931 34787 32004 34787 32003 34788 32004 34788 31743 34788 31743 34789 32004 34789 32005 34789 31743 34790 32005 34790 31746 34790 31746 34791 32005 34791 31933 34791 31746 34792 31933 34792 32006 34792 32006 34793 31933 34793 32007 34793 32006 34794 32007 34794 31747 34794 31747 34795 32007 34795 31936 34795 31747 34796 31936 34796 32008 34796 32008 34797 31936 34797 32009 34797 32008 34798 32009 34798 32010 34798 32010 34799 32009 34799 31937 34799 32010 34800 31937 34800 32011 34800 32011 34801 31937 34801 32012 34801 32011 34802 32012 34802 31750 34802 31750 34803 32012 34803 31939 34803 31750 34804 31939 34804 31751 34804 31751 34805 31939 34805 31940 34805 31751 34806 31940 34806 31753 34806 31753 34807 31940 34807 32013 34807 31753 34808 32013 34808 31755 34808 31755 34809 32013 34809 31941 34809 31755 34810 31941 34810 31756 34810 31756 34811 31941 34811 31942 34811 31756 34812 31942 34812 31758 34812 31758 34813 31942 34813 32014 34813 31758 34814 32014 34814 32015 34814 32015 34815 32014 34815 31943 34815 32015 34816 31943 34816 31759 34816 31759 34817 31943 34817 32016 34817 31759 34818 32016 34818 31762 34818 31762 34819 32016 34819 31945 34819 31762 34820 31945 34821 32017 34822 32017 34823 31945 34823 32018 34823 32017 34824 32018 34824 32019 34824 32019 34825 32018 34825 31948 34825 32019 34826 31948 34826 31764 34826 31764 34827 31948 34827 32020 34827 31764 34828 32020 34828 31765 34828 31765 34829 32020 34829 32021 34829 31765 34830 32021 34830 31766 34830 31766 34831 32021 34832 32022 34833 31766 34834 32022 34834 31768 34834 31768 34835 32022 34835 31950 34835 31768 34836 31950 34836 32023 34836 32023 34837 31950 34837 32024 34837 32023 34838 32024 34838 32025 34838 32025 34839 32024 34839 31883 34839 32344 34840 31845 34840 32340 34840 32026 34841 31844 34841 32342 34841 31840 34842 31838 34842 32332 34842 32027 34843 31834 34843 32316 34843 32298 34844 31828 34844 32299 34844 32028 34845 32283 34846 32284 34847 31823 34848 31822 34848 32281 34848 31820 34849 31818 34849 32275 34849 32274 34850 32268 34850 32269 34850 31816 34851 32265 34851 32266 34851 32029 34852 32030 34852 32261 34852 31809 34853 31807 34853 32247 34853 31799 34854 32031 34855 32221 34856 32219 34857 31796 34858 32217 34859 31795 34860 32214 34860 32215 34860 31793 34861 32209 34861 32211 34861 32210 34862 32204 34862 32206 34862 32205 34863 31791 34863 32197 34863 31787 34864 32032 34864 32033 34864 32176 34865 31780 34865 32034 34865 32035 34866 31777 34866 32036 34866 32151 34867 31882 34868 32144 34869 31881 34870 32142 34870 32145 34870 31880 34871 32137 34871 32143 34871 31878 34872 31877 34872 32132 34872 31876 34873 31873 34873 32037 34873 32126 34874 31871 34874 32038 34874 31869 34875 31868 34875 32039 34875 31858 34876 31857 34876 32088 34876 31852 34877 31850 34878 32079 34879 32080 34880 31849 34880 32075 34880 32040 34881 31846 34881 32077 34881 32190 34882 31683 34882 32191 34882 32066 34883 32314 34883 32313 34883 32097 34884 32041 34884 32098 34884 32042 34885 32243 34885 32241 34885 32242 34886 32043 34886 32244 34886 32228 34887 32042 34887 32233 34887 32046 34888 32044 34889 32045 34890 32045 34891 32044 34892 32208 34893 32045 34894 32208 34894 32048 34894 32046 34895 32045 34895 32047 34895 32047 34896 32045 34896 32048 34896 32047 34897 32048 34897 32049 34897 31681 34898 31680 34898 32202 34898 32202 34899 31680 34900 31678 34901 32179 34902 32180 34902 32178 34902 32162 34903 32173 34903 32161 34903 32050 34904 32141 34905 32051 34906 32051 34907 32141 34907 32133 34907 32051 34908 32133 34908 32052 34908 32050 34909 32051 34909 32053 34909 32053 34910 32051 34910 32052 34910 32053 34911 32052 34911 32135 34911 32131 34912 32055 34912 32054 34912 32054 34913 32055 34914 32136 34915 32107 34916 32056 34916 32108 34916 32092 34917 32097 34917 32090 34917 32057 34918 32346 34918 32058 34918 32058 34919 32346 34919 32059 34919 32058 34920 32059 34920 32061 34920 32057 34921 32058 34921 32060 34921 32060 34922 32058 34922 32061 34922 32060 34923 32061 34923 32343 34923 32338 34924 32062 34924 32337 34924 32337 34925 32062 34926 32063 34927 32064 34928 32065 34928 32315 34928 32301 34929 32066 34929 32067 34929 32069 34930 32280 34930 32071 34930 32071 34931 32280 34931 32068 34931 32071 34932 32068 34932 32072 34932 32069 34933 32071 34933 32070 34933 32070 34934 32071 34934 32072 34934 32070 34935 32072 34935 32272 34935 32267 34936 32073 34936 32273 34936 32273 34937 32073 34938 32074 34939 31849 34940 32040 34940 32075 34940 32075 34941 32040 34941 32077 34941 32075 34942 32077 34942 32076 34942 32076 34943 32077 34943 32078 34943 32076 34944 32078 34944 32081 34944 32081 34945 32078 34945 32095 34945 31850 34946 32080 34946 32079 34946 32079 34947 32080 34947 32075 34947 32079 34948 32075 34948 32084 34948 32084 34949 32075 34949 32076 34949 32084 34950 32076 34950 32085 34950 32085 34951 32076 34951 32081 34951 32086 34952 31854 34952 32082 34952 32082 34953 31854 34953 31853 34953 31853 34954 31852 34954 32082 34954 32082 34955 31852 34955 32079 34955 32082 34956 32079 34956 32083 34956 32083 34957 32079 34957 32084 34957 32083 34958 32084 34958 32094 34958 32094 34959 32084 34959 32085 34959 31857 34960 32086 34960 32088 34960 32088 34961 32086 34961 32082 34961 32088 34962 32082 34962 32089 34962 32089 34963 32082 34963 32083 34963 32089 34964 32083 34964 32091 34964 32091 34965 32083 34965 32094 34965 32087 34966 31863 34966 32101 34966 32101 34967 31863 34967 31860 34967 31860 34968 31858 34968 32101 34968 32101 34969 31858 34969 32088 34969 32101 34970 32088 34970 32099 34970 32099 34971 32088 34971 32089 34971 32099 34972 32089 34972 32090 34972 32090 34973 32089 34973 32091 34973 32090 34974 32091 34974 32092 34974 32092 34975 32091 34975 32094 34975 32092 34976 32094 34976 32093 34976 32093 34977 32094 34977 32085 34977 32093 34978 32085 34978 31692 34978 31692 34979 32085 34979 32081 34979 31692 34980 32081 34980 32096 34980 32096 34981 32081 34981 32095 34981 32096 34982 32095 34982 31688 34982 31688 34983 32095 34983 32345 34983 32097 34984 32098 34984 32090 34984 32090 34985 32098 34985 32100 34985 32090 34986 32100 34986 32099 34986 32099 34987 32100 34987 32102 34987 32099 34988 32102 34988 32101 34988 32101 34989 32102 34989 32103 34989 32101 34990 32103 34990 32087 34990 31866 34991 31865 34991 32103 34991 32103 34992 31865 34992 32104 34992 32103 34993 32104 34993 32087 34993 31868 34994 31866 34994 32039 34994 32039 34995 31866 34995 32103 34995 32039 34996 32103 34996 32105 34996 32105 34997 32103 34997 32102 34997 32105 34998 32102 34998 32106 34998 32106 34999 32102 34999 32100 34999 32106 35000 32100 35000 32108 35000 32108 35001 32100 35001 32098 35001 32108 35002 32098 35002 32107 35002 32107 35003 32098 35004 32041 35005 32056 35006 32118 35006 32108 35006 32108 35007 32118 35007 32117 35007 32108 35008 32117 35008 32106 35008 32106 35009 32117 35009 32109 35009 32106 35010 32109 35010 32105 35010 32105 35011 32109 35011 32110 35011 32105 35012 32110 35012 32039 35012 32039 35013 32110 35013 32111 35013 32039 35014 32111 35014 31869 35014 32114 35015 32112 35015 32111 35015 32111 35016 32112 35016 32113 35016 32111 35017 32113 35017 31869 35017 31871 35018 32114 35018 32038 35018 32038 35019 32114 35019 32111 35019 32038 35020 32111 35020 32115 35020 32115 35021 32111 35021 32110 35021 32115 35022 32110 35022 32123 35022 32123 35023 32110 35023 32109 35023 32123 35024 32109 35024 32120 35024 32120 35025 32109 35025 32117 35025 32120 35026 32117 35026 32116 35026 32116 35027 32117 35027 32118 35027 32116 35028 32118 35028 32119 35028 32116 35029 32121 35029 32120 35029 32120 35030 32121 35030 32122 35030 32120 35031 32122 35031 32123 35031 32123 35032 32122 35032 32130 35032 32123 35033 32130 35033 32115 35033 32115 35034 32130 35034 32124 35034 32115 35035 32124 35035 32038 35035 32038 35036 32124 35036 32128 35036 32038 35037 32128 35037 32126 35037 32127 35038 31872 35038 32128 35038 32128 35039 31872 35039 32125 35039 32128 35040 32125 35040 32126 35040 31873 35041 32127 35042 32037 35043 32037 35044 32127 35044 32128 35044 32037 35045 32128 35045 32129 35045 32129 35046 32128 35046 32124 35046 32129 35047 32124 35047 32134 35047 32134 35048 32124 35048 32130 35048 32134 35049 32130 35049 32054 35049 32054 35050 32130 35050 32122 35050 32054 35051 32122 35051 32131 35051 32131 35052 32122 35052 32121 35052 31877 35053 31876 35053 32132 35053 32132 35054 31876 35054 32037 35054 32132 35055 32037 35055 32139 35055 32139 35056 32037 35056 32129 35056 32139 35057 32129 35057 32133 35057 32133 35058 32129 35058 32134 35058 32133 35059 32134 35059 32052 35059 32052 35060 32134 35060 32054 35060 32052 35061 32054 35061 32135 35061 32135 35062 32054 35062 32136 35062 32137 35063 31878 35063 32143 35063 32143 35064 31878 35064 32132 35064 32143 35065 32132 35065 32138 35065 32138 35066 32132 35066 32139 35066 32138 35067 32139 35067 32166 35067 32166 35068 32139 35068 32133 35068 32166 35069 32133 35069 32140 35069 32140 35070 32133 35070 32141 35070 32142 35071 31880 35071 32145 35071 32145 35072 31880 35072 32143 35072 32145 35073 32143 35073 32146 35073 32146 35074 32143 35074 32138 35074 32146 35075 32138 35075 32147 35075 32147 35076 32138 35076 32166 35076 31882 35077 31881 35077 32144 35077 32144 35078 31881 35078 32145 35078 32144 35079 32145 35079 32154 35079 32154 35080 32145 35080 32146 35080 32154 35081 32146 35081 32163 35081 32163 35082 32146 35082 32147 35082 32148 35083 31776 35084 32150 35083 32150 35085 31776 35085 32149 35085 32149 35086 32151 35086 32150 35086 32150 35087 32151 35087 32144 35087 32150 35088 32144 35088 32152 35088 32152 35089 32144 35089 32154 35089 32152 35090 32154 35090 32153 35090 32153 35091 32154 35091 32163 35091 31777 35092 32148 35092 32036 35092 32036 35093 32148 35093 32150 35093 32036 35094 32150 35094 32160 35094 32160 35095 32150 35095 32152 35095 32160 35096 32152 35096 32155 35096 32155 35097 32152 35097 32153 35097 32156 35098 32157 35098 32169 35098 32169 35099 32157 35100 32158 35101 32158 35102 32035 35102 32169 35102 32169 35103 32035 35103 32036 35103 32169 35104 32036 35104 32159 35104 32159 35105 32036 35105 32160 35105 32159 35106 32160 35106 32161 35106 32161 35107 32160 35107 32155 35107 32161 35108 32155 35108 32162 35108 32162 35109 32155 35109 32153 35109 32162 35110 32153 35110 32164 35110 32164 35111 32153 35111 32163 35111 32164 35112 32163 35112 32165 35112 32165 35113 32163 35113 32147 35113 32165 35114 32147 35114 32167 35114 32167 35115 32147 35115 32166 35115 32167 35116 32166 35116 32168 35116 32168 35117 32166 35117 32140 35117 31780 35118 32156 35118 32034 35118 32034 35119 32156 35119 32169 35119 32034 35120 32169 35120 32170 35120 32170 35121 32169 35121 32159 35121 32170 35122 32159 35122 32171 35122 32171 35123 32159 35123 32161 35123 32171 35124 32161 35124 32172 35124 32172 35125 32161 35125 32173 35125 32172 35126 32173 35127 32174 35128 32182 35129 31782 35129 32175 35129 32175 35130 31782 35130 31781 35130 31781 35131 32176 35131 32175 35131 32175 35132 32176 35132 32034 35132 32175 35133 32034 35133 32181 35133 32181 35134 32034 35134 32170 35134 32181 35135 32170 35135 32177 35135 32177 35136 32170 35136 32171 35136 32177 35137 32171 35137 32178 35137 32178 35138 32171 35138 32172 35138 32178 35139 32172 35139 32179 35139 32179 35140 32172 35140 32174 35140 32180 35141 32189 35141 32178 35141 32178 35142 32189 35142 32188 35142 32178 35143 32188 35143 32177 35143 32177 35144 32188 35144 32187 35144 32177 35145 32187 35145 32181 35145 32181 35146 32187 35146 32186 35146 32181 35147 32186 35147 32175 35147 32175 35148 32186 35148 32184 35148 32175 35149 32184 35149 32182 35149 31785 35150 31784 35150 32184 35150 32184 35151 31784 35151 32183 35151 32184 35152 32183 35152 32182 35152 32032 35153 31785 35153 32033 35153 32033 35154 31785 35154 32184 35154 32033 35155 32184 35155 32185 35155 32185 35156 32184 35156 32186 35156 32185 35157 32186 35157 32193 35157 32193 35158 32186 35158 32187 35158 32193 35159 32187 35159 32191 35159 32191 35160 32187 35160 32188 35160 32191 35161 32188 35161 32190 35161 32190 35162 32188 35162 32189 35162 32190 35163 32189 35164 31685 35165 31683 35166 32203 35166 32191 35166 32191 35167 32203 35167 32192 35167 32191 35168 32192 35168 32193 35168 32193 35169 32192 35169 32201 35169 32193 35170 32201 35170 32185 35170 32185 35171 32201 35171 32198 35171 32185 35172 32198 35172 32033 35172 32033 35173 32198 35173 32194 35173 32033 35174 32194 35174 31787 35174 31789 35175 32195 35175 32194 35175 32194 35176 32195 35176 32196 35176 32194 35177 32196 35177 31787 35177 31791 35178 31789 35179 32197 35180 32197 35181 31789 35181 32194 35181 32197 35182 32194 35182 32199 35182 32199 35183 32194 35183 32198 35183 32199 35184 32198 35184 32200 35184 32200 35185 32198 35185 32201 35185 32200 35186 32201 35186 32202 35186 32202 35187 32201 35187 32192 35187 32202 35188 32192 35188 31681 35188 31681 35189 32192 35189 32203 35189 32204 35190 32205 35191 32206 35192 32206 35193 32205 35193 32197 35193 32206 35194 32197 35194 32207 35194 32207 35195 32197 35195 32199 35195 32207 35196 32199 35196 32208 35196 32208 35197 32199 35197 32200 35197 32208 35198 32200 35198 32048 35198 32048 35199 32200 35199 32202 35199 32048 35200 32202 35200 32049 35200 32049 35201 32202 35201 31678 35201 32209 35202 32210 35202 32211 35202 32211 35203 32210 35203 32206 35203 32211 35204 32206 35204 32212 35204 32212 35205 32206 35205 32207 35205 32212 35206 32207 35206 32232 35206 32232 35207 32207 35207 32208 35207 32232 35208 32208 35208 32213 35208 32213 35209 32208 35209 32044 35209 32214 35210 31793 35210 32215 35210 32215 35211 31793 35211 32211 35211 32215 35212 32211 35212 32216 35212 32216 35213 32211 35213 32212 35213 32216 35214 32212 35214 32231 35214 32231 35215 32212 35215 32232 35215 31796 35216 31795 35216 32217 35216 32217 35217 31795 35217 32215 35217 32217 35218 32215 35218 32220 35218 32220 35219 32215 35219 32216 35219 32220 35220 32216 35220 32230 35220 32230 35221 32216 35221 32231 35221 31798 35222 31797 35222 32222 35222 32222 35223 31797 35223 32218 35223 32218 35224 32219 35224 32222 35224 32222 35225 32219 35225 32217 35225 32222 35226 32217 35226 32223 35226 32223 35227 32217 35227 32220 35227 32223 35228 32220 35228 32225 35228 32225 35229 32220 35229 32230 35229 32031 35230 31798 35230 32221 35230 32221 35231 31798 35231 32222 35231 32221 35232 32222 35232 32227 35232 32227 35233 32222 35233 32223 35233 32227 35234 32223 35234 32224 35234 32224 35235 32223 35235 32225 35235 31803 35236 32226 35236 32236 35236 32236 35237 32226 35237 31800 35237 31800 35238 31799 35238 32236 35238 32236 35239 31799 35239 32221 35239 32236 35240 32221 35240 32235 35240 32235 35241 32221 35241 32227 35241 32235 35242 32227 35242 32233 35242 32233 35243 32227 35243 32224 35243 32233 35244 32224 35244 32228 35244 32228 35245 32224 35245 32225 35245 32228 35246 32225 35246 32229 35246 32229 35247 32225 35247 32230 35247 32229 35248 32230 35248 32353 35248 32353 35249 32230 35249 32231 35249 32353 35250 32231 35250 32355 35250 32355 35251 32231 35251 32232 35251 32355 35252 32232 35252 32349 35252 32349 35253 32232 35253 32213 35253 32042 35254 32241 35254 32233 35254 32233 35255 32241 35255 32234 35255 32233 35256 32234 35256 32235 35256 32235 35257 32234 35257 32238 35257 32235 35258 32238 35258 32236 35258 32236 35259 32238 35259 32237 35259 32236 35260 32237 35260 31803 35260 31806 35261 31805 35261 32237 35261 32237 35262 31805 35262 31804 35262 32237 35263 31804 35263 31803 35263 31807 35264 31806 35264 32247 35264 32247 35265 31806 35265 32237 35265 32247 35266 32237 35266 32239 35266 32239 35267 32237 35267 32238 35267 32239 35268 32238 35268 32240 35268 32240 35269 32238 35269 32234 35269 32240 35270 32234 35270 32244 35270 32244 35271 32234 35271 32241 35271 32244 35272 32241 35272 32242 35272 32242 35273 32241 35273 32243 35273 32043 35274 32254 35274 32244 35274 32244 35275 32254 35275 32245 35275 32244 35276 32245 35276 32240 35276 32240 35277 32245 35277 32246 35277 32240 35278 32246 35278 32239 35278 32239 35279 32246 35279 32253 35279 32239 35280 32253 35280 32247 35280 32247 35281 32253 35281 32251 35281 32247 35282 32251 35282 31809 35282 31811 35283 32248 35283 32251 35283 32251 35284 32248 35284 32249 35284 32251 35285 32249 35285 31809 35285 32030 35286 31811 35287 32261 35288 32261 35289 31811 35289 32251 35289 32261 35290 32251 35290 32250 35290 32250 35291 32251 35291 32253 35291 32250 35292 32253 35292 32252 35292 32252 35293 32253 35293 32246 35293 32252 35294 32246 35294 32258 35294 32258 35295 32246 35295 32245 35295 32258 35296 32245 35296 32256 35296 32256 35297 32245 35297 32254 35297 32256 35298 32254 35298 32255 35298 32256 35299 32257 35299 32258 35299 32258 35300 32257 35300 32259 35300 32258 35301 32259 35301 32252 35301 32252 35302 32259 35302 32260 35302 32252 35303 32260 35303 32250 35303 32250 35304 32260 35304 32262 35304 32250 35305 32262 35305 32261 35305 32261 35306 32262 35306 32263 35306 32261 35307 32263 35307 32029 35307 32264 35308 31814 35308 32263 35308 32263 35309 31814 35310 31813 35311 32263 35312 31813 35312 32029 35312 32265 35313 32264 35314 32266 35315 32266 35316 32264 35316 32263 35316 32266 35317 32263 35317 32270 35317 32270 35318 32263 35318 32262 35318 32270 35319 32262 35319 32271 35319 32271 35320 32262 35320 32260 35320 32271 35321 32260 35321 32273 35321 32273 35322 32260 35322 32259 35322 32273 35323 32259 35323 32267 35323 32267 35324 32259 35324 32257 35324 32268 35325 31816 35325 32269 35325 32269 35326 31816 35326 32266 35326 32269 35327 32266 35327 32277 35327 32277 35328 32266 35328 32270 35328 32277 35329 32270 35329 32068 35329 32068 35330 32270 35330 32271 35330 32068 35331 32271 35331 32072 35331 32072 35332 32271 35332 32273 35332 32072 35333 32273 35333 32272 35333 32272 35334 32273 35334 32074 35334 31818 35335 32274 35335 32275 35335 32275 35336 32274 35336 32269 35336 32275 35337 32269 35337 32276 35337 32276 35338 32269 35338 32277 35338 32276 35339 32277 35339 32278 35339 32278 35340 32277 35340 32068 35340 32278 35341 32068 35341 32279 35341 32279 35342 32068 35342 32280 35342 31822 35343 31820 35343 32281 35343 32281 35344 31820 35344 32275 35344 32281 35345 32275 35345 32285 35345 32285 35346 32275 35346 32276 35346 32285 35347 32276 35347 32282 35347 32282 35348 32276 35348 32278 35348 32283 35349 31823 35349 32284 35349 32284 35350 31823 35350 32281 35350 32284 35351 32281 35351 32288 35351 32288 35352 32281 35352 32285 35352 32288 35353 32285 35353 32290 35353 32290 35354 32285 35354 32282 35354 32291 35355 31827 35355 32287 35355 32287 35356 31827 35356 32286 35356 32286 35357 32028 35357 32287 35357 32287 35358 32028 35358 32284 35358 32287 35359 32284 35359 32293 35359 32293 35360 32284 35360 32288 35360 32293 35361 32288 35361 32289 35361 32289 35362 32288 35362 32290 35362 31828 35363 32291 35363 32299 35363 32299 35364 32291 35364 32287 35364 32299 35365 32287 35365 32292 35365 32292 35366 32287 35366 32293 35366 32292 35367 32293 35367 32294 35367 32294 35368 32293 35368 32289 35368 32295 35369 32296 35370 32297 35371 32297 35372 32296 35372 31829 35372 31829 35373 32298 35373 32297 35373 32297 35374 32298 35374 32299 35374 32297 35375 32299 35375 32300 35375 32300 35376 32299 35376 32292 35376 32300 35377 32292 35377 32067 35377 32067 35378 32292 35378 32294 35378 32067 35379 32294 35379 32301 35379 32301 35380 32294 35380 32289 35380 32301 35381 32289 35381 32302 35381 32302 35382 32289 35382 32290 35382 32302 35383 32290 35383 32303 35383 32303 35384 32290 35384 32282 35384 32303 35385 32282 35385 32304 35385 32304 35386 32282 35386 32278 35386 32304 35387 32278 35387 32305 35387 32305 35388 32278 35388 32279 35388 32066 35389 32313 35389 32067 35389 32067 35390 32313 35390 32312 35390 32067 35391 32312 35391 32300 35391 32300 35392 32312 35392 32306 35392 32300 35393 32306 35393 32297 35393 32297 35394 32306 35394 32307 35394 32297 35395 32307 35395 32295 35395 32309 35396 31831 35396 32307 35396 32307 35397 31831 35398 32308 35399 32307 35400 32308 35400 32295 35400 31834 35401 32309 35401 32316 35401 32316 35402 32309 35402 32307 35402 32316 35403 32307 35403 32310 35403 32310 35404 32307 35404 32306 35404 32310 35405 32306 35405 32311 35405 32311 35406 32306 35406 32312 35406 32311 35407 32312 35407 32315 35407 32315 35408 32312 35408 32313 35408 32315 35409 32313 35409 32064 35409 32064 35410 32313 35410 32314 35410 32065 35411 32326 35411 32315 35411 32315 35412 32326 35412 32325 35412 32315 35413 32325 35413 32311 35413 32311 35414 32325 35414 32323 35414 32311 35415 32323 35415 32310 35415 32310 35416 32323 35416 32322 35416 32310 35417 32322 35417 32316 35417 32316 35418 32322 35418 32319 35418 32316 35419 32319 35419 32027 35419 31836 35420 32317 35420 32319 35420 32319 35421 32317 35421 32318 35421 32319 35422 32318 35422 32027 35422 31838 35423 31836 35424 32332 35425 32332 35426 31836 35426 32319 35426 32332 35427 32319 35427 32320 35427 32320 35428 32319 35428 32322 35428 32320 35429 32322 35429 32321 35429 32321 35430 32322 35430 32323 35430 32321 35431 32323 35431 32324 35431 32324 35432 32323 35432 32325 35432 32324 35433 32325 35433 32328 35433 32328 35434 32325 35434 32326 35434 32328 35435 32326 35436 32327 35437 32328 35438 32339 35438 32324 35438 32324 35439 32339 35439 32329 35439 32324 35440 32329 35440 32321 35440 32321 35441 32329 35441 32330 35441 32321 35442 32330 35442 32320 35442 32320 35443 32330 35443 32331 35443 32320 35444 32331 35444 32332 35444 32332 35445 32331 35445 32334 35445 32332 35446 32334 35446 31840 35446 31843 35447 31841 35447 32334 35447 32334 35448 31841 35448 32333 35448 32334 35449 32333 35449 31840 35449 31844 35450 31843 35450 32342 35451 32342 35452 31843 35452 32334 35452 32342 35453 32334 35453 32335 35453 32335 35454 32334 35454 32331 35454 32335 35455 32331 35455 32336 35455 32336 35456 32331 35456 32330 35456 32336 35457 32330 35457 32337 35457 32337 35458 32330 35458 32329 35458 32337 35459 32329 35459 32338 35459 32338 35460 32329 35460 32339 35460 31845 35461 32026 35461 32340 35461 32340 35462 32026 35462 32342 35462 32340 35463 32342 35463 32341 35463 32341 35464 32342 35464 32335 35464 32341 35465 32335 35465 32059 35465 32059 35466 32335 35466 32336 35466 32059 35467 32336 35467 32061 35467 32061 35468 32336 35468 32337 35468 32061 35469 32337 35469 32343 35469 32343 35470 32337 35470 32063 35470 31846 35471 32344 35471 32077 35471 32077 35472 32344 35472 32340 35472 32077 35473 32340 35473 32078 35473 32078 35474 32340 35474 32341 35474 32078 35475 32341 35475 32095 35475 32095 35476 32341 35476 32059 35476 32095 35477 32059 35477 32345 35477 32345 35478 32059 35478 32346 35478 32347 35479 32348 35479 32213 35479 32213 35480 32348 35480 32354 35480 32213 35481 32354 35482 32349 35483 32350 35484 32351 35484 32352 35484 32352 35485 32351 35485 32042 35485 32352 35486 32042 35486 32228 35486 32228 35487 32229 35487 32352 35487 32352 35488 32229 35488 32353 35488 32352 35489 32353 35489 32354 35489 32354 35490 32353 35490 32355 35490 32354 35491 32355 35491 32349 35491 32912 35492 32356 35492 32357 35492 32357 35493 32358 35493 32912 35493 32912 35494 32358 35494 32361 35494 32912 35495 32361 35495 32916 35495 32361 35496 32930 35496 32359 35496 32359 35497 32360 35497 32361 35497 32361 35498 32360 35499 32719 35500 32361 35501 32719 35501 32916 35501 33025 35502 32363 35503 32362 35504 32362 35505 32363 35505 32724 35505 32362 35506 32724 35506 32364 35506 32724 35507 32868 35507 32364 35507 32364 35508 32868 35508 32365 35508 32364 35509 32365 35509 32366 35509 32366 35510 32365 35510 32367 35510 32366 35511 32367 35511 32368 35511 32370 35512 32442 35512 32369 35512 32369 35513 32622 35513 32370 35513 32370 35514 32622 35514 32623 35514 32370 35515 32623 35515 32371 35515 32623 35516 32624 35516 32371 35516 32371 35517 32624 35517 32627 35517 32371 35518 32627 35518 32372 35518 32627 35519 32628 35519 32372 35519 32372 35520 32628 35520 32374 35520 32372 35521 32374 35521 32373 35521 32374 35522 32375 35522 32373 35522 32373 35523 32375 35523 32376 35523 32373 35524 32376 35524 32377 35524 32376 35525 32630 35525 32377 35525 32377 35526 32630 35526 32378 35526 32377 35527 32378 35527 32381 35527 32378 35528 32379 35528 32381 35528 32381 35529 32379 35529 32380 35529 32381 35530 32380 35530 32383 35530 32380 35531 32382 35531 32383 35531 32383 35532 32382 35532 32634 35532 32383 35533 32634 35533 32384 35533 32634 35534 32385 35534 32384 35534 32384 35535 32385 35535 32635 35535 32384 35536 32635 35536 32386 35536 32635 35537 32636 35537 32386 35537 32386 35538 32636 35538 32387 35538 32386 35539 32387 35539 32388 35539 32387 35540 32638 35540 32388 35540 32388 35541 32638 35541 32640 35541 32388 35542 32640 35542 32389 35542 32640 35543 32642 35543 32389 35543 32389 35544 32642 35544 32644 35544 32389 35545 32644 35545 32390 35545 32644 35546 32645 35546 32390 35546 32390 35547 32645 35547 32391 35547 32390 35548 32391 35548 32392 35548 32391 35549 32647 35549 32392 35549 32392 35550 32647 35550 32648 35550 32392 35551 32648 35551 32393 35551 32648 35552 32649 35552 32393 35552 32393 35553 32649 35553 32394 35553 32393 35554 32394 35554 32395 35554 32394 35555 32652 35555 32395 35555 32395 35556 32652 35556 32396 35556 32395 35557 32396 35557 32397 35557 32396 35558 32654 35558 32397 35558 32397 35559 32654 35559 32398 35559 32397 35560 32398 35560 32401 35560 32398 35561 32399 35561 32401 35561 32401 35562 32399 35562 32400 35562 32401 35563 32400 35563 32403 35563 32400 35564 32402 35564 32403 35564 32403 35565 32402 35565 32404 35565 32403 35566 32404 35566 32405 35566 32404 35567 32657 35567 32405 35567 32405 35568 32657 35568 32406 35568 32405 35569 32406 35569 32407 35569 32406 35570 32658 35570 32407 35570 32407 35571 32658 35571 32409 35571 32407 35572 32409 35572 32408 35572 32409 35573 32410 35573 32408 35573 32408 35574 32410 35574 32662 35574 32408 35575 32662 35575 32411 35575 32662 35576 32663 35576 32411 35576 32411 35577 32663 35577 32664 35577 32411 35578 32664 35578 32412 35578 32664 35579 32413 35579 32412 35579 32412 35580 32413 35580 32666 35580 32412 35581 32666 35581 32414 35581 32666 35582 32668 35582 32414 35582 32414 35583 32668 35583 32415 35583 32414 35584 32415 35584 32417 35584 32415 35585 32416 35585 32417 35585 32417 35586 32416 35586 32670 35586 32417 35587 32670 35587 32418 35587 32670 35588 32672 35588 32418 35588 32418 35589 32672 35589 32419 35589 32418 35590 32419 35590 32420 35590 32419 35591 32673 35591 32420 35591 32420 35592 32673 35592 32421 35592 32420 35593 32421 35593 32423 35593 32421 35594 32675 35594 32423 35594 32423 35595 32675 35595 32422 35595 32423 35596 32422 35596 32424 35596 32422 35597 32677 35597 32424 35597 32424 35598 32677 35598 32425 35598 32424 35599 32425 35599 32426 35599 32425 35600 32427 35600 32426 35600 32426 35601 32427 35601 32680 35601 32426 35602 32680 35602 32428 35602 32680 35603 32429 35603 32428 35603 32428 35604 32429 35604 32430 35604 32428 35605 32430 35605 32431 35605 32430 35606 32682 35606 32431 35606 32431 35607 32682 35607 32432 35607 32431 35608 32432 35608 32433 35608 32432 35609 32683 35609 32433 35609 32433 35610 32683 35610 32435 35610 32433 35611 32435 35611 32434 35611 32435 35612 32685 35612 32434 35612 32434 35613 32685 35613 32687 35613 32434 35614 32687 35614 32436 35614 32687 35615 32437 35615 32436 35615 32436 35616 32437 35616 32688 35616 32436 35617 32688 35617 32438 35617 32688 35618 32439 35618 32438 35618 32438 35619 32439 35619 32691 35619 32438 35620 32691 35620 32440 35620 32691 35621 32692 35621 32440 35621 32440 35622 32692 35622 32693 35622 32440 35623 32693 35623 32442 35623 32442 35624 32693 35624 32441 35624 32442 35625 32441 35625 32369 35625 32822 35626 32443 35626 32545 35626 32822 35627 32827 35627 32443 35627 32443 35628 32827 35628 32444 35628 32443 35629 32444 35629 32445 35629 32445 35630 32444 35630 32826 35630 32445 35631 32826 35631 32446 35631 32826 35632 32831 35632 32446 35632 32446 35633 32831 35633 32830 35633 32446 35634 32830 35634 32549 35634 32830 35635 32835 35635 32549 35635 32549 35636 32835 35636 32833 35636 32549 35637 32833 35637 32550 35637 32550 35638 32833 35638 32447 35638 32550 35639 32447 35639 32551 35639 32551 35640 32447 35640 32448 35640 32551 35641 32448 35642 32553 35643 32553 35644 32448 35644 32710 35644 32710 35645 32851 35645 32553 35645 32553 35646 32851 35646 32449 35646 32553 35647 32449 35647 32555 35647 32555 35648 32449 35648 32850 35648 32555 35649 32850 35649 32557 35649 32557 35650 32850 35650 32450 35650 32557 35651 32450 35651 32558 35651 32558 35652 32450 35652 32451 35652 32451 35653 32452 35653 32558 35653 32558 35654 32452 35654 32454 35654 32558 35655 32454 35655 32453 35655 32453 35656 32454 35657 32456 35658 32453 35659 32456 35659 32455 35659 32455 35660 32456 35660 32457 35660 32455 35661 32457 35661 32561 35661 32561 35662 32457 35662 32458 35662 32458 35663 32459 35663 32561 35663 32561 35664 32459 35664 32460 35664 32561 35665 32460 35665 32563 35665 32563 35666 32460 35667 32461 35668 32563 35669 32461 35669 32462 35669 32462 35670 32461 35670 32876 35670 32462 35671 32876 35671 32463 35671 32463 35672 32876 35672 32709 35672 32709 35673 32464 35673 32463 35673 32463 35674 32464 35674 32465 35674 32463 35675 32465 35675 32566 35675 32566 35676 32465 35676 32466 35676 32566 35677 32466 35677 32467 35677 32467 35678 32466 35679 32468 35680 32467 35681 32468 35681 32469 35681 32468 35682 32708 35682 32469 35682 32469 35683 32708 35683 32470 35683 32469 35684 32470 35684 32472 35684 32470 35685 32471 35686 32472 35687 32472 35688 32471 35688 32473 35688 32472 35689 32473 35689 32568 35689 32568 35690 32473 35690 32474 35690 32568 35691 32474 35691 32569 35691 32474 35692 32893 35692 32569 35692 32569 35693 32893 35693 32475 35693 32569 35694 32475 35694 32571 35694 32475 35695 32899 35695 32571 35695 32571 35696 32899 35696 32476 35696 32571 35697 32476 35697 32477 35697 32477 35698 32476 35698 32897 35698 32477 35699 32897 35699 32573 35699 32573 35700 32897 35700 32478 35700 32573 35701 32478 35701 32479 35701 32479 35702 32478 35702 32706 35702 32706 35703 32913 35703 32479 35703 32479 35704 32913 35704 32480 35704 32479 35705 32480 35705 32576 35705 32576 35706 32480 35707 32481 35708 32576 35709 32481 35709 32482 35709 32482 35710 32481 35710 32483 35710 32482 35711 32483 35711 32484 35711 32484 35712 32483 35712 32485 35712 32485 35713 32925 35713 32484 35713 32484 35714 32925 35714 32924 35714 32484 35715 32924 35715 32578 35715 32578 35716 32924 35716 32486 35716 32578 35717 32486 35717 32487 35717 32487 35718 32486 35718 32935 35718 32487 35719 32935 35719 32580 35719 32580 35720 32935 35720 32934 35720 32934 35721 32933 35722 32580 35723 32580 35724 32933 35725 32488 35726 32580 35727 32488 35727 32489 35727 32489 35728 32488 35728 32704 35728 32489 35729 32704 35729 32583 35729 32583 35730 32704 35730 32490 35730 32583 35731 32490 35731 32491 35731 32491 35732 32490 35732 32703 35732 32703 35733 32702 35733 32491 35733 32491 35734 32702 35734 32701 35734 32491 35735 32701 35735 32492 35735 32492 35736 32701 35736 32700 35736 32492 35737 32700 35737 32585 35737 32585 35738 32700 35738 32952 35738 32585 35739 32952 35739 32493 35739 32952 35740 32494 35740 32493 35740 32493 35741 32494 35741 32699 35741 32493 35742 32699 35742 32588 35742 32699 35743 32959 35744 32588 35745 32588 35746 32959 35746 32957 35746 32588 35747 32957 35747 32495 35747 32495 35748 32957 35748 32496 35748 32495 35749 32496 35749 32497 35749 32496 35750 32964 35750 32497 35750 32497 35751 32964 35751 32698 35751 32497 35752 32698 35752 32498 35752 32698 35753 32499 35753 32498 35753 32498 35754 32499 35754 32500 35754 32498 35755 32500 35755 32502 35755 32502 35756 32500 35757 32501 35758 32502 35759 32501 35759 32504 35759 32504 35760 32501 35760 32503 35760 32504 35761 32503 35761 32505 35761 32505 35762 32503 35762 32982 35762 32982 35763 32981 35763 32505 35763 32505 35764 32981 35764 32983 35764 32505 35765 32983 35766 32592 35767 32592 35768 32983 35768 32697 35768 32592 35769 32697 35769 32506 35769 32506 35770 32697 35770 32996 35770 32506 35771 32996 35771 32508 35771 32508 35772 32996 35772 32994 35772 32994 35773 32993 35773 32508 35773 32508 35774 32993 35774 32507 35774 32508 35775 32507 35775 32595 35775 32595 35776 32507 35776 32696 35776 32595 35777 32696 35777 32509 35777 32509 35778 32696 35778 32510 35778 32509 35779 32510 35779 32511 35779 32511 35780 32510 35780 33010 35780 33010 35781 32512 35781 32511 35781 32511 35782 32512 35782 33011 35782 32511 35783 33011 35783 32596 35783 32596 35784 33011 35785 32695 35786 32596 35787 32695 35787 32599 35787 32599 35788 32695 35788 33014 35788 32599 35789 33014 35789 32513 35789 32513 35790 33014 35790 32694 35790 32694 35791 32514 35791 32513 35791 32513 35792 32514 35792 32515 35792 32513 35793 32515 35793 32601 35793 32601 35794 32515 35794 32718 35794 32601 35795 32718 35795 32603 35795 32603 35796 32718 35796 32746 35796 32603 35797 32746 35797 32517 35797 32746 35798 32516 35799 32517 35800 32517 35801 32516 35801 32716 35801 32517 35802 32716 35802 32520 35802 32716 35803 32518 35803 32520 35803 32520 35804 32518 35804 32519 35804 32520 35805 32519 35805 32605 35805 32605 35806 32519 35807 32521 35808 32605 35809 32521 35809 32606 35809 32521 35810 32750 35810 32606 35810 32606 35811 32750 35811 32522 35811 32606 35812 32522 35812 32523 35812 32522 35813 32758 35814 32523 35815 32523 35816 32758 35816 32757 35816 32523 35817 32757 35817 32524 35817 32524 35818 32757 35818 32525 35818 32524 35819 32525 35819 32609 35819 32609 35820 32525 35820 32526 35820 32609 35821 32526 35821 32611 35821 32611 35822 32526 35822 32769 35822 32769 35823 32527 35823 32611 35823 32611 35824 32527 35824 32778 35824 32611 35825 32778 35825 32613 35825 32613 35826 32778 35827 32776 35828 32613 35829 32776 35829 32615 35829 32615 35830 32776 35830 32790 35830 32615 35831 32790 35831 32528 35831 32528 35832 32790 35832 32789 35832 32789 35833 32788 35834 32528 35835 32528 35836 32788 35836 32787 35836 32528 35837 32787 35837 32529 35837 32529 35838 32787 35839 32530 35840 32529 35841 32530 35841 32531 35841 32531 35842 32530 35842 32532 35842 32531 35843 32532 35843 32533 35843 32533 35844 32532 35844 32534 35844 32534 35845 32804 35845 32533 35845 32533 35846 32804 35846 32805 35846 32533 35847 32805 35847 32536 35847 32536 35848 32805 35849 32535 35850 32536 35851 32535 35851 32537 35851 32537 35852 32535 35852 32538 35852 32537 35853 32538 35853 32539 35853 32539 35854 32538 35854 32714 35854 32714 35855 32713 35855 32539 35855 32539 35856 32713 35856 32541 35856 32539 35857 32541 35857 32540 35857 32540 35858 32541 35858 32542 35858 32540 35859 32542 35859 32543 35859 32543 35860 32542 35860 32544 35860 32543 35861 32544 35861 32545 35861 32545 35862 32544 35863 32823 35864 32545 35865 32823 35865 32822 35865 32619 35866 32540 35866 32620 35866 32620 35867 32540 35867 32543 35867 32620 35868 32543 35868 32621 35868 32621 35869 32543 35869 32545 35869 32621 35870 32545 35870 32546 35870 32546 35871 32545 35871 32443 35871 32546 35872 32443 35872 32547 35872 32547 35873 32443 35873 32445 35873 32547 35874 32445 35874 32625 35874 32625 35875 32445 35875 32446 35875 32625 35876 32446 35876 32626 35876 32626 35877 32446 35877 32549 35877 32626 35878 32549 35878 32548 35878 32548 35879 32549 35879 32550 35879 32548 35880 32550 35880 32552 35880 32552 35881 32550 35881 32551 35881 32552 35882 32551 35882 32554 35882 32554 35883 32551 35883 32553 35883 32554 35884 32553 35884 32629 35884 32629 35885 32553 35885 32555 35885 32629 35886 32555 35886 32556 35886 32556 35887 32555 35887 32557 35887 32556 35888 32557 35888 32631 35888 32631 35889 32557 35889 32558 35889 32631 35890 32558 35890 32632 35890 32632 35891 32558 35891 32453 35891 32632 35892 32453 35892 32559 35892 32559 35893 32453 35893 32455 35893 32559 35894 32455 35894 32560 35894 32560 35895 32455 35895 32561 35895 32560 35896 32561 35896 32633 35896 32633 35897 32561 35897 32563 35897 32633 35898 32563 35898 32562 35898 32562 35899 32563 35899 32462 35899 32562 35900 32462 35900 32564 35900 32564 35901 32462 35901 32463 35901 32564 35902 32463 35902 32637 35902 32637 35903 32463 35903 32566 35903 32637 35904 32566 35904 32565 35904 32565 35905 32566 35905 32467 35905 32565 35906 32467 35906 32639 35906 32639 35907 32467 35907 32469 35907 32639 35908 32469 35908 32567 35908 32567 35909 32469 35909 32472 35909 32567 35910 32472 35910 32641 35910 32641 35911 32472 35911 32568 35911 32641 35912 32568 35912 32643 35912 32643 35913 32568 35913 32569 35913 32643 35914 32569 35914 32570 35914 32570 35915 32569 35915 32571 35915 32570 35916 32571 35916 32572 35916 32572 35917 32571 35917 32477 35917 32572 35918 32477 35918 32646 35918 32646 35919 32477 35919 32573 35919 32646 35920 32573 35920 32574 35920 32574 35921 32573 35921 32479 35921 32574 35922 32479 35922 32575 35922 32575 35923 32479 35923 32576 35923 32575 35924 32576 35925 32650 35926 32650 35927 32576 35927 32482 35927 32650 35928 32482 35928 32651 35928 32651 35929 32482 35929 32484 35929 32651 35930 32484 35930 32577 35930 32577 35931 32484 35931 32578 35931 32577 35932 32578 35932 32579 35932 32579 35933 32578 35933 32487 35933 32579 35934 32487 35934 32653 35934 32653 35935 32487 35935 32580 35935 32653 35936 32580 35936 32581 35936 32581 35937 32580 35937 32489 35937 32581 35938 32489 35938 32582 35938 32582 35939 32489 35939 32583 35939 32582 35940 32583 35941 32655 35940 32655 35942 32583 35942 32491 35942 32655 35943 32491 35943 32656 35943 32656 35944 32491 35944 32492 35944 32656 35945 32492 35945 32584 35945 32584 35946 32492 35946 32585 35946 32584 35947 32585 35947 32586 35947 32586 35948 32585 35948 32493 35948 32586 35949 32493 35949 32587 35949 32587 35950 32493 35950 32588 35950 32587 35951 32588 35951 32659 35951 32659 35952 32588 35952 32495 35952 32659 35953 32495 35953 32589 35953 32589 35954 32495 35954 32497 35954 32589 35955 32497 35955 32660 35955 32660 35956 32497 35956 32498 35956 32660 35957 32498 35957 32661 35957 32661 35958 32498 35959 32502 35960 32661 35961 32502 35961 32590 35961 32590 35962 32502 35962 32504 35962 32590 35963 32504 35963 32591 35963 32591 35964 32504 35964 32505 35964 32591 35965 32505 35966 32665 35965 32665 35967 32505 35967 32592 35967 32665 35968 32592 35968 32667 35968 32667 35969 32592 35969 32506 35969 32667 35970 32506 35970 32593 35970 32593 35971 32506 35971 32508 35971 32593 35972 32508 35972 32594 35972 32594 35973 32508 35973 32595 35973 32594 35974 32595 35974 32669 35974 32669 35975 32595 35975 32509 35975 32669 35976 32509 35976 32671 35976 32671 35977 32509 35977 32511 35977 32671 35978 32511 35978 32597 35978 32597 35979 32511 35979 32596 35979 32597 35980 32596 35980 32598 35980 32598 35981 32596 35981 32599 35981 32598 35982 32599 35982 32600 35982 32600 35983 32599 35983 32513 35983 32600 35984 32513 35984 32674 35984 32674 35985 32513 35985 32601 35985 32674 35986 32601 35986 32676 35986 32676 35987 32601 35987 32603 35987 32676 35988 32603 35988 32602 35988 32602 35989 32603 35989 32517 35989 32602 35990 32517 35990 32678 35990 32678 35991 32517 35991 32520 35991 32678 35992 32520 35992 32604 35992 32604 35993 32520 35993 32605 35993 32604 35994 32605 35994 32679 35994 32679 35995 32605 35995 32606 35995 32679 35996 32606 35996 32607 35996 32607 35997 32606 35997 32523 35997 32607 35998 32523 35998 32681 35998 32681 35999 32523 35999 32524 35999 32681 36000 32524 36000 32608 36000 32608 36001 32524 36001 32609 36001 32608 36002 32609 36002 32610 36002 32610 36003 32609 36003 32611 36003 32610 36004 32611 36004 32612 36004 32612 36005 32611 36005 32613 36005 32612 36006 32613 36006 32684 36006 32684 36007 32613 36007 32615 36007 32684 36008 32615 36008 32614 36008 32614 36009 32615 36009 32528 36009 32614 36010 32528 36010 32686 36010 32686 36011 32528 36011 32529 36011 32686 36012 32529 36012 32616 36012 32616 36013 32529 36013 32531 36013 32616 36014 32531 36014 32689 36014 32689 36015 32531 36016 32533 36015 32689 36017 32533 36017 32617 36017 32617 36018 32533 36018 32536 36018 32617 36019 32536 36019 32690 36019 32690 36020 32536 36020 32537 36020 32690 36021 32537 36022 32618 36023 32618 36024 32537 36024 32539 36024 32618 36025 32539 36025 32619 36025 32619 36026 32539 36026 32540 36026 32693 36027 32620 36027 32441 36027 32441 36028 32620 36028 32621 36028 32441 36029 32621 36029 32369 36029 32369 36030 32621 36030 32546 36030 32369 36031 32546 36031 32622 36031 32622 36032 32546 36033 32547 36034 32622 36035 32547 36035 32623 36035 32623 36036 32547 36036 32625 36036 32623 36037 32625 36037 32624 36037 32624 36038 32625 36038 32626 36038 32624 36039 32626 36039 32627 36039 32627 36040 32626 36040 32548 36040 32627 36041 32548 36041 32628 36041 32628 36042 32548 36042 32552 36042 32628 36043 32552 36043 32374 36043 32374 36044 32552 36044 32554 36044 32374 36045 32554 36046 32375 36047 32375 36048 32554 36048 32629 36048 32375 36049 32629 36049 32376 36049 32376 36050 32629 36050 32556 36050 32376 36051 32556 36051 32630 36051 32630 36052 32556 36052 32631 36052 32630 36053 32631 36053 32378 36053 32378 36054 32631 36054 32632 36054 32378 36055 32632 36055 32379 36055 32379 36056 32632 36056 32559 36056 32379 36057 32559 36057 32380 36057 32380 36058 32559 36058 32560 36058 32380 36059 32560 36059 32382 36059 32382 36060 32560 36061 32633 36062 32382 36063 32633 36063 32634 36063 32634 36064 32633 36064 32562 36064 32634 36065 32562 36065 32385 36065 32385 36066 32562 36066 32564 36066 32385 36067 32564 36067 32635 36067 32635 36068 32564 36068 32637 36068 32635 36069 32637 36069 32636 36069 32636 36070 32637 36070 32565 36070 32636 36071 32565 36071 32387 36071 32387 36072 32565 36073 32639 36074 32387 36075 32639 36075 32638 36075 32638 36076 32639 36076 32567 36076 32638 36077 32567 36077 32640 36077 32640 36078 32567 36079 32641 36080 32640 36081 32641 36081 32642 36081 32642 36082 32641 36082 32643 36082 32642 36083 32643 36083 32644 36083 32644 36084 32643 36084 32570 36084 32644 36085 32570 36085 32645 36085 32645 36086 32570 36086 32572 36086 32645 36087 32572 36087 32391 36087 32391 36088 32572 36088 32646 36088 32391 36089 32646 36089 32647 36089 32647 36090 32646 36090 32574 36090 32647 36091 32574 36091 32648 36091 32648 36092 32574 36092 32575 36092 32648 36093 32575 36093 32649 36093 32649 36094 32575 36094 32650 36094 32649 36095 32650 36095 32394 36095 32394 36096 32650 36096 32651 36096 32394 36097 32651 36097 32652 36097 32652 36098 32651 36098 32577 36098 32652 36099 32577 36099 32396 36099 32396 36100 32577 36100 32579 36100 32396 36101 32579 36101 32654 36101 32654 36102 32579 36102 32653 36102 32654 36103 32653 36103 32398 36103 32398 36104 32653 36104 32581 36104 32398 36105 32581 36105 32399 36105 32399 36106 32581 36106 32582 36106 32399 36107 32582 36107 32400 36107 32400 36108 32582 36108 32655 36108 32400 36109 32655 36109 32402 36109 32402 36110 32655 36110 32656 36110 32402 36111 32656 36111 32404 36111 32404 36112 32656 36112 32584 36112 32404 36113 32584 36113 32657 36113 32657 36114 32584 36114 32586 36114 32657 36115 32586 36115 32406 36115 32406 36116 32586 36116 32587 36116 32406 36117 32587 36117 32658 36117 32658 36118 32587 36118 32659 36118 32658 36119 32659 36119 32409 36119 32409 36120 32659 36120 32589 36120 32409 36121 32589 36121 32410 36121 32410 36122 32589 36122 32660 36122 32410 36123 32660 36124 32662 36125 32662 36126 32660 36126 32661 36126 32662 36127 32661 36127 32663 36127 32663 36128 32661 36128 32590 36128 32663 36129 32590 36129 32664 36129 32664 36130 32590 36130 32591 36130 32664 36131 32591 36131 32413 36131 32413 36132 32591 36132 32665 36132 32413 36133 32665 36134 32666 36135 32666 36136 32665 36137 32667 36138 32666 36139 32667 36139 32668 36139 32668 36140 32667 36140 32593 36140 32668 36141 32593 36141 32415 36141 32415 36142 32593 36142 32594 36142 32415 36143 32594 36143 32416 36143 32416 36144 32594 36144 32669 36144 32416 36145 32669 36146 32670 36147 32670 36148 32669 36148 32671 36148 32670 36149 32671 36150 32672 36151 32672 36152 32671 36152 32597 36152 32672 36153 32597 36153 32419 36153 32419 36154 32597 36154 32598 36154 32419 36155 32598 36155 32673 36155 32673 36156 32598 36156 32600 36156 32673 36157 32600 36157 32421 36157 32421 36158 32600 36158 32674 36158 32421 36159 32674 36159 32675 36159 32675 36160 32674 36160 32676 36160 32675 36161 32676 36162 32422 36163 32422 36164 32676 36164 32602 36164 32422 36165 32602 36165 32677 36165 32677 36166 32602 36166 32678 36166 32677 36167 32678 36168 32425 36169 32425 36170 32678 36171 32604 36172 32425 36173 32604 36173 32427 36173 32427 36174 32604 36174 32679 36174 32427 36175 32679 36175 32680 36175 32680 36176 32679 36176 32607 36176 32680 36177 32607 36177 32429 36177 32429 36178 32607 36178 32681 36178 32429 36179 32681 36179 32430 36179 32430 36180 32681 36180 32608 36180 32430 36181 32608 36181 32682 36181 32682 36182 32608 36182 32610 36182 32682 36183 32610 36183 32432 36183 32432 36184 32610 36184 32612 36184 32432 36185 32612 36185 32683 36185 32683 36186 32612 36186 32684 36186 32683 36187 32684 36187 32435 36187 32435 36188 32684 36188 32614 36188 32435 36189 32614 36189 32685 36189 32685 36190 32614 36190 32686 36190 32685 36191 32686 36191 32687 36191 32687 36192 32686 36192 32616 36192 32687 36193 32616 36193 32437 36193 32437 36194 32616 36194 32689 36194 32437 36195 32689 36195 32688 36195 32688 36196 32689 36196 32617 36196 32688 36197 32617 36197 32439 36197 32439 36198 32617 36198 32690 36198 32439 36199 32690 36199 32691 36199 32691 36200 32690 36201 32618 36201 32691 36202 32618 36203 32692 36204 32692 36205 32618 36205 32619 36205 32692 36206 32619 36206 32693 36206 32693 36207 32619 36207 32620 36207 32514 36208 32694 36208 33021 36208 33014 36209 32695 36209 33012 36209 32510 36210 32696 36210 33008 36210 32996 36211 32697 36211 32984 36211 32499 36212 32698 36213 32968 36214 32959 36215 32699 36215 32960 36215 32494 36216 32952 36216 32953 36216 32700 36217 32701 36217 32954 36217 32702 36218 32703 36218 32949 36218 32490 36219 32704 36219 32705 36219 32935 36220 32486 36220 32926 36220 32913 36221 32706 36221 32707 36221 32899 36222 32475 36223 32894 36224 32471 36225 32470 36225 32888 36225 32708 36226 32468 36226 32884 36226 32466 36227 32465 36227 32881 36227 32464 36228 32709 36228 32875 36228 32876 36229 32461 36229 32877 36229 32457 36230 32456 36230 32871 36230 32851 36231 32710 36231 32845 36231 32835 36232 32830 36233 32711 36234 32827 36235 32822 36235 32824 36235 32823 36236 32544 36236 32819 36236 32542 36237 32541 36237 32712 36237 32713 36238 32714 36238 32809 36238 32538 36239 32535 36239 32715 36239 32532 36240 32530 36240 32791 36240 32527 36241 32769 36241 32780 36241 32758 36242 32522 36242 32754 36242 32518 36243 32716 36244 32717 36245 32516 36246 32746 36247 32748 36248 32718 36249 32515 36249 33020 36249 32367 36250 32365 36250 32867 36250 32974 36251 32988 36251 32975 36251 32719 36252 32360 36252 32917 36252 32901 36253 32912 36253 32911 36253 32722 36254 32720 36255 32721 36256 32721 36257 32720 36257 32883 36257 32721 36258 32883 36258 32723 36258 32722 36259 32721 36260 33026 36261 33026 36262 32721 36262 32723 36262 33026 36263 32723 36263 32880 36263 32724 36264 32363 36264 32879 36264 32879 36265 32363 36266 33025 36267 32854 36268 32855 36268 32856 36268 32837 36269 32848 36269 32725 36269 32727 36270 32818 36270 32726 36270 32726 36271 32818 36271 32811 36271 32726 36272 32811 36272 32728 36272 32727 36273 32726 36273 32729 36273 32729 36274 32726 36274 32728 36274 32729 36275 32728 36275 32812 36275 32807 36276 32730 36276 32813 36276 32813 36277 32730 36277 32814 36277 32783 36278 32731 36278 32784 36278 32761 36279 32773 36279 32772 36279 32734 36280 33023 36280 32732 36280 32732 36281 33023 36281 32733 36281 32732 36282 32733 36282 33017 36282 32734 36283 32732 36284 32735 36285 32735 36286 32732 36286 33017 36286 32735 36287 33017 36287 33018 36287 32736 36288 32737 36288 33019 36288 33019 36289 32737 36289 32738 36289 32987 36290 32739 36290 32986 36290 32740 36291 32974 36291 32976 36291 32741 36292 32951 36292 32742 36292 32742 36293 32951 36293 32944 36293 32742 36294 32944 36294 32744 36294 32741 36295 32742 36296 32743 36297 32743 36298 32742 36298 32744 36298 32743 36299 32744 36299 32946 36299 32941 36300 32745 36300 32940 36300 32940 36301 32745 36301 32947 36301 32746 36302 32718 36302 32748 36302 32748 36303 32718 36303 33020 36303 32748 36304 33020 36304 32749 36304 32749 36305 33020 36305 32747 36305 32749 36306 32747 36306 32765 36306 32765 36307 32747 36307 33022 36307 32716 36308 32516 36308 32717 36308 32717 36309 32516 36309 32748 36309 32717 36310 32748 36310 32753 36310 32753 36311 32748 36311 32749 36311 32753 36312 32749 36312 32763 36312 32763 36313 32749 36313 32765 36313 32750 36314 32521 36314 32755 36314 32755 36315 32521 36315 32519 36315 32519 36316 32518 36316 32755 36316 32755 36317 32518 36317 32717 36317 32755 36318 32717 36318 32751 36318 32751 36319 32717 36319 32753 36319 32751 36320 32753 36320 32752 36320 32752 36321 32753 36321 32763 36321 32522 36322 32750 36322 32754 36322 32754 36323 32750 36323 32755 36323 32754 36324 32755 36324 32759 36324 32759 36325 32755 36325 32751 36325 32759 36326 32751 36326 32760 36326 32760 36327 32751 36327 32752 36327 32526 36328 32525 36328 32756 36328 32756 36329 32525 36329 32757 36329 32757 36330 32758 36330 32756 36330 32756 36331 32758 36331 32754 36331 32756 36332 32754 36332 32771 36332 32771 36333 32754 36333 32759 36333 32771 36334 32759 36334 32772 36334 32772 36335 32759 36335 32760 36335 32772 36336 32760 36336 32761 36336 32761 36337 32760 36337 32752 36337 32761 36338 32752 36338 32762 36338 32762 36339 32752 36339 32763 36339 32762 36340 32763 36340 32764 36340 32764 36341 32763 36341 32765 36341 32764 36342 32765 36342 32766 36342 32766 36343 32765 36343 33022 36343 32766 36344 33022 36344 32767 36344 32767 36345 33022 36345 32768 36345 32769 36346 32526 36346 32780 36346 32780 36347 32526 36347 32756 36347 32780 36348 32756 36348 32770 36348 32770 36349 32756 36349 32771 36349 32770 36350 32771 36350 32782 36350 32782 36351 32771 36351 32772 36351 32782 36352 32772 36352 32774 36352 32774 36353 32772 36353 32773 36353 32774 36354 32773 36355 32775 36356 32790 36357 32776 36357 32777 36357 32777 36358 32776 36358 32778 36358 32778 36359 32527 36359 32777 36359 32777 36360 32527 36360 32780 36360 32777 36361 32780 36361 32779 36361 32779 36362 32780 36362 32770 36362 32779 36363 32770 36363 32781 36363 32781 36364 32770 36364 32782 36364 32781 36365 32782 36365 32784 36365 32784 36366 32782 36366 32774 36366 32784 36367 32774 36367 32783 36367 32783 36368 32774 36368 32775 36368 32731 36369 32796 36369 32784 36369 32784 36370 32796 36370 32795 36370 32784 36371 32795 36371 32781 36371 32781 36372 32795 36372 32785 36372 32781 36373 32785 36373 32779 36373 32779 36374 32785 36374 32786 36374 32779 36375 32786 36375 32777 36375 32777 36376 32786 36376 32792 36376 32777 36377 32792 36377 32790 36377 32787 36378 32788 36378 32792 36378 32792 36379 32788 36380 32789 36379 32792 36381 32789 36381 32790 36381 32530 36382 32787 36382 32791 36382 32791 36383 32787 36383 32792 36383 32791 36384 32792 36384 32801 36384 32801 36385 32792 36385 32786 36385 32801 36386 32786 36386 32799 36386 32799 36387 32786 36387 32785 36387 32799 36388 32785 36388 32793 36388 32793 36389 32785 36389 32795 36389 32793 36390 32795 36390 32794 36390 32794 36391 32795 36391 32796 36391 32794 36392 32796 36392 32797 36392 32794 36393 32798 36393 32793 36393 32793 36394 32798 36394 32808 36394 32793 36395 32808 36395 32799 36395 32799 36396 32808 36396 32800 36396 32799 36397 32800 36397 32801 36397 32801 36398 32800 36398 32802 36398 32801 36399 32802 36399 32791 36399 32791 36400 32802 36400 32803 36400 32791 36401 32803 36401 32532 36401 32805 36402 32804 36402 32803 36402 32803 36403 32804 36403 32534 36403 32803 36404 32534 36404 32532 36404 32535 36405 32805 36406 32715 36407 32715 36408 32805 36408 32803 36408 32715 36409 32803 36409 32806 36409 32806 36410 32803 36410 32802 36410 32806 36411 32802 36411 32810 36411 32810 36412 32802 36412 32800 36412 32810 36413 32800 36413 32813 36413 32813 36414 32800 36414 32808 36414 32813 36415 32808 36415 32807 36415 32807 36416 32808 36416 32798 36416 32714 36417 32538 36417 32809 36417 32809 36418 32538 36418 32715 36418 32809 36419 32715 36419 32815 36419 32815 36420 32715 36420 32806 36420 32815 36421 32806 36421 32811 36421 32811 36422 32806 36422 32810 36422 32811 36423 32810 36423 32728 36423 32728 36424 32810 36424 32813 36424 32728 36425 32813 36425 32812 36425 32812 36426 32813 36426 32814 36426 32541 36427 32713 36427 32712 36427 32712 36428 32713 36428 32809 36428 32712 36429 32809 36429 32821 36429 32821 36430 32809 36430 32815 36430 32821 36431 32815 36431 32816 36431 32816 36432 32815 36432 32811 36432 32816 36433 32811 36433 32817 36433 32817 36434 32811 36434 32818 36434 32544 36435 32542 36435 32819 36435 32819 36436 32542 36436 32712 36436 32819 36437 32712 36437 32825 36437 32825 36438 32712 36438 32821 36438 32825 36439 32821 36439 32820 36439 32820 36440 32821 36440 32816 36440 32822 36441 32823 36441 32824 36441 32824 36442 32823 36442 32819 36442 32824 36443 32819 36443 32829 36443 32829 36444 32819 36444 32825 36444 32829 36445 32825 36445 32841 36445 32841 36446 32825 36446 32820 36446 32831 36447 32826 36447 32832 36447 32832 36448 32826 36448 32444 36448 32444 36449 32827 36449 32832 36449 32832 36450 32827 36450 32824 36450 32832 36451 32824 36451 32828 36451 32828 36452 32824 36452 32829 36452 32828 36453 32829 36453 32839 36453 32839 36454 32829 36454 32841 36454 32830 36455 32831 36455 32711 36455 32711 36456 32831 36456 32832 36456 32711 36457 32832 36457 32836 36457 32836 36458 32832 36458 32828 36458 32836 36459 32828 36459 32838 36459 32838 36460 32828 36460 32839 36460 32448 36461 32447 36461 32834 36461 32834 36462 32447 36462 32833 36462 32833 36463 32835 36463 32834 36463 32834 36464 32835 36464 32711 36464 32834 36465 32711 36465 32846 36465 32846 36466 32711 36466 32836 36466 32846 36467 32836 36467 32725 36467 32725 36468 32836 36468 32838 36468 32725 36469 32838 36469 32837 36469 32837 36470 32838 36470 32839 36470 32837 36471 32839 36471 32840 36471 32840 36472 32839 36472 32841 36472 32840 36473 32841 36473 32842 36473 32842 36474 32841 36474 32820 36474 32842 36475 32820 36475 32843 36475 32843 36476 32820 36476 32816 36476 32843 36477 32816 36477 32844 36477 32844 36478 32816 36478 32817 36478 32710 36479 32448 36479 32845 36479 32845 36480 32448 36480 32834 36480 32845 36481 32834 36481 32852 36481 32852 36482 32834 36482 32846 36482 32852 36483 32846 36483 32847 36483 32847 36484 32846 36484 32725 36484 32847 36485 32725 36485 32853 36485 32853 36486 32725 36486 32848 36486 32853 36487 32848 36487 32849 36487 32450 36488 32850 36488 32863 36488 32863 36489 32850 36489 32449 36489 32449 36490 32851 36490 32863 36490 32863 36491 32851 36491 32845 36491 32863 36492 32845 36492 32861 36492 32861 36493 32845 36493 32852 36493 32861 36494 32852 36494 32859 36494 32859 36495 32852 36495 32847 36495 32859 36496 32847 36496 32856 36496 32856 36497 32847 36497 32853 36497 32856 36498 32853 36498 32854 36498 32854 36499 32853 36500 32849 36501 32855 36502 32857 36502 32856 36502 32856 36503 32857 36503 32858 36503 32856 36504 32858 36504 32859 36504 32859 36505 32858 36505 32860 36505 32859 36506 32860 36506 32861 36506 32861 36507 32860 36507 32862 36507 32861 36508 32862 36508 32863 36508 32863 36509 32862 36509 32864 36509 32863 36510 32864 36510 32450 36510 32454 36511 32452 36511 32864 36511 32864 36512 32452 36512 32451 36512 32864 36513 32451 36513 32450 36513 32456 36514 32454 36515 32871 36516 32871 36517 32454 36517 32864 36517 32871 36518 32864 36518 32865 36518 32865 36519 32864 36519 32862 36519 32865 36520 32862 36520 32866 36520 32866 36521 32862 36521 32860 36521 32866 36522 32860 36522 32867 36522 32867 36523 32860 36523 32858 36523 32867 36524 32858 36524 32367 36524 32367 36525 32858 36525 32857 36525 32367 36526 32857 36527 32368 36528 32365 36529 32868 36529 32867 36529 32867 36530 32868 36530 32874 36530 32867 36531 32874 36531 32866 36531 32866 36532 32874 36532 32869 36532 32866 36533 32869 36533 32865 36533 32865 36534 32869 36534 32870 36534 32865 36535 32870 36535 32871 36535 32871 36536 32870 36536 32872 36536 32871 36537 32872 36537 32457 36537 32460 36538 32459 36538 32872 36538 32872 36539 32459 36539 32458 36539 32872 36540 32458 36540 32457 36540 32461 36541 32460 36542 32877 36543 32877 36544 32460 36544 32872 36544 32877 36545 32872 36545 32878 36545 32878 36546 32872 36546 32870 36546 32878 36547 32870 36547 32873 36547 32873 36548 32870 36548 32869 36548 32873 36549 32869 36549 32879 36549 32879 36550 32869 36550 32874 36550 32879 36551 32874 36551 32724 36551 32724 36552 32874 36552 32868 36552 32709 36553 32876 36553 32875 36553 32875 36554 32876 36554 32877 36554 32875 36555 32877 36555 32882 36555 32882 36556 32877 36556 32878 36556 32882 36557 32878 36557 32883 36557 32883 36558 32878 36558 32873 36558 32883 36559 32873 36559 32723 36559 32723 36560 32873 36560 32879 36560 32723 36561 32879 36561 32880 36561 32880 36562 32879 36562 33025 36562 32465 36563 32464 36563 32881 36563 32881 36564 32464 36564 32875 36564 32881 36565 32875 36565 32887 36565 32887 36566 32875 36566 32882 36566 32887 36567 32882 36567 32904 36567 32904 36568 32882 36568 32883 36568 32904 36569 32883 36569 32907 36569 32907 36570 32883 36570 32720 36570 32468 36571 32466 36572 32884 36573 32884 36574 32466 36574 32881 36574 32884 36575 32881 36575 32885 36575 32885 36576 32881 36576 32887 36576 32885 36577 32887 36577 32886 36577 32886 36578 32887 36578 32904 36578 32470 36579 32708 36579 32888 36579 32888 36580 32708 36580 32884 36580 32888 36581 32884 36581 32889 36581 32889 36582 32884 36582 32885 36582 32889 36583 32885 36583 32890 36583 32890 36584 32885 36584 32886 36584 32893 36585 32474 36585 32891 36585 32891 36586 32474 36586 32473 36586 32473 36587 32471 36587 32891 36587 32891 36588 32471 36588 32888 36588 32891 36589 32888 36589 32896 36589 32896 36590 32888 36590 32889 36590 32896 36591 32889 36591 32892 36591 32892 36592 32889 36592 32890 36592 32475 36593 32893 36593 32894 36593 32894 36594 32893 36594 32891 36594 32894 36595 32891 36595 32900 36595 32900 36596 32891 36596 32896 36596 32900 36597 32896 36597 32895 36597 32895 36598 32896 36598 32892 36598 32478 36599 32897 36599 32898 36599 32898 36600 32897 36600 32476 36600 32476 36601 32899 36601 32898 36601 32898 36602 32899 36602 32894 36602 32898 36603 32894 36603 32909 36603 32909 36604 32894 36604 32900 36604 32909 36605 32900 36605 32911 36605 32911 36606 32900 36606 32895 36606 32911 36607 32895 36607 32901 36607 32901 36608 32895 36608 32892 36608 32901 36609 32892 36609 32902 36609 32902 36610 32892 36610 32890 36610 32902 36611 32890 36611 32903 36611 32903 36612 32890 36612 32886 36612 32903 36613 32886 36613 32905 36613 32905 36614 32886 36614 32904 36614 32905 36615 32904 36615 32906 36615 32906 36616 32904 36616 32907 36616 32706 36617 32478 36617 32707 36617 32707 36618 32478 36618 32898 36618 32707 36619 32898 36619 32908 36619 32908 36620 32898 36620 32909 36620 32908 36621 32909 36621 32910 36621 32910 36622 32909 36622 32911 36622 32910 36623 32911 36623 32915 36623 32915 36624 32911 36624 32912 36624 32915 36625 32912 36625 32916 36625 32483 36626 32481 36626 32922 36626 32922 36627 32481 36627 32480 36627 32480 36628 32913 36628 32922 36628 32922 36629 32913 36629 32707 36629 32922 36630 32707 36630 32914 36630 32914 36631 32707 36631 32908 36631 32914 36632 32908 36632 32919 36632 32919 36633 32908 36633 32910 36633 32919 36634 32910 36634 32917 36634 32917 36635 32910 36635 32915 36635 32917 36636 32915 36636 32719 36636 32719 36637 32915 36637 32916 36637 32360 36638 32359 36638 32917 36638 32917 36639 32359 36639 32918 36639 32917 36640 32918 36640 32919 36640 32919 36641 32918 36641 32920 36641 32919 36642 32920 36642 32914 36642 32914 36643 32920 36643 32921 36643 32914 36644 32921 36644 32922 36644 32922 36645 32921 36645 32923 36645 32922 36646 32923 36646 32483 36646 32924 36647 32925 36647 32923 36647 32923 36648 32925 36648 32485 36648 32923 36649 32485 36649 32483 36649 32486 36650 32924 36650 32926 36650 32926 36651 32924 36651 32923 36651 32926 36652 32923 36652 32927 36652 32927 36653 32923 36653 32921 36653 32927 36654 32921 36654 32928 36654 32928 36655 32921 36655 32920 36655 32928 36656 32920 36656 32929 36656 32929 36657 32920 36657 32918 36657 32929 36658 32918 36658 32931 36658 32931 36659 32918 36659 32359 36659 32931 36660 32359 36660 32930 36660 32931 36661 32932 36661 32929 36661 32929 36662 32932 36662 32942 36662 32929 36663 32942 36663 32928 36663 32928 36664 32942 36664 32939 36664 32928 36665 32939 36665 32927 36665 32927 36666 32939 36666 32938 36666 32927 36667 32938 36667 32926 36667 32926 36668 32938 36668 32937 36668 32926 36669 32937 36669 32935 36669 32488 36670 32933 36670 32937 36670 32937 36671 32933 36671 32934 36671 32937 36672 32934 36672 32935 36672 32704 36673 32488 36674 32705 36675 32705 36676 32488 36676 32937 36676 32705 36677 32937 36677 32936 36677 32936 36678 32937 36678 32938 36678 32936 36679 32938 36679 32945 36679 32945 36680 32938 36680 32939 36680 32945 36681 32939 36681 32940 36681 32940 36682 32939 36682 32942 36682 32940 36683 32942 36683 32941 36683 32941 36684 32942 36684 32932 36684 32703 36685 32490 36685 32949 36685 32949 36686 32490 36686 32705 36686 32949 36687 32705 36687 32943 36687 32943 36688 32705 36688 32936 36688 32943 36689 32936 36689 32944 36689 32944 36690 32936 36690 32945 36690 32944 36691 32945 36691 32744 36691 32744 36692 32945 36692 32940 36692 32744 36693 32940 36693 32946 36693 32946 36694 32940 36694 32947 36694 32701 36695 32702 36695 32954 36695 32954 36696 32702 36696 32949 36696 32954 36697 32949 36697 32948 36697 32948 36698 32949 36698 32943 36698 32948 36699 32943 36699 32950 36699 32950 36700 32943 36700 32944 36700 32950 36701 32944 36701 32973 36701 32973 36702 32944 36702 32951 36702 32952 36703 32700 36703 32953 36703 32953 36704 32700 36704 32954 36704 32953 36705 32954 36705 32955 36705 32955 36706 32954 36706 32948 36706 32955 36707 32948 36707 32956 36707 32956 36708 32948 36708 32950 36708 32699 36709 32494 36709 32960 36709 32960 36710 32494 36710 32953 36710 32960 36711 32953 36711 32961 36711 32961 36712 32953 36712 32955 36712 32961 36713 32955 36713 32963 36713 32963 36714 32955 36714 32956 36714 32964 36715 32496 36715 32958 36715 32958 36716 32496 36716 32957 36716 32957 36717 32959 36717 32958 36717 32958 36718 32959 36718 32960 36718 32958 36719 32960 36719 32966 36719 32966 36720 32960 36720 32961 36720 32966 36721 32961 36721 32962 36721 32962 36722 32961 36722 32963 36722 32698 36723 32964 36723 32968 36723 32968 36724 32964 36724 32958 36724 32968 36725 32958 36725 32965 36725 32965 36726 32958 36726 32966 36726 32965 36727 32966 36727 32967 36727 32967 36728 32966 36728 32962 36728 32503 36729 32501 36729 32979 36729 32979 36730 32501 36730 32500 36730 32500 36731 32499 36731 32979 36731 32979 36732 32499 36732 32968 36732 32979 36733 32968 36733 32978 36733 32978 36734 32968 36734 32965 36734 32978 36735 32965 36735 32976 36735 32976 36736 32965 36736 32967 36736 32976 36737 32967 36737 32740 36737 32740 36738 32967 36738 32962 36738 32740 36739 32962 36739 32969 36739 32969 36740 32962 36740 32963 36740 32969 36741 32963 36741 32970 36741 32970 36742 32963 36742 32956 36742 32970 36743 32956 36743 32971 36743 32971 36744 32956 36744 32950 36744 32971 36745 32950 36745 32972 36745 32972 36746 32950 36746 32973 36746 32974 36747 32975 36747 32976 36747 32976 36748 32975 36748 32977 36748 32976 36749 32977 36749 32978 36749 32978 36750 32977 36750 32985 36750 32978 36751 32985 36751 32979 36751 32979 36752 32985 36752 32980 36752 32979 36753 32980 36753 32503 36753 32983 36754 32981 36754 32980 36754 32980 36755 32981 36756 32982 36757 32980 36758 32982 36758 32503 36758 32697 36759 32983 36759 32984 36759 32984 36760 32983 36760 32980 36760 32984 36761 32980 36761 32992 36761 32992 36762 32980 36762 32985 36762 32992 36763 32985 36763 32990 36763 32990 36764 32985 36764 32977 36764 32990 36765 32977 36765 32986 36765 32986 36766 32977 36766 32975 36766 32986 36767 32975 36767 32987 36767 32987 36768 32975 36768 32988 36768 32739 36769 33001 36769 32986 36769 32986 36770 33001 36770 32989 36770 32986 36771 32989 36771 32990 36771 32990 36772 32989 36772 32991 36772 32990 36773 32991 36773 32992 36773 32992 36774 32991 36774 32998 36774 32992 36775 32998 36775 32984 36775 32984 36776 32998 36776 32995 36776 32984 36777 32995 36777 32996 36777 32507 36778 32993 36778 32995 36778 32995 36779 32993 36779 32994 36779 32995 36780 32994 36780 32996 36780 32696 36781 32507 36781 33008 36781 33008 36782 32507 36782 32995 36782 33008 36783 32995 36783 32997 36783 32997 36784 32995 36784 32998 36784 32997 36785 32998 36785 32999 36785 32999 36786 32998 36786 32991 36786 32999 36787 32991 36787 33004 36787 33004 36788 32991 36788 32989 36788 33004 36789 32989 36789 33000 36789 33000 36790 32989 36790 33001 36790 33000 36791 33001 36791 33002 36791 33000 36792 33003 36792 33004 36792 33004 36793 33003 36793 33005 36793 33004 36794 33005 36794 32999 36794 32999 36795 33005 36795 33006 36795 32999 36796 33006 36796 32997 36796 32997 36797 33006 36797 33007 36797 32997 36798 33007 36798 33008 36798 33008 36799 33007 36799 33009 36799 33008 36800 33009 36800 32510 36800 33011 36801 32512 36801 33009 36801 33009 36802 32512 36802 33010 36802 33009 36803 33010 36803 32510 36803 32695 36804 33011 36805 33012 36806 33012 36807 33011 36807 33009 36807 33012 36808 33009 36808 33016 36808 33016 36809 33009 36809 33007 36809 33016 36810 33007 36810 33013 36810 33013 36811 33007 36811 33006 36811 33013 36812 33006 36812 33019 36812 33019 36813 33006 36813 33005 36813 33019 36814 33005 36814 32736 36814 32736 36815 33005 36815 33003 36815 32694 36816 33014 36816 33021 36816 33021 36817 33014 36817 33012 36817 33021 36818 33012 36818 33015 36818 33015 36819 33012 36819 33016 36819 33015 36820 33016 36820 32733 36820 32733 36821 33016 36821 33013 36821 32733 36822 33013 36822 33017 36822 33017 36823 33013 36823 33019 36823 33017 36824 33019 36824 33018 36824 33018 36825 33019 36825 32738 36825 32515 36826 32514 36826 33020 36826 33020 36827 32514 36827 33021 36827 33020 36828 33021 36828 32747 36828 32747 36829 33021 36829 33015 36829 32747 36830 33015 36830 33022 36830 33022 36831 33015 36831 32733 36831 33022 36832 32733 36832 32768 36832 32768 36833 32733 36833 33023 36833 32722 36834 33024 36834 32720 36834 32720 36835 33024 36835 32907 36835 33025 36836 32362 36836 32880 36836 32880 36837 32362 36837 33024 36837 32880 36838 33024 36838 33026 36838 33026 36839 33024 36839 32722 36839 33027 36840 33028 36840 33029 36840 33029 36841 33028 36841 33550 36841 33029 36842 33550 36842 33033 36842 33033 36843 33550 36843 33384 36843 33033 36844 33384 36844 33030 36844 33030 36845 33031 36845 33033 36845 33033 36846 33031 36846 33032 36846 33033 36847 33032 36847 33547 36847 33036 36848 33034 36848 33035 36848 33035 36849 33037 36849 33036 36849 33036 36850 33037 36850 33038 36850 33036 36851 33038 36852 33039 36853 33038 36854 33673 36855 33659 36856 33659 36857 33658 36857 33038 36857 33038 36858 33658 36858 33657 36858 33038 36859 33657 36860 33039 36861 33283 32714 33041 32714 33108 32714 33283 32715 33040 32715 33041 32715 33041 32716 33040 32716 33284 32716 33041 36862 33284 36862 33042 36862 33284 36863 33285 36863 33042 36863 33042 36864 33285 36864 33043 36864 33042 36865 33043 36865 33044 36865 33043 32721 33288 32721 33044 32721 33044 32722 33288 32722 33289 32722 33044 36866 33289 36866 33045 36866 33289 32724 33290 32724 33045 32724 33045 36867 33290 36867 33292 36867 33045 36868 33292 36868 33046 36868 33292 36869 33047 36869 33046 36869 33046 32728 33047 32728 33048 32728 33046 36870 33048 36870 33049 36870 33048 32730 33050 32730 33049 32730 33049 36871 33050 36871 33294 36871 33049 36872 33294 36872 33052 36872 33294 36873 33051 36873 33052 36873 33052 32734 33051 32734 33053 32734 33052 36874 33053 36874 33054 36874 33053 32736 33296 32736 33054 32736 33054 32737 33296 32737 33298 32737 33054 36875 33298 36875 33055 36875 33298 36876 33056 36876 33055 36876 33055 36877 33056 36877 33300 36877 33055 36878 33300 36878 33057 36878 33300 32742 33301 32742 33057 32742 33057 36879 33301 36879 33303 36879 33057 36880 33303 36880 33058 36880 33303 36881 33305 36881 33058 36881 33058 36882 33305 36882 33307 36882 33058 36883 33307 36883 33061 36883 33307 36884 33059 36884 33061 36884 33061 36885 33059 36885 33060 36885 33061 36886 33060 36886 33062 36886 33060 36887 33063 36887 33062 36887 33062 32752 33063 32752 33064 32752 33062 36888 33064 36888 33065 36888 33064 36889 33066 36889 33065 36889 33065 36890 33066 36890 33310 36890 33065 36891 33310 36891 33067 36891 33310 32757 33068 32757 33067 32757 33067 32758 33068 32758 33069 32758 33067 36892 33069 36892 33070 36892 33069 32760 33071 32760 33070 32760 33070 32761 33071 32761 33312 32761 33070 36893 33312 36893 33072 36893 33312 36894 33314 36894 33072 36894 33072 32764 33314 32764 33073 32764 33072 36895 33073 36895 33074 36895 33073 36896 33316 36896 33074 36896 33074 32767 33316 32767 33317 32767 33074 36897 33317 36897 33075 36897 33317 32769 33318 32769 33075 32769 33075 32770 33318 32770 33076 32770 33075 32657 33076 32657 33077 32657 33076 32658 33320 32658 33077 32658 33077 32659 33320 32659 33321 32659 33077 36898 33321 36898 33078 36898 33321 36899 33322 36899 33078 36899 33078 36900 33322 36900 33323 36900 33078 36901 33323 36901 33079 36901 33323 32664 33325 32664 33079 32664 33079 32665 33325 32665 33326 32665 33079 36902 33326 36902 33080 36902 33326 32667 33327 32667 33080 32667 33080 36903 33327 36903 33329 36903 33080 36904 33329 36904 33082 36904 33329 36905 33081 36905 33082 36905 33082 32671 33081 32671 33330 32671 33082 36906 33330 36906 33084 36906 33330 32673 33331 32673 33084 32673 33084 36907 33331 36907 33083 36907 33084 36908 33083 36908 33085 36908 33083 36909 33333 36909 33085 36909 33085 32677 33333 32677 33334 32677 33085 36910 33334 36910 33086 36910 33334 32679 33087 32679 33086 32679 33086 32680 33087 32680 33088 32680 33086 36911 33088 36911 33089 36911 33088 36912 33337 36912 33089 36912 33089 36913 33337 36913 33090 36913 33089 36914 33090 36914 33091 36914 33090 32685 33092 32685 33091 32685 33091 36915 33092 36915 33093 36915 33091 36916 33093 36916 33094 36916 33093 36917 33341 36917 33094 36917 33094 36918 33341 36918 33343 36918 33094 36919 33343 36919 33096 36919 33343 36920 33095 36920 33096 36920 33096 36921 33095 36921 33344 36921 33096 36922 33344 36922 33097 36922 33344 36923 33346 36923 33097 36923 33097 32695 33346 32695 33098 32695 33097 36924 33098 36924 33099 36924 33098 36925 33349 36925 33099 36925 33099 36926 33349 36926 33350 36926 33099 36927 33350 36927 33100 36927 33350 32700 33351 32700 33100 32700 33100 32701 33351 32701 33101 32701 33100 36928 33101 36928 33102 36928 33101 32703 33352 32703 33102 32703 33102 32704 33352 32704 33103 32704 33102 36929 33103 36929 33104 36929 33103 36930 33105 36930 33104 36930 33104 32707 33105 32707 33106 32707 33104 36931 33106 36931 33107 36931 33106 36932 33355 36932 33107 36932 33107 32710 33355 32710 33356 32710 33107 36933 33356 36933 33108 36933 33108 32712 33356 32712 33109 32712 33108 32713 33109 32713 33283 32713 33371 36934 33196 36934 33195 36934 33371 36935 33110 36936 33196 36937 33196 32907 33110 32907 33488 32907 33196 36938 33488 36938 33197 36938 33197 36939 33488 36940 33487 36941 33197 36942 33487 36942 33200 36942 33487 32913 33490 32913 33200 32913 33200 36943 33490 36943 33370 36943 33200 36944 33370 36944 33201 36944 33370 36945 33369 36945 33201 36945 33201 36946 33369 36946 33495 36946 33201 36947 33495 36947 33202 36947 33202 36948 33495 36949 33494 36950 33202 36951 33494 36951 33204 36951 33204 36952 33494 36952 33111 36952 33204 36953 33111 36953 33113 36953 33113 36954 33111 36954 33512 36954 33512 36955 33112 36955 33113 36955 33113 36956 33112 36957 33114 36956 33113 36958 33114 36958 33206 36958 33206 36959 33114 36959 33115 36959 33206 36960 33115 36961 33208 36962 33208 36963 33115 36963 33524 36963 33208 36964 33524 36964 33118 36964 33118 36965 33524 36965 33522 36965 33522 32935 33116 32935 33118 32935 33118 36966 33116 36967 33117 36968 33118 36969 33117 36969 33211 36969 33211 36970 33117 36970 33525 36970 33211 36971 33525 36971 33119 36971 33119 36972 33525 36972 33538 36972 33119 36973 33538 36974 33212 36975 33212 36976 33538 36977 33120 36977 33120 36978 33539 36978 33212 36978 33212 36979 33539 36979 33121 36979 33212 36980 33121 36981 33215 36982 33215 36983 33121 36984 33122 36985 33215 36986 33122 36986 33123 36986 33123 36987 33122 36987 33124 36987 33123 36988 33124 36988 33127 36989 33127 36990 33124 36990 33125 36990 33125 36991 33126 36991 33127 36991 33127 36992 33126 36992 33128 36992 33127 36993 33128 36993 33217 36993 33217 36994 33128 36994 33551 36994 33217 36995 33551 36995 33129 36995 33129 36996 33551 36996 33367 36996 33129 36997 33367 36997 33219 36997 33367 36998 33556 36998 33219 36998 33219 32963 33556 32963 33130 32963 33219 36999 33130 36999 33220 36999 33130 37000 33561 37001 33220 37002 33220 37003 33561 37003 33131 37003 33220 37004 33131 37004 33132 37004 33132 37005 33131 37005 33560 37005 33132 37006 33560 37006 33133 37006 33560 37007 33559 37007 33133 37007 33133 37008 33559 37008 33134 37008 33133 37009 33134 37009 33135 37009 33134 32978 33366 32978 33135 32978 33135 37010 33366 37010 33568 37010 33135 37011 33568 37011 33222 37011 33222 37012 33568 37012 33567 37012 33222 37013 33567 37013 33136 37013 33136 37014 33567 37014 33137 37014 33136 37015 33137 37016 33138 37017 33138 37018 33137 37018 33579 37018 33579 37019 33578 37019 33138 37019 33138 37020 33578 37020 33140 37020 33138 37021 33140 37021 33139 37021 33139 37022 33140 37022 33141 37022 33139 37023 33141 37024 33226 37023 33226 37025 33141 37026 33142 37027 33226 32992 33142 32992 33228 32992 33228 37028 33142 37028 33592 37028 33592 37029 33591 37029 33228 37029 33228 37030 33591 37030 33143 37030 33228 32996 33143 32996 33144 32996 33144 37031 33143 37031 33593 37031 33144 37032 33593 37032 33231 37032 33231 37033 33593 37033 33364 37033 33231 33000 33364 33000 33232 33000 33232 37034 33364 37034 33605 37034 33605 37035 33604 37036 33232 37037 33232 33003 33604 33003 33145 33003 33232 37038 33145 37038 33146 37038 33146 37039 33145 37040 33147 37041 33146 37042 33147 37042 33233 37042 33233 33009 33147 33009 33363 33009 33233 33010 33363 33010 33148 33010 33148 37043 33363 37044 33362 37045 33362 37046 33615 37046 33148 37046 33148 37047 33615 37047 33361 37047 33148 37048 33361 37048 33237 37048 33237 37049 33361 37049 33623 37049 33237 37050 33623 37050 33238 37050 33238 37051 33623 37051 33149 37051 33238 37052 33149 37052 33150 37052 33149 37053 33627 37053 33150 37053 33150 37054 33627 37054 33626 37054 33150 37055 33626 37055 33241 37055 33626 37056 33630 37057 33241 37058 33241 32775 33630 32775 33151 32775 33241 37059 33151 37059 33152 37059 33152 37060 33151 37061 33629 37062 33152 37063 33629 37063 33243 37063 33629 32781 33635 32781 33243 32781 33243 37064 33635 37064 33360 37064 33243 37065 33360 37065 33153 37065 33360 37066 33639 37066 33153 37066 33153 37067 33639 37067 33154 37067 33153 37068 33154 37068 33245 37068 33245 37069 33154 37069 33155 37069 33245 37070 33155 37070 33156 37070 33156 37071 33155 37071 33157 37071 33156 37072 33157 37072 33248 37072 33248 37073 33157 37074 33653 37074 33653 37075 33652 37075 33248 37075 33248 37076 33652 37076 33654 37076 33248 37077 33654 37077 33158 37077 33158 37078 33654 37078 33359 37078 33158 37079 33359 37079 33250 37079 33250 37080 33359 37080 33159 37080 33250 37081 33159 37081 33253 37081 33253 37082 33159 37083 33160 37084 33160 32805 33666 32805 33253 32805 33253 37085 33666 37085 33664 37085 33253 37086 33664 37086 33254 37086 33254 37087 33664 37088 33358 37089 33254 37090 33358 37090 33161 37090 33161 37091 33358 37091 33679 37091 33161 37092 33679 37092 33163 37092 33163 37093 33679 37093 33162 37093 33162 37094 33677 37094 33163 37094 33163 37095 33677 37095 33164 37095 33163 37096 33164 37096 33256 37096 33256 37097 33164 37097 33680 37097 33256 37098 33680 37098 33259 37098 33259 37099 33680 37099 33683 37099 33259 37100 33683 37100 33260 37100 33260 37101 33683 37101 33357 37101 33357 37102 33690 37102 33260 37102 33260 37103 33690 37103 33165 37103 33260 37104 33165 37104 33261 37104 33261 37105 33165 37106 33166 37107 33261 37108 33166 37108 33262 37108 33262 37109 33166 37109 33167 37109 33262 37110 33167 37110 33169 37110 33167 37111 33168 37111 33169 37111 33169 32839 33168 32839 33414 32839 33169 37112 33414 37112 33263 37112 33414 37113 33378 37113 33263 37114 33263 37115 33378 37115 33171 37115 33263 37116 33171 37116 33170 37116 33170 37117 33171 37117 33172 37117 33170 37118 33172 37119 33173 37120 33172 37121 33174 37121 33173 37121 33173 37122 33174 37123 33377 37124 33173 37125 33377 37125 33266 37125 33377 32851 33426 32851 33266 32851 33266 37126 33426 37126 33424 37126 33266 37127 33424 37127 33267 37127 33267 37128 33424 37128 33423 37128 33267 37129 33423 37129 33269 37129 33269 37130 33423 37130 33175 37130 33269 37131 33175 37131 33178 37131 33178 37132 33175 37132 33176 37132 33176 37133 33177 37133 33178 37133 33178 37134 33177 37134 33438 37134 33178 37135 33438 37135 33271 37135 33271 37136 33438 37136 33179 37136 33271 37137 33179 37137 33272 37137 33272 37138 33179 37138 33180 37138 33272 32870 33180 32870 33181 32870 33181 37139 33180 37139 33182 37139 33182 37140 33183 37140 33181 37140 33181 37141 33183 37141 33453 37141 33181 32874 33453 32874 33275 32874 33275 32875 33453 32875 33184 32875 33275 32876 33184 32876 33277 32876 33277 37142 33184 37142 33186 37142 33277 32878 33186 32878 33185 32878 33185 37143 33186 37143 33464 37143 33464 37144 33463 37144 33185 37144 33185 32883 33463 32883 33188 32883 33185 37145 33188 37145 33187 37145 33187 37146 33188 37147 33190 37148 33187 37149 33190 37149 33189 37149 33189 32889 33190 32889 33375 32889 33189 32890 33375 32890 33191 32890 33191 37150 33375 37150 33471 37150 33471 37151 33373 37151 33191 37151 33191 37152 33373 37152 33476 37152 33191 37153 33476 37153 33280 37153 33280 37154 33476 37154 33481 37154 33280 37155 33481 37155 33192 37155 33192 37156 33481 37156 33372 37156 33192 37157 33372 37157 33195 37157 33195 37158 33372 37158 33484 37158 33195 37159 33484 37159 33371 37159 33193 37160 33280 37160 33281 37160 33281 37161 33280 37161 33192 37161 33281 33119 33192 33119 33282 33119 33282 37162 33192 37162 33195 37162 33282 37163 33195 37163 33194 37163 33194 37164 33195 37164 33196 37164 33194 37165 33196 37165 33198 37165 33198 37166 33196 37166 33197 37166 33198 37167 33197 37167 33199 37167 33199 37168 33197 37168 33200 37168 33199 37169 33200 37170 33286 37171 33286 33130 33200 33130 33201 33130 33286 37172 33201 37172 33287 37172 33287 37173 33201 37173 33202 37173 33287 33133 33202 33133 33203 33133 33203 33134 33202 33134 33204 33134 33203 37174 33204 37174 33291 37174 33291 37175 33204 37175 33113 37175 33291 37176 33113 37176 33205 37176 33205 37177 33113 37178 33206 37179 33205 37180 33206 37180 33207 37180 33207 37181 33206 37181 33208 37181 33207 37182 33208 37182 33209 37182 33209 37183 33208 37184 33118 37185 33209 33147 33118 33147 33293 33147 33293 37186 33118 37187 33211 37188 33293 37189 33211 37189 33210 37189 33210 33150 33211 33150 33119 33150 33210 37190 33119 37190 33295 37190 33295 33153 33119 33153 33212 33153 33295 37191 33212 37191 33213 37191 33213 33155 33212 33155 33215 33155 33213 37192 33215 37192 33214 37192 33214 37193 33215 37193 33123 37193 33214 37194 33123 37194 33297 37194 33297 37195 33123 37195 33127 37195 33297 37196 33127 37196 33216 37196 33216 37197 33127 37197 33217 37197 33216 37198 33217 37198 33299 37198 33299 37199 33217 37199 33129 37199 33299 37200 33129 37200 33218 37200 33218 37201 33129 37202 33219 37203 33218 37204 33219 37204 33302 37204 33302 37205 33219 37206 33220 37207 33302 37208 33220 37208 33304 37208 33304 37209 33220 37209 33132 37209 33304 37210 33132 37210 33221 37210 33221 37211 33132 37211 33133 37211 33221 37212 33133 37212 33306 37212 33306 33179 33133 33179 33135 33179 33306 37213 33135 37213 33223 37213 33223 37214 33135 37214 33222 37214 33223 37215 33222 37215 33308 37215 33308 37216 33222 37216 33136 37216 33308 37217 33136 37217 33224 37217 33224 37218 33136 37218 33138 37218 33224 37219 33138 37220 33309 37221 33309 37222 33138 37223 33139 37224 33309 37225 33139 37225 33225 37225 33225 37226 33139 37226 33226 37226 33225 37227 33226 37228 33227 37229 33227 37230 33226 37230 33228 37230 33227 37231 33228 37231 33311 37231 33311 37232 33228 37232 33144 37232 33311 37233 33144 37233 33229 37233 33229 37234 33144 37234 33231 37234 33229 37235 33231 37235 33230 37235 33230 37236 33231 37236 33232 37236 33230 37237 33232 37237 33313 37237 33313 37238 33232 37238 33146 37238 33313 33204 33146 33204 33315 33204 33315 33205 33146 33205 33233 33205 33315 33206 33233 33206 33234 33206 33234 33207 33233 33207 33148 33207 33234 37239 33148 37239 33235 37239 33235 33209 33148 33209 33237 33209 33235 37240 33237 37240 33236 37240 33236 37241 33237 37241 33238 37241 33236 33023 33238 33023 33239 33023 33239 37242 33238 37242 33150 37242 33239 37243 33150 37243 33240 37243 33240 37244 33150 37244 33241 37244 33240 37245 33241 37245 33319 37245 33319 37246 33241 37246 33152 37246 33319 37247 33152 37248 33242 37249 33242 37250 33152 37250 33243 37250 33242 37251 33243 37251 33244 37251 33244 33034 33243 33034 33153 33034 33244 37252 33153 37252 33246 37252 33246 37253 33153 37253 33245 37253 33246 33037 33245 33037 33324 33037 33324 33038 33245 33038 33156 33038 33324 37254 33156 37254 33247 37254 33247 37255 33156 37256 33248 37256 33247 37257 33248 37257 33328 37257 33328 37258 33248 37259 33158 37259 33328 37260 33158 37260 33249 37260 33249 37261 33158 37261 33250 37261 33249 37262 33250 37263 33251 37264 33251 37265 33250 37265 33253 37265 33251 33051 33253 33051 33252 33051 33252 37266 33253 37266 33254 37266 33252 37267 33254 37267 33255 37267 33255 33056 33254 33056 33161 33056 33255 37268 33161 37269 33332 37269 33332 33058 33161 33058 33163 33058 33332 37270 33163 37270 33335 37270 33335 33060 33163 33060 33256 33060 33335 37271 33256 37271 33257 37271 33257 37272 33256 37272 33259 37272 33257 37273 33259 37273 33258 37273 33258 37274 33259 37274 33260 37274 33258 37275 33260 37275 33336 37275 33336 37276 33260 37276 33261 37276 33336 37277 33261 37277 33338 37277 33338 37278 33261 37279 33262 37280 33338 37281 33262 37281 33339 37281 33339 37282 33262 37282 33169 37282 33339 37283 33169 37283 33340 37283 33340 37284 33169 37284 33263 37284 33340 37285 33263 37285 33264 37285 33264 37286 33263 37287 33170 37288 33264 37289 33170 37290 33342 37291 33342 37292 33170 37292 33173 37292 33342 37293 33173 37293 33265 37293 33265 33084 33173 33084 33266 33084 33265 37294 33266 37294 33345 37294 33345 37295 33266 37295 33267 37295 33345 37296 33267 37296 33268 37296 33268 37297 33267 37297 33269 37297 33268 37298 33269 37298 33347 37298 33347 37299 33269 37300 33178 37301 33347 37302 33178 37302 33348 37302 33348 37303 33178 37304 33271 37305 33348 37306 33271 37306 33270 37306 33270 37307 33271 37307 33272 37307 33270 37308 33272 37308 33273 37308 33273 37309 33272 37309 33181 37309 33273 37310 33181 37310 33274 37310 33274 37311 33181 37311 33275 37311 33274 37312 33275 37312 33276 37312 33276 37313 33275 37313 33277 37313 33276 37314 33277 37314 33353 37314 33353 37315 33277 37315 33185 37315 33353 37316 33185 37316 33354 37316 33354 37317 33185 37317 33187 37317 33354 33111 33187 33111 33278 33111 33278 33112 33187 33112 33189 33112 33278 33113 33189 33113 33279 33113 33279 33114 33189 33114 33191 33114 33279 37318 33191 37318 33193 37318 33193 33116 33191 33116 33280 33116 33356 37319 33281 37319 33109 37319 33109 37320 33281 37320 33282 37320 33109 37321 33282 37321 33283 37321 33283 37322 33282 37322 33194 37322 33283 37323 33194 37323 33040 37323 33040 37324 33194 37324 33198 37324 33040 37325 33198 37325 33284 37325 33284 33323 33198 33323 33199 33323 33284 37326 33199 37326 33285 37326 33285 37327 33199 37327 33286 37327 33285 37328 33286 37328 33043 37328 33043 37329 33286 37329 33287 37329 33043 37330 33287 37330 33288 37330 33288 37331 33287 37331 33203 37331 33288 37332 33203 37333 33289 37334 33289 37335 33203 37335 33291 37335 33289 37336 33291 37337 33290 37338 33290 37339 33291 37340 33205 37341 33290 37342 33205 37342 33292 37342 33292 37343 33205 37343 33207 37343 33292 37344 33207 37344 33047 37344 33047 37345 33207 37345 33209 37345 33047 37346 33209 37346 33048 37346 33048 37347 33209 37348 33293 37349 33048 37350 33293 37350 33050 37350 33050 37351 33293 37351 33210 37351 33050 37352 33210 37353 33294 37354 33294 37355 33210 37355 33295 37355 33294 37356 33295 37356 33051 37356 33051 37357 33295 37357 33213 37357 33051 37358 33213 37359 33053 37360 33053 37361 33213 37362 33214 37363 33053 37364 33214 37365 33296 37366 33296 33359 33214 33359 33297 33359 33296 37367 33297 37367 33298 37367 33298 37368 33297 37369 33216 37370 33298 37371 33216 37371 33056 37371 33056 37372 33216 37372 33299 37372 33056 37373 33299 37374 33300 37375 33300 37376 33299 37376 33218 37376 33300 37377 33218 37377 33301 37377 33301 37378 33218 37378 33302 37378 33301 37379 33302 37379 33303 37379 33303 37380 33302 37380 33304 37380 33303 37381 33304 37381 33305 37381 33305 37382 33304 37382 33221 37382 33305 37383 33221 37384 33307 37385 33307 37386 33221 37387 33306 37388 33307 37389 33306 37389 33059 37389 33059 37390 33306 37390 33223 37390 33059 37391 33223 37391 33060 37391 33060 33389 33223 33389 33308 33389 33060 37392 33308 37392 33063 37392 33063 33391 33308 33391 33224 33391 33063 37393 33224 37393 33064 37393 33064 33393 33224 33393 33309 33393 33064 37394 33309 37394 33066 37394 33066 37395 33309 37395 33225 37395 33066 37396 33225 37397 33310 37398 33310 37399 33225 37399 33227 37399 33310 37400 33227 37400 33068 37400 33068 37401 33227 37401 33311 37401 33068 37402 33311 37402 33069 37402 33069 37403 33311 37403 33229 37403 33069 37404 33229 37404 33071 37404 33071 37405 33229 37405 33230 37405 33071 37406 33230 37407 33312 37408 33312 37409 33230 37409 33313 37409 33312 37410 33313 37410 33314 37410 33314 37411 33313 37411 33315 37411 33314 37412 33315 37413 33073 37414 33073 37415 33315 37415 33234 37415 33073 37416 33234 37416 33316 37416 33316 33413 33234 33413 33235 33413 33316 37417 33235 37417 33317 37417 33317 33415 33235 33415 33236 33415 33317 37418 33236 37418 33318 37418 33318 37419 33236 37419 33239 37419 33318 37420 33239 37420 33076 37420 33076 37421 33239 37421 33240 37421 33076 37422 33240 37422 33320 37422 33320 37423 33240 37423 33319 37423 33320 37424 33319 37424 33321 37424 33321 33217 33319 33217 33242 33217 33321 37425 33242 37425 33322 37425 33322 37426 33242 37426 33244 37426 33322 37427 33244 37427 33323 37427 33323 37428 33244 37429 33246 37430 33323 37431 33246 37431 33325 37431 33325 37432 33246 37432 33324 37432 33325 37433 33324 37433 33326 37433 33326 37434 33324 37434 33247 37434 33326 37435 33247 37435 33327 37435 33327 37436 33247 37436 33328 37436 33327 37437 33328 37438 33329 37439 33329 37440 33328 37441 33249 37442 33329 37443 33249 37443 33081 37443 33081 37444 33249 37444 33251 37444 33081 37445 33251 37445 33330 37445 33330 37446 33251 37446 33252 37446 33330 37447 33252 37447 33331 37447 33331 37448 33252 37448 33255 37448 33331 37449 33255 37449 33083 37449 33083 37450 33255 37450 33332 37450 33083 37451 33332 37452 33333 37453 33333 37454 33332 37455 33335 37456 33333 37457 33335 37457 33334 37457 33334 37458 33335 37458 33257 37458 33334 37459 33257 37459 33087 37459 33087 33259 33257 33259 33258 33259 33087 37460 33258 37461 33088 37462 33088 37463 33258 37464 33336 37465 33088 37466 33336 37466 33337 37466 33337 37467 33336 37468 33338 37469 33337 37470 33338 37470 33090 37470 33090 37471 33338 37471 33339 37471 33090 37472 33339 37473 33092 37474 33092 37475 33339 37476 33340 37477 33092 37478 33340 37478 33093 37478 33093 37479 33340 37479 33264 37479 33093 37480 33264 37480 33341 37480 33341 37481 33264 37481 33342 37481 33341 37482 33342 37482 33343 37482 33343 37483 33342 37483 33265 37483 33343 37484 33265 37484 33095 37484 33095 37485 33265 37486 33345 37487 33095 37488 33345 37488 33344 37488 33344 33285 33345 33285 33268 33285 33344 37489 33268 37489 33346 37489 33346 33287 33268 33287 33347 33287 33346 37490 33347 37490 33098 37490 33098 33289 33347 33289 33348 33289 33098 37491 33348 37491 33349 37491 33349 37492 33348 37492 33270 37492 33349 37493 33270 37493 33350 37493 33350 37494 33270 37494 33273 37494 33350 37495 33273 37495 33351 37495 33351 37496 33273 37496 33274 37496 33351 37497 33274 37497 33101 37497 33101 37498 33274 37498 33276 37498 33101 37499 33276 37499 33352 37499 33352 37500 33276 37500 33353 37500 33352 37501 33353 37501 33103 37501 33103 37502 33353 37502 33354 37502 33103 37503 33354 37503 33105 37503 33105 37504 33354 37505 33278 37506 33105 37507 33278 37507 33106 37507 33106 37508 33278 37508 33279 37508 33106 37509 33279 37509 33355 37509 33355 33313 33279 33313 33193 33313 33355 37510 33193 37510 33356 37510 33356 33315 33193 33315 33281 33315 33690 37511 33357 37511 33691 37511 33683 37512 33680 37512 33684 37512 33679 37513 33358 37513 33667 37513 33159 37514 33359 37514 33663 37514 33639 37515 33360 37515 33640 37515 33630 33440 33626 33440 33631 33440 33627 37516 33149 37516 33628 37516 33623 33442 33361 33442 33616 33442 33615 37517 33362 37517 33610 37517 33363 37518 33147 37518 33611 37518 33364 37519 33593 37519 33595 37519 33142 37520 33141 37520 33365 37520 33366 37521 33134 37521 33564 37521 33561 37522 33130 37523 33555 37524 33556 37525 33367 37525 33557 37525 33551 37526 33128 37526 33552 37526 33126 37527 33125 37527 33548 37527 33124 37528 33122 37528 33540 37528 33538 37529 33525 37529 33368 37529 33524 37530 33115 37530 33513 37530 33369 37531 33370 37531 33497 37532 33110 33421 33371 33421 33485 33421 33484 37533 33372 37533 33486 37533 33481 33423 33476 33423 33477 33423 33373 37534 33471 37534 33374 37534 33375 37535 33190 37535 33465 37535 33186 37536 33184 37536 33376 37536 33180 37537 33179 37537 33451 37537 33426 37538 33377 37538 33427 37538 33378 37539 33414 37540 33416 37541 33168 37542 33167 37542 33415 37542 33166 37543 33165 37543 33412 37543 33036 37544 33039 37544 33646 37544 33379 37545 33447 37545 33445 37545 33508 37546 33380 37546 33509 37546 33575 37547 33696 37547 33584 37547 33585 37548 33586 37548 33381 37548 33382 37549 33575 37549 33383 37549 33030 37550 33384 37550 33385 37550 33385 37551 33384 37551 33545 37551 33385 37552 33545 37552 33386 37552 33030 37553 33385 37553 33031 37553 33031 37554 33385 37554 33386 37554 33031 37555 33386 37555 33032 37555 33542 37556 33387 37556 33388 37556 33388 37557 33387 37557 33547 37557 33517 37558 33518 37558 33516 37558 33500 37559 33508 37559 33499 37559 33391 37560 33390 37561 33389 37562 33389 37563 33390 37563 33479 37563 33389 37564 33479 37564 33474 37564 33391 37565 33389 37565 33392 37565 33392 37566 33389 37566 33474 37566 33392 37567 33474 37567 33393 37567 33469 37568 33394 37568 33395 37568 33395 37569 33394 37569 33475 37569 33446 37570 33448 37570 33443 37570 33430 37571 33379 37572 33429 37573 33398 37574 33396 37574 33397 37574 33397 37575 33396 37576 33686 37577 33397 37578 33686 37578 33400 37578 33398 37579 33397 37580 33399 37581 33399 37582 33397 37582 33400 37582 33399 37583 33400 37583 33688 37583 33401 37584 33402 37584 33403 37584 33403 37585 33402 37585 33689 37585 33657 37586 33658 37586 33656 37586 33404 37587 33036 37588 33405 37589 33406 37590 33622 37590 33407 37590 33407 37591 33622 37592 33621 37593 33407 37594 33621 37594 33613 37594 33406 37595 33407 37596 33408 37597 33408 37598 33407 37598 33613 37598 33408 37599 33613 37599 33409 37599 33609 37600 33410 37600 33614 37600 33614 37601 33410 37601 33411 37601 33167 33772 33166 33772 33415 33772 33415 37602 33166 37602 33412 37602 33415 37603 33412 37603 33417 37603 33417 37604 33412 37604 33692 37604 33417 37605 33692 37605 33434 37605 33434 37606 33692 37606 33413 37606 33414 37607 33168 37607 33416 37607 33416 37608 33168 37608 33415 37608 33416 37609 33415 37609 33421 37609 33421 37610 33415 37610 33417 37610 33421 37611 33417 37611 33431 37611 33431 37612 33417 37612 33434 37612 33174 37613 33172 37613 33418 37613 33418 37614 33172 37614 33171 37614 33171 37615 33378 37615 33418 37615 33418 37616 33378 37616 33416 37616 33418 37617 33416 37617 33419 37617 33419 37618 33416 37618 33421 37618 33419 37619 33421 37619 33420 37619 33420 33791 33421 33791 33431 33791 33377 37620 33174 37620 33427 37620 33427 37621 33174 37621 33418 37621 33427 37622 33418 37622 33428 37622 33428 33795 33418 33795 33419 33795 33428 37623 33419 37623 33422 37623 33422 37624 33419 37624 33420 37624 33175 37625 33423 37625 33425 37625 33425 37626 33423 37626 33424 37626 33424 37627 33426 37627 33425 37627 33425 37628 33426 37628 33427 37628 33425 37629 33427 37629 33437 37629 33437 37630 33427 37630 33428 37630 33437 37631 33428 37631 33429 37631 33429 33805 33428 33805 33422 33805 33429 37632 33422 37632 33430 37632 33430 37633 33422 37633 33420 37633 33430 37634 33420 37634 33432 37634 33432 33809 33420 33809 33431 33809 33432 37635 33431 37635 33433 37635 33433 37636 33431 37636 33434 37636 33433 37637 33434 37637 33435 37637 33435 37638 33434 37638 33413 37638 33435 37639 33413 37639 33436 37639 33436 37640 33413 37640 33693 37640 33379 37641 33445 37641 33429 37641 33429 37642 33445 37642 33444 37642 33429 37643 33444 37643 33437 37643 33437 37644 33444 37644 33440 37644 33437 37645 33440 37645 33425 37645 33425 37646 33440 37646 33439 37646 33425 37647 33439 37647 33175 37647 33438 37648 33177 37648 33439 37648 33439 37649 33177 37649 33176 37649 33439 37650 33176 37650 33175 37650 33179 37651 33438 37651 33451 37651 33451 37652 33438 37652 33439 37652 33451 37653 33439 37653 33441 37653 33441 33830 33439 33830 33440 33830 33441 33831 33440 33831 33442 33831 33442 37654 33440 37654 33444 37654 33442 37655 33444 37655 33443 37655 33443 37656 33444 37656 33445 37656 33443 37657 33445 37657 33446 37657 33446 37658 33445 37658 33447 37658 33448 37659 33449 37659 33443 37659 33443 37660 33449 37660 33457 37660 33443 37661 33457 37661 33442 37661 33442 37662 33457 37662 33455 37662 33442 37663 33455 37663 33441 37663 33441 37664 33455 37664 33450 37664 33441 37665 33450 37665 33451 37665 33451 37666 33450 37666 33452 37666 33451 37667 33452 37667 33180 37667 33453 37668 33183 37668 33452 37668 33452 37669 33183 37669 33182 37669 33452 37670 33182 37670 33180 37670 33184 33851 33453 33851 33376 33851 33376 37671 33453 37671 33452 37671 33376 37672 33452 37672 33462 37672 33462 37673 33452 37673 33450 37673 33462 37674 33450 37674 33454 37674 33454 37675 33450 37675 33455 37675 33454 37676 33455 37676 33456 37676 33456 37677 33455 37677 33457 37677 33456 37678 33457 37678 33459 37678 33459 37679 33457 37679 33449 37679 33459 37680 33449 37680 33458 37680 33459 37681 33470 37681 33456 37681 33456 37682 33470 37682 33460 37682 33456 37683 33460 37683 33454 37683 33454 33865 33460 33865 33461 33865 33454 33866 33461 33866 33462 33866 33462 37684 33461 37684 33468 37684 33462 37685 33468 37685 33376 37685 33376 37686 33468 37686 33467 37686 33376 33870 33467 33870 33186 33870 33188 37687 33463 37687 33467 37687 33467 37688 33463 37688 33464 37688 33467 37689 33464 37689 33186 37689 33190 33874 33188 33875 33465 33876 33465 37690 33188 37690 33467 37690 33465 33878 33467 33878 33466 33878 33466 37691 33467 37691 33468 37691 33466 37692 33468 37692 33473 37692 33473 37693 33468 37693 33461 37693 33473 37694 33461 37694 33395 37694 33395 33883 33461 33883 33460 33883 33395 37695 33460 37695 33469 37695 33469 37696 33460 37696 33470 37696 33471 37697 33375 37697 33374 37697 33374 33887 33375 33887 33465 33887 33374 37698 33465 37698 33472 37698 33472 37699 33465 37699 33466 37699 33472 37700 33466 37700 33479 37700 33479 33891 33466 33891 33473 33891 33479 33892 33473 33892 33474 33892 33474 37701 33473 37701 33395 37701 33474 33894 33395 33894 33393 33894 33393 37702 33395 37702 33475 37702 33476 37703 33373 37703 33477 37703 33477 37704 33373 37704 33374 37704 33477 37705 33374 37705 33478 37705 33478 37706 33374 37706 33472 37706 33478 33900 33472 33900 33483 33900 33483 33901 33472 33901 33479 33901 33483 37707 33479 37707 33480 37707 33480 37708 33479 37708 33390 37708 33372 37709 33481 37709 33486 37709 33486 37710 33481 37710 33477 37710 33486 37711 33477 37711 33482 37711 33482 37712 33477 37712 33478 37712 33482 33908 33478 33908 33506 33908 33506 33909 33478 33909 33483 33909 33371 37713 33484 37713 33485 37713 33485 33911 33484 33911 33486 33911 33485 37714 33486 37714 33489 37714 33489 33913 33486 33913 33482 33913 33489 37715 33482 37715 33502 37715 33502 37716 33482 37716 33506 37716 33490 37717 33487 37717 33491 37717 33491 37718 33487 37718 33488 37718 33488 37719 33110 37719 33491 37719 33491 37720 33110 37720 33485 37720 33491 33920 33485 33920 33493 33920 33493 33921 33485 33921 33489 33921 33493 33922 33489 33922 33501 33922 33501 33923 33489 33923 33502 33923 33370 37721 33490 37721 33497 37721 33497 37722 33490 37722 33491 37722 33497 37723 33491 37723 33492 37723 33492 33927 33491 33927 33493 33927 33492 37724 33493 37724 33498 37724 33498 37725 33493 37725 33501 37725 33111 33930 33494 33930 33496 33930 33496 37726 33494 37726 33495 37726 33495 33932 33369 33932 33496 33932 33496 37727 33369 37727 33497 37727 33496 37728 33497 37728 33510 37728 33510 37729 33497 37729 33492 37729 33510 37730 33492 37730 33499 37730 33499 37731 33492 37731 33498 37731 33499 37732 33498 37732 33500 37732 33500 37733 33498 37733 33501 37733 33500 37734 33501 37734 33503 37734 33503 37735 33501 37735 33502 37735 33503 37736 33502 37736 33504 37736 33504 37737 33502 37737 33506 37737 33504 37738 33506 37738 33505 37738 33505 37739 33506 37739 33483 37739 33505 37740 33483 37740 33507 37740 33507 37741 33483 37742 33480 37743 33508 37744 33509 37744 33499 37744 33499 37745 33509 37745 33515 37745 33499 37746 33515 37746 33510 37746 33510 33952 33515 33952 33511 33952 33510 37747 33511 37747 33496 37747 33496 37748 33511 37748 33514 37748 33496 37749 33514 37749 33111 37749 33114 37750 33112 37750 33514 37750 33514 37751 33112 37751 33512 37751 33514 37752 33512 37752 33111 37752 33115 37753 33114 37753 33513 37753 33513 37754 33114 37754 33514 37754 33513 37755 33514 37755 33520 37755 33520 37756 33514 37756 33511 37756 33520 37757 33511 37757 33519 37757 33519 33965 33511 33965 33515 33965 33519 33966 33515 33966 33516 33966 33516 37758 33515 37758 33509 37758 33516 37759 33509 37759 33517 37759 33517 37760 33509 37761 33380 37762 33518 37763 33530 37763 33516 37763 33516 37764 33530 37764 33529 37764 33516 37765 33529 37765 33519 37765 33519 33973 33529 33973 33527 33973 33519 33974 33527 33974 33520 33974 33520 37766 33527 37766 33521 37766 33520 37767 33521 37767 33513 37767 33513 37768 33521 37768 33523 37768 33513 37769 33523 37769 33524 37769 33117 37770 33116 37770 33523 37770 33523 37771 33116 37771 33522 37771 33523 33981 33522 33981 33524 33981 33525 37772 33117 37773 33368 37774 33368 37775 33117 37775 33523 37775 33368 37776 33523 37776 33535 37776 33535 37777 33523 37777 33521 37777 33535 33986 33521 33986 33526 33986 33526 37778 33521 37778 33527 37778 33526 37779 33527 37779 33528 37779 33528 37780 33527 37780 33529 37780 33528 37781 33529 37781 33532 37781 33532 37782 33529 37782 33530 37782 33532 37783 33530 37783 33531 37783 33532 37784 33533 37784 33528 37784 33528 33996 33533 33996 33534 33996 33528 37785 33534 37785 33526 37785 33526 37786 33534 37786 33541 37786 33526 37787 33541 37787 33535 37787 33535 37788 33541 37788 33536 37788 33535 37789 33536 37789 33368 37789 33368 37790 33536 37790 33537 37790 33368 34003 33537 34003 33538 34003 33121 37791 33539 37791 33537 37791 33537 37792 33539 37792 33120 37792 33537 37793 33120 37793 33538 37793 33122 37794 33121 37794 33540 37794 33540 37795 33121 37795 33537 37795 33540 34009 33537 34009 33544 34009 33544 37796 33537 37796 33536 37796 33544 37797 33536 37797 33546 37797 33546 37798 33536 37798 33541 37798 33546 37799 33541 37799 33388 37799 33388 37800 33541 37800 33534 37800 33388 34015 33534 34015 33542 34015 33542 34016 33534 34016 33533 34016 33125 34017 33124 34017 33548 34017 33548 37801 33124 37801 33540 37801 33548 37802 33540 37802 33543 37802 33543 37803 33540 37803 33544 37803 33543 37804 33544 37804 33545 37804 33545 37805 33544 37805 33546 37805 33545 37806 33546 37806 33386 37806 33386 34024 33546 34024 33388 34024 33386 34025 33388 34025 33032 34025 33032 37807 33388 37807 33547 37807 33128 37808 33126 37808 33552 37808 33552 37809 33126 37809 33548 37809 33552 37810 33548 37810 33553 37810 33553 37811 33548 37811 33543 37811 33553 37812 33543 37812 33549 37812 33549 37813 33543 37813 33545 37813 33549 37814 33545 37814 33550 37814 33550 34034 33545 34034 33384 34034 33367 33509 33551 33509 33557 33509 33557 37815 33551 37815 33552 37815 33557 37816 33552 37816 33554 37816 33554 37817 33552 37817 33553 37817 33554 37818 33553 37818 33558 37818 33558 37819 33553 37819 33549 37819 33130 37820 33556 37820 33555 37820 33555 37821 33556 37821 33557 37821 33555 37822 33557 37822 33562 37822 33562 37823 33557 37823 33554 37823 33562 37824 33554 37824 33572 37824 33572 37825 33554 37825 33558 37825 33559 37826 33560 37826 33563 37826 33563 37827 33560 37827 33131 37827 33131 37828 33561 37828 33563 37828 33563 37829 33561 37829 33555 37829 33563 37830 33555 37830 33565 37830 33565 37831 33555 37831 33562 37831 33565 37832 33562 37832 33566 37832 33566 33528 33562 33528 33572 33528 33134 37833 33559 37833 33564 37833 33564 37834 33559 37834 33563 37834 33564 37835 33563 37835 33569 37835 33569 33532 33563 33532 33565 33532 33569 37836 33565 37836 33570 37836 33570 37837 33565 37837 33566 37837 33137 37838 33567 37838 33577 37838 33577 37839 33567 37839 33568 37839 33568 37840 33366 37840 33577 37840 33577 37841 33366 37841 33564 37841 33577 37842 33564 37842 33576 37842 33576 37843 33564 37843 33569 37843 33576 37844 33569 37844 33383 37844 33383 33542 33569 33542 33570 33542 33383 37845 33570 37845 33382 37845 33382 37846 33570 37846 33566 37846 33382 37847 33566 37847 33571 37847 33571 33546 33566 33546 33572 33546 33571 37848 33572 37848 33704 37848 33704 37849 33572 37849 33558 37849 33704 37850 33558 37850 33573 37850 33573 37851 33558 37851 33549 37851 33573 37852 33549 37852 33574 37852 33574 37853 33549 37853 33550 37853 33575 37854 33584 37854 33383 37854 33383 37855 33584 37855 33583 37855 33383 37856 33583 37856 33576 37856 33576 37857 33583 37857 33581 37857 33576 37858 33581 37858 33577 37858 33577 37859 33581 37859 33580 37859 33577 37860 33580 37860 33137 37860 33140 37861 33578 37861 33580 37861 33580 37862 33578 37862 33579 37862 33580 37863 33579 37863 33137 37863 33141 37864 33140 37864 33365 37864 33365 37865 33140 37865 33580 37865 33365 37866 33580 37866 33589 37866 33589 33567 33580 33567 33581 33567 33589 33568 33581 33568 33582 33568 33582 37867 33581 37867 33583 37867 33582 37868 33583 37868 33381 37868 33381 37869 33583 37869 33584 37869 33381 37870 33584 37870 33585 37870 33585 37871 33584 37872 33696 37873 33586 37874 33598 37874 33381 37874 33381 37875 33598 37875 33587 37875 33381 37876 33587 37876 33582 37876 33582 37877 33587 37877 33588 37877 33582 37878 33588 37878 33589 37878 33589 37879 33588 37879 33590 37879 33589 37880 33590 37880 33365 37880 33365 37881 33590 37881 33594 37881 33365 37882 33594 37882 33142 37882 33143 37883 33591 37883 33594 37883 33594 37884 33591 37884 33592 37884 33594 37885 33592 37885 33142 37885 33593 37886 33143 37886 33595 37886 33595 37887 33143 37887 33594 37887 33595 37888 33594 37888 33596 37888 33596 37889 33594 37889 33590 37889 33596 37890 33590 37890 33602 37890 33602 37891 33590 37891 33588 37891 33602 37892 33588 37892 33597 37892 33597 37893 33588 37893 33587 37893 33597 37894 33587 37894 33599 37894 33599 37895 33587 37895 33598 37895 33599 37896 33598 37896 33697 37896 33599 37897 33600 37897 33597 37897 33597 37898 33600 37898 33608 37898 33597 37899 33608 37899 33602 37899 33602 33600 33608 33600 33601 33600 33602 33601 33601 33601 33596 33601 33596 37900 33601 37900 33603 37900 33596 37901 33603 37901 33595 37901 33595 37902 33603 37902 33606 37902 33595 33605 33606 33605 33364 33605 33145 37903 33604 37903 33606 37903 33606 37904 33604 37904 33605 37904 33606 37905 33605 37905 33364 37905 33147 33609 33145 33610 33611 33611 33611 37906 33145 37906 33606 37906 33611 33613 33606 33613 33612 33613 33612 37907 33606 37907 33603 37907 33612 37908 33603 37908 33607 37908 33607 37909 33603 37909 33601 37909 33607 37910 33601 37910 33614 37910 33614 33618 33601 33618 33608 33618 33614 37911 33608 37911 33609 37911 33609 37912 33608 37912 33600 37912 33362 37913 33363 37913 33610 37913 33610 33622 33363 33622 33611 33622 33610 37914 33611 37914 33617 37914 33617 37915 33611 37915 33612 37915 33617 37916 33612 37916 33621 37916 33621 33626 33612 33626 33607 33626 33621 33627 33607 33627 33613 33627 33613 37917 33607 37917 33614 37917 33613 33629 33614 33629 33409 33629 33409 37918 33614 37918 33411 37918 33361 37919 33615 37919 33616 37919 33616 37920 33615 37920 33610 37920 33616 37921 33610 37921 33618 37921 33618 37922 33610 37922 33617 37922 33618 33635 33617 33635 33619 33635 33619 33636 33617 33636 33621 33636 33619 37923 33621 37923 33620 37923 33620 37924 33621 37924 33622 37924 33149 37925 33623 37925 33628 37925 33628 37926 33623 37926 33616 37926 33628 37927 33616 37927 33624 37927 33624 37928 33616 37928 33618 37928 33624 33643 33618 33643 33625 33643 33625 33644 33618 33644 33619 33644 33626 37929 33627 37929 33631 37929 33631 33646 33627 33646 33628 33646 33631 37930 33628 37930 33633 37930 33633 33648 33628 33648 33624 33648 33633 37931 33624 37931 33634 37931 33634 37932 33624 37932 33625 37932 33635 37933 33629 37933 33636 37933 33636 37934 33629 37934 33151 37934 33151 37935 33630 37935 33636 37935 33636 37936 33630 37936 33631 37936 33636 33655 33631 33655 33632 33655 33632 33656 33631 33656 33633 33656 33632 33657 33633 33657 33638 33657 33638 33658 33633 33658 33634 33658 33360 37937 33635 37937 33640 37937 33640 37938 33635 37938 33636 37938 33640 37939 33636 37939 33641 37939 33641 33662 33636 33662 33632 33662 33641 37940 33632 37940 33637 37940 33637 37941 33632 37941 33638 37941 33157 33665 33155 33665 33651 33665 33651 37942 33155 37942 33154 37942 33154 33667 33639 33667 33651 33667 33651 37943 33639 37943 33640 37943 33651 37944 33640 37944 33648 37944 33648 37945 33640 37945 33641 37945 33648 37946 33641 37946 33405 37946 33405 37947 33641 37947 33637 37947 33405 37948 33637 37948 33404 37948 33404 37949 33637 37949 33638 37949 33404 37950 33638 37950 33642 37950 33642 37951 33638 37951 33634 37951 33642 37952 33634 37952 33643 37952 33643 37953 33634 37953 33625 37953 33643 37954 33625 37954 33644 37954 33644 37955 33625 37955 33619 37955 33644 37956 33619 37956 33645 37956 33645 37957 33619 37958 33620 37957 33036 37959 33646 37959 33405 37959 33405 37960 33646 37960 33647 37960 33405 37961 33647 37961 33648 37961 33648 33688 33647 33688 33649 33688 33648 37962 33649 37962 33651 37962 33651 37963 33649 37963 33650 37963 33651 37964 33650 37964 33157 37964 33654 37965 33652 37965 33650 37965 33650 37966 33652 37966 33653 37966 33650 37967 33653 37967 33157 37967 33359 37968 33654 37968 33663 37969 33663 37970 33654 37970 33650 37970 33663 37971 33650 37971 33655 37971 33655 37972 33650 37972 33649 37972 33655 37973 33649 37973 33661 37973 33661 33700 33649 33700 33647 33700 33661 33701 33647 33701 33656 33701 33656 37974 33647 37974 33646 37974 33656 37975 33646 37975 33657 37975 33657 37976 33646 37976 33039 37976 33658 37977 33659 37977 33656 37977 33656 37978 33659 37978 33660 37978 33656 37979 33660 37979 33661 37979 33661 37980 33660 37980 33662 37980 33661 33711 33662 33711 33655 33711 33655 37981 33662 37981 33669 37981 33655 37982 33669 37982 33663 37982 33663 37983 33669 37983 33665 37983 33663 37984 33665 37984 33159 37984 33664 37985 33666 37985 33665 37985 33665 37986 33666 37986 33160 37986 33665 33718 33160 33718 33159 33718 33358 37987 33664 37987 33667 37987 33667 37988 33664 37988 33665 37988 33667 37989 33665 37989 33668 37989 33668 37990 33665 37990 33669 37990 33668 33725 33669 33725 33670 33725 33670 37991 33669 37991 33662 37991 33670 37992 33662 37992 33671 37992 33671 37993 33662 37993 33660 37993 33671 37994 33660 37994 33672 37994 33672 37995 33660 37995 33659 37995 33672 37996 33659 37997 33673 37998 33672 37999 33674 37999 33671 37999 33671 33733 33674 33733 33682 33733 33671 38000 33682 38000 33670 38000 33670 38001 33682 38001 33675 38001 33670 38002 33675 38002 33668 38002 33668 38003 33675 38003 33676 38003 33668 38004 33676 38004 33667 38004 33667 38005 33676 38005 33678 38005 33667 33740 33678 33740 33679 33740 33164 38006 33677 38006 33678 38006 33678 38007 33677 38007 33162 38007 33678 38008 33162 38008 33679 38008 33680 38009 33164 38009 33684 38009 33684 38010 33164 38010 33678 38010 33684 33746 33678 33746 33687 33746 33687 38011 33678 38011 33676 38011 33687 38012 33676 38012 33681 38012 33681 38013 33676 38013 33675 38013 33681 38014 33675 38014 33403 38014 33403 38015 33675 38015 33682 38015 33403 33752 33682 33752 33401 33752 33401 33753 33682 33753 33674 33753 33357 33754 33683 33754 33691 33754 33691 38016 33683 38016 33684 38016 33691 38017 33684 38017 33685 38017 33685 38018 33684 38018 33687 38018 33685 38019 33687 38019 33686 38019 33686 38020 33687 38020 33681 38020 33686 38021 33681 38021 33400 38021 33400 33761 33681 33761 33403 33761 33400 33762 33403 33762 33688 33762 33688 38022 33403 38022 33689 38022 33165 38023 33690 38023 33412 38023 33412 38024 33690 38024 33691 38024 33412 38025 33691 38025 33692 38025 33692 38026 33691 38026 33685 38026 33692 38027 33685 38027 33413 38027 33413 38028 33685 38028 33686 38028 33413 38029 33686 38029 33693 38029 33693 33771 33686 33771 33396 33771 33575 38030 33701 38030 33694 38030 33694 38031 33695 38031 33575 38031 33575 38032 33695 38032 33698 38032 33575 38033 33698 38033 33696 38033 33698 38034 33697 38034 33598 38034 33598 38035 33586 38035 33698 38035 33698 38036 33586 38036 33585 38036 33698 38037 33585 38037 33696 38037 33028 38038 33699 38038 33550 38038 33550 38039 33699 38039 33703 38039 33550 38040 33703 38040 33574 38040 33700 38041 33701 38042 33702 38043 33702 38044 33701 38044 33575 38044 33702 38045 33575 38045 33382 38045 33382 38046 33571 38046 33702 38046 33702 38047 33571 38047 33704 38047 33702 38048 33704 38049 33703 38048 33703 38050 33704 38050 33573 38050 33703 38051 33573 38051 33574 38051 33705 38052 33707 38052 33706 38052 33706 38053 33707 38053 33709 38053 33706 38053 33709 38053 33708 38053 33708 38054 33709 38054 33710 38054 33708 38055 33710 38055 33711 38055 33711 38056 33710 38056 33712 38056 33711 38057 33712 38057 33714 38057 33714 38058 33712 38058 33713 38058 33714 38059 33713 38059 33715 38059 33715 38060 33713 38060 33717 38060 33715 38061 33717 38061 33716 38061 33716 38062 33717 38062 33718 38062 33716 38063 33718 38063 33719 38063 33719 38064 33718 38064 33720 38064 33719 38065 33720 38065 33721 38065 33721 38066 33720 38066 33723 38066 33721 38067 33723 38067 33722 38067 33722 38068 33723 38068 33724 38068 33722 38069 33724 38069 33725 38069 33725 38070 33724 38070 33726 38070 33725 38070 33726 38070 33727 38070 33727 38071 33726 38071 33728 38071 33727 38072 33728 38072 33730 38072 33730 38073 33728 38073 33729 38073 33730 38073 33729 38073 33732 38073 33732 38074 33729 38074 33731 38074 33732 38075 33731 38075 33733 38075 33733 38076 33731 38076 33734 38076 33733 38077 33734 38077 33735 38077 33735 38078 33734 38078 33737 38078 33735 38079 33737 38079 33736 38079 33736 38080 33737 38080 33738 38080 33736 38081 33738 38081 33739 38081 33739 38082 33738 38082 33740 38082 33739 38083 33740 38083 33741 38083 33741 38084 33740 38084 33742 38084 33741 38084 33742 38084 33743 38084 33743 38085 33742 38085 33744 38085 33743 38086 33744 38086 33745 38086 33745 38087 33744 38087 33746 38087 33745 38088 33746 38088 33748 38088 33748 38089 33746 38089 33747 38089 33748 38090 33747 38090 33749 38090 33749 38091 33747 38091 33751 38091 33749 38092 33751 38092 33750 38092 33750 38093 33751 38093 33753 38093 33750 38093 33753 38093 33752 38093 33752 38094 33753 38094 33754 38094 33752 38095 33754 38095 33755 38095 33755 38096 33754 38096 33756 38096 33755 38097 33756 38097 33758 38097 33758 38098 33756 38098 33757 38098 33758 38099 33757 38099 33705 38099 33705 38100 33757 38100 33707 38100 34113 38101 33759 38101 33760 38101 33760 38102 33761 38102 34113 38102 34113 38103 33761 38103 33762 38103 34113 38104 33762 38104 33766 38104 33762 38105 34338 38105 33763 38105 33763 38106 33764 38106 33762 38106 33762 38107 33764 38107 33765 38107 33762 38108 33765 38109 33766 38110 33767 38111 33768 38111 33770 38111 33770 38112 33768 38112 33769 38112 33770 38113 33769 38113 33772 38113 33772 38114 33769 38114 33771 38114 33772 38115 33771 38116 34115 38117 34115 38118 34116 38119 33772 38120 33772 38121 34116 38121 34118 38121 33772 38122 34118 38122 33773 38122 33776 38123 33855 38123 33774 38123 33774 38124 33775 38124 33776 38124 33776 38125 33775 38125 34021 38125 33776 38126 34021 38126 33777 38126 34021 38127 34022 38127 33777 38127 33777 38128 34022 38128 33778 38128 33777 38129 33778 38129 33779 38129 33778 38130 34023 38130 33779 38130 33779 34205 34023 34205 33781 34205 33779 38131 33781 38131 33780 38131 33781 38132 33782 38132 33780 38132 33780 38133 33782 38133 33783 38133 33780 38134 33783 38134 33785 38134 33783 38135 33784 38135 33785 38135 33785 34211 33784 34211 34028 34211 33785 38136 34028 38136 33786 38136 34028 34213 33787 34213 33786 34213 33786 38137 33787 38137 33788 38137 33786 38138 33788 38138 33789 38138 33788 38139 33790 38139 33789 38139 33789 38140 33790 38140 33791 38140 33789 38141 33791 38141 33792 38141 33791 38142 34030 38142 33792 38142 33792 34220 34030 34220 34031 34220 33792 38143 34031 38143 33794 38143 34031 38144 33793 38144 33794 38144 33794 38145 33793 38145 33795 38145 33794 38146 33795 38146 33796 38146 33795 38147 34033 38147 33796 38147 33796 38148 34033 38148 33798 38148 33796 38149 33798 38149 33797 38149 33798 38150 33799 38150 33797 38150 33797 38151 33799 38151 34035 38151 33797 38152 34035 38152 33801 38152 34035 38153 33800 38153 33801 38153 33801 38154 33800 38154 34036 38154 33801 38155 34036 38155 33802 38155 34036 38156 34038 38156 33802 38156 33802 38157 34038 38157 34040 38157 33802 38158 34040 38158 33804 38158 34040 38159 33803 38159 33804 38159 33804 38160 33803 38160 34042 38160 33804 38161 34042 38161 33805 38161 34042 38162 34044 38162 33805 38162 33805 34241 34044 34241 33806 34241 33805 38163 33806 38163 33808 38163 33806 38164 33807 38164 33808 38164 33808 38165 33807 38165 34046 38165 33808 38166 34046 38166 33809 38166 34046 38167 33810 38167 33809 38167 33809 34247 33810 34247 33811 34247 33809 38168 33811 38168 33814 38168 33811 38169 33812 38169 33814 38169 33814 38170 33812 38170 33813 38170 33814 38171 33813 38171 33816 38171 33813 34252 33815 34252 33816 34252 33816 38172 33815 38172 33817 38172 33816 38173 33817 38173 33818 38173 33817 38174 33819 38174 33818 38174 33818 38175 33819 38175 33820 38175 33818 38176 33820 38176 33822 38176 33820 38177 33821 38177 33822 38177 33822 38178 33821 38178 34054 38178 33822 38179 34054 38179 33823 38179 34054 38180 34056 38180 33823 38180 33823 34148 34056 34148 33824 34148 33823 38181 33824 38181 33825 38181 33824 38182 34058 38182 33825 38182 33825 38183 34058 38183 33826 38183 33825 38184 33826 38184 33827 38184 33826 38185 33828 38185 33827 38185 33827 34154 33828 34154 34061 34154 33827 38186 34061 38186 33830 38186 34061 34156 33829 34156 33830 34156 33830 38187 33829 38187 34064 38187 33830 38188 34064 38188 33832 38188 34064 38189 33831 38189 33832 38189 33832 38190 33831 38190 34066 38190 33832 38191 34066 38191 33833 38191 34066 38192 34068 38192 33833 38192 33833 34163 34068 34163 33834 34163 33833 38193 33834 38193 33835 38193 33834 38194 34069 38194 33835 38194 33835 38195 34069 38195 33836 38195 33835 38196 33836 38196 33837 38196 33836 38197 34071 38197 33837 38197 33837 38198 34071 38198 34072 38198 33837 38199 34072 38199 33838 38199 34072 38200 34073 38200 33838 38200 33838 38201 34073 38201 33839 38201 33838 38202 33839 38202 33841 38202 33839 38203 33840 38203 33841 38203 33841 38204 33840 38204 33843 38204 33841 38205 33843 38205 33842 38205 33843 38206 33844 38206 33842 38206 33842 38207 33844 38207 33845 38207 33842 38208 33845 38208 33847 38208 33845 38209 33846 38209 33847 38209 33847 38210 33846 38210 34079 38210 33847 38211 34079 38211 33848 38211 34079 38212 34080 38212 33848 38212 33848 34184 34080 34184 34082 34184 33848 38213 34082 38213 33849 38213 34082 38214 34084 38214 33849 38214 33849 38215 34084 38215 34085 38215 33849 38216 34085 38216 33850 38216 34085 38217 33851 38217 33850 38217 33850 34190 33851 34190 34089 34190 33850 38218 34089 38218 33852 38218 34089 38219 34090 38219 33852 38219 33852 38220 34090 38220 33853 38220 33852 38221 33853 38221 33855 38221 33855 34195 33853 34195 33854 34195 33855 38222 33854 38222 33774 38222 33856 38223 33947 38223 33946 38223 33856 38224 34229 38224 33947 38224 33947 38225 34229 38225 34228 38225 33947 38226 34228 38226 33948 38226 33948 38227 34228 38228 33857 38229 33948 38230 33857 38230 33858 38230 33857 38231 34235 38231 33858 38231 33858 34386 34235 34386 33859 34386 33858 38232 33859 38232 33860 38232 33859 38233 34102 38234 33860 38235 33860 38236 34102 38236 34239 38236 33860 38237 34239 38237 33861 38237 33861 38238 34239 38238 34238 38238 33861 38239 34238 38239 33862 38239 33862 38240 34238 38240 34237 38240 33862 34397 34237 34397 33863 34397 33863 38241 34237 38241 34101 38241 34101 38242 34253 38242 33863 38242 33863 38243 34253 38243 34252 38243 33863 38244 34252 38244 33953 38244 33953 38245 34252 38245 33865 38245 33953 38246 33865 38246 33864 38246 33864 38247 33865 38247 33867 38247 33864 38248 33867 38248 33866 38248 33866 38249 33867 38249 34267 38249 34267 38250 33868 38250 33866 38250 33866 38251 33868 38251 33870 38251 33866 38252 33870 38252 33869 38252 33869 38253 33870 38254 34268 38255 33869 38256 34268 38256 33871 38256 33871 38257 34268 38257 34100 38257 33871 38258 34100 38258 33957 38258 33957 38259 34100 38259 34280 38259 34280 38260 33872 38260 33957 38260 33957 38261 33872 38261 33873 38261 33957 38262 33873 38262 33959 38262 33959 38263 33873 38264 33874 38265 33959 38266 33874 38266 33960 38266 33960 38267 33874 38267 34099 38267 33960 38268 34099 38268 33877 38268 33877 38269 34099 38270 33875 38271 33875 38272 33876 38273 33877 38274 33877 38275 33876 38275 34288 38275 33877 38276 34288 38276 33962 38276 33962 38277 34288 38277 34098 38277 33962 38278 34098 38278 33964 38278 33964 38279 34098 38279 33878 38279 33964 38280 33878 38280 33965 38280 33878 38281 34295 38281 33965 38281 33965 38282 34295 38282 33879 38282 33965 38283 33879 38283 33880 38283 33879 38284 34299 38285 33880 38286 33880 38287 34299 38287 34298 38287 33880 38288 34298 38288 33968 38288 33968 38289 34298 38289 33881 38289 33968 38290 33881 38290 33969 38290 33881 38291 34297 38291 33969 38291 33969 38292 34297 38292 33882 38292 33969 38293 33882 38293 33971 38293 33882 38294 33883 38295 33971 38295 33971 38296 33883 38296 33884 38296 33971 38297 33884 38297 33974 38297 33974 38298 33884 38298 33885 38298 33974 38299 33885 38299 33886 38299 33886 38300 33885 38300 34315 38300 33886 38301 34315 38301 33975 38301 33975 38302 34315 38302 34096 38302 34096 38303 34320 38303 33975 38303 33975 38304 34320 38304 34319 38304 33975 38305 34319 38305 33976 38305 33976 38306 34319 38306 33887 38306 33976 34466 33887 34466 33978 34466 33978 38307 33887 38308 34329 38308 33978 38309 34329 38309 33979 38309 33979 38310 34329 38310 34331 38310 34331 38311 33888 38311 33979 38311 33979 38312 33888 38312 34330 38312 33979 38313 34330 38313 33980 38313 33980 38314 34330 38314 33889 38314 33980 38315 33889 38315 33890 38315 33890 38316 33889 38316 34343 38316 33890 38317 34343 38317 33983 38317 33983 38318 34343 38318 34345 38318 34345 38319 33891 38319 33983 38319 33983 38320 33891 38320 34347 38320 33983 38321 34347 38321 33892 38321 33892 38322 34347 38323 34346 38324 33892 38325 34346 38325 33984 38325 33984 38326 34346 38326 33893 38326 33984 38327 33893 38327 33894 38327 33894 38328 33893 38328 34351 38328 34351 38329 33895 38329 33894 38329 33894 38330 33895 38330 33897 38330 33894 38331 33897 38331 33896 38331 33896 38332 33897 38332 33898 38332 33896 38333 33898 38333 33899 38333 33899 34497 33898 34497 33900 34497 33899 38334 33900 38335 33902 38336 33900 38337 33901 38338 33902 38339 33902 38340 33901 38341 34364 38342 33902 38343 34364 38343 33903 38343 34364 38344 34367 38344 33903 38345 33903 38346 34367 38346 33904 38346 33903 38347 33904 38347 33905 38347 33905 38348 33904 38348 34366 38348 33905 38349 34366 38349 33987 38349 34366 38350 33906 38350 33987 38350 33987 34263 33906 34263 34095 34263 33987 38351 34095 38351 33907 38351 34095 38352 34094 38353 33907 38353 33907 38354 34094 38354 34375 38354 33907 38355 34375 38355 33908 38355 33908 38356 34375 38357 33909 38358 33908 38359 33909 38359 33990 38359 33990 38360 33909 38360 34386 38360 33990 34273 34386 34273 33991 34273 33991 38361 34386 38361 33910 38361 33910 38362 33911 38362 33991 38362 33991 38363 33911 38363 33912 38363 33991 38364 33912 38364 33993 38364 33993 38365 33912 38365 33913 38365 33993 38366 33913 38366 33994 38366 33994 38367 33913 38367 33914 38367 33994 38368 33914 38368 33916 38368 33916 38369 33914 38369 33915 38369 33915 38370 34400 38370 33916 38370 33916 38371 34400 38371 34399 38371 33916 38372 34399 38372 33917 38372 33917 38373 34399 38374 34093 38375 33917 38376 34093 38376 33918 38376 33918 38377 34093 38377 34413 38377 33918 38378 34413 38378 33919 38378 33919 38379 34413 38379 34412 38379 34412 38380 34410 38381 33919 38382 33919 38383 34410 38383 34414 38383 33919 38384 34414 38384 33920 38384 33920 38385 34414 38386 34092 38387 33920 38388 34092 38388 33921 38388 33921 38389 34092 38390 33922 38391 33921 38392 33922 38392 33998 38392 33998 38393 33922 38393 33923 38393 33923 38394 34091 38394 33998 38394 33998 38395 34091 38395 34112 38395 33998 38396 34112 38396 33924 38396 33924 38397 34112 38397 34150 38397 33924 38398 34150 38398 33999 38398 33999 38399 34150 38399 34111 38399 33999 38400 34111 38400 34001 38400 34111 38401 34110 38401 34001 38401 34001 38402 34110 38402 34109 38402 34001 38403 34109 38403 33925 38403 34109 38404 34159 38405 33925 38406 33925 38407 34159 38407 34158 38407 33925 38408 34158 38408 33926 38408 33926 38409 34158 38409 34157 38409 33926 38410 34157 38410 34004 38410 34157 38411 34155 38411 34004 38411 34004 38412 34155 38412 34108 38412 34004 38413 34108 38413 33928 38413 34108 38414 33927 38414 33928 38414 33928 38415 33927 38415 33929 38415 33928 38416 33929 38417 34005 38416 34005 38418 33929 38418 34164 38418 34005 38419 34164 38419 33931 38419 33931 38420 34164 38420 33930 38420 33931 38421 33930 38421 33932 38421 33932 38422 33930 38422 33933 38422 33933 38423 34182 38424 33932 38425 33932 38426 34182 38426 34181 38426 33932 38427 34181 38427 34006 38427 34006 38428 34181 38428 34180 38428 34006 34340 34180 34340 34009 34340 34009 38429 34180 38429 33934 38429 34009 38430 33934 38430 33936 38430 33936 38431 33934 38431 33935 38431 33935 38432 34191 38432 33936 38432 33936 38433 34191 38433 34194 38433 33936 38434 34194 38434 34011 38434 34011 38435 34194 38435 34193 38435 34011 38436 34193 38436 34012 38436 34012 38437 34193 38437 33937 38437 34012 38438 33937 38438 34014 38438 34014 38439 33937 38439 33938 38439 33938 38440 34207 38440 34014 38440 34014 38441 34207 38441 34209 38441 34014 38442 34209 38442 34015 38442 34015 38443 34209 38444 34208 38445 34015 38446 34208 38446 34016 38446 34016 38447 34208 38448 34214 38449 34016 38450 34214 38450 33940 38450 33940 38451 34214 38451 33939 38451 33939 38452 34106 38452 33940 38452 33940 38453 34106 38454 33941 38455 33940 38456 33941 38456 34017 38456 34017 38457 33941 38457 34104 38457 34017 38458 34104 38458 33942 38458 33942 34368 34104 34368 33943 34368 33942 38459 33943 38459 33946 38459 33946 38460 33943 38460 34227 38460 33946 38461 34227 38461 33856 38461 33944 38462 34017 38462 34018 38462 34018 38463 34017 38463 33942 38463 34018 38464 33942 38464 34019 38464 34019 38465 33942 38465 33946 38465 34019 38466 33946 38466 33945 38466 33945 38467 33946 38467 33947 38467 33945 38468 33947 38468 34020 38468 34020 38469 33947 38469 33948 38469 34020 38470 33948 38470 33949 38470 33949 38471 33948 38471 33858 38471 33949 38472 33858 38472 33950 38472 33950 38473 33858 38473 33860 38473 33950 38474 33860 38474 33951 38474 33951 34597 33860 34597 33861 34597 33951 38475 33861 38476 34024 38477 34024 38478 33861 38478 33862 38478 34024 38479 33862 38480 33952 38481 33952 38482 33862 38482 33863 38482 33952 38483 33863 38483 34025 38483 34025 38484 33863 38484 33953 38484 34025 38485 33953 38485 34026 38485 34026 38486 33953 38486 33864 38487 34026 38488 33864 38488 34027 38488 34027 38489 33864 38489 33866 38489 34027 38490 33866 38490 33954 38490 33954 38491 33866 38491 33869 38491 33954 38492 33869 38492 33955 38492 33955 38493 33869 38493 33871 38493 33955 38494 33871 38494 33956 38494 33956 38495 33871 38495 33957 38495 33956 38496 33957 38496 33958 38496 33958 38497 33957 38497 33959 38497 33958 38498 33959 38498 34029 38498 34029 34617 33959 34617 33960 34617 34029 38499 33960 38499 33961 38499 33961 38500 33960 38500 33877 38500 33961 38501 33877 38501 34032 38501 34032 38502 33877 38502 33962 38502 34032 38503 33962 38503 33963 38503 33963 38504 33962 38504 33964 38504 33963 38505 33964 38505 34034 38505 34034 38506 33964 38506 33965 38506 34034 38507 33965 38507 33966 38507 33966 38508 33965 38508 33880 38508 33966 38509 33880 38509 33967 38509 33967 38510 33880 38510 33968 38510 33967 38511 33968 38511 33970 38511 33970 38512 33968 38512 33969 38512 33970 38513 33969 38513 33972 38513 33972 38514 33969 38514 33971 38514 33972 38515 33971 38515 33973 38515 33973 38516 33971 38517 33974 38518 33973 38519 33974 38519 34037 38519 34037 38520 33974 38520 33886 38520 34037 38521 33886 38521 34039 38521 34039 34641 33886 34641 33975 34641 34039 38522 33975 38522 34041 38522 34041 38523 33975 38523 33976 38523 34041 38524 33976 38524 33977 38524 33977 38525 33976 38525 33978 38525 33977 38526 33978 38526 34043 38526 34043 38527 33978 38527 33979 38527 34043 38528 33979 38528 34045 38528 34045 38529 33979 38529 33980 38529 34045 38530 33980 38530 33981 38530 33981 38531 33980 38531 33890 38531 33981 38532 33890 38532 33982 38532 33982 38533 33890 38533 33983 38533 33982 38534 33983 38534 34047 38534 34047 38535 33983 38535 33892 38535 34047 38536 33892 38536 34048 38536 34048 38537 33892 38537 33984 38537 34048 38538 33984 38538 33985 38538 33985 38539 33984 38539 33894 38539 33985 38540 33894 38540 33986 38540 33986 38541 33894 38541 33896 38541 33986 38542 33896 38542 34049 38542 34049 38543 33896 38543 33899 38543 34049 38544 33899 38544 34050 38544 34050 38545 33899 38545 33902 38545 34050 38546 33902 38546 34051 38546 34051 38547 33902 38547 33903 38547 34051 38548 33903 38548 34052 38548 34052 38549 33903 38549 33905 38549 34052 38550 33905 38550 34053 38550 34053 38551 33905 38551 33987 38551 34053 38552 33987 38552 33988 38552 33988 38553 33987 38553 33907 38553 33988 38554 33907 38554 34055 38554 34055 34514 33907 34514 33908 34514 34055 38555 33908 38555 33989 38555 33989 38556 33908 38556 33990 38556 33989 38557 33990 38557 34057 38557 34057 38558 33990 38558 33991 38558 34057 38559 33991 38559 33992 38559 33992 38560 33991 38560 33993 38560 33992 38561 33993 38561 34059 38561 34059 38562 33993 38562 33994 38562 34059 38563 33994 38563 34060 38563 34060 38564 33994 38564 33916 38564 34060 38565 33916 38565 34062 38565 34062 38566 33916 38566 33917 38566 34062 38567 33917 38567 34063 38567 34063 38568 33917 38568 33918 38568 34063 38569 33918 38569 34065 38569 34065 38570 33918 38570 33919 38570 34065 38571 33919 38571 33995 38571 33995 38572 33919 38572 33920 38572 33995 38573 33920 38573 34067 38573 34067 34539 33920 34539 33921 34539 34067 38574 33921 38574 33996 38574 33996 38575 33921 38575 33998 38575 33996 38576 33998 38576 33997 38576 33997 38577 33998 38577 33924 38577 33997 38578 33924 38578 34070 38578 34070 38579 33924 38579 33999 38579 34070 38580 33999 38580 34000 38580 34000 38581 33999 38581 34001 38581 34000 38582 34001 38582 34002 38582 34002 38583 34001 38584 33925 38585 34002 38586 33925 38586 34074 38586 34074 38587 33925 38587 33926 38587 34074 38588 33926 38588 34075 38588 34075 38589 33926 38589 34004 38589 34075 38590 34004 38590 34003 38590 34003 38591 34004 38591 33928 38591 34003 38592 33928 38592 34076 38592 34076 38593 33928 38593 34005 38593 34076 38594 34005 38594 34077 38594 34077 38595 34005 38595 33931 38595 34077 38596 33931 38596 34078 38596 34078 34563 33931 34563 33932 34563 34078 38597 33932 38597 34007 38597 34007 38598 33932 38598 34006 38598 34007 38599 34006 38599 34008 38599 34008 38600 34006 38600 34009 38600 34008 38601 34009 38601 34010 38601 34010 38602 34009 38602 33936 38602 34010 38603 33936 38603 34081 38603 34081 38604 33936 38604 34011 38604 34081 38605 34011 38605 34083 38605 34083 38606 34011 38606 34012 38606 34083 38607 34012 38607 34013 38607 34013 38608 34012 38608 34014 38608 34013 38609 34014 38609 34086 38609 34086 38610 34014 38610 34015 38610 34086 38611 34015 38611 34087 38611 34087 38612 34015 38612 34016 38612 34087 38613 34016 38613 34088 38613 34088 38614 34016 38614 33940 38614 34088 38615 33940 38615 33944 38615 33944 38616 33940 38616 34017 38616 33853 38617 34018 38617 33854 38617 33854 38618 34018 38619 34019 38620 33854 38621 34019 38621 33774 38621 33774 38622 34019 38622 33945 38622 33774 38623 33945 38623 33775 38623 33775 38624 33945 38624 34020 38624 33775 38625 34020 38625 34021 38625 34021 38626 34020 38626 33949 38626 34021 38627 33949 38627 34022 38627 34022 38628 33949 38628 33950 38628 34022 38629 33950 38629 33778 38629 33778 38630 33950 38630 33951 38630 33778 38631 33951 38631 34023 38631 34023 38632 33951 38632 34024 38632 34023 38633 34024 38633 33781 38633 33781 34773 34024 34773 33952 34773 33781 38634 33952 38634 33782 38634 33782 38635 33952 38635 34025 38635 33782 38636 34025 38636 33783 38636 33783 38637 34025 38637 34026 38637 33783 38638 34026 38639 33784 38640 33784 38641 34026 38641 34027 38641 33784 38642 34027 38642 34028 38642 34028 38643 34027 38643 33954 38643 34028 38644 33954 38644 33787 38644 33787 38645 33954 38645 33955 38645 33787 34784 33955 34785 33788 34786 33788 38646 33955 38646 33956 38646 33788 38647 33956 38647 33790 38647 33790 38648 33956 38649 33958 38650 33790 38651 33958 38651 33791 38651 33791 38652 33958 38653 34029 38654 33791 38655 34029 38655 34030 38655 34030 38656 34029 38656 33961 38656 34030 38657 33961 38657 34031 38657 34031 38658 33961 38658 34032 38658 34031 38659 34032 38659 33793 38659 33793 38660 34032 38660 33963 38660 33793 38661 33963 38661 33795 38661 33795 38662 33963 38662 34034 38662 33795 38663 34034 38663 34033 38663 34033 38664 34034 38665 33966 38666 34033 38667 33966 38667 33798 38667 33798 38668 33966 38668 33967 38668 33798 38669 33967 38669 33799 38669 33799 38670 33967 38670 33970 38670 33799 38671 33970 38671 34035 38671 34035 38672 33970 38672 33972 38672 34035 38673 33972 38673 33800 38673 33800 38674 33972 38674 33973 38674 33800 38675 33973 38675 34036 38675 34036 34811 33973 34811 34037 34811 34036 38676 34037 38676 34038 38676 34038 38677 34037 38677 34039 38677 34038 38678 34039 38678 34040 38678 34040 38679 34039 38680 34041 38681 34040 38682 34041 38682 33803 38682 33803 38683 34041 38683 33977 38683 33803 38684 33977 38684 34042 38684 34042 38685 33977 38685 34043 38685 34042 38686 34043 38686 34044 38686 34044 38687 34043 38688 34045 38689 34044 38690 34045 38690 33806 38690 33806 38691 34045 38691 33981 38691 33806 38692 33981 38692 33807 38692 33807 38693 33981 38693 33982 38693 33807 38694 33982 38694 34046 38694 34046 38695 33982 38695 34047 38695 34046 38696 34047 38696 33810 38696 33810 38697 34047 38697 34048 38697 33810 38698 34048 38699 33811 38700 33811 38701 34048 38701 33985 38701 33811 38702 33985 38702 33812 38702 33812 38703 33985 38704 33986 38705 33812 38706 33986 38706 33813 38706 33813 38707 33986 38707 34049 38707 33813 38708 34049 38708 33815 38708 33815 38709 34049 38709 34050 38709 33815 38710 34050 38710 33817 38710 33817 38711 34050 38711 34051 38711 33817 38712 34051 38712 33819 38712 33819 38713 34051 38713 34052 38713 33819 38714 34052 38714 33820 38714 33820 38715 34052 38715 34053 38715 33820 38716 34053 38716 33821 38716 33821 38717 34053 38717 33988 38717 33821 38718 33988 38718 34054 38718 34054 38719 33988 38719 34055 38719 34054 38720 34055 38720 34056 38720 34056 38721 34055 38721 33989 38721 34056 38722 33989 38722 33824 38722 33824 34679 33989 34679 34057 34679 33824 38723 34057 38723 34058 38723 34058 38724 34057 38724 33992 38724 34058 38725 33992 38725 33826 38725 33826 38726 33992 38726 34059 38726 33826 38727 34059 38727 33828 38727 33828 38728 34059 38728 34060 38728 33828 38729 34060 38729 34061 38729 34061 38730 34060 38730 34062 38730 34061 38731 34062 38731 33829 38731 33829 38732 34062 38732 34063 38732 33829 34692 34063 34693 34064 34694 34064 38733 34063 38733 34065 38733 34064 38734 34065 38734 33831 38734 33831 38735 34065 38735 33995 38735 33831 38736 33995 38736 34066 38736 34066 38737 33995 38737 34067 38737 34066 38738 34067 38738 34068 38738 34068 38739 34067 38739 33996 38739 34068 38740 33996 38740 33834 38740 33834 38741 33996 38741 33997 38741 33834 38742 33997 38742 34069 38742 34069 38743 33997 38743 34070 38743 34069 38744 34070 38744 33836 38744 33836 38745 34070 38745 34000 38745 33836 38746 34000 38746 34071 38746 34071 38747 34000 38747 34002 38747 34071 38748 34002 38748 34072 38748 34072 38749 34002 38749 34074 38749 34072 38750 34074 38750 34073 38750 34073 38751 34074 38751 34075 38751 34073 38752 34075 38752 33839 38752 33839 38753 34075 38753 34003 38753 33839 38754 34003 38754 33840 38754 33840 38755 34003 38755 34076 38755 33840 38756 34076 38756 33843 38756 33843 34725 34076 34725 34077 34725 33843 38757 34077 38757 33844 38757 33844 38758 34077 38758 34078 38758 33844 38759 34078 38759 33845 38759 33845 38760 34078 38760 34007 38760 33845 38761 34007 38761 33846 38761 33846 38762 34007 38762 34008 38762 33846 38763 34008 38763 34079 38763 34079 38764 34008 38764 34010 38764 34079 38765 34010 38766 34080 38767 34080 38768 34010 38768 34081 38768 34080 38769 34081 38769 34082 38769 34082 38770 34081 38770 34083 38770 34082 38771 34083 38771 34084 38771 34084 38772 34083 38772 34013 38772 34084 38773 34013 38773 34085 38773 34085 38774 34013 38774 34086 38774 34085 38775 34086 38775 33851 38775 33851 38776 34086 38777 34087 38778 33851 38779 34087 38779 34089 38779 34089 38780 34087 38780 34088 38780 34089 38781 34088 38781 34090 38781 34090 38782 34088 38782 33944 38782 34090 38783 33944 38783 33853 38783 33853 38784 33944 38784 34018 38784 34091 38785 33923 38785 34422 38785 33922 38786 34092 38786 34415 38786 34413 38787 34093 38787 34409 38787 33911 38788 33910 38788 34391 38788 34094 38789 34095 38789 34371 38789 34367 38790 34364 38791 34369 38792 33901 38793 33900 38793 34365 38793 33898 38794 33897 38794 34361 38794 33895 38795 34351 38795 34357 38795 33893 38796 34346 38796 34352 38796 34343 38797 33889 38797 34342 38797 34320 38798 34096 38798 34321 38798 33883 38799 33882 38800 34097 38801 34299 38802 33879 38803 34300 38804 34295 34880 33878 34880 34296 34880 34098 38805 34288 38805 34291 38805 33876 38806 33875 38806 34285 38806 34099 38807 33874 38807 34281 38807 34100 38808 34268 38808 34269 38808 34253 38809 34101 38809 34255 38809 34102 38810 33859 38810 34103 38810 34229 38811 33856 38812 34230 38813 34227 38814 33943 38814 34224 38814 34104 38815 33941 38815 34105 38815 34106 38816 33939 38816 34215 38816 34214 38817 34208 38817 34210 38817 33937 38818 34193 38818 34205 38818 34182 38819 33933 38819 34107 38819 33927 38820 34108 38820 34165 38820 34159 38821 34109 38822 34160 38823 34110 34860 34111 34860 34149 34860 34150 38824 34112 38824 34151 38824 33765 38825 33764 38825 34325 38825 34307 38826 34113 38826 34317 38826 34115 38827 33771 38828 34117 38829 34117 38830 33771 38831 34290 38832 34117 38833 34290 38833 34114 38833 34115 38834 34117 38834 34116 38834 34116 38835 34117 38835 34114 38835 34116 38836 34114 38836 34118 38836 34284 38837 34119 38837 34287 38837 34287 38838 34119 38839 33773 38840 34120 38841 34260 38841 34257 38841 34121 38842 34251 38842 34242 38842 34123 38843 34223 38844 34124 38845 34124 38846 34223 38846 34222 38846 34124 34932 34222 34932 34122 34932 34123 38847 34124 38847 34125 38847 34125 38848 34124 38848 34122 38848 34125 38849 34122 38849 34219 38849 34126 38850 34127 38850 34218 38850 34218 38851 34127 38852 34128 38853 34184 38854 34186 38854 34187 38854 34168 38855 34178 38855 34177 38855 34129 38856 34130 38856 34131 38856 34131 38857 34130 38857 34426 38857 34131 38858 34426 38858 34132 38858 34129 38859 34131 38859 34133 38859 34133 38860 34131 38860 34132 38860 34133 38861 34132 38861 34134 38861 34419 38862 34135 38862 34418 38862 34418 38863 34135 38864 34136 38865 34137 38866 34138 38866 34139 38866 34378 38867 34389 38867 34140 38867 34144 38868 34141 38868 34142 38868 34142 38869 34141 38869 34143 38869 34142 34908 34143 34908 34355 34908 34144 38870 34142 38870 34145 38870 34145 38871 34142 38871 34355 38871 34145 38872 34355 38872 34146 38872 34349 38873 34147 38873 34148 38873 34148 38874 34147 38875 34356 38876 34111 38877 34150 38877 34149 38877 34149 38878 34150 38878 34151 38878 34149 38879 34151 38879 34153 38879 34153 38880 34151 38880 34425 38880 34153 38881 34425 38881 34152 38881 34152 38882 34425 38882 34172 38882 34109 38883 34110 38883 34160 38883 34160 38884 34110 38884 34149 38884 34160 38885 34149 38885 34161 38885 34161 38886 34149 38886 34153 38886 34161 38887 34153 38887 34154 38887 34154 38888 34153 38888 34152 38888 34155 38889 34157 38889 34156 38889 34156 38890 34157 38890 34158 38890 34158 38891 34159 38891 34156 38891 34156 38892 34159 38892 34160 38892 34156 38893 34160 38893 34163 38893 34163 38894 34160 38894 34161 38894 34163 38895 34161 38895 34169 38895 34169 38896 34161 38896 34154 38896 34108 35230 34155 35230 34165 35230 34165 38897 34155 38897 34156 38897 34165 38898 34156 38898 34162 38898 34162 38899 34156 38899 34163 38899 34162 38900 34163 38900 34167 38900 34167 38901 34163 38901 34169 38901 33930 38902 34164 38902 34174 38902 34174 38903 34164 38903 33929 38903 33929 38904 33927 38904 34174 38904 34174 38905 33927 38905 34165 38905 34174 38906 34165 38906 34166 38906 34166 38907 34165 38907 34162 38907 34166 38908 34162 38908 34177 38908 34177 38909 34162 38909 34167 38909 34177 38910 34167 38910 34168 38910 34168 38911 34167 38911 34169 38911 34168 38912 34169 38912 34170 38912 34170 38913 34169 38913 34154 38913 34170 38914 34154 38914 34171 38914 34171 38915 34154 38915 34152 38915 34171 38916 34152 38916 34433 38916 34433 38917 34152 38917 34172 38917 34433 38918 34172 38918 34434 38918 34434 38919 34172 38919 34173 38919 33933 38920 33930 38920 34107 38920 34107 38921 33930 38921 34174 38921 34107 38922 34174 38922 34175 38922 34175 38923 34174 38923 34166 38923 34175 38924 34166 38924 34176 38924 34176 38925 34166 38925 34177 38925 34176 38926 34177 38926 34183 38926 34183 38927 34177 38927 34178 38927 34183 38928 34178 38928 34185 38928 33934 38929 34180 38929 34179 38929 34179 38930 34180 38930 34181 38930 34181 38931 34182 38931 34179 38931 34179 38932 34182 38932 34107 38932 34179 38933 34107 38933 34190 38933 34190 38934 34107 38934 34175 38934 34190 38935 34175 38935 34189 38935 34189 38936 34175 38936 34176 38936 34189 38937 34176 38937 34187 38937 34187 38938 34176 38938 34183 38938 34187 38939 34183 38939 34184 38939 34184 38940 34183 38941 34185 38942 34186 35274 34188 35274 34187 35274 34187 38943 34188 38943 34200 38943 34187 38944 34200 38944 34189 38944 34189 38945 34200 38945 34197 38945 34189 38946 34197 38946 34190 38946 34190 38947 34197 38947 34195 38947 34190 38948 34195 38948 34179 38948 34179 38949 34195 38949 34192 38949 34179 38950 34192 38950 33934 38950 34194 38951 34191 38951 34192 38951 34192 38952 34191 38952 33935 38952 34192 35285 33935 35285 33934 35285 34193 38953 34194 38953 34205 38953 34205 38954 34194 38954 34192 38954 34205 38955 34192 38955 34196 38955 34196 38956 34192 38956 34195 38956 34196 38957 34195 38957 34203 38957 34203 38958 34195 38958 34197 38958 34203 38959 34197 38959 34198 38959 34198 38960 34197 38960 34200 38960 34198 38961 34200 38961 34199 38961 34199 38962 34200 38962 34188 38962 34199 38963 34188 38963 34201 38963 34199 38964 34202 38964 34198 38964 34198 38965 34202 38965 34204 38965 34198 35301 34204 35301 34203 35301 34203 38966 34204 38966 34212 38966 34203 38967 34212 38967 34196 38967 34196 38968 34212 38968 34211 38968 34196 38969 34211 38969 34205 38969 34205 35306 34211 35306 34206 35306 34205 38970 34206 38970 33937 38970 34209 38971 34207 38971 34206 38971 34206 38972 34207 38972 33938 38972 34206 38973 33938 38973 33937 38973 34208 35313 34209 35314 34210 35315 34210 35316 34209 35316 34206 35316 34210 38974 34206 38974 34217 38974 34217 38975 34206 38975 34211 38975 34217 38976 34211 38976 34213 38976 34213 38977 34211 38977 34212 38977 34213 38978 34212 38978 34218 38978 34218 38979 34212 38979 34204 38979 34218 38980 34204 38980 34126 38980 34126 38981 34204 38981 34202 38981 33939 38982 34214 38982 34215 38982 34215 38983 34214 38983 34210 38983 34215 38984 34210 38984 34216 38984 34216 38985 34210 38985 34217 38985 34216 38986 34217 38986 34222 38986 34222 38987 34217 38987 34213 38987 34222 38988 34213 38988 34122 38988 34122 38989 34213 38989 34218 38989 34122 38990 34218 38990 34219 38990 34219 38991 34218 38991 34128 38991 33941 38992 34106 38992 34105 38992 34105 38993 34106 38993 34215 38993 34105 38994 34215 38994 34220 38994 34220 38995 34215 38995 34216 38995 34220 38996 34216 38996 34221 38996 34221 38997 34216 38997 34222 38997 34221 38998 34222 38998 34248 38998 34248 38999 34222 38999 34223 38999 33943 39000 34104 39000 34224 39000 34224 39001 34104 39001 34105 39001 34224 39002 34105 39002 34225 39002 34225 39003 34105 39003 34220 39003 34225 39004 34220 39004 34226 39004 34226 39005 34220 39005 34221 39005 33856 39006 34227 39006 34230 39006 34230 39007 34227 39007 34224 39007 34230 39008 34224 39008 34233 39008 34233 39009 34224 39009 34225 39009 34233 39010 34225 39010 34234 39010 34234 39011 34225 39011 34226 39011 34235 39012 33857 39013 34231 39012 34231 39014 33857 39014 34228 39014 34228 39015 34229 39015 34231 39015 34231 39016 34229 39016 34230 39016 34231 39017 34230 39017 34236 39017 34236 39018 34230 39018 34233 39018 34236 39019 34233 39019 34232 39019 34232 39020 34233 39020 34234 39020 33859 39021 34235 39021 34103 39021 34103 39022 34235 39022 34231 39022 34103 39023 34231 39023 34241 39023 34241 39024 34231 39024 34236 39024 34241 39025 34236 39025 34243 39025 34243 39026 34236 39026 34232 39026 34237 39027 34238 39027 34240 39027 34240 39028 34238 39029 34239 39030 34239 39031 34102 39031 34240 39031 34240 39032 34102 39032 34103 39032 34240 39033 34103 39033 34249 39033 34249 39034 34103 39034 34241 39034 34249 39035 34241 39035 34242 39035 34242 39036 34241 39036 34243 39036 34242 39037 34243 39037 34121 39037 34121 39038 34243 39038 34232 39038 34121 39039 34232 39039 34244 39039 34244 35382 34232 35382 34234 35382 34244 39040 34234 39040 34245 39040 34245 39041 34234 39041 34226 39041 34245 39042 34226 39042 34246 39042 34246 35386 34226 35386 34221 35386 34246 39043 34221 39043 34247 39043 34247 39044 34221 39044 34248 39044 34101 39045 34237 39045 34255 39045 34255 39046 34237 39046 34240 39046 34255 39047 34240 39047 34256 39047 34256 39048 34240 39048 34249 39048 34256 39049 34249 39049 34250 39049 34250 39050 34249 39050 34242 39050 34250 39051 34242 39051 34258 39051 34258 39052 34242 39052 34251 39052 34258 39053 34251 39054 34259 39055 33867 39056 33865 39056 34254 39056 34254 39057 33865 39057 34252 39057 34252 39058 34253 39058 34254 39058 34254 39059 34253 39059 34255 39059 34254 39060 34255 39060 34264 39060 34264 39061 34255 39061 34256 39061 34264 39062 34256 39062 34262 39062 34262 39063 34256 39063 34250 39063 34262 39064 34250 39064 34257 39064 34257 39065 34250 39065 34258 39065 34257 39066 34258 39066 34120 39066 34120 39067 34258 39067 34259 39067 34260 39068 34272 39068 34257 39068 34257 39069 34272 39069 34261 39069 34257 39070 34261 39070 34262 39070 34262 39071 34261 39071 34263 39071 34262 39072 34263 39072 34264 39072 34264 39073 34263 39073 34265 39073 34264 39074 34265 39074 34254 39074 34254 39075 34265 39075 34266 39075 34254 35419 34266 35419 33867 35419 33870 39076 33868 39076 34266 39076 34266 39077 33868 39077 34267 39077 34266 39078 34267 39078 33867 39078 34268 39079 33870 39079 34269 39079 34269 39080 33870 39080 34266 39080 34269 39081 34266 39081 34277 39081 34277 39082 34266 39082 34265 39082 34277 39083 34265 39083 34270 39083 34270 39084 34265 39084 34263 39084 34270 39085 34263 39085 34275 39085 34275 39086 34263 39086 34261 39086 34275 39087 34261 39087 34271 39087 34271 39088 34261 39088 34272 39088 34271 39089 34272 39090 34273 39091 34271 35438 34274 35438 34275 35438 34275 39092 34274 39092 34276 39092 34275 39093 34276 39093 34270 39093 34270 39094 34276 39094 34283 39094 34270 39095 34283 39095 34277 39095 34277 39096 34283 39096 34278 39096 34277 39097 34278 39097 34269 39097 34269 39098 34278 39098 34279 39098 34269 39099 34279 39099 34100 39099 33873 39100 33872 39100 34279 39100 34279 39101 33872 39101 34280 39101 34279 39102 34280 39102 34100 39102 33874 39103 33873 39104 34281 39105 34281 39106 33873 39106 34279 39106 34281 39107 34279 39107 34282 39107 34282 35454 34279 35454 34278 35454 34282 39108 34278 39108 34286 39108 34286 35456 34278 35456 34283 35456 34286 39109 34283 39109 34287 39109 34287 39110 34283 39110 34276 39110 34287 39111 34276 39111 34284 39111 34284 39112 34276 39112 34274 39112 33875 39113 34099 39114 34285 39115 34285 39116 34099 39116 34281 39116 34285 39117 34281 39117 34289 39117 34289 39118 34281 39118 34282 39118 34289 39119 34282 39119 34290 39119 34290 39120 34282 39120 34286 39120 34290 39121 34286 39121 34114 39121 34114 39122 34286 39122 34287 39122 34114 39123 34287 39123 34118 39123 34118 39124 34287 39124 33773 39124 34288 39125 33876 39125 34291 39125 34291 39126 33876 39126 34285 39126 34291 39127 34285 39127 34293 39127 34293 39128 34285 39128 34289 39128 34293 39129 34289 39129 34294 39129 34294 39130 34289 39130 34290 39130 34294 39131 34290 39131 33769 39131 33769 39132 34290 39132 33771 39132 33878 39133 34098 39133 34296 39133 34296 39134 34098 39134 34291 39134 34296 39135 34291 39135 34292 39135 34292 39136 34291 39136 34293 39136 34292 39137 34293 39137 34311 39137 34311 39138 34293 39138 34294 39138 33879 39139 34295 39139 34300 39139 34300 39140 34295 39140 34296 39140 34300 39141 34296 39141 34301 39141 34301 39142 34296 39142 34292 39142 34301 39143 34292 39143 34310 39143 34310 39144 34292 39144 34311 39144 34297 39145 33881 39145 34303 39145 34303 39146 33881 39146 34298 39146 34298 39147 34299 39147 34303 39147 34303 39148 34299 39148 34300 39148 34303 39149 34300 39149 34302 39149 34302 39150 34300 39150 34301 39150 34302 39151 34301 39151 34308 39151 34308 39152 34301 39152 34310 39152 33882 34960 34297 34960 34097 34960 34097 39153 34297 39153 34303 39153 34097 39154 34303 39154 34305 39154 34305 39155 34303 39155 34302 39155 34305 39156 34302 39156 34306 39156 34306 39157 34302 39157 34308 39157 34315 39158 33885 39158 34316 39158 34316 39159 33885 39159 33884 39159 33884 39160 33883 39160 34316 39160 34316 39161 33883 39161 34097 39161 34316 39162 34097 39162 34304 39162 34304 39163 34097 39163 34305 39163 34304 39164 34305 39164 34317 39164 34317 39165 34305 39165 34306 39165 34317 39166 34306 39166 34307 39166 34307 39167 34306 39167 34308 39167 34307 39168 34308 39168 34309 39168 34309 39169 34308 39169 34310 39169 34309 39170 34310 39170 34312 39170 34312 39171 34310 39171 34311 39171 34312 39172 34311 39172 34313 39172 34313 39173 34311 39173 34294 39173 34313 39174 34294 39174 34314 39174 34314 39175 34294 39175 33769 39175 34096 39176 34315 39176 34321 39176 34321 39177 34315 39177 34316 39177 34321 39178 34316 39178 34322 39178 34322 39179 34316 39179 34304 39179 34322 39180 34304 39180 34324 39180 34324 39181 34304 39181 34317 39181 34324 39182 34317 39182 34326 39182 34326 39183 34317 39183 34113 39183 34326 39184 34113 39184 33766 39184 34329 39185 33887 39185 34318 39185 34318 39186 33887 39186 34319 39186 34319 39187 34320 39187 34318 39187 34318 39188 34320 39188 34321 39188 34318 39189 34321 39189 34327 39189 34327 39190 34321 39190 34322 39190 34327 39191 34322 39191 34323 39191 34323 39192 34322 39192 34324 39192 34323 39193 34324 39193 34325 39193 34325 39194 34324 39194 34326 39194 34325 39195 34326 39195 33765 39195 33765 39196 34326 39196 33766 39196 33764 35006 33763 35006 34325 35006 34325 39197 33763 39197 34336 39197 34325 39198 34336 39198 34323 39198 34323 39199 34336 39199 34335 39199 34323 39200 34335 39200 34327 39200 34327 39201 34335 39201 34328 39201 34327 39202 34328 39202 34318 39202 34318 39203 34328 39203 34332 39203 34318 39204 34332 39204 34329 39204 34330 39205 33888 39205 34332 39205 34332 39206 33888 39206 34331 39206 34332 35017 34331 35017 34329 35017 33889 39207 34330 39208 34342 39209 34342 39210 34330 39210 34332 39210 34342 39211 34332 39211 34333 39211 34333 39212 34332 39212 34328 39212 34333 39213 34328 39213 34334 39213 34334 39214 34328 39214 34335 39214 34334 39215 34335 39215 34339 39215 34339 39216 34335 39216 34336 39216 34339 39217 34336 39217 34337 39217 34337 39218 34336 39218 33763 39218 34337 39219 33763 39219 34338 39219 34337 39220 34350 39220 34339 39220 34339 39221 34350 39221 34340 39221 34339 35031 34340 35031 34334 35031 34334 39222 34340 39222 34341 39222 34334 39223 34341 39223 34333 39223 34333 39224 34341 39224 34348 39224 34333 39225 34348 39225 34342 39225 34342 35036 34348 35036 34344 35036 34342 39226 34344 39226 34343 39226 34347 39227 33891 39227 34344 39227 34344 39228 33891 39229 34345 39230 34344 39231 34345 39231 34343 39231 34346 35041 34347 35042 34352 35043 34352 35044 34347 35044 34344 35044 34352 39232 34344 39232 34353 39232 34353 39233 34344 39233 34348 39233 34353 39234 34348 39234 34354 39234 34354 39235 34348 39235 34341 39235 34354 39236 34341 39236 34148 39236 34148 39237 34341 39237 34340 39237 34148 39238 34340 39238 34349 39238 34349 39239 34340 39239 34350 39239 34351 39240 33893 39240 34357 39240 34357 39241 33893 39241 34352 39241 34357 39242 34352 39242 34358 39242 34358 39243 34352 39243 34353 39243 34358 39244 34353 39244 34143 39244 34143 39245 34353 39245 34354 39245 34143 39246 34354 39246 34355 39246 34355 39247 34354 39247 34148 39247 34355 39248 34148 39248 34146 39248 34146 39249 34148 39249 34356 39249 33897 39250 33895 39250 34361 39250 34361 39251 33895 39251 34357 39251 34361 39252 34357 39252 34363 39252 34363 39253 34357 39253 34358 39253 34363 39254 34358 39254 34359 39254 34359 39255 34358 39255 34143 39255 34359 39256 34143 39256 34360 39256 34360 39257 34143 39257 34141 39257 33900 39258 33898 39258 34365 39258 34365 39259 33898 39259 34361 39259 34365 39260 34361 39260 34362 39260 34362 39261 34361 39261 34363 39261 34362 39262 34363 39262 34383 39262 34383 39263 34363 39263 34359 39263 34364 39264 33901 39264 34369 39264 34369 39265 33901 39265 34365 39265 34369 39266 34365 39266 34370 39266 34370 39267 34365 39267 34362 39267 34370 39268 34362 39268 34382 39268 34382 39269 34362 39269 34383 39269 33906 39270 34366 39270 34372 39270 34372 39271 34366 39271 33904 39271 33904 39272 34367 39272 34372 39272 34372 39273 34367 39273 34369 39273 34372 39274 34369 39274 34368 39274 34368 39275 34369 39275 34370 39275 34368 39276 34370 39276 34380 39276 34380 39277 34370 39277 34382 39277 34095 39278 33906 39278 34371 39278 34371 39279 33906 39279 34372 39279 34371 39280 34372 39280 34373 39280 34373 39281 34372 39281 34368 39281 34373 39282 34368 39282 34374 39282 34374 39283 34368 39283 34380 39283 34386 39284 33909 39285 34376 39286 34376 39287 33909 39287 34375 39287 34375 39288 34094 39288 34376 39288 34376 39289 34094 39289 34371 39289 34376 39290 34371 39290 34377 39290 34377 39291 34371 39291 34373 39291 34377 39292 34373 39292 34140 39292 34140 39293 34373 39293 34374 39293 34140 39294 34374 39294 34378 39294 34378 39295 34374 39295 34380 39295 34378 39296 34380 39296 34379 39296 34379 35111 34380 35111 34382 35111 34379 39297 34382 39297 34381 39297 34381 39298 34382 39298 34383 39298 34381 39299 34383 39299 34384 39299 34384 35115 34383 35115 34359 35115 34384 39300 34359 39300 34385 39300 34385 39301 34359 39301 34360 39301 33910 39302 34386 39302 34391 39302 34391 39303 34386 39303 34376 39303 34391 39304 34376 39304 34395 39304 34395 39305 34376 39305 34377 39305 34395 39306 34377 39306 34387 39306 34387 39307 34377 39307 34140 39307 34387 39308 34140 39308 34388 39308 34388 39309 34140 39309 34389 39309 34388 39310 34389 39310 34390 39310 33914 39311 33913 39311 34392 39311 34392 39312 33913 39312 33912 39312 33912 39313 33911 39313 34392 39313 34392 39314 33911 39314 34391 39314 34392 39315 34391 39315 34393 39315 34393 39316 34391 39316 34395 39316 34393 39317 34395 39317 34394 39317 34394 39318 34395 39318 34387 39318 34394 39319 34387 39319 34139 39319 34139 39320 34387 39320 34388 39320 34139 39321 34388 39321 34137 39321 34137 39322 34388 39322 34390 39322 34138 39323 34404 39323 34139 39323 34139 39324 34404 39324 34396 39324 34139 39325 34396 39325 34394 39325 34394 39326 34396 39326 34397 39326 34394 39327 34397 39327 34393 39327 34393 39328 34397 39328 34398 39328 34393 39329 34398 39329 34392 39329 34392 39330 34398 39330 34401 39330 34392 35149 34401 35149 33914 35149 34399 39331 34400 39331 34401 39331 34401 39332 34400 39332 33915 39332 34401 39333 33915 39333 33914 39333 34093 39334 34399 39335 34409 39336 34409 39337 34399 39337 34401 39337 34409 39338 34401 39338 34408 39338 34408 39339 34401 39339 34398 39339 34408 39340 34398 39340 34402 39340 34402 39341 34398 39341 34397 39341 34402 39342 34397 39342 34403 39342 34403 39343 34397 39343 34396 39343 34403 39344 34396 39344 34406 39344 34406 39345 34396 39345 34404 39345 34406 39346 34404 39347 34405 39348 34406 34882 34421 34882 34403 34882 34403 39349 34421 39349 34420 39349 34403 39350 34420 39350 34402 39350 34402 39351 34420 39351 34417 39351 34402 39352 34417 39352 34408 39352 34408 39353 34417 39353 34407 39353 34408 39354 34407 39354 34409 39354 34409 39355 34407 39355 34411 39355 34409 39356 34411 39356 34413 39356 34414 39357 34410 39357 34411 39357 34411 39358 34410 39358 34412 39358 34411 39359 34412 39359 34413 39359 34092 39360 34414 39360 34415 39361 34415 39362 34414 39362 34411 39362 34415 39363 34411 39363 34416 39363 34416 35183 34411 35183 34407 35183 34416 39364 34407 39364 34424 39364 34424 35185 34407 35185 34417 35185 34424 39365 34417 39365 34418 39365 34418 39366 34417 39366 34420 39366 34418 39367 34420 39367 34419 39367 34419 39368 34420 39368 34421 39368 33923 39369 33922 39369 34422 39369 34422 39370 33922 39370 34415 39370 34422 39371 34415 39371 34423 39371 34423 39372 34415 39372 34416 39372 34423 39373 34416 39373 34426 39373 34426 39374 34416 39374 34424 39374 34426 39375 34424 39375 34132 39375 34132 39376 34424 39376 34418 39376 34132 39377 34418 39377 34134 39377 34134 39378 34418 39378 34136 39378 34112 39379 34091 39379 34151 39379 34151 39380 34091 39380 34422 39380 34151 39381 34422 39381 34425 39381 34425 39382 34422 39382 34423 39382 34425 39383 34423 39383 34172 39383 34172 39384 34423 39384 34426 39384 34172 39385 34426 39385 34173 39385 34173 39386 34426 39386 34130 39386 34427 39387 34428 39387 34173 39387 34173 39388 34428 39388 34432 39388 34173 39389 34432 39389 34434 39389 34429 39390 34430 39391 34431 39392 34431 35485 34430 35485 34178 35485 34431 39393 34178 39393 34168 39393 34168 39394 34170 39394 34431 39395 34431 39396 34170 39397 34171 39398 34431 39399 34171 39399 34432 39399 34432 39400 34171 39400 34433 39400 34432 39401 34433 39401 34434 39401 34435 39402 34436 39402 35036 39402 35036 39403 34436 39403 34437 39403 35036 39404 34437 39404 34438 39404 34439 39405 34441 39405 34440 39405 34440 39406 34441 39406 34442 39406 34440 39407 34442 39407 34443 39407 34443 39408 35055 39408 34440 39408 34440 39409 35055 39409 35057 39409 34440 39410 35057 39410 34437 39410 34437 39411 35057 39411 35059 39411 34437 39412 35059 39412 34438 39412 34444 39413 34445 39413 34446 39413 34444 39414 34447 39414 34445 39414 34445 39415 34447 39415 34691 39415 34445 39416 34691 39416 34448 39416 34691 39417 34449 39417 34448 39417 34448 39418 34449 39418 34450 39418 34448 39419 34450 39419 34451 39419 34450 39420 34694 39420 34451 39420 34451 39421 34694 39421 34696 39421 34451 39422 34696 39422 34452 39422 34696 39423 34698 39423 34452 39423 34452 39424 34698 39424 34699 39424 34452 39425 34699 39425 34453 39425 34699 39426 34701 39426 34453 39426 34453 39427 34701 39427 34704 39427 34453 39428 34704 39428 34454 39428 34704 39429 34705 39429 34454 39429 34454 39430 34705 39430 34455 39430 34454 39431 34455 39431 34457 39431 34455 39432 34456 39432 34457 39432 34457 39433 34456 39433 34708 39433 34457 39434 34708 39434 34458 39434 34708 39435 34710 39435 34458 39435 34458 39436 34710 39436 34713 39436 34458 39437 34713 39437 34459 39437 34713 39438 34714 39438 34459 39438 34459 39439 34714 39439 34715 39439 34459 39440 34715 39440 34460 39440 34715 39441 34717 39441 34460 39441 34460 39442 34717 39442 34461 39442 34460 39443 34461 39443 34462 39443 34461 39444 34719 39444 34462 39444 34462 39445 34719 39445 34721 39445 34462 39446 34721 39446 34464 39446 34721 39447 34463 39447 34464 39447 34464 49 34463 49 34723 49 34464 39448 34723 39448 34465 39448 34723 39449 34726 39449 34465 39449 34465 39450 34726 39450 34727 39450 34465 39451 34727 39451 34466 39451 34727 39452 34728 39452 34466 39452 34466 39453 34728 39453 34467 39453 34466 39454 34467 39454 34468 39454 34467 39455 34731 39455 34468 39455 34468 39456 34731 39456 34469 39456 34468 39457 34469 39457 34470 39457 34469 39458 34733 39458 34470 39458 34470 39459 34733 39459 34734 39459 34470 39460 34734 39460 34471 39460 34734 39461 34472 39461 34471 39461 34471 39462 34472 39462 34473 39462 34471 39463 34473 39463 34476 39463 34473 39464 34474 39464 34476 39464 34476 39465 34474 39465 34475 39465 34476 39466 34475 39466 34477 39466 34475 39467 34737 39467 34477 39467 34477 39468 34737 39468 34478 39468 34477 39469 34478 39469 34480 39469 34478 39470 34479 39470 34480 39470 34480 39471 34479 39471 34739 39471 34480 39472 34739 39472 34482 39472 34739 39473 34741 39473 34482 39473 34482 39474 34741 39474 34481 39474 34482 39475 34481 39475 34483 39475 34481 39476 34743 39476 34483 39476 34483 39477 34743 39477 34484 39477 34483 39478 34484 39478 34485 39478 34484 39479 34744 39479 34485 39479 34485 39480 34744 39480 34745 39480 34485 39481 34745 39481 34486 39481 34745 39482 34487 39482 34486 39482 34486 39483 34487 39483 34747 39483 34486 39484 34747 39484 34488 39484 34747 39485 34489 39485 34488 39485 34488 39486 34489 39486 34749 39486 34488 39487 34749 39487 34491 39487 34749 39488 34490 39488 34491 39488 34491 39489 34490 39489 34751 39489 34491 39490 34751 39490 34492 39490 34751 39491 34752 39491 34492 39491 34492 39492 34752 39492 34493 39492 34492 39493 34493 39493 34494 39493 34493 39494 34495 39494 34494 39494 34494 39495 34495 39495 34496 39495 34494 39496 34496 39496 34497 39496 34496 39497 34498 39497 34497 39497 34497 39498 34498 39498 34499 39498 34497 39499 34499 39499 34500 39499 34499 39500 34755 39500 34500 39500 34500 39501 34755 39501 34756 39501 34500 39502 34756 39502 34501 39502 34756 39503 34502 39503 34501 39503 34501 50 34502 50 34758 50 34501 39504 34758 39504 34503 39504 34758 39505 34759 39505 34503 39505 34503 39506 34759 39506 34505 39506 34503 39507 34505 39507 34504 39507 34505 39508 34506 39508 34504 39508 34504 39509 34506 39509 34507 39509 34504 39510 34507 39510 34508 39510 34507 39511 34763 39511 34508 39511 34508 39512 34763 39512 34509 39512 34508 39513 34509 39513 34510 39513 34509 39514 34765 39514 34510 39514 34510 39515 34765 39515 34511 39515 34510 39516 34511 39516 34512 39516 34511 39517 34767 39517 34512 39517 34512 39518 34767 39518 34513 39518 34512 39519 34513 39519 34514 39519 34513 39520 34771 39520 34514 39520 34514 39521 34771 39521 34515 39521 34514 39522 34515 39522 34446 39522 34446 39523 34515 39523 34688 39523 34446 39524 34688 39524 34444 39524 34789 39525 34620 39525 34619 39525 34789 39526 34907 39526 34620 39526 34620 39527 34907 39527 34516 39527 34620 39528 34516 39528 34622 39528 34622 39529 34516 39529 34906 39529 34622 39530 34906 39530 34623 39530 34906 39531 34910 39531 34623 39531 34623 39532 34910 39532 34517 39532 34623 39533 34517 39533 34624 39533 34517 39534 34788 39535 34624 39536 34624 39537 34788 39537 34518 39537 34624 39538 34518 39538 34625 39538 34625 39539 34518 39540 34917 39541 34625 39542 34917 39542 34519 39542 34519 39543 34917 39543 34916 39543 34519 39544 34916 39544 34627 39544 34627 39545 34916 39545 34927 39545 34927 39546 34520 39546 34627 39546 34627 39547 34520 39547 34521 39547 34627 39548 34521 39548 34522 39548 34522 39549 34521 39549 34524 39549 34522 39550 34524 39550 34523 39550 34523 39551 34524 39551 34936 39551 34523 39552 34936 39552 34528 39552 34528 39553 34936 39553 34525 39553 34525 39554 34526 39554 34528 39554 34528 39555 34526 39555 34527 39555 34528 39556 34527 39556 34628 39556 34628 39557 34527 39557 34529 39557 34628 39558 34529 39558 34530 39558 34530 39559 34529 39559 34954 39559 34530 39560 34954 39560 34531 39560 34531 39561 34954 39561 34955 39561 34955 39562 34532 39562 34531 39562 34531 39563 34532 39564 34533 39565 34531 39566 34533 39566 34630 39566 34630 39567 34533 39568 34534 39569 34630 39570 34534 39570 34631 39570 34631 39571 34534 39571 34535 39571 34631 39572 34535 39573 34537 39574 34537 39575 34535 39575 34536 39575 34536 39576 34786 39576 34537 39576 34537 39577 34786 39577 34785 39577 34537 39578 34785 39578 34632 39578 34632 39579 34785 39579 34784 39579 34632 39580 34784 39580 34538 39580 34538 39581 34784 39581 34539 39581 34538 39582 34539 39582 34634 39582 34539 39583 34782 39583 34634 39583 34634 39584 34782 39584 34781 39584 34634 39585 34781 39585 34635 39585 34781 39586 34780 39586 34635 39586 34635 39587 34780 39587 34976 39587 34635 39588 34976 39588 34636 39588 34636 39589 34976 39589 34975 39589 34636 39590 34975 39590 34540 39590 34975 39591 34980 39592 34540 39593 34540 39594 34980 39594 34779 39594 34540 39595 34779 39595 34638 39595 34779 39596 34778 39596 34638 39596 34638 39597 34778 39597 34541 39597 34638 39598 34541 39598 34543 39598 34543 39599 34541 39599 34542 39599 34543 39600 34542 39601 34640 39602 34640 39603 34542 39603 34998 39603 34640 39604 34998 39604 34544 39604 34544 39605 34998 39606 35000 39607 35000 39608 34999 39608 34544 39608 34544 39609 34999 39609 34545 39609 34544 39610 34545 39610 34641 39610 34641 39611 34545 39611 34546 39611 34641 39612 34546 39612 34547 39612 34547 39613 34546 39614 35007 39615 34547 39616 35007 39616 34644 39616 34644 39617 35007 39617 34548 39617 34548 39618 35008 39618 34644 39618 34644 39619 35008 39619 34549 39619 34644 39620 34549 39620 34645 39620 34645 39621 34549 39622 34551 39623 34645 39624 34551 39625 34550 39626 34550 39627 34551 39627 35024 39627 34550 39628 35024 39628 34552 39628 34552 39629 35024 39629 35023 39629 35023 39630 34553 39630 34552 39630 34552 39631 34553 39631 34555 39631 34552 39632 34555 39632 34554 39632 34554 39633 34555 39633 34776 39633 34554 39634 34776 39634 34648 39634 34648 39635 34776 39635 35029 39635 34648 39636 35029 39636 34557 39636 34557 39637 35029 39637 34775 39637 34775 39638 34556 39638 34557 39638 34557 39639 34556 39639 34558 39639 34557 39640 34558 39640 34559 39640 34559 39641 34558 39641 34774 39641 34559 39642 34774 39642 34651 39642 34651 39643 34774 39643 35038 39643 34651 39644 35038 39644 34652 39644 35038 39645 34560 39645 34652 39645 34652 39646 34560 39646 35041 39646 34652 39647 35041 39647 34561 39647 35041 39648 34773 39648 34561 39648 34561 39649 34773 39649 34562 39649 34561 39650 34562 39650 34564 39650 34564 39651 34562 39651 34563 39651 34564 39652 34563 39652 34565 39652 34563 39653 34566 39653 34565 39653 34565 39654 34566 39654 34567 39654 34565 39655 34567 39655 34655 39655 34567 39656 35053 39656 34655 39656 34655 39657 35053 39657 35052 39657 34655 39658 35052 39658 34568 39658 34568 39659 35052 39659 35051 39659 34568 39660 35051 39660 34569 39660 34569 39661 35051 39661 35060 39661 34569 39662 35060 39662 34570 39662 34570 39663 35060 39663 34571 39663 34571 39664 35068 39664 34570 39664 34570 39665 35068 39665 34572 39665 34570 39666 34572 39666 34660 39666 34660 39667 34572 39668 34573 39669 34660 39670 34573 39670 34663 39670 34663 39671 34573 39671 35076 39671 34663 39672 35076 39672 34574 39672 34574 39673 35076 39673 34575 39673 34575 39674 34576 39674 34574 39674 34574 39675 34576 39675 34577 39675 34574 39676 34577 39676 34664 39676 34664 39677 34577 39677 34578 39677 34664 39678 34578 39678 34665 39678 34665 39679 34578 39679 35087 39679 34665 39680 35087 39680 34667 39680 34667 39681 35087 39681 34579 39681 34579 39682 34580 39682 34667 39682 34667 39683 34580 39683 35090 39683 34667 39684 35090 39684 34668 39684 34668 39685 35090 39686 35088 39687 34668 39688 35088 39688 34581 39688 34581 39689 35088 39689 35098 39689 34581 39690 35098 39690 34582 39690 34582 39691 35098 39691 35097 39691 35097 39692 34772 39692 34582 39692 34582 39693 34772 39693 34796 39693 34582 39694 34796 39694 34583 39694 34583 39695 34796 39695 34795 39695 34583 39696 34795 39696 34584 39696 34584 39697 34795 39697 34793 39697 34584 39698 34793 39698 34586 39698 34793 39699 34585 39699 34586 39699 34586 39700 34585 39700 34838 39700 34586 39701 34838 39702 34588 39703 34838 39704 34587 39704 34588 39704 34588 39705 34587 39705 34842 39705 34588 39706 34842 39706 34674 39706 34674 39707 34842 39708 34590 39709 34674 39710 34590 39710 34589 39710 34590 39711 34591 39711 34589 39711 34589 39712 34591 39712 34592 39712 34589 39713 34592 39713 34594 39713 34592 39714 34593 39714 34594 39714 34594 39715 34593 39715 34595 39715 34594 39716 34595 39716 34676 39716 34676 39717 34595 39717 34596 39717 34676 39718 34596 39718 34597 39718 34597 39719 34596 39719 34862 39719 34597 39720 34862 39720 34679 39720 34679 39721 34862 39721 34598 39721 34598 39722 34599 39722 34679 39722 34679 39723 34599 39723 34600 39723 34679 39724 34600 39724 34681 39724 34681 39725 34600 39725 34863 39726 34681 39727 34863 39727 34601 39727 34601 39728 34863 39728 34602 39728 34601 39729 34602 39729 34604 39729 34604 39730 34602 39731 34603 39732 34603 39733 34872 39733 34604 39733 34604 39734 34872 39734 34871 39734 34604 39735 34871 39735 34683 39735 34683 39736 34871 39736 34605 39736 34683 39737 34605 39738 34684 39737 34684 39739 34605 39739 34886 39739 34684 39740 34886 39740 34685 39740 34685 39741 34886 39741 34885 39741 34885 39742 34884 39742 34685 39742 34685 39743 34884 39743 34607 39743 34685 39744 34607 39744 34606 39744 34606 39745 34607 39745 34608 39745 34606 39746 34608 39746 34686 39746 34686 39747 34608 39747 34892 39747 34686 39748 34892 39748 34687 39748 34687 39749 34892 39749 34609 39749 34609 39750 34610 39750 34687 39750 34687 39751 34610 39751 34791 39751 34687 39752 34791 39752 34611 39752 34611 39753 34791 39753 34613 39753 34611 39754 34613 39754 34612 39754 34612 39755 34613 39755 34614 39755 34612 39756 34614 39756 34619 39756 34619 39757 34614 39757 34615 39757 34619 39758 34615 39758 34789 39758 34616 39759 34611 39759 34617 39759 34617 39760 34611 39760 34612 39760 34617 39761 34612 39761 34618 39761 34618 39762 34612 39762 34619 39762 34618 39763 34619 39763 34689 39763 34689 39764 34619 39764 34620 39764 34689 39765 34620 39765 34690 39765 34690 39766 34620 39766 34622 39766 34690 39767 34622 39767 34621 39767 34621 39768 34622 39768 34623 39768 34621 39769 34623 39769 34692 39769 34692 39770 34623 39770 34624 39770 34692 39771 34624 39771 34693 39771 34693 39772 34624 39772 34625 39772 34693 39773 34625 39773 34695 39773 34695 39774 34625 39774 34519 39774 34695 39775 34519 39775 34697 39775 34697 39776 34519 39776 34627 39776 34697 39777 34627 39777 34626 39777 34626 39778 34627 39778 34522 39778 34626 39779 34522 39779 34700 39779 34700 39780 34522 39780 34523 39780 34700 39781 34523 39781 34702 39781 34702 39782 34523 39782 34528 39782 34702 39783 34528 39783 34703 39783 34703 39784 34528 39784 34628 39784 34703 39785 34628 39785 34629 39785 34629 39786 34628 39786 34530 39786 34629 39787 34530 39787 34706 39787 34706 39788 34530 39788 34531 39788 34706 39789 34531 39789 34707 39789 34707 39790 34531 39790 34630 39790 34707 39791 34630 39791 34709 39791 34709 39792 34630 39792 34631 39792 34709 39793 34631 39793 34711 39793 34711 39794 34631 39794 34537 39794 34711 39795 34537 39795 34712 39795 34712 39796 34537 39796 34632 39796 34712 39797 34632 39797 34716 39797 34716 39798 34632 39798 34538 39798 34716 39799 34538 39799 34633 39799 34633 39800 34538 39800 34634 39800 34633 39801 34634 39801 34718 39801 34718 39802 34634 39802 34635 39802 34718 39803 34635 39803 34720 39803 34720 39804 34635 39804 34636 39804 34720 39805 34636 39805 34637 39805 34637 39806 34636 39807 34540 39808 34637 39809 34540 39809 34722 39809 34722 39810 34540 39810 34638 39810 34722 39811 34638 39811 34639 39811 34639 39812 34638 39812 34543 39812 34639 39813 34543 39814 34724 39815 34724 39816 34543 39816 34640 39816 34724 39817 34640 39817 34725 39817 34725 39818 34640 39819 34544 39820 34725 39821 34544 39821 34729 39821 34729 39822 34544 39822 34641 39822 34729 39823 34641 39823 34730 39823 34730 39824 34641 39824 34547 39824 34730 39825 34547 39825 34642 39825 34642 39826 34547 39826 34644 39826 34642 39827 34644 39827 34643 39827 34643 39828 34644 39828 34645 39828 34643 39829 34645 39829 34732 39829 34732 39830 34645 39830 34550 39830 34732 39831 34550 39831 34646 39831 34646 39832 34550 39832 34552 39832 34646 39833 34552 39833 34647 39833 34647 39834 34552 39834 34554 39834 34647 39835 34554 39836 34735 39835 34735 39837 34554 39837 34648 39837 34735 39838 34648 39838 34736 39838 34736 39839 34648 39840 34557 39841 34736 39842 34557 39842 34649 39842 34649 39843 34557 39843 34559 39843 34649 39844 34559 39844 34650 39844 34650 39845 34559 39845 34651 39845 34650 39846 34651 39846 34738 39846 34738 39847 34651 39847 34652 39847 34738 39848 34652 39848 34653 39848 34653 39849 34652 39849 34561 39849 34653 39850 34561 39850 34740 39850 34740 39851 34561 39851 34564 39851 34740 39852 34564 39852 34654 39852 34654 39853 34564 39853 34565 39853 34654 39854 34565 39854 34656 39854 34656 39855 34565 39855 34655 39855 34656 39856 34655 39856 34742 39856 34742 39857 34655 39857 34568 39857 34742 39858 34568 39858 34657 39858 34657 39859 34568 39859 34569 39859 34657 39860 34569 39860 34658 39860 34658 39861 34569 39861 34570 39861 34658 39862 34570 39862 34659 39862 34659 39863 34570 39863 34660 39863 34659 39864 34660 39864 34661 39864 34661 39865 34660 39865 34663 39865 34661 39866 34663 39866 34662 39866 34662 39867 34663 39867 34574 39867 34662 39868 34574 39868 34746 39868 34746 39869 34574 39869 34664 39869 34746 39870 34664 39870 34748 39870 34748 39871 34664 39871 34665 39871 34748 39872 34665 39872 34666 39872 34666 39873 34665 39874 34667 39875 34666 39876 34667 39877 34750 39878 34750 39879 34667 39879 34668 39879 34750 39880 34668 39880 34753 39880 34753 39881 34668 39881 34581 39881 34753 39882 34581 39882 34669 39882 34669 39883 34581 39883 34582 39883 34669 39884 34582 39884 34754 39884 34754 39885 34582 39885 34583 39885 34754 39886 34583 39886 34670 39886 34670 39887 34583 39887 34584 39887 34670 39888 34584 39888 34671 39888 34671 39889 34584 39889 34586 39889 34671 39890 34586 39891 34672 39892 34672 39893 34586 39893 34588 39893 34672 39894 34588 39895 34673 39896 34673 39897 34588 39897 34674 39897 34673 39898 34674 39898 34675 39898 34675 39899 34674 39899 34589 39899 34675 39900 34589 39900 34757 39901 34757 39902 34589 39903 34594 39904 34757 39905 34594 39906 34677 39907 34677 39908 34594 39909 34676 39910 34677 39911 34676 39911 34678 39911 34678 39912 34676 39912 34597 39912 34678 39913 34597 39914 34680 39915 34680 39916 34597 39917 34679 39918 34680 39919 34679 39919 34760 39919 34760 39920 34679 39920 34681 39920 34760 39921 34681 39921 34761 39921 34761 39922 34681 39922 34601 39922 34761 39923 34601 39923 34762 39923 34762 39924 34601 39924 34604 39924 34762 39925 34604 39925 34682 39925 34682 39926 34604 39926 34683 39926 34682 39927 34683 39927 34764 39927 34764 39928 34683 39928 34684 39928 34764 39929 34684 39930 34766 39931 34766 39932 34684 39932 34685 39932 34766 39933 34685 39933 34768 39933 34768 39934 34685 39934 34606 39934 34768 39935 34606 39935 34769 39935 34769 39936 34606 39936 34686 39936 34769 39937 34686 39937 34770 39937 34770 39938 34686 39938 34687 39938 34770 39939 34687 39939 34616 39939 34616 39940 34687 39940 34611 39940 34515 39941 34617 39941 34688 39941 34688 39942 34617 39942 34618 39942 34688 39943 34618 39943 34444 39943 34444 39944 34618 39944 34689 39944 34444 39945 34689 39945 34447 39945 34447 39946 34689 39946 34690 39946 34447 39947 34690 39947 34691 39947 34691 39948 34690 39948 34621 39948 34691 39949 34621 39949 34449 39949 34449 39950 34621 39950 34692 39950 34449 39951 34692 39951 34450 39951 34450 39952 34692 39952 34693 39952 34450 39953 34693 39953 34694 39953 34694 39954 34693 39954 34695 39954 34694 39955 34695 39955 34696 39955 34696 39956 34695 39956 34697 39956 34696 39957 34697 39957 34698 39957 34698 39958 34697 39958 34626 39958 34698 39959 34626 39959 34699 39959 34699 39960 34626 39960 34700 39960 34699 39961 34700 39961 34701 39961 34701 39962 34700 39962 34702 39962 34701 39963 34702 39963 34704 39963 34704 39964 34702 39964 34703 39964 34704 39965 34703 39965 34705 39965 34705 39966 34703 39966 34629 39966 34705 39967 34629 39967 34455 39967 34455 39968 34629 39968 34706 39968 34455 39969 34706 39969 34456 39969 34456 39970 34706 39970 34707 39970 34456 39971 34707 39971 34708 39971 34708 39972 34707 39973 34709 39974 34708 39975 34709 39975 34710 39975 34710 39976 34709 39976 34711 39976 34710 39977 34711 39978 34713 39979 34713 39980 34711 39981 34712 39982 34713 39983 34712 39983 34714 39983 34714 39984 34712 39984 34716 39984 34714 39985 34716 39985 34715 39985 34715 39986 34716 39986 34633 39986 34715 39987 34633 39988 34717 39989 34717 39990 34633 39990 34718 39990 34717 39991 34718 39991 34461 39991 34461 39992 34718 39992 34720 39992 34461 39993 34720 39993 34719 39993 34719 39994 34720 39995 34637 39996 34719 39997 34637 39997 34721 39997 34721 39998 34637 39998 34722 39998 34721 39999 34722 39999 34463 39999 34463 40000 34722 40000 34639 40000 34463 40001 34639 40001 34723 40001 34723 40002 34639 40002 34724 40002 34723 40003 34724 40003 34726 40003 34726 40004 34724 40004 34725 40004 34726 40005 34725 40005 34727 40005 34727 40006 34725 40006 34729 40007 34727 40008 34729 40008 34728 40008 34728 40009 34729 40010 34730 40011 34728 40012 34730 40012 34467 40012 34467 40013 34730 40014 34642 40015 34467 40016 34642 40016 34731 40016 34731 40017 34642 40017 34643 40017 34731 40018 34643 40018 34469 40018 34469 40019 34643 40019 34732 40019 34469 40020 34732 40021 34733 40022 34733 40023 34732 40024 34646 40025 34733 40026 34646 40026 34734 40026 34734 40027 34646 40027 34647 40027 34734 40028 34647 40028 34472 40028 34472 40029 34647 40029 34735 40029 34472 40030 34735 40030 34473 40030 34473 40031 34735 40031 34736 40031 34473 40032 34736 40033 34474 40034 34474 40035 34736 40035 34649 40035 34474 40036 34649 40036 34475 40036 34475 40037 34649 40037 34650 40037 34475 40038 34650 40038 34737 40038 34737 40039 34650 40039 34738 40039 34737 40040 34738 40040 34478 40040 34478 40041 34738 40041 34653 40041 34478 40042 34653 40042 34479 40042 34479 40043 34653 40043 34740 40043 34479 40044 34740 40044 34739 40044 34739 40045 34740 40045 34654 40045 34739 40046 34654 40046 34741 40046 34741 40047 34654 40047 34656 40047 34741 40048 34656 40048 34481 40048 34481 40049 34656 40049 34742 40049 34481 40050 34742 40050 34743 40050 34743 40051 34742 40051 34657 40051 34743 40052 34657 40052 34484 40052 34484 40053 34657 40053 34658 40053 34484 40054 34658 40054 34744 40054 34744 40055 34658 40055 34659 40055 34744 40056 34659 40056 34745 40056 34745 40057 34659 40057 34661 40057 34745 40058 34661 40058 34487 40058 34487 40059 34661 40059 34662 40059 34487 40060 34662 40060 34747 40060 34747 40061 34662 40061 34746 40061 34747 40062 34746 40062 34489 40062 34489 40063 34746 40063 34748 40063 34489 40064 34748 40064 34749 40064 34749 40065 34748 40065 34666 40065 34749 40066 34666 40067 34490 40068 34490 40069 34666 40069 34750 40069 34490 40070 34750 40071 34751 40072 34751 40073 34750 40073 34753 40073 34751 40074 34753 40074 34752 40074 34752 40075 34753 40075 34669 40075 34752 40076 34669 40076 34493 40076 34493 40077 34669 40077 34754 40077 34493 40078 34754 40078 34495 40078 34495 40079 34754 40079 34670 40079 34495 40080 34670 40080 34496 40080 34496 40081 34670 40081 34671 40081 34496 40082 34671 40082 34498 40082 34498 40083 34671 40083 34672 40083 34498 40084 34672 40084 34499 40084 34499 40085 34672 40085 34673 40085 34499 40086 34673 40087 34755 40088 34755 40089 34673 40089 34675 40089 34755 40090 34675 40090 34756 40090 34756 40091 34675 40091 34757 40091 34756 40092 34757 40092 34502 40092 34502 40093 34757 40093 34677 40093 34502 40094 34677 40094 34758 40094 34758 40095 34677 40095 34678 40095 34758 40096 34678 40096 34759 40096 34759 40097 34678 40098 34680 40099 34759 40100 34680 40100 34505 40100 34505 40101 34680 40101 34760 40101 34505 40102 34760 40102 34506 40102 34506 40103 34760 40103 34761 40103 34506 40104 34761 40104 34507 40104 34507 40105 34761 40106 34762 40107 34507 40108 34762 40108 34763 40108 34763 40109 34762 40109 34682 40109 34763 40110 34682 40110 34509 40110 34509 40111 34682 40111 34764 40111 34509 40112 34764 40112 34765 40112 34765 40113 34764 40114 34766 40115 34765 40116 34766 40116 34511 40116 34511 40117 34766 40117 34768 40117 34511 40118 34768 40118 34767 40118 34767 40119 34768 40119 34769 40119 34767 40120 34769 40120 34513 40120 34513 40121 34769 40121 34770 40121 34513 40122 34770 40122 34771 40122 34771 40123 34770 40123 34616 40123 34771 40124 34616 40124 34515 40124 34515 40125 34616 40125 34617 40125 34772 40126 35097 40126 35101 40126 35098 40127 35088 40127 35089 40127 35087 40128 34578 40128 35086 40128 35068 40129 34571 40130 35061 40131 35053 40132 34567 40132 35047 40132 34773 40133 35041 40134 35042 40135 34560 40136 35038 40136 35039 40136 34774 40137 34558 40137 35034 40137 34556 40138 34775 40138 35030 40138 35029 40139 34776 40139 35031 40139 35024 40140 34551 40140 35010 40140 35007 40141 34546 40141 34777 40141 34778 40142 34779 40142 34984 40142 34780 40143 34781 40143 34978 40143 34782 40144 34539 40144 34783 40144 34784 40145 34785 40145 34971 40145 34786 40146 34536 40146 34961 40146 34535 40147 34534 40147 34962 40147 34954 40148 34529 40148 34787 40148 34520 40149 34927 40149 34928 40149 34788 40150 34517 40150 34911 40150 34907 40151 34789 40152 34908 40153 34615 40154 34614 40154 34790 40154 34613 40155 34791 40155 34898 40155 34610 40156 34609 40156 34894 40156 34892 40157 34608 40157 34893 40157 34886 40158 34605 40158 34792 40158 34602 40159 34863 40159 34864 40159 34593 40160 34592 40160 34845 40160 34587 40161 34838 40161 34839 40161 34585 40162 34793 40162 34794 40162 34795 40163 34796 40163 34836 40163 34816 40164 34797 40164 34866 40164 34994 40165 34798 40165 34799 40165 35004 40166 34800 40166 35005 40166 34987 40167 34994 40168 34985 40169 34801 40170 34803 40171 34802 40172 34802 40173 34803 40173 34964 40173 34802 40174 34964 40174 34965 40174 34801 40175 34802 40175 34804 40175 34804 40176 34802 40176 34965 40176 34804 40177 34965 40177 34967 40177 34959 40178 34805 40178 34966 40178 34966 40179 34805 40179 34806 40179 34941 40180 34807 40181 34940 40182 34919 40183 34934 40184 34918 40185 34808 40186 34903 40186 34809 40186 34809 40187 34903 40187 34902 40187 34809 40188 34902 40188 34896 40188 34808 40189 34809 40189 34810 40189 34810 40190 34809 40190 34896 40190 34810 40191 34896 40191 34897 40191 34891 40192 34811 40192 34889 40192 34889 40193 34811 40193 34812 40193 34813 40194 34814 40194 34867 40194 34815 40195 34816 40195 34848 40195 34821 40196 34817 40197 34818 40198 34818 40199 34817 40199 34819 40199 34818 40200 34819 40200 34820 40200 34821 40201 34818 40201 34822 40201 34822 40202 34818 40202 34820 40202 34822 40203 34820 40203 34823 40203 34824 40204 34825 40204 34826 40204 34826 40205 34825 40205 35100 40205 34827 40206 35071 40206 35070 40206 34443 40207 34442 40208 35065 40209 34829 40210 35037 40210 34831 40210 34831 40211 35037 40211 34828 40211 34831 40212 34828 40212 35033 40212 34829 40213 34831 40214 34830 40215 34830 40216 34831 40216 35033 40216 34830 40217 35033 40217 34832 40217 35028 40218 34833 40218 34834 40218 34834 40219 34833 40219 34835 40219 34793 40220 34795 40220 34794 40220 34794 40221 34795 40221 34836 40221 34794 40222 34836 40222 34840 40222 34840 40223 34836 40223 34837 40223 34840 40224 34837 40224 34841 40224 34841 40225 34837 40225 34855 40225 34838 40226 34585 40226 34839 40226 34839 40227 34585 40227 34794 40227 34839 40228 34794 40228 34844 40228 34844 40229 34794 40229 34840 40229 34844 40230 34840 40230 34853 40230 34853 40231 34840 40231 34841 40231 34591 40232 34590 40232 34843 40232 34843 40233 34590 40233 34842 40233 34842 40234 34587 40234 34843 40234 34843 40235 34587 40235 34839 40235 34843 40236 34839 40236 34846 40236 34846 40237 34839 40237 34844 40237 34846 40238 34844 40238 34850 40238 34850 40239 34844 40239 34853 40239 34592 40240 34591 40240 34845 40240 34845 40241 34591 40241 34843 40241 34845 40242 34843 40242 34847 40242 34847 40243 34843 40243 34846 40243 34847 40244 34846 40244 34849 40244 34849 40245 34846 40245 34850 40245 34862 40246 34596 40246 34861 40246 34861 40247 34596 40247 34595 40247 34595 40248 34593 40248 34861 40248 34861 40249 34593 40249 34845 40249 34861 40250 34845 40250 34858 40250 34858 40251 34845 40251 34847 40251 34858 40252 34847 40252 34848 40252 34848 40253 34847 40253 34849 40253 34848 40254 34849 40254 34815 40254 34815 40255 34849 40255 34850 40255 34815 40256 34850 40256 34851 40256 34851 40257 34850 40257 34853 40257 34851 40258 34853 40258 34852 40258 34852 40259 34853 40259 34841 40259 34852 40260 34841 40260 34854 40260 34854 40261 34841 40261 34855 40261 34854 40262 34855 40262 34856 40262 34856 40263 34855 40263 35102 40263 34816 40264 34866 40264 34848 40264 34848 40265 34866 40265 34857 40265 34848 40266 34857 40266 34858 40266 34858 40267 34857 40267 34859 40267 34858 40268 34859 40268 34861 40268 34861 40269 34859 40269 34860 40269 34861 40270 34860 40270 34862 40270 34600 40271 34599 40271 34860 40271 34860 40272 34599 40272 34598 40272 34860 40273 34598 40273 34862 40273 34863 40274 34600 40274 34864 40274 34864 40275 34600 40275 34860 40275 34864 40276 34860 40276 34870 40276 34870 40277 34860 40277 34859 40277 34870 40278 34859 40278 34865 40278 34865 40279 34859 40279 34857 40279 34865 40280 34857 40280 34867 40280 34867 40281 34857 40281 34866 40281 34867 40282 34866 40282 34813 40282 34813 40283 34866 40283 34797 40283 34814 40284 34877 40284 34867 40284 34867 40285 34877 40285 34868 40285 34867 40286 34868 40286 34865 40286 34865 40287 34868 40287 34869 40287 34865 40288 34869 40288 34870 40288 34870 40289 34869 40289 34875 40289 34870 40290 34875 40290 34864 40290 34864 40291 34875 40291 34873 40291 34864 40292 34873 40292 34602 40292 34871 40293 34872 40293 34873 40293 34873 40294 34872 40294 34603 40294 34873 40295 34603 40295 34602 40295 34605 40296 34871 40297 34792 40298 34792 40299 34871 40299 34873 40299 34792 40300 34873 40300 34874 40300 34874 40301 34873 40301 34875 40301 34874 40302 34875 40302 34882 40302 34882 40303 34875 40303 34869 40303 34882 40304 34869 40304 34876 40304 34876 40305 34869 40305 34868 40305 34876 40306 34868 40306 34879 40306 34879 40307 34868 40307 34877 40307 34879 40308 34877 40308 34878 40308 34879 40309 34880 40309 34876 40309 34876 40310 34880 40310 34890 40310 34876 40311 34890 40311 34882 40311 34882 40312 34890 40312 34881 40312 34882 40313 34881 40313 34874 40313 34874 40314 34881 40314 34883 40314 34874 40315 34883 40315 34792 40315 34792 40316 34883 40316 34887 40316 34792 40317 34887 40317 34886 40317 34607 40318 34884 40318 34887 40318 34887 40319 34884 40319 34885 40319 34887 40320 34885 40320 34886 40320 34608 40321 34607 40322 34893 40323 34893 40324 34607 40324 34887 40324 34893 40325 34887 40325 34895 40325 34895 40326 34887 40326 34883 40326 34895 40327 34883 40327 34888 40327 34888 40328 34883 40328 34881 40328 34888 40329 34881 40329 34889 40329 34889 40330 34881 40330 34890 40330 34889 40331 34890 40331 34891 40331 34891 40332 34890 40332 34880 40332 34609 40333 34892 40333 34894 40333 34894 40334 34892 40334 34893 40334 34894 40335 34893 40335 34900 40335 34900 40336 34893 40336 34895 40336 34900 40337 34895 40337 34902 40337 34902 40338 34895 40338 34888 40338 34902 40339 34888 40339 34896 40339 34896 40340 34888 40340 34889 40340 34896 40341 34889 40341 34897 40341 34897 40342 34889 40342 34812 40342 34791 40343 34610 40343 34898 40343 34898 40344 34610 40344 34894 40344 34898 40345 34894 40345 34899 40345 34899 40346 34894 40346 34900 40346 34899 40347 34900 40347 34901 40347 34901 40348 34900 40348 34902 40348 34901 40349 34902 40349 34926 40349 34926 40350 34902 40350 34903 40350 34614 40351 34613 40351 34790 40351 34790 40352 34613 40352 34898 40352 34790 40353 34898 40353 34905 40353 34905 40354 34898 40354 34899 40354 34905 40355 34899 40355 34923 40355 34923 40356 34899 40356 34901 40356 34789 40357 34615 40357 34908 40357 34908 40358 34615 40358 34790 40358 34908 40359 34790 40359 34904 40359 34904 40360 34790 40360 34905 40360 34904 40361 34905 40361 34909 40361 34909 40362 34905 40362 34923 40362 34910 40363 34906 40363 34913 40363 34913 40364 34906 40364 34516 40364 34516 40365 34907 40365 34913 40365 34913 40366 34907 40366 34908 40366 34913 40367 34908 40367 34915 40367 34915 40368 34908 40368 34904 40368 34915 40369 34904 40369 34920 40369 34920 40370 34904 40370 34909 40370 34517 40371 34910 40371 34911 40371 34911 40372 34910 40372 34913 40372 34911 40373 34913 40373 34912 40373 34912 40374 34913 40374 34915 40374 34912 40375 34915 40375 34914 40375 34914 40376 34915 40376 34920 40376 34916 40377 34917 40377 34929 40377 34929 40378 34917 40378 34518 40378 34518 40379 34788 40379 34929 40379 34929 40380 34788 40380 34911 40380 34929 40381 34911 40381 34932 40381 34932 40382 34911 40382 34912 40382 34932 40383 34912 40383 34918 40383 34918 40384 34912 40384 34914 40384 34918 40385 34914 40385 34919 40385 34919 40386 34914 40386 34920 40386 34919 40387 34920 40387 34921 40387 34921 40388 34920 40388 34909 40388 34921 40389 34909 40389 34922 40389 34922 40390 34909 40390 34923 40390 34922 40391 34923 40391 34924 40391 34924 40392 34923 40392 34901 40392 34924 40393 34901 40393 34925 40393 34925 40394 34901 40394 34926 40394 34927 40395 34916 40395 34928 40395 34928 40396 34916 40396 34929 40396 34928 40397 34929 40397 34930 40397 34930 40398 34929 40398 34932 40398 34930 40399 34932 40399 34931 40399 34931 40400 34932 40400 34918 40400 34931 40401 34918 40401 34933 40401 34933 40402 34918 40402 34934 40402 34933 40403 34934 40403 34935 40403 34936 40404 34524 40404 34937 40404 34937 40405 34524 40405 34521 40405 34521 40406 34520 40406 34937 40406 34937 40407 34520 40407 34928 40407 34937 40408 34928 40408 34938 40408 34938 40409 34928 40409 34930 40409 34938 40410 34930 40410 34939 40410 34939 40411 34930 40411 34931 40411 34939 40412 34931 40412 34940 40412 34940 40413 34931 40413 34933 40413 34940 40414 34933 40414 34941 40414 34941 40415 34933 40415 34935 40415 34807 40416 34942 40416 34940 40416 34940 40417 34942 40417 34948 40417 34940 40418 34948 40418 34939 40418 34939 40419 34948 40419 34947 40419 34939 40420 34947 40420 34938 40420 34938 40421 34947 40421 34946 40421 34938 40422 34946 40422 34937 40422 34937 40423 34946 40423 34943 40423 34937 40424 34943 40424 34936 40424 34527 40425 34526 40425 34943 40425 34943 40426 34526 40426 34525 40426 34943 40427 34525 40427 34936 40427 34529 40428 34527 40428 34787 40428 34787 40429 34527 40429 34943 40429 34787 40430 34943 40430 34944 40430 34944 40431 34943 40431 34946 40431 34944 40432 34946 40432 34945 40432 34945 40433 34946 40433 34947 40433 34945 40434 34947 40434 34951 40434 34951 40435 34947 40435 34948 40435 34951 40436 34948 40436 34950 40436 34950 40437 34948 40437 34942 40437 34950 40438 34942 40438 34949 40438 34950 40439 34960 40439 34951 40439 34951 40440 34960 40440 34958 40440 34951 40441 34958 40441 34945 40441 34945 40442 34958 40442 34957 40442 34945 40443 34957 40443 34944 40443 34944 40444 34957 40444 34952 40444 34944 40445 34952 40445 34787 40445 34787 40446 34952 40446 34953 40446 34787 40447 34953 40447 34954 40447 34533 40448 34532 40448 34953 40448 34953 40449 34532 40449 34955 40449 34953 40450 34955 40450 34954 40450 34534 40451 34533 40452 34962 40453 34962 40454 34533 40454 34953 40454 34962 40455 34953 40455 34963 40455 34963 40456 34953 40456 34952 40456 34963 40457 34952 40457 34956 40457 34956 40458 34952 40458 34957 40458 34956 40459 34957 40459 34966 40459 34966 40460 34957 40460 34958 40460 34966 40461 34958 40461 34959 40461 34959 40462 34958 40462 34960 40462 34536 40463 34535 40463 34961 40463 34961 40464 34535 40464 34962 40464 34961 40465 34962 40465 34969 40465 34969 40466 34962 40466 34963 40466 34969 40467 34963 40467 34964 40467 34964 40468 34963 40468 34956 40468 34964 40469 34956 40469 34965 40469 34965 40470 34956 40470 34966 40470 34965 40471 34966 40471 34967 40471 34967 40472 34966 40472 34806 40472 34785 40473 34786 40473 34971 40473 34971 40474 34786 40474 34961 40474 34971 40475 34961 40475 34968 40475 34968 40476 34961 40476 34969 40476 34968 40477 34969 40477 34972 40477 34972 40478 34969 40478 34964 40478 34972 40479 34964 40479 34970 40479 34970 40480 34964 40480 34803 40480 34539 40481 34784 40481 34783 40481 34783 40482 34784 40482 34971 40482 34783 40483 34971 40483 34974 40483 34974 40484 34971 40484 34968 40484 34974 40485 34968 40485 34990 40485 34990 40486 34968 40486 34972 40486 34781 40487 34782 40487 34978 40487 34978 40488 34782 40488 34783 40488 34978 40489 34783 40489 34979 40489 34979 40490 34783 40490 34974 40490 34979 40491 34974 40491 34973 40491 34973 40492 34974 40492 34990 40492 34980 40493 34975 40493 34977 40493 34977 40494 34975 40494 34976 40494 34976 40495 34780 40495 34977 40495 34977 40496 34780 40496 34978 40496 34977 40497 34978 40497 34981 40497 34981 40498 34978 40498 34979 40498 34981 40499 34979 40499 34988 40499 34988 40500 34979 40500 34973 40500 34779 40501 34980 40501 34984 40501 34984 40502 34980 40502 34977 40502 34984 40503 34977 40503 34982 40503 34982 40504 34977 40504 34981 40504 34982 40505 34981 40505 34986 40505 34986 40506 34981 40506 34988 40506 34998 40507 34542 40507 34997 40507 34997 40508 34542 40508 34541 40508 34541 40509 34778 40509 34997 40509 34997 40510 34778 40510 34984 40510 34997 40511 34984 40511 34983 40511 34983 40512 34984 40512 34982 40512 34983 40513 34982 40513 34985 40513 34985 40514 34982 40514 34986 40514 34985 40515 34986 40515 34987 40515 34987 40516 34986 40516 34988 40516 34987 40517 34988 40517 34989 40517 34989 40518 34988 40518 34973 40518 34989 40519 34973 40519 34991 40519 34991 40520 34973 40520 34990 40520 34991 40521 34990 40521 34992 40521 34992 40522 34990 40522 34972 40522 34992 40523 34972 40523 34993 40523 34993 40524 34972 40524 34970 40524 34994 40525 34799 40525 34985 40525 34985 40526 34799 40526 34995 40526 34985 40527 34995 40527 34983 40527 34983 40528 34995 40528 34996 40528 34983 40529 34996 40529 34997 40529 34997 40530 34996 40530 35001 40530 34997 40531 35001 40531 34998 40531 34545 40532 34999 40532 35001 40532 35001 40533 34999 40533 35000 40533 35001 40534 35000 40534 34998 40534 34546 40535 34545 40535 34777 40535 34777 40536 34545 40536 35001 40536 34777 40537 35001 40537 35002 40537 35002 40538 35001 40538 34996 40538 35002 40539 34996 40539 35003 40539 35003 40540 34996 40540 34995 40540 35003 40541 34995 40541 35005 40541 35005 40542 34995 40542 34799 40542 35005 40543 34799 40543 35004 40543 35004 40544 34799 40544 34798 40544 34800 40545 35016 40545 35005 40545 35005 40546 35016 40546 35014 40546 35005 40547 35014 40547 35003 40547 35003 40548 35014 40548 35013 40548 35003 40549 35013 40549 35002 40549 35002 40550 35013 40550 35006 40550 35002 40551 35006 40551 34777 40551 34777 40552 35006 40552 35009 40552 34777 40553 35009 40553 35007 40553 34549 40554 35008 40554 35009 40554 35009 40555 35008 40555 34548 40555 35009 40556 34548 40556 35007 40556 34551 40557 34549 40558 35010 40558 35010 40559 34549 40559 35009 40559 35010 40560 35009 40560 35011 40560 35011 40561 35009 40561 35006 40561 35011 40562 35006 40562 35012 40562 35012 40563 35006 40563 35013 40563 35012 40564 35013 40564 35019 40564 35019 40565 35013 40565 35014 40565 35019 40566 35014 40566 35015 40566 35015 40567 35014 40567 35016 40567 35015 40568 35016 40568 35017 40568 35015 40569 35018 40569 35019 40569 35019 40570 35018 40570 35020 40570 35019 40571 35020 40571 35012 40571 35012 40572 35020 40572 35021 40572 35012 40573 35021 40573 35011 40573 35011 40574 35021 40574 35022 40574 35011 40575 35022 40575 35010 40575 35010 40576 35022 40576 35025 40576 35010 40577 35025 40577 35024 40577 34555 40578 34553 40578 35025 40578 35025 40579 34553 40579 35023 40579 35025 40580 35023 40580 35024 40580 34776 40581 34555 40581 35031 40581 35031 40582 34555 40582 35025 40582 35031 40583 35025 40583 35026 40583 35026 40584 35025 40584 35022 40584 35026 40585 35022 40585 35027 40585 35027 40586 35022 40586 35021 40586 35027 40587 35021 40587 34834 40587 34834 40588 35021 40588 35020 40588 34834 40589 35020 40589 35028 40589 35028 40590 35020 40590 35018 40590 34775 40591 35029 40591 35030 40591 35030 40592 35029 40592 35031 40592 35030 40593 35031 40593 35032 40593 35032 40594 35031 40594 35026 40594 35032 40595 35026 40595 34828 40595 34828 40596 35026 40596 35027 40596 34828 40597 35027 40597 35033 40597 35033 40598 35027 40598 34834 40598 35033 40599 34834 40599 34832 40599 34832 40600 34834 40600 34835 40600 34558 40601 34556 40601 35034 40601 35034 40602 34556 40602 35030 40602 35034 40603 35030 40603 35040 40603 35040 40604 35030 40604 35032 40604 35040 40605 35032 40605 35035 40605 35035 40606 35032 40606 34828 40606 35035 40607 34828 40607 35036 40607 35036 40608 34828 40608 35037 40608 35038 40609 34774 40609 35039 40609 35039 40610 34774 40610 35034 40610 35039 40611 35034 40611 35044 40611 35044 40612 35034 40612 35040 40612 35044 40613 35040 40613 35058 40613 35058 40614 35040 40614 35035 40614 35041 40615 34560 40615 35042 40615 35042 40616 34560 40616 35039 40616 35042 40617 35039 40617 35043 40617 35043 40618 35039 40618 35044 40618 35043 40619 35044 40619 35056 40619 35056 40620 35044 40620 35058 40620 34566 40621 34563 40621 35048 40621 35048 40622 34563 40622 34562 40622 34562 40623 34773 40623 35048 40623 35048 40624 34773 40624 35042 40624 35048 40625 35042 40625 35045 40625 35045 40626 35042 40626 35043 40626 35045 40627 35043 40627 35046 40627 35046 40628 35043 40628 35056 40628 34567 40629 34566 40629 35047 40629 35047 40630 34566 40630 35048 40630 35047 40631 35048 40631 35049 40631 35049 40632 35048 40632 35045 40632 35049 40633 35045 40633 35050 40633 35050 40634 35045 40634 35046 40634 35060 40635 35051 40635 35062 40635 35062 40636 35051 40636 35052 40636 35052 40637 35053 40637 35062 40637 35062 40638 35053 40638 35047 40638 35062 40639 35047 40639 35054 40639 35054 40640 35047 40640 35049 40640 35054 40641 35049 40641 35065 40641 35065 40642 35049 40642 35050 40642 35065 40643 35050 40643 34443 40643 34443 40644 35050 40644 35046 40644 34443 40645 35046 40645 35055 40645 35055 40646 35046 40646 35056 40646 35055 40647 35056 40647 35057 40647 35057 40648 35056 40648 35058 40648 35057 40649 35058 40649 35059 40649 35059 40650 35058 40650 35035 40650 35059 40651 35035 40651 34438 40651 34438 40652 35035 40652 35036 40652 34571 40653 35060 40653 35061 40653 35061 40654 35060 40654 35062 40654 35061 40655 35062 40655 35063 40655 35063 40656 35062 40656 35054 40656 35063 40657 35054 40657 35069 40657 35069 40658 35054 40658 35065 40658 35069 40659 35065 40659 35064 40659 35064 40660 35065 40660 34442 40660 35064 40661 34442 40661 35066 40661 35076 40662 34573 40662 35067 40662 35067 40663 34573 40663 34572 40663 34572 40664 35068 40664 35067 40664 35067 40665 35068 40665 35061 40665 35067 40666 35061 40666 35074 40666 35074 40667 35061 40667 35063 40667 35074 40668 35063 40668 35072 40668 35072 40669 35063 40669 35069 40669 35072 40670 35069 40670 35070 40670 35070 40671 35069 40671 35064 40671 35070 40672 35064 40672 34827 40672 34827 40673 35064 40673 35066 40673 35071 40674 35082 40674 35070 40674 35070 40675 35082 40675 35081 40675 35070 40676 35081 40676 35072 40676 35072 40677 35081 40677 35079 40677 35072 40678 35079 40678 35074 40678 35074 40679 35079 40679 35073 40679 35074 40680 35073 40680 35067 40680 35067 40681 35073 40681 35075 40681 35067 40682 35075 40682 35076 40682 34577 40683 34576 40683 35075 40683 35075 40684 34576 40684 34575 40684 35075 40685 34575 40685 35076 40685 34578 40686 34577 40686 35086 40686 35086 40687 34577 40687 35075 40687 35086 40688 35075 40688 35077 40688 35077 40689 35075 40689 35073 40689 35077 40690 35073 40690 35078 40690 35078 40691 35073 40691 35079 40691 35078 40692 35079 40692 35084 40692 35084 40693 35079 40693 35081 40693 35084 40694 35081 40694 35080 40694 35080 40695 35081 40695 35082 40695 35080 40696 35082 40696 35083 40696 35080 40697 35096 40697 35084 40697 35084 40698 35096 40698 35085 40698 35084 40699 35085 40699 35078 40699 35078 40700 35085 40700 35094 40700 35078 40701 35094 40701 35077 40701 35077 40702 35094 40702 35093 40702 35077 40703 35093 40703 35086 40703 35086 40704 35093 40704 35091 40704 35086 40705 35091 40705 35087 40705 35090 40706 34580 40706 35091 40706 35091 40707 34580 40707 34579 40707 35091 40708 34579 40708 35087 40708 35088 40709 35090 40710 35089 40711 35089 40712 35090 40712 35091 40712 35089 40713 35091 40713 35092 40713 35092 40714 35091 40714 35093 40714 35092 40715 35093 40715 35095 40715 35095 40716 35093 40716 35094 40716 35095 40717 35094 40717 34826 40717 34826 40718 35094 40718 35085 40718 34826 40719 35085 40719 34824 40719 34824 40720 35085 40720 35096 40720 35097 40721 35098 40721 35101 40721 35101 40722 35098 40722 35089 40722 35101 40723 35089 40723 35099 40723 35099 40724 35089 40724 35092 40724 35099 40725 35092 40725 34819 40725 34819 40726 35092 40726 35095 40726 34819 40727 35095 40727 34820 40727 34820 40728 35095 40728 34826 40728 34820 40729 34826 40729 34823 40729 34823 40730 34826 40730 35100 40730 34796 40731 34772 40731 34836 40731 34836 40732 34772 40732 35101 40732 34836 40733 35101 40733 34837 40733 34837 40734 35101 40734 35099 40734 34837 40735 35099 40735 34855 40735 34855 40736 35099 40736 34819 40736 34855 40737 34819 40737 35102 40737 35102 40738 34819 40738 34817 40738 35103 40739 35104 40739 35105 40739 35105 40740 35104 40740 35110 40740 35105 40741 35110 40741 35725 40741 35106 40742 35107 40742 35108 40742 35108 40743 35107 40743 35109 40743 35108 40744 35109 40744 35491 40744 35491 40745 35720 40745 35108 40745 35108 40746 35720 40746 35111 40746 35108 40747 35111 40747 35110 40747 35110 40748 35111 40748 35724 40748 35110 40749 35724 40749 35725 40749 35179 40750 35113 40750 35112 40750 35179 40751 35362 40751 35113 40751 35113 40752 35362 40752 35365 40752 35113 40753 35365 40753 35114 40753 35365 40754 35366 40754 35114 40754 35114 40755 35366 40755 35115 40755 35114 40756 35115 40756 35116 40756 35115 40757 35367 40757 35116 40757 35116 40758 35367 40758 35370 40758 35116 40759 35370 40759 35118 40759 35370 40760 35117 40760 35118 40760 35118 40761 35117 40761 35119 40761 35118 40762 35119 40762 35121 40762 35119 40763 35120 40763 35121 40763 35121 40764 35120 40764 35122 40764 35121 40765 35122 40765 35123 40765 35122 40766 35373 40766 35123 40766 35123 40767 35373 40767 35124 40767 35123 40768 35124 40768 35125 40768 35124 40769 35375 40769 35125 40769 35125 40770 35375 40770 35126 40770 35125 40771 35126 40771 35127 40771 35126 40772 35128 40773 35127 40774 35127 40775 35128 40775 35378 40775 35127 40776 35378 40776 35129 40776 35378 40777 35381 40777 35129 40777 35129 40778 35381 40778 35383 40778 35129 40779 35383 40779 35130 40779 35383 40780 35384 40780 35130 40780 35130 40781 35384 40781 35386 40781 35130 40782 35386 40782 35131 40782 35386 40783 35387 40783 35131 40783 35131 40784 35387 40784 35133 40784 35131 40785 35133 40785 35132 40785 35133 40786 35389 40786 35132 40786 35132 40787 35389 40787 35135 40787 35132 40788 35135 40788 35134 40788 35135 40789 35391 40789 35134 40789 35134 40790 35391 40790 35392 40790 35134 40791 35392 40791 35136 40791 35392 40792 35393 40792 35136 40792 35136 40793 35393 40793 35138 40793 35136 40794 35138 40794 35137 40794 35138 40795 35139 40795 35137 40795 35137 40796 35139 40796 35397 40796 35137 40797 35397 40797 35140 40797 35397 40798 35399 40798 35140 40798 35140 40799 35399 40799 35141 40799 35140 40800 35141 40800 35142 40800 35141 40801 35143 40801 35142 40801 35142 40802 35143 40802 35401 40802 35142 40803 35401 40803 35145 40803 35401 40804 35144 40804 35145 40804 35145 40805 35144 40805 35403 40805 35145 40806 35403 40806 35147 40806 35403 40807 35146 40807 35147 40807 35147 40808 35146 40808 35149 40808 35147 40809 35149 40809 35148 40809 35149 40810 35407 40810 35148 40810 35148 40811 35407 40811 35408 40811 35148 40812 35408 40812 35150 40812 35408 40813 35410 40813 35150 40813 35150 40814 35410 40814 35151 40814 35150 40815 35151 40815 35152 40815 35151 40816 35412 40816 35152 40816 35152 40817 35412 40817 35153 40817 35152 40818 35153 40818 35154 40818 35153 40819 35415 40819 35154 40819 35154 40820 35415 40820 35155 40820 35154 40821 35155 40821 35157 40821 35155 40822 35156 40822 35157 40822 35157 40823 35156 40823 35158 40823 35157 40824 35158 40824 35159 40824 35158 40825 35417 40825 35159 40825 35159 40826 35417 40826 35161 40826 35159 40827 35161 40827 35160 40827 35161 40828 35420 40828 35160 40828 35160 40829 35420 40829 35421 40829 35160 40830 35421 40830 35163 40830 35421 40831 35162 40831 35163 40831 35163 40832 35162 40832 35165 40832 35163 40833 35165 40833 35164 40833 35165 40834 35423 40834 35164 40834 35164 40835 35423 40835 35425 40835 35164 40836 35425 40836 35166 40836 35425 40837 35426 40837 35166 40837 35166 40838 35426 40838 35167 40838 35166 40839 35167 40839 35168 40839 35167 40840 35427 40840 35168 40840 35168 40841 35427 40841 35429 40841 35168 40842 35429 40842 35171 40842 35429 40843 35169 40843 35171 40843 35171 40844 35169 40844 35170 40844 35171 40845 35170 40845 35172 40845 35170 40846 35431 40846 35172 40846 35172 40847 35431 40847 35432 40847 35172 40848 35432 40848 35173 40848 35432 40849 35433 40849 35173 40849 35173 40850 35433 40850 35434 40850 35173 40851 35434 40851 35174 40851 35434 40852 35437 40852 35174 40852 35174 40853 35437 40853 35175 40853 35174 40854 35175 40854 35176 40854 35175 40855 35438 40855 35176 40855 35176 40856 35438 40856 35439 40856 35176 40857 35439 40857 35177 40857 35439 40858 35440 40858 35177 40858 35177 40859 35440 40859 35442 40859 35177 40860 35442 40860 35178 40860 35442 40861 35444 40861 35178 40861 35178 40862 35444 40862 35445 40862 35178 40863 35445 40863 35112 40863 35112 40864 35445 40864 35361 40864 35112 40865 35361 40865 35179 40865 35280 40866 35180 40866 35279 40866 35280 40867 35578 40868 35180 40869 35180 40870 35578 40870 35576 40870 35180 40871 35576 40871 35282 40871 35282 40872 35576 40873 35575 40874 35282 40875 35575 40875 35284 40875 35575 40876 35581 40876 35284 40876 35284 40877 35581 40877 35181 40877 35284 40878 35181 40878 35182 40878 35181 40879 35183 40879 35182 40879 35182 40880 35183 40880 35184 40880 35182 40881 35184 40881 35285 40881 35285 40882 35184 40882 35185 40882 35285 40883 35185 40883 35187 40883 35187 40884 35185 40884 35186 40884 35187 40885 35186 40885 35188 40885 35188 40886 35186 40886 35189 40886 35189 40887 35598 40887 35188 40887 35188 40888 35598 40888 35597 40888 35188 40889 35597 40889 35191 40889 35191 40890 35597 40890 35190 40890 35191 40891 35190 40891 35193 40891 35193 40892 35190 40893 35192 40894 35193 40895 35192 40895 35288 40895 35288 40896 35192 40896 35194 40896 35194 40897 35195 40897 35288 40897 35288 40898 35195 40898 35196 40898 35288 40899 35196 40899 35197 40899 35197 40900 35196 40900 35609 40900 35197 40901 35609 40901 35198 40901 35198 40902 35609 40902 35622 40902 35198 40903 35622 40903 35199 40903 35199 40904 35622 40904 35200 40904 35200 40905 35201 40905 35199 40905 35199 40906 35201 40906 35625 40906 35199 40907 35625 40907 35291 40907 35291 40908 35625 40908 35624 40908 35291 40909 35624 40909 35202 40909 35202 40910 35624 40910 35203 40910 35202 40911 35203 40911 35292 40911 35292 40912 35203 40912 35204 40912 35204 40913 35633 40913 35292 40913 35292 40914 35633 40914 35205 40914 35292 40915 35205 40915 35294 40915 35294 40916 35205 40916 35206 40916 35294 40917 35206 40917 35295 40917 35295 40918 35206 40918 35456 40918 35295 40919 35456 40919 35296 40919 35456 40920 35639 40920 35296 40920 35296 40921 35639 40921 35208 40921 35296 40922 35208 40922 35207 40922 35208 40923 35209 40923 35207 40923 35207 40924 35209 40924 35211 40924 35207 40925 35211 40925 35210 40925 35210 40926 35211 40926 35642 40926 35210 40927 35642 40927 35212 40927 35642 40928 35641 40928 35212 40928 35212 40929 35641 40929 35213 40929 35212 40930 35213 40930 35298 40930 35213 40931 35214 40931 35298 40931 35298 40932 35214 40932 35215 40932 35298 40933 35215 40933 35300 40933 35300 40934 35215 40934 35216 40934 35300 40935 35216 40935 35217 40935 35217 40936 35216 40936 35661 40936 35217 40937 35661 40937 35303 40937 35303 40938 35661 40938 35455 40938 35455 40939 35667 40940 35303 40941 35303 40942 35667 40942 35666 40942 35303 40943 35666 40943 35304 40943 35304 40944 35666 40944 35665 40944 35304 40945 35665 40945 35305 40945 35305 40946 35665 40946 35218 40946 35305 40947 35218 40947 35306 40947 35306 40948 35218 40949 35679 40950 35679 40951 35219 40951 35306 40951 35306 40952 35219 40952 35678 40952 35306 40953 35678 40953 35308 40953 35308 40954 35678 40955 35220 40956 35308 40957 35220 40957 35310 40957 35310 40958 35220 40958 35221 40958 35310 40959 35221 40959 35311 40959 35311 40960 35221 40960 35692 40960 35692 40961 35222 40961 35311 40961 35311 40962 35222 40962 35223 40962 35311 40963 35223 40963 35224 40963 35224 40964 35223 40965 35693 40966 35224 40967 35693 40967 35226 40967 35226 40968 35693 40968 35225 40968 35226 40969 35225 40969 35314 40969 35314 40970 35225 40970 35227 40970 35227 40971 35703 40971 35314 40971 35314 40972 35703 40972 35702 40972 35314 40973 35702 40973 35315 40973 35315 40974 35702 40974 35453 40974 35315 40975 35453 40975 35228 40975 35228 40976 35453 40976 35229 40976 35228 40977 35229 40977 35316 40977 35229 40978 35452 40978 35316 40978 35316 40979 35452 40979 35451 40979 35316 40980 35451 40980 35317 40980 35451 40981 35230 40982 35317 40983 35317 40984 35230 40984 35231 40984 35317 40985 35231 40986 35318 40986 35318 40987 35231 40987 35232 40987 35318 40988 35232 40988 35320 40988 35232 40989 35233 40989 35320 40989 35320 40990 35233 40990 35713 40990 35320 40991 35713 40991 35234 40991 35713 40992 35449 40993 35234 40994 35234 40995 35449 40995 35235 40995 35234 40996 35235 40996 35237 40996 35237 40997 35235 40997 35236 40997 35237 40998 35236 40998 35322 40998 35322 40999 35236 40999 35238 40999 35322 41000 35238 41000 35324 41000 35324 41001 35238 41001 35239 41001 35239 41002 35730 41002 35324 41002 35324 41003 35730 41003 35729 41003 35324 41004 35729 41004 35325 41004 35325 41005 35729 41006 35728 41007 35325 41008 35728 41008 35326 41008 35326 41009 35728 41009 35240 41009 35326 41010 35240 41010 35329 41010 35329 41011 35240 41011 35739 41011 35739 41012 35738 41012 35329 41012 35329 41013 35738 41013 35241 41013 35329 41014 35241 41014 35242 41014 35242 41015 35241 41015 35740 41015 35242 41016 35740 41016 35330 41016 35330 41017 35740 41017 35243 41017 35330 41018 35243 41018 35244 41018 35244 41019 35243 41019 35755 41019 35755 41020 35754 41020 35244 41020 35244 41021 35754 41021 35245 41021 35244 41022 35245 41022 35333 41022 35333 41023 35245 41024 35246 41025 35333 41026 35246 41026 35247 41026 35247 41027 35246 41027 35248 41027 35247 41028 35248 41028 35335 41028 35335 41029 35248 41029 35446 41029 35446 41030 35768 41030 35335 41030 35335 41031 35768 41031 35460 41031 35335 41032 35460 41032 35336 41032 35336 41033 35460 41033 35249 41033 35336 41034 35249 41034 35337 41034 35337 41035 35249 41035 35459 41035 35337 41036 35459 41037 35339 41038 35459 41039 35504 41039 35339 41039 35339 41040 35504 41040 35458 41040 35339 41041 35458 41041 35340 41041 35458 41042 35250 41042 35340 41042 35340 41043 35250 41043 35251 41043 35340 41044 35251 41044 35252 41044 35252 41045 35251 41045 35253 41045 35252 41046 35253 41046 35343 41046 35253 41047 35507 41048 35343 41048 35343 41049 35507 41049 35254 41049 35343 41050 35254 41050 35257 41050 35254 41051 35255 41051 35257 41051 35257 41052 35255 41052 35256 41052 35257 41053 35256 41053 35258 41053 35258 41054 35256 41054 35512 41054 35258 41055 35512 41055 35346 41055 35346 41056 35512 41056 35523 41056 35346 41057 35523 41057 35259 41057 35259 41058 35523 41058 35457 41058 35457 41059 35530 41059 35259 41059 35259 41060 35530 41060 35260 41060 35259 41061 35260 41061 35262 41061 35262 41062 35260 41062 35261 41062 35262 41063 35261 41063 35263 41063 35263 41064 35261 41064 35264 41064 35263 41065 35264 41065 35349 41065 35349 41066 35264 41066 35541 41066 35541 41067 35265 41067 35349 41067 35349 41068 35265 41068 35266 41068 35349 41069 35266 41069 35351 41069 35351 41070 35266 41070 35542 41070 35351 41071 35542 41071 35267 41071 35267 41072 35542 41072 35554 41072 35267 41073 35554 41073 35354 41073 35354 41074 35554 41074 35268 41074 35268 41075 35555 41075 35354 41075 35354 41076 35555 41076 35269 41076 35354 41077 35269 41077 35355 41077 35355 41078 35269 41078 35270 41078 35355 41079 35270 41079 35271 41079 35271 41080 35270 41080 35272 41080 35271 41081 35272 41081 35358 41081 35358 41082 35272 41082 35273 41082 35273 41083 35274 41083 35358 41083 35358 41084 35274 41084 35565 41084 35358 41085 35565 41085 35275 41085 35275 41086 35565 41086 35276 41086 35275 41087 35276 41087 35277 41087 35277 41088 35276 41088 35278 41088 35277 41089 35278 41089 35279 41089 35279 41090 35278 41090 35572 41090 35279 41091 35572 41091 35280 41091 35357 41092 35275 41092 35359 41092 35359 41093 35275 41093 35277 41093 35359 41094 35277 41094 35360 41094 35360 41095 35277 41095 35279 41095 35360 41096 35279 41096 35281 41096 35281 41097 35279 41097 35180 41097 35281 41098 35180 41098 35363 41098 35363 41099 35180 41099 35282 41099 35363 41100 35282 41100 35364 41100 35364 41101 35282 41101 35284 41101 35364 41102 35284 41102 35283 41102 35283 41103 35284 41103 35182 41103 35283 41104 35182 41104 35368 41104 35368 41105 35182 41105 35285 41105 35368 41106 35285 41106 35369 41106 35369 41107 35285 41107 35187 41107 35369 41108 35187 41108 35286 41108 35286 41109 35187 41109 35188 41109 35286 41110 35188 41110 35287 41110 35287 41111 35188 41111 35191 41111 35287 41112 35191 41112 35371 41112 35371 41113 35191 41113 35193 41113 35371 41114 35193 41114 35372 41114 35372 41115 35193 41116 35288 41117 35372 41118 35288 41118 35289 41118 35289 41119 35288 41119 35197 41119 35289 41120 35197 41120 35374 41120 35374 41121 35197 41121 35198 41121 35374 41122 35198 41122 35290 41122 35290 41123 35198 41123 35199 41123 35290 41124 35199 41124 35376 41124 35376 41125 35199 41125 35291 41125 35376 41126 35291 41126 35377 41126 35377 41127 35291 41127 35202 41127 35377 41128 35202 41128 35293 41128 35293 41129 35202 41129 35292 41129 35293 41130 35292 41130 35379 41130 35379 41131 35292 41131 35294 41131 35379 41132 35294 41132 35380 41132 35380 41133 35294 41133 35295 41133 35380 41134 35295 41134 35382 41134 35382 41135 35295 41135 35296 41135 35382 41136 35296 41136 35385 41136 35385 41137 35296 41137 35207 41137 35385 41138 35207 41138 35297 41138 35297 41139 35207 41139 35210 41139 35297 41140 35210 41140 35388 41140 35388 41141 35210 41141 35212 41141 35388 41142 35212 41142 35299 41142 35299 41143 35212 41143 35298 41143 35299 41144 35298 41144 35390 41144 35390 41145 35298 41145 35300 41145 35390 41146 35300 41146 35301 41146 35301 41147 35300 41147 35217 41147 35301 41148 35217 41148 35302 41148 35302 41149 35217 41149 35303 41149 35302 41150 35303 41150 35394 41150 35394 41151 35303 41151 35304 41151 35394 41152 35304 41152 35395 41152 35395 41153 35304 41153 35305 41153 35395 41154 35305 41154 35396 41154 35396 41155 35305 41155 35306 41155 35396 41156 35306 41156 35307 41156 35307 41157 35306 41157 35308 41157 35307 41158 35308 41158 35398 41158 35398 41159 35308 41159 35310 41159 35398 41160 35310 41160 35309 41160 35309 41161 35310 41161 35311 41161 35309 41162 35311 41162 35312 41162 35312 41163 35311 41163 35224 41163 35312 41164 35224 41164 35400 41164 35400 41165 35224 41165 35226 41165 35400 41166 35226 41166 35313 41166 35313 41167 35226 41167 35314 41167 35313 41168 35314 41168 35402 41168 35402 41169 35314 41169 35315 41169 35402 41170 35315 41170 35404 41170 35404 41171 35315 41171 35228 41171 35404 41172 35228 41172 35405 41172 35405 41173 35228 41173 35316 41173 35405 41174 35316 41174 35406 41174 35406 41175 35316 41175 35317 41175 35406 41176 35317 41176 35409 41176 35409 41177 35317 41177 35318 41177 35409 41178 35318 41178 35319 41178 35319 41179 35318 41179 35320 41179 35319 41180 35320 41180 35321 41180 35321 41181 35320 41182 35234 41183 35321 41184 35234 41184 35411 41184 35411 41185 35234 41185 35237 41185 35411 41186 35237 41187 35413 41186 35413 41188 35237 41188 35322 41188 35413 41189 35322 41190 35323 41189 35323 41191 35322 41191 35324 41191 35323 41192 35324 41192 35414 41192 35414 41193 35324 41193 35325 41193 35414 41194 35325 41194 35416 41194 35416 41195 35325 41195 35326 41195 35416 41196 35326 41196 35327 41196 35327 41197 35326 41197 35329 41197 35327 41198 35329 41198 35328 41198 35328 41199 35329 41199 35242 41199 35328 41200 35242 41200 35418 41200 35418 41201 35242 41201 35330 41201 35418 41202 35330 41202 35419 41202 35419 41203 35330 41203 35244 41203 35419 41204 35244 41204 35331 41204 35331 41205 35244 41205 35333 41205 35331 41206 35333 41206 35332 41206 35332 41207 35333 41207 35247 41207 35332 41208 35247 41208 35334 41208 35334 41209 35247 41209 35335 41209 35334 41210 35335 41210 35422 41210 35422 41211 35335 41211 35336 41211 35422 41212 35336 41212 35424 41212 35424 41213 35336 41213 35337 41213 35424 41214 35337 41214 35338 41214 35338 41215 35337 41215 35339 41215 35338 41216 35339 41216 35341 41216 35341 41217 35339 41217 35340 41217 35341 41218 35340 41218 35342 41218 35342 41219 35340 41219 35252 41219 35342 41220 35252 41221 35428 41220 35428 41222 35252 41222 35343 41222 35428 41223 35343 41223 35430 41223 35430 41224 35343 41224 35257 41224 35430 41225 35257 41225 35344 41225 35344 41226 35257 41226 35258 41226 35344 41227 35258 41227 35345 41227 35345 41228 35258 41228 35346 41228 35345 41229 35346 41229 35347 41229 35347 41230 35346 41230 35259 41230 35347 41231 35259 41231 35348 41231 35348 41232 35259 41232 35262 41232 35348 41233 35262 41233 35435 41233 35435 41234 35262 41234 35263 41234 35435 41235 35263 41235 35436 41235 35436 41236 35263 41236 35349 41236 35436 41237 35349 41237 35350 41237 35350 41238 35349 41238 35351 41238 35350 41239 35351 41239 35352 41239 35352 41240 35351 41240 35267 41240 35352 41241 35267 41241 35353 41241 35353 41242 35267 41242 35354 41242 35353 41243 35354 41243 35441 41243 35441 41244 35354 41244 35355 41244 35441 41245 35355 41245 35356 41245 35356 41246 35355 41246 35271 41246 35356 41247 35271 41247 35443 41247 35443 41248 35271 41248 35358 41248 35443 41249 35358 41249 35357 41249 35357 41250 35358 41250 35275 41250 35445 41251 35359 41251 35361 41251 35361 41252 35359 41252 35360 41252 35361 41253 35360 41253 35179 41253 35179 41254 35360 41254 35281 41254 35179 41255 35281 41255 35362 41255 35362 41256 35281 41256 35363 41256 35362 41257 35363 41257 35365 41257 35365 41258 35363 41258 35364 41258 35365 41259 35364 41259 35366 41259 35366 41260 35364 41260 35283 41260 35366 41261 35283 41261 35115 41261 35115 41262 35283 41262 35368 41262 35115 41263 35368 41263 35367 41263 35367 41264 35368 41264 35369 41264 35367 41265 35369 41265 35370 41265 35370 41266 35369 41267 35286 41268 35370 41269 35286 41269 35117 41269 35117 41270 35286 41270 35287 41270 35117 41271 35287 41271 35119 41271 35119 41272 35287 41272 35371 41272 35119 41273 35371 41274 35120 41275 35120 41276 35371 41276 35372 41276 35120 41277 35372 41277 35122 41277 35122 41278 35372 41278 35289 41278 35122 41279 35289 41279 35373 41279 35373 41280 35289 41280 35374 41280 35373 41281 35374 41281 35124 41281 35124 41282 35374 41282 35290 41282 35124 41283 35290 41283 35375 41283 35375 41284 35290 41284 35376 41284 35375 41285 35376 41285 35126 41285 35126 41286 35376 41286 35377 41286 35126 41287 35377 41287 35128 41287 35128 41288 35377 41288 35293 41288 35128 41289 35293 41289 35378 41289 35378 41290 35293 41291 35379 41292 35378 41293 35379 41293 35381 41293 35381 41294 35379 41294 35380 41294 35381 41295 35380 41295 35383 41295 35383 41296 35380 41296 35382 41296 35383 41297 35382 41297 35384 41297 35384 41298 35382 41298 35385 41298 35384 41299 35385 41299 35386 41299 35386 41300 35385 41300 35297 41300 35386 41301 35297 41301 35387 41301 35387 41302 35297 41302 35388 41302 35387 41303 35388 41303 35133 41303 35133 41304 35388 41304 35299 41304 35133 41305 35299 41305 35389 41305 35389 41306 35299 41306 35390 41306 35389 41307 35390 41307 35135 41307 35135 41308 35390 41309 35301 41310 35135 41311 35301 41311 35391 41311 35391 41312 35301 41313 35302 41314 35391 41315 35302 41316 35392 41317 35392 41318 35302 41318 35394 41318 35392 41319 35394 41319 35393 41319 35393 41320 35394 41320 35395 41320 35393 41321 35395 41321 35138 41321 35138 41322 35395 41322 35396 41322 35138 41323 35396 41323 35139 41323 35139 41324 35396 41324 35307 41324 35139 41325 35307 41325 35397 41325 35397 41326 35307 41326 35398 41326 35397 41327 35398 41327 35399 41327 35399 41328 35398 41328 35309 41328 35399 41329 35309 41329 35141 41329 35141 41330 35309 41330 35312 41330 35141 41331 35312 41331 35143 41331 35143 41332 35312 41332 35400 41332 35143 41333 35400 41333 35401 41333 35401 41334 35400 41334 35313 41334 35401 41335 35313 41335 35144 41335 35144 41336 35313 41336 35402 41336 35144 41337 35402 41337 35403 41337 35403 41338 35402 41338 35404 41338 35403 41339 35404 41339 35146 41339 35146 41340 35404 41340 35405 41340 35146 41341 35405 41341 35149 41341 35149 41342 35405 41342 35406 41342 35149 41343 35406 41343 35407 41343 35407 41344 35406 41344 35409 41344 35407 41345 35409 41345 35408 41345 35408 41346 35409 41346 35319 41346 35408 41347 35319 41347 35410 41347 35410 41348 35319 41348 35321 41348 35410 41349 35321 41349 35151 41349 35151 41350 35321 41350 35411 41350 35151 41351 35411 41352 35412 41353 35412 41354 35411 41354 35413 41354 35412 41355 35413 41355 35153 41355 35153 41356 35413 41356 35323 41356 35153 41357 35323 41357 35415 41357 35415 41358 35323 41358 35414 41358 35415 41359 35414 41359 35155 41359 35155 41360 35414 41360 35416 41360 35155 41361 35416 41361 35156 41361 35156 41362 35416 41362 35327 41362 35156 41363 35327 41363 35158 41363 35158 41364 35327 41364 35328 41364 35158 41365 35328 41365 35417 41365 35417 41366 35328 41366 35418 41366 35417 41367 35418 41367 35161 41367 35161 41368 35418 41368 35419 41368 35161 41369 35419 41369 35420 41369 35420 41370 35419 41370 35331 41370 35420 41371 35331 41371 35421 41371 35421 41372 35331 41372 35332 41372 35421 41373 35332 41373 35162 41373 35162 41374 35332 41374 35334 41374 35162 41375 35334 41375 35165 41375 35165 41376 35334 41376 35422 41376 35165 41377 35422 41377 35423 41377 35423 41378 35422 41378 35424 41378 35423 41379 35424 41379 35425 41379 35425 41380 35424 41380 35338 41380 35425 41381 35338 41381 35426 41381 35426 41382 35338 41382 35341 41382 35426 41383 35341 41383 35167 41383 35167 41384 35341 41384 35342 41384 35167 41385 35342 41385 35427 41385 35427 41386 35342 41386 35428 41386 35427 41387 35428 41387 35429 41387 35429 41388 35428 41388 35430 41388 35429 41389 35430 41389 35169 41389 35169 41390 35430 41390 35344 41390 35169 41391 35344 41391 35170 41391 35170 41392 35344 41392 35345 41392 35170 41393 35345 41393 35431 41393 35431 41394 35345 41394 35347 41394 35431 41395 35347 41395 35432 41395 35432 41396 35347 41396 35348 41396 35432 41397 35348 41397 35433 41397 35433 41398 35348 41398 35435 41398 35433 41399 35435 41399 35434 41399 35434 41400 35435 41400 35436 41400 35434 41401 35436 41401 35437 41401 35437 41402 35436 41402 35350 41402 35437 41403 35350 41403 35175 41403 35175 41404 35350 41404 35352 41404 35175 41405 35352 41405 35438 41405 35438 41406 35352 41406 35353 41406 35438 41407 35353 41407 35439 41407 35439 41408 35353 41409 35441 41410 35439 41411 35441 41411 35440 41411 35440 41412 35441 41412 35356 41412 35440 41413 35356 41413 35442 41413 35442 41414 35356 41414 35443 41414 35442 41415 35443 41415 35444 41415 35444 41416 35443 41416 35357 41416 35444 41417 35357 41418 35445 41419 35445 41420 35357 41420 35359 41420 35768 41421 35446 41421 35447 41421 35248 41422 35246 41422 35760 41422 35243 41423 35740 41423 35741 41423 35730 41424 35239 41424 35448 41424 35449 41425 35713 41426 35450 41427 35230 41428 35451 41429 35712 41430 35452 41431 35229 41431 35707 41431 35453 41432 35702 41432 35454 41432 35703 41433 35227 41433 35705 41433 35225 41434 35693 41434 35694 41434 35221 41435 35220 41435 35680 41435 35667 41436 35455 41436 35660 41436 35214 41437 35213 41437 35647 41437 35209 41438 35208 41438 35644 41438 35639 41439 35456 41439 35640 41439 35206 41440 35205 41440 35634 41440 35633 41441 35204 41441 35629 41441 35203 41442 35624 41442 35626 41442 35622 41443 35609 41443 35610 41443 35598 41444 35189 41445 35600 41446 35183 41447 35181 41447 35580 41447 35578 41448 35280 41449 35573 41450 35572 41451 35278 41451 35569 41451 35276 41452 35565 41452 35570 41452 35274 41453 35273 41453 35561 41453 35272 41454 35270 41454 35556 41454 35554 41455 35542 41455 35552 41455 35530 41456 35457 41456 35531 41456 35255 41457 35254 41458 35513 41459 35250 41460 35458 41460 35506 41460 35504 41461 35459 41462 35505 41463 35249 41464 35460 41464 35500 41464 35671 41465 35461 41465 35672 41465 35462 41466 35663 41467 35662 41468 35463 41469 35464 41469 35466 41469 35466 41470 35464 41470 35630 41470 35466 41471 35630 41471 35465 41471 35463 41472 35466 41473 35467 41474 35467 41475 35466 41475 35465 41475 35467 41476 35465 41476 35468 41476 35628 41477 35469 41477 35632 41477 35632 41478 35469 41478 35470 41478 35471 41479 35472 41479 35605 41479 35473 41480 35474 41480 35594 41480 35475 41481 35476 41481 35477 41481 35477 41482 35476 41483 35567 41484 35477 41485 35567 41485 35479 41485 35475 41486 35477 41486 35478 41486 35478 41487 35477 41487 35479 41487 35478 41488 35479 41488 35480 41488 35559 41489 35482 41489 35481 41489 35481 41490 35482 41490 35564 41490 35534 41491 35483 41491 35533 41491 35774 41492 35528 41492 35527 41492 35485 41493 35484 41493 35486 41493 35486 41494 35484 41495 35763 41496 35486 41497 35763 41497 35764 41497 35485 41498 35486 41498 35487 41498 35487 41499 35486 41499 35764 41499 35487 41500 35764 41500 35765 41500 35758 41501 35488 41501 35766 41501 35766 41502 35488 41502 35767 41502 35489 41503 35490 41503 35733 41503 35491 41504 35109 41504 35718 41504 35494 41505 35493 41505 35492 41505 35492 41506 35493 41506 35698 41506 35492 41507 35698 41507 35701 41507 35494 41508 35492 41509 35495 41510 35495 41511 35492 41511 35701 41511 35495 41512 35701 41512 35496 41512 35497 41513 35498 41513 35696 41513 35696 41514 35498 41514 35499 41514 35459 41515 35249 41515 35505 41515 35505 41516 35249 41516 35500 41516 35505 41517 35500 41517 35501 41517 35501 41518 35500 41518 35502 41518 35501 41519 35502 41519 35520 41519 35520 41520 35502 41520 35503 41520 35458 41521 35504 41521 35506 41521 35506 41522 35504 41522 35505 41522 35506 41523 35505 41523 35509 41523 35509 41524 35505 41524 35501 41524 35509 41525 35501 41525 35519 41525 35519 41526 35501 41526 35520 41526 35507 41527 35253 41527 35508 41527 35508 41528 35253 41528 35251 41528 35251 41529 35250 41529 35508 41529 35508 41530 35250 41530 35506 41530 35508 41531 35506 41531 35511 41531 35511 41532 35506 41532 35509 41532 35511 41533 35509 41533 35516 41533 35516 41534 35509 41534 35519 41534 35254 41535 35507 41535 35513 41535 35513 41536 35507 41536 35508 41536 35513 41537 35508 41537 35515 41537 35515 41538 35508 41538 35511 41538 35515 41539 35511 41539 35510 41539 35510 41540 35511 41540 35516 41540 35523 41541 35512 41541 35524 41541 35524 41542 35512 41542 35256 41542 35256 41543 35255 41543 35524 41543 35524 41544 35255 41544 35513 41544 35524 41545 35513 41545 35514 41545 35514 41546 35513 41546 35515 41546 35514 41547 35515 41547 35527 41547 35527 41548 35515 41548 35510 41548 35527 41549 35510 41549 35774 41549 35774 41550 35510 41550 35516 41550 35774 41551 35516 41551 35517 41551 35517 41552 35516 41552 35519 41552 35517 41553 35519 41553 35518 41553 35518 41554 35519 41554 35520 41554 35518 41555 35520 41555 35521 41555 35521 41556 35520 41556 35503 41556 35521 41557 35503 41557 35776 41557 35776 41558 35503 41558 35522 41558 35457 41559 35523 41559 35531 41559 35531 41560 35523 41560 35524 41560 35531 41561 35524 41561 35532 41561 35532 41562 35524 41562 35514 41562 35532 41563 35514 41563 35525 41563 35525 41564 35514 41564 35527 41564 35525 41565 35527 41565 35526 41565 35526 41566 35527 41566 35528 41566 35526 41567 35528 41567 35535 41567 35264 41568 35261 41568 35529 41568 35529 41569 35261 41570 35260 41570 35260 41571 35530 41571 35529 41571 35529 41572 35530 41572 35531 41572 35529 41573 35531 41573 35538 41573 35538 41574 35531 41574 35532 41574 35538 41575 35532 41575 35537 41575 35537 41576 35532 41576 35525 41576 35537 41577 35525 41577 35533 41577 35533 41578 35525 41578 35526 41578 35533 41579 35526 41579 35534 41579 35534 41580 35526 41581 35535 41582 35483 41583 35547 41583 35533 41583 35533 41584 35547 41584 35536 41584 35533 41585 35536 41585 35537 41585 35537 41586 35536 41586 35539 41586 35537 41587 35539 41587 35538 41587 35538 41588 35539 41588 35543 41588 35538 41589 35543 41589 35529 41589 35529 41590 35543 41590 35540 41590 35529 41591 35540 41591 35264 41591 35266 41592 35265 41592 35540 41592 35540 41593 35265 41593 35541 41593 35540 41594 35541 41594 35264 41594 35542 41595 35266 41595 35552 41595 35552 41596 35266 41596 35540 41596 35552 41597 35540 41597 35551 41597 35551 41598 35540 41598 35543 41598 35551 41599 35543 41599 35544 41599 35544 41600 35543 41600 35539 41600 35544 41601 35539 41601 35545 41601 35545 41602 35539 41602 35536 41602 35545 41603 35536 41603 35546 41603 35546 41604 35536 41604 35547 41604 35546 41605 35547 41605 35548 41605 35546 41606 35560 41606 35545 41606 35545 41607 35560 41607 35549 41607 35545 41608 35549 41608 35544 41608 35544 41609 35549 41609 35550 41609 35544 41610 35550 41610 35551 41610 35551 41611 35550 41611 35557 41611 35551 41612 35557 41612 35552 41612 35552 41613 35557 41613 35553 41613 35552 41614 35553 41614 35554 41614 35269 41615 35555 41615 35553 41615 35553 41616 35555 41616 35268 41616 35553 41617 35268 41617 35554 41617 35270 41618 35269 41619 35556 41620 35556 41621 35269 41621 35553 41621 35556 41622 35553 41622 35558 41622 35558 41623 35553 41623 35557 41623 35558 41624 35557 41624 35563 41624 35563 41625 35557 41625 35550 41625 35563 41626 35550 41626 35481 41626 35481 41627 35550 41627 35549 41627 35481 41628 35549 41628 35559 41628 35559 41629 35549 41629 35560 41629 35273 41630 35272 41630 35561 41630 35561 41631 35272 41631 35556 41631 35561 41632 35556 41632 35562 41632 35562 41633 35556 41633 35558 41633 35562 41634 35558 41634 35567 41634 35567 41635 35558 41635 35563 41635 35567 41636 35563 41636 35479 41636 35479 41637 35563 41637 35481 41637 35479 41638 35481 41638 35480 41638 35480 41639 35481 41639 35564 41639 35565 41640 35274 41640 35570 41640 35570 41641 35274 41641 35561 41641 35570 41642 35561 41642 35571 41642 35571 41643 35561 41643 35562 41643 35571 41644 35562 41644 35566 41644 35566 41645 35562 41645 35567 41645 35566 41646 35567 41646 35568 41646 35568 41647 35567 41647 35476 41647 35278 41648 35276 41648 35569 41648 35569 41649 35276 41649 35570 41649 35569 41650 35570 41650 35574 41650 35574 41651 35570 41651 35571 41651 35574 41652 35571 41652 35588 41652 35588 41653 35571 41653 35566 41653 35280 41654 35572 41654 35573 41654 35573 41655 35572 41655 35569 41655 35573 41656 35569 41656 35579 41656 35579 41657 35569 41657 35574 41657 35579 41658 35574 41658 35587 41658 35587 41659 35574 41659 35588 41659 35581 41660 35575 41660 35577 41660 35577 41661 35575 41661 35576 41661 35576 41662 35578 41662 35577 41662 35577 41663 35578 41663 35573 41663 35577 41664 35573 41664 35582 41664 35582 41665 35573 41665 35579 41665 35582 41666 35579 41666 35585 41666 35585 41667 35579 41667 35587 41667 35181 41668 35581 41668 35580 41668 35580 41669 35581 41669 35577 41669 35580 41670 35577 41670 35583 41670 35583 41671 35577 41671 35582 41671 35583 41672 35582 41672 35584 41672 35584 41673 35582 41673 35585 41673 35186 41674 35185 41674 35592 41674 35592 41675 35185 41675 35184 41675 35184 41676 35183 41676 35592 41676 35592 41677 35183 41677 35580 41677 35592 41678 35580 41678 35593 41678 35593 41679 35580 41679 35583 41679 35593 41680 35583 41680 35594 41680 35594 41681 35583 41681 35584 41681 35594 41682 35584 41682 35473 41682 35473 41683 35584 41683 35585 41683 35473 41684 35585 41684 35586 41684 35586 41685 35585 41685 35587 41685 35586 41686 35587 41686 35589 41686 35589 41687 35587 41687 35588 41687 35589 41688 35588 41688 35590 41688 35590 41689 35588 41689 35566 41689 35590 41690 35566 41690 35591 41690 35591 41691 35566 41692 35568 41693 35189 41694 35186 41694 35600 41694 35600 41695 35186 41695 35592 41695 35600 41696 35592 41696 35602 41696 35602 41697 35592 41697 35593 41697 35602 41698 35593 41698 35595 41698 35595 41699 35593 41699 35594 41699 35595 41700 35594 41700 35596 41700 35596 41701 35594 41701 35474 41701 35596 41702 35474 41703 35604 41704 35192 41705 35190 41705 35599 41705 35599 41706 35190 41706 35597 41706 35597 41707 35598 41707 35599 41707 35599 41708 35598 41708 35600 41708 35599 41709 35600 41709 35601 41709 35601 41710 35600 41710 35602 41710 35601 41711 35602 41711 35603 41711 35603 41712 35602 41712 35595 41712 35603 41713 35595 41713 35605 41713 35605 41714 35595 41714 35596 41714 35605 41715 35596 41715 35471 41715 35471 41716 35596 41716 35604 41716 35472 41717 35613 41717 35605 41717 35605 41718 35613 41718 35606 41718 35605 41719 35606 41719 35603 41719 35603 41720 35606 41720 35612 41720 35603 41721 35612 41721 35601 41721 35601 41722 35612 41722 35607 41722 35601 41723 35607 41723 35599 41723 35599 41724 35607 41724 35608 41724 35599 41725 35608 41725 35192 41725 35196 41726 35195 41726 35608 41726 35608 41727 35195 41727 35194 41727 35608 41728 35194 41728 35192 41728 35609 41729 35196 41730 35610 41731 35610 41732 35196 41732 35608 41732 35610 41733 35608 41733 35611 41733 35611 41734 35608 41734 35607 41734 35611 41735 35607 41735 35619 41735 35619 41736 35607 41736 35612 41736 35619 41737 35612 41737 35618 41737 35618 41738 35612 41738 35606 41738 35618 41739 35606 41739 35615 41739 35615 41740 35606 41740 35613 41740 35615 41741 35613 41741 35614 41741 35615 41742 35616 41742 35618 41742 35618 41743 35616 41743 35617 41743 35618 41744 35617 41744 35619 41744 35619 41745 35617 41745 35620 41745 35619 41746 35620 41746 35611 41746 35611 41747 35620 41747 35621 41747 35611 41748 35621 41748 35610 41748 35610 41749 35621 41749 35623 41749 35610 41750 35623 41750 35622 41750 35625 41751 35201 41751 35623 41751 35623 41752 35201 41752 35200 41752 35623 41753 35200 41753 35622 41753 35624 41754 35625 41754 35626 41754 35626 41755 35625 41755 35623 41755 35626 41756 35623 41756 35631 41756 35631 41757 35623 41757 35621 41757 35631 41758 35621 41758 35627 41758 35627 41759 35621 41759 35620 41759 35627 41760 35620 41760 35632 41760 35632 41761 35620 41761 35617 41761 35632 41762 35617 41762 35628 41762 35628 41763 35617 41763 35616 41763 35204 41764 35203 41764 35629 41764 35629 41765 35203 41765 35626 41765 35629 41766 35626 41766 35635 41766 35635 41767 35626 41767 35631 41767 35635 41768 35631 41768 35630 41768 35630 41769 35631 41769 35627 41769 35630 41770 35627 41770 35465 41770 35465 41771 35627 41771 35632 41771 35465 41772 35632 41772 35468 41772 35468 41773 35632 41773 35470 41773 35205 41774 35633 41774 35634 41774 35634 41775 35633 41775 35629 41775 35634 41776 35629 41776 35638 41776 35638 41777 35629 41777 35635 41777 35638 41778 35635 41778 35658 41778 35658 41779 35635 41779 35630 41779 35658 41780 35630 41780 35636 41780 35636 41781 35630 41781 35464 41781 35456 41782 35206 41782 35640 41782 35640 41783 35206 41783 35634 41783 35640 41784 35634 41784 35637 41784 35637 41785 35634 41785 35638 41785 35637 41786 35638 41786 35655 41786 35655 41787 35638 41787 35658 41787 35208 41788 35639 41788 35644 41788 35644 41789 35639 41789 35640 41789 35644 41790 35640 41790 35645 41790 35645 41791 35640 41791 35637 41791 35645 41792 35637 41792 35653 41792 35653 41793 35637 41793 35655 41793 35641 41794 35642 41794 35643 41794 35643 41795 35642 41795 35211 41795 35211 41796 35209 41796 35643 41796 35643 41797 35209 41797 35644 41797 35643 41798 35644 41798 35648 41798 35648 41799 35644 41799 35645 41799 35648 41800 35645 41800 35646 41800 35646 41801 35645 41801 35653 41801 35213 41802 35641 41802 35647 41802 35647 41803 35641 41803 35643 41803 35647 41804 35643 41804 35651 41804 35651 41805 35643 41805 35648 41805 35651 41806 35648 41806 35652 41806 35652 41807 35648 41807 35646 41807 35661 41808 35216 41808 35649 41808 35649 41809 35216 41809 35215 41809 35215 41810 35214 41810 35649 41810 35649 41811 35214 41811 35647 41811 35649 41812 35647 41812 35650 41812 35650 41813 35647 41813 35651 41813 35650 41814 35651 41814 35662 41814 35662 41815 35651 41815 35652 41815 35662 41816 35652 41816 35462 41816 35462 41817 35652 41817 35646 41817 35462 41818 35646 41818 35654 41818 35654 41819 35646 41819 35653 41819 35654 41820 35653 41820 35656 41820 35656 41821 35653 41821 35655 41821 35656 41822 35655 41822 35657 41822 35657 41823 35655 41823 35658 41823 35657 41824 35658 41824 35659 41824 35659 41825 35658 41825 35636 41825 35455 41826 35661 41826 35660 41826 35660 41827 35661 41827 35649 41827 35660 41828 35649 41828 35668 41828 35668 41829 35649 41829 35650 41829 35668 41830 35650 41830 35669 41830 35669 41831 35650 41831 35662 41831 35669 41832 35662 41832 35670 41832 35670 41833 35662 41833 35663 41833 35670 41834 35663 41834 35664 41834 35218 41835 35665 41835 35677 41835 35677 41836 35665 41836 35666 41836 35666 41837 35667 41837 35677 41837 35677 41838 35667 41838 35660 41838 35677 41839 35660 41839 35675 41839 35675 41840 35660 41840 35668 41840 35675 41841 35668 41841 35674 41841 35674 41842 35668 41842 35669 41842 35674 41843 35669 41843 35672 41843 35672 41844 35669 41844 35670 41844 35672 41845 35670 41845 35671 41845 35671 41846 35670 41847 35664 41848 35461 41849 35673 41849 35672 41849 35672 41850 35673 41850 35685 41850 35672 41851 35685 41851 35674 41851 35674 41852 35685 41852 35683 41852 35674 41853 35683 41853 35675 41853 35675 41854 35683 41854 35676 41854 35675 41855 35676 41855 35677 41855 35677 41856 35676 41856 35681 41856 35677 41857 35681 41857 35218 41857 35678 41858 35219 41858 35681 41858 35681 41859 35219 41859 35679 41859 35681 41860 35679 41860 35218 41860 35220 41861 35678 41861 35680 41861 35680 41862 35678 41862 35681 41862 35680 41863 35681 41863 35689 41863 35689 41864 35681 41864 35676 41864 35689 41865 35676 41865 35682 41865 35682 41866 35676 41866 35683 41866 35682 41867 35683 41867 35684 41867 35684 41868 35683 41868 35685 41868 35684 41869 35685 41869 35687 41869 35687 41870 35685 41870 35673 41870 35687 41871 35673 41871 35686 41871 35687 41872 35697 41872 35684 41872 35684 41873 35697 41873 35688 41873 35684 41874 35688 41874 35682 41874 35682 41875 35688 41875 35695 41875 35682 41876 35695 41876 35689 41876 35689 41877 35695 41877 35690 41877 35689 41878 35690 41878 35680 41878 35680 41879 35690 41879 35691 41879 35680 41880 35691 41880 35221 41880 35223 41881 35222 41881 35691 41881 35691 41882 35222 41882 35692 41882 35691 41883 35692 41883 35221 41883 35693 41884 35223 41885 35694 41886 35694 41887 35223 41887 35691 41887 35694 41888 35691 41888 35699 41888 35699 41889 35691 41889 35690 41889 35699 41890 35690 41890 35700 41890 35700 41891 35690 41891 35695 41891 35700 41892 35695 41892 35696 41892 35696 41893 35695 41893 35688 41893 35696 41894 35688 41894 35497 41894 35497 41895 35688 41895 35697 41895 35227 41896 35225 41896 35705 41896 35705 41897 35225 41897 35694 41897 35705 41898 35694 41898 35706 41898 35706 41899 35694 41899 35699 41899 35706 41900 35699 41900 35698 41900 35698 41901 35699 41901 35700 41901 35698 41902 35700 41902 35701 41902 35701 41903 35700 41903 35696 41903 35701 41904 35696 41904 35496 41904 35496 41905 35696 41905 35499 41905 35702 41906 35703 41906 35454 41906 35454 41907 35703 41907 35705 41907 35454 41908 35705 41908 35704 41908 35704 41909 35705 41909 35706 41909 35704 41910 35706 41910 35723 41910 35723 41911 35706 41911 35698 41911 35723 41912 35698 41912 35105 41912 35105 41913 35698 41913 35493 41913 35229 41914 35453 41914 35707 41915 35707 41916 35453 41916 35454 41916 35707 41917 35454 41917 35709 41917 35709 41918 35454 41918 35704 41918 35709 41919 35704 41919 35710 41919 35710 41920 35704 41920 35723 41920 35451 41921 35452 41921 35712 41921 35712 41922 35452 41922 35707 41922 35712 41923 35707 41923 35708 41923 35708 41924 35707 41924 35709 41924 35708 41925 35709 41925 35722 41925 35722 41926 35709 41926 35710 41926 35233 41927 35232 41927 35714 41927 35714 41928 35232 41928 35231 41928 35231 41929 35230 41929 35714 41929 35714 41930 35230 41930 35712 41930 35714 41931 35712 41931 35711 41931 35711 41932 35712 41932 35708 41932 35711 41933 35708 41933 35721 41933 35721 41934 35708 41934 35722 41934 35713 41935 35233 41935 35450 41935 35450 41936 35233 41936 35714 41936 35450 41937 35714 41937 35719 41937 35719 41938 35714 41938 35711 41938 35719 41939 35711 41939 35715 41939 35715 41940 35711 41940 35721 41940 35238 41941 35236 41941 35716 41941 35716 41942 35236 41942 35235 41942 35235 41943 35449 41943 35716 41943 35716 41944 35449 41944 35450 41944 35716 41945 35450 41945 35717 41945 35717 41946 35450 41946 35719 41946 35717 41947 35719 41947 35718 41947 35718 41948 35719 41948 35715 41948 35718 41949 35715 41949 35491 41949 35491 41950 35715 41950 35721 41950 35491 41951 35721 41951 35720 41951 35720 41952 35721 41952 35722 41952 35720 41953 35722 41953 35111 41953 35111 41954 35722 41954 35710 41954 35111 41955 35710 41955 35724 41955 35724 41956 35710 41956 35723 41956 35724 41957 35723 41957 35725 41957 35725 41958 35723 41958 35105 41958 35239 41959 35238 41959 35448 41959 35448 41960 35238 41960 35716 41960 35448 41961 35716 41961 35731 41961 35731 41962 35716 41962 35717 41962 35731 41963 35717 41963 35726 41963 35726 41964 35717 41964 35718 41964 35726 41965 35718 41965 35727 41965 35727 41966 35718 41966 35109 41966 35727 41967 35109 41967 35734 41967 35240 41968 35728 41968 35737 41968 35737 41969 35728 41969 35729 41969 35729 41970 35730 41970 35737 41970 35737 41971 35730 41971 35448 41971 35737 41972 35448 41972 35736 41972 35736 41973 35448 41973 35731 41973 35736 41974 35731 41974 35732 41974 35732 41975 35731 41975 35726 41975 35732 41976 35726 41976 35733 41976 35733 41977 35726 41977 35727 41977 35733 41978 35727 41978 35489 41978 35489 41979 35727 41979 35734 41979 35490 41980 35735 41980 35733 41980 35733 41981 35735 41981 35746 41981 35733 41982 35746 41982 35732 41982 35732 41983 35746 41983 35745 41983 35732 41984 35745 41984 35736 41984 35736 41985 35745 41985 35744 41985 35736 41986 35744 41986 35737 41986 35737 41987 35744 41987 35743 41987 35737 41988 35743 41988 35240 41988 35241 41989 35738 41989 35743 41989 35743 41990 35738 41990 35739 41990 35743 41991 35739 41991 35240 41991 35740 41992 35241 41992 35741 41992 35741 41993 35241 41993 35743 41993 35741 41994 35743 41994 35742 41994 35742 41995 35743 41995 35744 41995 35742 41996 35744 41996 35751 41996 35751 41997 35744 41997 35745 41997 35751 41998 35745 41998 35750 41998 35750 41999 35745 41999 35746 41999 35750 42000 35746 42000 35748 42000 35748 42001 35746 42001 35735 42001 35748 42002 35735 42003 35747 42004 35748 42005 35759 42005 35750 42005 35750 42006 35759 42006 35749 42006 35750 42007 35749 42007 35751 42007 35751 42008 35749 42008 35756 42008 35751 42009 35756 42009 35742 42009 35742 42010 35756 42010 35752 42010 35742 42011 35752 42011 35741 42011 35741 42012 35752 42012 35753 42012 35741 42013 35753 42013 35243 42013 35245 42014 35754 42014 35753 42014 35753 42015 35754 42015 35755 42015 35753 42016 35755 42016 35243 42016 35246 42017 35245 42018 35760 42019 35760 42020 35245 42020 35753 42020 35760 42021 35753 42021 35762 42021 35762 42022 35753 42022 35752 42022 35762 42023 35752 42023 35757 42023 35757 42024 35752 42024 35756 42024 35757 42025 35756 42025 35766 42025 35766 42026 35756 42026 35749 42026 35766 42027 35749 42027 35758 42027 35758 42028 35749 42028 35759 42028 35446 42029 35248 42029 35447 42029 35447 42030 35248 42030 35760 42030 35447 42031 35760 42031 35761 42031 35761 42032 35760 42032 35762 42032 35761 42033 35762 42033 35763 42033 35763 42034 35762 42034 35757 42034 35763 42035 35757 42035 35764 42035 35764 42036 35757 42036 35766 42036 35764 42037 35766 42037 35765 42037 35765 42038 35766 42038 35767 42038 35460 42039 35768 42039 35500 42039 35500 42040 35768 42040 35447 42040 35500 42041 35447 42041 35502 42041 35502 42042 35447 42042 35761 42042 35502 42043 35761 42043 35503 42043 35503 42044 35761 42044 35763 42044 35503 42045 35763 42045 35522 42045 35522 42046 35763 42046 35484 42046 35769 42047 35770 42047 35522 42047 35522 42048 35770 42048 35771 42048 35522 42049 35771 42050 35776 42051 35772 42052 35773 42052 35775 42052 35775 42053 35773 42053 35528 42053 35775 42054 35528 42054 35774 42054 35774 42055 35517 42055 35775 42055 35775 42056 35517 42057 35518 42058 35775 42059 35518 42059 35771 42059 35771 42060 35518 42060 35521 42060 35771 42061 35521 42061 35776 42061 35777 42062 35778 42062 35780 42062 35780 42063 35778 42063 35779 42063 35780 42064 35779 42065 35787 42066 35781 42067 35782 42067 35786 42068 35786 42069 35782 42069 35783 42069 35786 42070 35783 42070 36201 42070 36201 42071 35784 42071 35786 42071 35786 42072 35784 42072 35785 42072 35786 42073 35785 42073 35779 42073 35779 42074 35785 42074 36203 42074 35779 42075 36203 42075 35787 42075 35789 42076 35857 42076 36034 42076 36034 42077 35788 42077 35789 42077 35789 42078 35788 42078 36036 42078 35789 42079 36036 42079 35790 42079 36036 42080 36037 42080 35790 42080 35790 42081 36037 42081 35791 42081 35790 42082 35791 42082 35792 42082 35791 42083 35793 42083 35792 42083 35792 42084 35793 42084 35794 42084 35792 42085 35794 42085 35795 42085 35794 42086 35796 42086 35795 42086 35795 42087 35796 42087 36040 42087 35795 42088 36040 42088 35797 42088 36040 42089 36042 42089 35797 42089 35797 42090 36042 42090 36044 42090 35797 42091 36044 42091 35799 42091 36044 42092 35798 42092 35799 42092 35799 42093 35798 42093 36045 42093 35799 42094 36045 42094 35800 42094 36045 42095 36047 42095 35800 42095 35800 42096 36047 42096 35801 42096 35800 42097 35801 42097 35802 42097 35801 42098 36050 42098 35802 42098 35802 42099 36050 42099 35803 42099 35802 42100 35803 42100 35805 42100 35803 42101 35804 42101 35805 42101 35805 42102 35804 42102 35806 42102 35805 42103 35806 42103 35808 42103 35806 42104 36052 42104 35808 42104 35808 42105 36052 42105 35807 42105 35808 42106 35807 42106 35809 42106 35807 42107 36055 42107 35809 42107 35809 42108 36055 42108 36057 42108 35809 42109 36057 42109 35810 42109 36057 42110 36058 42110 35810 42110 35810 42111 36058 42111 36059 42111 35810 42112 36059 42112 35811 42112 36059 42113 36060 42113 35811 42113 35811 42114 36060 42114 36061 42114 35811 42115 36061 42115 35812 42115 36061 42116 35813 42116 35812 42116 35812 42117 35813 42117 35814 42117 35812 42118 35814 42118 35815 42118 35814 42119 35816 42119 35815 42119 35815 42120 35816 42120 36063 42120 35815 42121 36063 42121 35818 42121 36063 42122 35817 42122 35818 42122 35818 42123 35817 42123 35819 42123 35818 42124 35819 42124 35820 42124 35819 42125 36067 42126 35820 42127 35820 42128 36067 42128 35822 42128 35820 42129 35822 42129 35821 42129 35822 42130 36069 42130 35821 42130 35821 42131 36069 42131 35823 42131 35821 42132 35823 42132 35824 42132 35823 42133 36071 42133 35824 42133 35824 42134 36071 42134 36072 42134 35824 42135 36072 42135 35825 42135 36072 42136 36073 42136 35825 42136 35825 42137 36073 42137 35827 42137 35825 42138 35827 42138 35826 42138 35827 42139 35828 42139 35826 42139 35826 42140 35828 42140 36077 42140 35826 42141 36077 42141 35831 42141 36077 42142 35829 42142 35831 42142 35831 42143 35829 42143 35830 42143 35831 42144 35830 42144 35832 42144 35830 42145 36080 42145 35832 42145 35832 42146 36080 42146 36081 42146 35832 42147 36081 42147 35833 42147 36081 42148 35834 42148 35833 42148 35833 42149 35834 42149 35835 42149 35833 42150 35835 42150 35837 42150 35835 42151 35836 42151 35837 42151 35837 42152 35836 42152 35838 42152 35837 42153 35838 42153 35839 42153 35838 42154 36084 42154 35839 42154 35839 42155 36084 42155 36085 42155 35839 42156 36085 42156 35840 42156 36085 42157 36086 42157 35840 42157 35840 42158 36086 42158 36087 42158 35840 42159 36087 42159 35842 42159 36087 42160 35841 42160 35842 42160 35842 42161 35841 42161 36090 42161 35842 42162 36090 42162 35843 42162 36090 42163 36091 42163 35843 42163 35843 42164 36091 42164 36092 42164 35843 42165 36092 42165 35844 42165 36092 42166 36094 42166 35844 42166 35844 42167 36094 42167 35845 42167 35844 42168 35845 42168 35846 42168 35845 42169 36095 42169 35846 42169 35846 42170 36095 42170 36097 42170 35846 42171 36097 42171 35847 42171 36097 42172 36100 42172 35847 42172 35847 42173 36100 42173 36101 42173 35847 42174 36101 42174 35849 42174 36101 42175 35848 42175 35849 42175 35849 42176 35848 42177 35850 42178 35849 42179 35850 42179 35851 42179 35850 42180 36102 42180 35851 42180 35851 42181 36102 42181 36103 42181 35851 42182 36103 42182 35852 42182 36103 42183 35853 42183 35852 42183 35852 42184 35853 42184 36106 42184 35852 42185 36106 42185 35854 42185 36106 42186 36107 42186 35854 42186 35854 42187 36107 42187 36110 42187 35854 42188 36110 42188 35856 42188 36110 42189 35855 42190 35856 42191 35856 42192 35855 42192 36112 42192 35856 42193 36112 42193 35857 42193 35857 42194 36112 42194 36032 42194 35857 42195 36032 42195 36034 42195 36135 42196 35966 42196 35965 42196 36135 42197 35858 42198 35966 42199 35966 42200 35858 42200 35859 42200 35966 42201 35859 42201 35968 42201 35968 42202 35859 42202 36248 42202 35968 42203 36248 42203 35860 42203 36248 42204 35861 42204 35860 42204 35860 42205 35861 42205 35862 42205 35860 42206 35862 42206 35863 42206 35862 42207 36133 42207 35863 42207 35863 42208 36133 42208 36255 42208 35863 42209 36255 42209 35864 42209 35864 42210 36255 42210 35865 42210 35864 42211 35865 42211 35970 42211 35970 42212 35865 42212 36253 42212 35970 42213 36253 42213 35973 42213 35973 42214 36253 42214 36265 42214 36265 42215 35866 42215 35973 42215 35973 42216 35866 42216 35867 42216 35973 42217 35867 42217 35975 42217 35975 42218 35867 42219 35868 42220 35975 42221 35868 42221 35976 42221 35976 42222 35868 42222 36282 42222 35976 42223 36282 42223 35870 42223 35870 42224 36282 42224 36281 42224 36281 42225 35869 42225 35870 42225 35870 42226 35869 42226 36284 42226 35870 42227 36284 42227 35871 42227 35871 42228 36284 42228 36283 42228 35871 42229 36283 42229 35978 42229 35978 42230 36283 42230 35872 42230 35978 42231 35872 42231 35873 42231 35873 42232 35872 42232 36294 42232 36294 42233 35874 42234 35873 42235 35873 42236 35874 42236 35875 42236 35873 42237 35875 42237 35980 42237 35980 42238 35875 42239 35876 42240 35980 42241 35876 42241 35877 42241 35877 42242 35876 42242 36303 42242 35877 42243 36303 42243 35981 42243 35981 42244 36303 42244 36302 42244 36302 42245 36130 42245 35981 42245 35981 42246 36130 42246 35878 42246 35981 42247 35878 42247 35879 42247 35879 42248 35878 42248 36310 42248 35879 42249 36310 42249 35880 42249 35880 42250 36310 42250 36309 42250 35880 42251 36309 42251 35881 42251 36309 42252 36127 42252 35881 42252 35881 42253 36127 42253 36126 42253 35881 42254 36126 42254 35882 42254 36126 42255 36317 42256 35882 42257 35882 42258 36317 42258 35883 42258 35882 42259 35883 42259 35884 42259 35884 42260 35883 42260 35886 42260 35884 42261 35886 42261 35885 42261 35886 42262 36316 42262 35885 42262 35885 42263 36316 42263 36125 42263 35885 42264 36125 42264 35887 42264 36125 42265 36323 42265 35887 42265 35887 42266 36323 42266 36322 42266 35887 42267 36322 42267 35987 42267 35987 42268 36322 42268 35889 42268 35987 42269 35889 42269 35888 42269 35888 42270 35889 42270 35890 42270 35888 42271 35890 42271 35990 42271 35990 42272 35890 42272 35891 42272 35891 42273 35892 42273 35990 42273 35990 42274 35892 42274 35893 42274 35990 42275 35893 42275 35895 42275 35895 42276 35893 42276 35894 42276 35895 42277 35894 42277 35896 42277 35896 42278 35894 42278 36347 42278 35896 42279 36347 42279 35897 42279 35897 42280 36347 42280 36346 42280 36346 42281 36345 42281 35897 42281 35897 42282 36345 42282 35898 42282 35897 42283 35898 42283 35899 42283 35899 42284 35898 42284 35901 42284 35899 42285 35901 42285 35900 42285 35900 42286 35901 42286 36363 42286 35900 42287 36363 42287 35903 42287 35903 42288 36363 42288 35902 42288 35902 42289 35904 42289 35903 42289 35903 42290 35904 42290 35906 42290 35903 42291 35906 42291 35905 42291 35905 42292 35906 42293 35907 42294 35905 42295 35907 42295 35994 42295 35994 42296 35907 42296 36368 42296 35994 42297 36368 42297 35996 42297 35996 42298 36368 42298 35908 42298 35908 42299 35909 42299 35996 42299 35996 42300 35909 42300 36122 42300 35996 42301 36122 42301 35997 42301 35997 42302 36122 42302 35910 42302 35997 42303 35910 42303 35999 42303 35999 42304 35910 42304 35911 42304 35999 42305 35911 42305 35912 42305 35911 42306 36120 42306 35912 42306 35912 42307 36120 42307 35913 42307 35912 42308 35913 42308 35914 42308 35913 42309 36379 42310 35914 42311 35914 42312 36379 42312 35915 42312 35914 42313 35915 42314 35916 42315 35916 42316 35915 42316 35917 42316 35916 42317 35917 42317 35918 42317 35917 42318 36380 42318 35918 42318 35918 42319 36380 42319 36118 42319 35918 42320 36118 42320 35919 42320 36118 42321 36117 42322 35919 42323 35919 42324 36117 42324 35920 42324 35919 42325 35920 42325 35921 42325 35921 42326 35920 42326 36385 42326 35921 42327 36385 42327 35922 42327 35922 42328 36385 42328 35924 42328 35922 42329 35924 42329 35923 42329 35923 42330 35924 42330 36401 42330 36401 42331 36400 42331 35923 42331 35923 42332 36400 42332 35925 42332 35923 42333 35925 42333 36005 42333 36005 42334 35925 42335 36116 42336 36005 42337 36116 42337 36006 42337 36006 42338 36116 42338 36412 42338 36006 42339 36412 42339 35926 42339 35926 42340 36412 42340 36414 42340 36414 42341 36413 42341 35926 42341 35926 42342 36413 42342 36416 42342 35926 42343 36416 42343 36008 42343 36008 42344 36416 42344 36415 42344 36008 42345 36415 42345 35927 42345 35927 42346 36415 42346 35928 42346 35927 42347 35928 42347 36010 42347 36010 42348 35928 42349 36430 42350 36430 42351 36429 42351 36010 42351 36010 42352 36429 42352 35929 42352 36010 42353 35929 42353 36012 42353 36012 42354 35929 42355 36115 42356 36012 42357 36115 42357 36013 42357 36013 42358 36115 42358 35930 42358 36013 42359 35930 42359 36016 42359 36016 42360 35930 42360 36433 42360 36433 42361 36114 42361 36016 42361 36016 42362 36114 42362 36439 42362 36016 42363 36439 42363 36017 42363 36017 42364 36439 42364 35931 42364 36017 42365 35931 42365 35932 42365 35932 42366 35931 42366 35933 42366 35932 42367 35933 42367 35934 42367 35933 42368 36145 42368 35934 42368 35934 42369 36145 42369 36144 42369 35934 42370 36144 42370 36019 42370 36144 42371 36143 42371 36019 42371 36019 42372 36143 42372 36190 42372 36019 42373 36190 42373 35935 42373 35935 42374 36190 42374 36189 42374 35935 42375 36189 42375 35936 42375 36189 42376 35937 42376 35936 42376 35936 42377 35937 42377 35939 42377 35936 42378 35939 42378 35938 42378 35939 42379 36142 42380 35938 42381 35938 42382 36142 42382 35941 42382 35938 42383 35941 42383 35940 42383 35940 42384 35941 42384 35942 42384 35940 42385 35942 42385 35943 42385 35943 42386 35942 42386 36194 42386 35943 42387 36194 42387 36023 42387 36023 42388 36194 42388 35944 42388 35944 42389 36141 42389 36023 42389 36023 42390 36141 42391 35945 42392 36023 42393 35945 42393 35947 42393 35947 42394 35945 42394 35946 42394 35947 42395 35946 42395 35948 42395 35948 42396 35946 42396 35949 42396 35948 42397 35949 42397 35950 42397 35950 42398 35949 42398 36217 42398 36217 42399 36216 42399 35950 42399 35950 42400 36216 42400 35951 42400 35950 42401 35951 42401 36027 42401 36027 42402 35951 42402 35952 42402 36027 42403 35952 42403 36028 42403 36028 42404 35952 42404 36230 42404 36028 42405 36230 42405 35953 42405 35953 42406 36230 42406 35954 42406 35954 42407 35955 42407 35953 42407 35953 42408 35955 42408 35956 42408 35953 42409 35956 42409 36030 42409 36030 42410 35956 42411 35958 42412 36030 42413 35958 42413 35957 42413 35957 42414 35958 42414 36140 42414 35957 42415 36140 42415 35959 42415 35959 42416 36140 42416 36237 42416 36237 42417 36138 42417 35959 42417 35959 42418 36138 42418 35960 42418 35959 42419 35960 42419 36031 42419 36031 42420 35960 42420 35961 42420 36031 42421 35961 42421 35964 42421 35964 42422 35961 42422 35962 42422 35964 42423 35962 42423 35965 42423 35965 42424 35962 42425 36136 42426 35965 42427 36136 42427 36135 42427 36113 42428 36031 42428 35963 42428 35963 42429 36031 42429 35964 42429 35963 42430 35964 42430 36033 42430 36033 42431 35964 42431 35965 42431 36033 42432 35965 42432 36035 42432 36035 42433 35965 42433 35966 42433 36035 42434 35966 42434 35967 42434 35967 42435 35966 42435 35968 42435 35967 42436 35968 42436 35969 42436 35969 42437 35968 42437 35860 42437 35969 42438 35860 42438 36038 42438 36038 42439 35860 42439 35863 42439 36038 42440 35863 42441 36039 42442 36039 42443 35863 42443 35864 42443 36039 42444 35864 42444 35971 42444 35971 42445 35864 42446 35970 42447 35971 42448 35970 42448 35972 42448 35972 42449 35970 42449 35973 42449 35972 42450 35973 42450 35974 42450 35974 42451 35973 42451 35975 42451 35974 42452 35975 42452 36041 42452 36041 42453 35975 42453 35976 42453 36041 42454 35976 42454 36043 42454 36043 42455 35976 42455 35870 42455 36043 42456 35870 42456 35977 42456 35977 42457 35870 42457 35871 42457 35977 42458 35871 42458 36046 42458 36046 42459 35871 42459 35978 42459 36046 42460 35978 42460 36048 42460 36048 42461 35978 42461 35873 42461 36048 42462 35873 42462 36049 42462 36049 42463 35873 42464 35980 42465 36049 42466 35980 42466 35979 42466 35979 42467 35980 42467 35877 42467 35979 42468 35877 42468 35982 42468 35982 42469 35877 42469 35981 42469 35982 42470 35981 42470 35983 42470 35983 42471 35981 42471 35879 42471 35983 42472 35879 42472 35984 42472 35984 42473 35879 42473 35880 42473 35984 42474 35880 42474 36051 42474 36051 42475 35880 42475 35881 42475 36051 42476 35881 42476 36053 42476 36053 42477 35881 42477 35882 42477 36053 42478 35882 42478 36054 42478 36054 42479 35882 42479 35884 42479 36054 42480 35884 42480 36056 42480 36056 42481 35884 42481 35885 42481 36056 42482 35885 42482 35985 42482 35985 42483 35885 42483 35887 42483 35985 42484 35887 42484 35986 42484 35986 42485 35887 42485 35987 42485 35986 42486 35987 42486 35988 42486 35988 42487 35987 42487 35888 42487 35988 42488 35888 42488 35989 42488 35989 42489 35888 42489 35990 42489 35989 42490 35990 42490 36062 42490 36062 42491 35990 42491 35895 42491 36062 42492 35895 42493 35991 42494 35991 42495 35895 42495 35896 42495 35991 42496 35896 42496 35992 42496 35992 42497 35896 42497 35897 42497 35992 42498 35897 42498 35993 42498 35993 42499 35897 42499 35899 42499 35993 42500 35899 42500 36064 42500 36064 42501 35899 42501 35900 42501 36064 42502 35900 42502 36065 42502 36065 42503 35900 42503 35903 42503 36065 42504 35903 42504 36066 42504 36066 42505 35903 42505 35905 42505 36066 42506 35905 42506 36068 42506 36068 42507 35905 42507 35994 42507 36068 42508 35994 42508 35995 42508 35995 42509 35994 42509 35996 42509 35995 42510 35996 42510 36070 42510 36070 42511 35996 42511 35997 42511 36070 42512 35997 42512 35998 42512 35998 42513 35997 42513 35999 42513 35998 42514 35999 42514 36000 42514 36000 42515 35999 42515 35912 42515 36000 42516 35912 42516 36074 42516 36074 42517 35912 42517 35914 42517 36074 42518 35914 42518 36075 42518 36075 42519 35914 42519 35916 42519 36075 42520 35916 42520 36076 42520 36076 42521 35916 42521 35918 42521 36076 42522 35918 42522 36001 42522 36001 42523 35918 42523 35919 42523 36001 42524 35919 42524 36078 42524 36078 42525 35919 42525 35921 42525 36078 42526 35921 42526 36002 42526 36002 42527 35921 42527 35922 42527 36002 42528 35922 42528 36079 42528 36079 42529 35922 42530 35923 42531 36079 42532 35923 42532 36003 42532 36003 42533 35923 42533 36005 42533 36003 42534 36005 42534 36004 42534 36004 42535 36005 42535 36006 42535 36004 42536 36006 42536 36082 42536 36082 42537 36006 42537 35926 42537 36082 42538 35926 42538 36083 42538 36083 42539 35926 42539 36008 42539 36083 42540 36008 42540 36007 42540 36007 42541 36008 42541 35927 42541 36007 42542 35927 42542 36009 42542 36009 42543 35927 42543 36010 42543 36009 42544 36010 42544 36011 42544 36011 42545 36010 42545 36012 42545 36011 42546 36012 42547 36014 42548 36014 42549 36012 42549 36013 42549 36014 42550 36013 42550 36015 42550 36015 42551 36013 42551 36016 42551 36015 42552 36016 42552 36088 42552 36088 42553 36016 42553 36017 42553 36088 42554 36017 42554 36089 42554 36089 42555 36017 42555 35932 42555 36089 42556 35932 42556 36018 42556 36018 42557 35932 42557 35934 42557 36018 42558 35934 42558 36093 42558 36093 42559 35934 42559 36019 42559 36093 42560 36019 42560 36020 42560 36020 42561 36019 42561 35935 42561 36020 42562 35935 42562 36021 42562 36021 42563 35935 42563 35936 42563 36021 42564 35936 42565 36022 42565 36022 42566 35936 42566 35938 42566 36022 42567 35938 42567 36096 42567 36096 42568 35938 42568 35940 42568 36096 42569 35940 42569 36098 42569 36098 42570 35940 42571 35943 42572 36098 42573 35943 42573 36099 42573 36099 42574 35943 42574 36023 42574 36099 42575 36023 42575 36024 42575 36024 42576 36023 42576 35947 42576 36024 42577 35947 42577 36025 42577 36025 42578 35947 42578 35948 42578 36025 42579 35948 42579 36026 42579 36026 42580 35948 42580 35950 42580 36026 42581 35950 42581 36104 42581 36104 42582 35950 42582 36027 42582 36104 42583 36027 42583 36105 42583 36105 42584 36027 42585 36028 42586 36105 42587 36028 42587 36029 42587 36029 42588 36028 42588 35953 42588 36029 42589 35953 42589 36108 42589 36108 42590 35953 42590 36030 42590 36108 42591 36030 42591 36109 42591 36109 42592 36030 42592 35957 42592 36109 42593 35957 42593 36111 42593 36111 42594 35957 42594 35959 42594 36111 42595 35959 42595 36113 42595 36113 42596 35959 42596 36031 42596 36112 42597 35963 42597 36032 42597 36032 42598 35963 42598 36033 42598 36032 42599 36033 42599 36034 42599 36034 42600 36033 42601 36035 42601 36034 42602 36035 42602 35788 42602 35788 42603 36035 42603 35967 42603 35788 42604 35967 42604 36036 42604 36036 42605 35967 42605 35969 42605 36036 42606 35969 42606 36037 42606 36037 42607 35969 42607 36038 42607 36037 42608 36038 42608 35791 42608 35791 42609 36038 42609 36039 42609 35791 42610 36039 42610 35793 42610 35793 42611 36039 42611 35971 42611 35793 42612 35971 42612 35794 42612 35794 42613 35971 42613 35972 42613 35794 42614 35972 42614 35796 42614 35796 42615 35972 42615 35974 42615 35796 42616 35974 42616 36040 42616 36040 42617 35974 42617 36041 42617 36040 42618 36041 42618 36042 42618 36042 42619 36041 42619 36043 42619 36042 42620 36043 42620 36044 42620 36044 42621 36043 42621 35977 42621 36044 42622 35977 42622 35798 42622 35798 42623 35977 42623 36046 42623 35798 42624 36046 42624 36045 42624 36045 42625 36046 42625 36048 42625 36045 42626 36048 42626 36047 42626 36047 42627 36048 42627 36049 42627 36047 42628 36049 42628 35801 42628 35801 42629 36049 42629 35979 42629 35801 42630 35979 42630 36050 42630 36050 42631 35979 42631 35982 42631 36050 42632 35982 42632 35803 42632 35803 42633 35982 42633 35983 42633 35803 42634 35983 42634 35804 42634 35804 42635 35983 42635 35984 42635 35804 42636 35984 42636 35806 42636 35806 42637 35984 42637 36051 42637 35806 42638 36051 42638 36052 42638 36052 42639 36051 42639 36053 42639 36052 42640 36053 42640 35807 42640 35807 42641 36053 42641 36054 42641 35807 42642 36054 42642 36055 42642 36055 42643 36054 42644 36056 42645 36055 42646 36056 42646 36057 42646 36057 42647 36056 42647 35985 42647 36057 42648 35985 42648 36058 42648 36058 42649 35985 42649 35986 42649 36058 42650 35986 42650 36059 42650 36059 42651 35986 42651 35988 42651 36059 42652 35988 42652 36060 42652 36060 42653 35988 42653 35989 42653 36060 42654 35989 42654 36061 42654 36061 42655 35989 42655 36062 42655 36061 42656 36062 42656 35813 42656 35813 42657 36062 42657 35991 42657 35813 42658 35991 42658 35814 42658 35814 42659 35991 42659 35992 42659 35814 42660 35992 42660 35816 42660 35816 42661 35992 42661 35993 42661 35816 42662 35993 42662 36063 42662 36063 42663 35993 42663 36064 42663 36063 42664 36064 42664 35817 42664 35817 42665 36064 42665 36065 42665 35817 42666 36065 42666 35819 42666 35819 42667 36065 42667 36066 42667 35819 42668 36066 42668 36067 42668 36067 42669 36066 42669 36068 42669 36067 42670 36068 42670 35822 42670 35822 42671 36068 42671 35995 42671 35822 42672 35995 42672 36069 42672 36069 42673 35995 42673 36070 42673 36069 42674 36070 42674 35823 42674 35823 42675 36070 42675 35998 42675 35823 42676 35998 42676 36071 42676 36071 42677 35998 42677 36000 42677 36071 42678 36000 42678 36072 42678 36072 42679 36000 42679 36074 42679 36072 42680 36074 42680 36073 42680 36073 42681 36074 42681 36075 42681 36073 42682 36075 42682 35827 42682 35827 42683 36075 42683 36076 42683 35827 42684 36076 42684 35828 42684 35828 42685 36076 42685 36001 42685 35828 42686 36001 42686 36077 42686 36077 42687 36001 42687 36078 42687 36077 42688 36078 42688 35829 42688 35829 42689 36078 42689 36002 42689 35829 42690 36002 42691 35830 42692 35830 42693 36002 42693 36079 42693 35830 42694 36079 42694 36080 42694 36080 42695 36079 42695 36003 42695 36080 42696 36003 42696 36081 42696 36081 42697 36003 42697 36004 42697 36081 42698 36004 42698 35834 42698 35834 42699 36004 42699 36082 42699 35834 42700 36082 42700 35835 42700 35835 42701 36082 42701 36083 42701 35835 42702 36083 42702 35836 42702 35836 42703 36083 42703 36007 42703 35836 42704 36007 42704 35838 42704 35838 42705 36007 42705 36009 42705 35838 42706 36009 42706 36084 42706 36084 42707 36009 42707 36011 42707 36084 42708 36011 42709 36085 42710 36085 42711 36011 42711 36014 42711 36085 42712 36014 42712 36086 42712 36086 42713 36014 42713 36015 42713 36086 42714 36015 42714 36087 42714 36087 42715 36015 42715 36088 42715 36087 42716 36088 42716 35841 42716 35841 42717 36088 42717 36089 42717 35841 42718 36089 42718 36090 42718 36090 42719 36089 42719 36018 42719 36090 42720 36018 42720 36091 42720 36091 42721 36018 42721 36093 42721 36091 42722 36093 42722 36092 42722 36092 42723 36093 42723 36020 42723 36092 42724 36020 42724 36094 42724 36094 42725 36020 42725 36021 42725 36094 42726 36021 42726 35845 42726 35845 42727 36021 42727 36022 42727 35845 42728 36022 42729 36095 42730 36095 42731 36022 42731 36096 42731 36095 42732 36096 42732 36097 42732 36097 42733 36096 42733 36098 42733 36097 42734 36098 42734 36100 42734 36100 42735 36098 42735 36099 42735 36100 42736 36099 42736 36101 42736 36101 42737 36099 42737 36024 42737 36101 42738 36024 42738 35848 42738 35848 42739 36024 42739 36025 42739 35848 42740 36025 42741 35850 42742 35850 42743 36025 42743 36026 42743 35850 42744 36026 42745 36102 42746 36102 42747 36026 42747 36104 42747 36102 42748 36104 42748 36103 42748 36103 42749 36104 42749 36105 42749 36103 42750 36105 42750 35853 42750 35853 42751 36105 42751 36029 42751 35853 42752 36029 42752 36106 42752 36106 42753 36029 42753 36108 42753 36106 42754 36108 42754 36107 42754 36107 42755 36108 42755 36109 42755 36107 42756 36109 42756 36110 42756 36110 42757 36109 42757 36111 42757 36110 42758 36111 42758 35855 42758 35855 42759 36111 42759 36113 42759 35855 42760 36113 42760 36112 42760 36112 42761 36113 42761 35963 42761 36114 42762 36433 42762 36441 42762 35930 42763 36115 42763 36434 42763 35928 42764 36415 42764 36418 42764 36412 42765 36116 42765 36411 42765 36117 42766 36118 42766 36381 42766 36379 42767 35913 42768 36119 42769 36120 42770 35911 42770 36121 42770 35910 42771 36122 42771 36375 42771 35909 42772 35908 42772 36123 42772 36368 42773 35907 42773 36364 42773 36363 42774 35901 42774 36348 42774 36347 42775 35894 42775 36124 42775 36323 42776 36125 42776 36324 42776 36317 42777 36126 42778 36313 42779 36127 42780 36309 42780 36128 42780 36310 42781 35878 42781 36129 42781 36130 42782 36302 42782 36304 42782 36303 42783 35876 42783 36131 42783 35872 42784 36283 42784 36132 42784 35866 42785 36265 42785 36266 42785 36133 42786 35862 42787 36134 42788 35858 42789 36135 42790 36250 42791 36136 42792 35962 42792 36245 42792 35961 42793 35960 42793 36137 42793 36138 42794 36237 42794 36139 42794 36140 42795 35958 42795 36239 42795 36230 42796 35952 42796 36229 42796 36141 42797 35944 42797 36206 42797 36142 42798 35939 42798 36196 42798 36143 42799 36144 42800 36185 42801 36145 42802 35933 42802 36183 42802 35931 42803 36439 42803 36440 42803 36146 42804 36147 42804 36397 42804 36332 42805 36341 42806 36148 42807 36340 42808 36342 42808 36339 42808 36149 42809 36332 42809 36325 42809 36152 42810 36151 42810 36150 42810 36150 42811 36151 42811 36305 42811 36150 42812 36305 42812 36154 42812 36152 42813 36150 42813 36153 42813 36153 42814 36150 42814 36154 42814 36153 42815 36154 42815 36306 42815 36300 42816 36155 42816 36299 42816 36299 42817 36155 42818 36156 42819 36273 42820 36275 42820 36157 42820 36258 42821 36269 42821 36268 42821 36160 42822 36158 42822 36161 42822 36161 42823 36158 42823 36159 42823 36161 42824 36159 42824 36240 42824 36160 42825 36161 42826 36162 42827 36162 42828 36161 42828 36240 42828 36162 42829 36240 42829 36163 42829 36164 42830 36165 42830 36235 42830 36235 42831 36165 42831 36166 42831 36210 42832 36213 42832 36209 42832 36201 42833 35783 42833 36199 42833 36167 42834 36168 42834 36169 42834 36169 42835 36168 42835 36170 42835 36169 42836 36170 42836 36172 42836 36167 42837 36169 42837 36171 42837 36171 42838 36169 42838 36172 42838 36171 42839 36172 42839 36173 42839 36432 42840 36174 42840 36437 42840 36437 42841 36174 42842 36438 42843 36406 42844 36175 42844 36405 42844 36176 42845 36146 42846 36396 42847 36179 42848 36178 42848 36177 42848 36177 42849 36178 42850 36369 42851 36177 42852 36369 42852 36371 42852 36179 42853 36177 42854 36180 42855 36180 42856 36177 42856 36371 42856 36180 42857 36371 42857 36181 42857 36367 42858 36182 42858 36366 42858 36366 42859 36182 42859 36372 42859 35933 42860 35931 42860 36183 42860 36183 42861 35931 42861 36440 42861 36183 42862 36440 42862 36187 42862 36187 42863 36440 42863 36442 42863 36187 42864 36442 42864 36202 42864 36202 42865 36442 42865 36184 42865 36144 42866 36145 42866 36185 42866 36185 42867 36145 42867 36183 42867 36185 42868 36183 42868 36186 42868 36186 42869 36183 42869 36187 42869 36186 42870 36187 42870 36192 42870 36192 42871 36187 42871 36202 42871 35937 42872 36189 42872 36188 42872 36188 42873 36189 42873 36190 42873 36190 42874 36143 42874 36188 42874 36188 42875 36143 42875 36185 42875 36188 42876 36185 42876 36191 42876 36191 42877 36185 42877 36186 42877 36191 42878 36186 42878 36193 42878 36193 42879 36186 42879 36192 42879 35939 42880 35937 42880 36196 42880 36196 42881 35937 42881 36188 42881 36196 42882 36188 42882 36198 42882 36198 42883 36188 42883 36191 42883 36198 42884 36191 42884 36200 42884 36200 42885 36191 42885 36193 42885 36194 42886 35942 42886 36195 42886 36195 42887 35942 42887 35941 42887 35941 42888 36142 42888 36195 42888 36195 42889 36142 42889 36196 42889 36195 42890 36196 42890 36197 42890 36197 42891 36196 42891 36198 42891 36197 42892 36198 42892 36199 42892 36199 42893 36198 42893 36200 42893 36199 42894 36200 42894 36201 42894 36201 42895 36200 42895 36193 42895 36201 42896 36193 42896 35784 42896 35784 42897 36193 42897 36192 42897 35784 42898 36192 42898 35785 42898 35785 42899 36192 42899 36202 42899 35785 42900 36202 42900 36203 42900 36203 42901 36202 42901 36184 42901 36203 42902 36184 42902 35787 42902 35787 42903 36184 42903 35780 42903 35944 42904 36194 42904 36206 42904 36206 42905 36194 42905 36195 42905 36206 42906 36195 42906 36204 42906 36204 42907 36195 42907 36197 42907 36204 42908 36197 42908 36208 42908 36208 42909 36197 42909 36199 42909 36208 42910 36199 42910 36211 42910 36211 42911 36199 42911 35783 42911 36211 42912 35783 42913 36212 42914 35949 42915 35946 42915 36205 42915 36205 42916 35946 42916 35945 42916 35945 42917 36141 42917 36205 42917 36205 42918 36141 42918 36206 42918 36205 42919 36206 42919 36215 42919 36215 42920 36206 42920 36204 42920 36215 42921 36204 42921 36207 42921 36207 42922 36204 42922 36208 42922 36207 42923 36208 42923 36209 42923 36209 42924 36208 42924 36211 42924 36209 42925 36211 42925 36210 42925 36210 42926 36211 42926 36212 42926 36213 42927 36214 42927 36209 42927 36209 42928 36214 42928 36222 42928 36209 42929 36222 42929 36207 42929 36207 42930 36222 42930 36220 42930 36207 42931 36220 42931 36215 42931 36215 42932 36220 42932 36219 42932 36215 42933 36219 42933 36205 42933 36205 42934 36219 42934 36218 42934 36205 42935 36218 42935 35949 42935 35951 42936 36216 42937 36218 42938 36218 42939 36216 42939 36217 42939 36218 42940 36217 42940 35949 42940 35952 42941 35951 42941 36229 42941 36229 42942 35951 42942 36218 42942 36229 42943 36218 42943 36228 42943 36228 42944 36218 42944 36219 42944 36228 42945 36219 42945 36227 42945 36227 42946 36219 42946 36220 42946 36227 42947 36220 42947 36225 42947 36225 42948 36220 42948 36222 42948 36225 42949 36222 42949 36221 42949 36221 42950 36222 42950 36214 42950 36221 42951 36214 42952 36223 42953 36221 42954 36224 42954 36225 42954 36225 42955 36224 42955 36236 42955 36225 42956 36236 42956 36227 42956 36227 42957 36236 42957 36226 42957 36227 42958 36226 42958 36228 42958 36228 42959 36226 42959 36233 42959 36228 42960 36233 42960 36229 42960 36229 42961 36233 42961 36231 42961 36229 42962 36231 42962 36230 42962 35956 42963 35955 42963 36231 42963 36231 42964 35955 42964 35954 42964 36231 42965 35954 42965 36230 42965 35958 42966 35956 42967 36239 42968 36239 42969 35956 42969 36231 42969 36239 42970 36231 42970 36232 42970 36232 42971 36231 42971 36233 42971 36232 42972 36233 42972 36234 42972 36234 42973 36233 42973 36226 42973 36234 42974 36226 42974 36235 42974 36235 42975 36226 42975 36236 42975 36235 42976 36236 42976 36164 42976 36164 42977 36236 42977 36224 42977 36237 42978 36140 42978 36139 42978 36139 42979 36140 42979 36239 42979 36139 42980 36239 42980 36238 42980 36238 42981 36239 42981 36232 42981 36238 42982 36232 42982 36159 42982 36159 42983 36232 42983 36234 42983 36159 42984 36234 42984 36240 42984 36240 42985 36234 42985 36235 42985 36240 42986 36235 42986 36163 42986 36163 42987 36235 42987 36166 42987 35960 42988 36138 42988 36137 42988 36137 42989 36138 42989 36139 42989 36137 42990 36139 42990 36243 42990 36243 42991 36139 42991 36238 42991 36243 42992 36238 42992 36241 42992 36241 42993 36238 42993 36159 42993 36241 42994 36159 42994 36242 42994 36242 42995 36159 42995 36158 42995 35962 42996 35961 42996 36245 42996 36245 42997 35961 42997 36137 42997 36245 42998 36137 42998 36244 42998 36244 42999 36137 42999 36243 42999 36244 43000 36243 43000 36261 43000 36261 43001 36243 43001 36241 43001 36135 43002 36136 43002 36250 43002 36250 43003 36136 43003 36245 43003 36250 43004 36245 43004 36246 43004 36246 43005 36245 43005 36244 43005 36246 43006 36244 43006 36247 43006 36247 43007 36244 43007 36261 43007 35861 43008 36248 43008 36249 43008 36249 43009 36248 43009 35859 43009 35859 43010 35858 43010 36249 43010 36249 43011 35858 43011 36250 43011 36249 43012 36250 43012 36252 43012 36252 43013 36250 43013 36246 43013 36252 43014 36246 43014 36259 43014 36259 43015 36246 43015 36247 43015 35862 43016 35861 43016 36134 43016 36134 43017 35861 43017 36249 43017 36134 43018 36249 43018 36257 43018 36257 43019 36249 43019 36252 43019 36257 43020 36252 43020 36251 43020 36251 43021 36252 43021 36259 43021 36253 43022 35865 43022 36254 43022 36254 43023 35865 43023 36255 43023 36255 43024 36133 43024 36254 43024 36254 43025 36133 43025 36134 43025 36254 43026 36134 43026 36256 43026 36256 43027 36134 43027 36257 43027 36256 43028 36257 43028 36268 43028 36268 43029 36257 43029 36251 43029 36268 43030 36251 43030 36258 43030 36258 43031 36251 43031 36259 43031 36258 43032 36259 43032 36260 43032 36260 43033 36259 43033 36247 43033 36260 43034 36247 43034 36262 43034 36262 43035 36247 43035 36261 43035 36262 43036 36261 43036 36263 43036 36263 43037 36261 43037 36241 43037 36263 43038 36241 43038 36264 43038 36264 43039 36241 43039 36242 43039 36265 43040 36253 43040 36266 43040 36266 43041 36253 43041 36254 43041 36266 43042 36254 43042 36267 43042 36267 43043 36254 43043 36256 43043 36267 43044 36256 43044 36271 43044 36271 43045 36256 43045 36268 43045 36271 43046 36268 43046 36272 43046 36272 43047 36268 43047 36269 43047 36272 43048 36269 43048 36274 43048 36282 43049 35868 43049 36270 43049 36270 43050 35868 43050 35867 43050 35867 43051 35866 43051 36270 43051 36270 43052 35866 43052 36266 43052 36270 43053 36266 43053 36278 43053 36278 43054 36266 43054 36267 43054 36278 43055 36267 43055 36277 43055 36277 43056 36267 43056 36271 43056 36277 43057 36271 43057 36157 43057 36157 43058 36271 43058 36272 43058 36157 43059 36272 43059 36273 43059 36273 43060 36272 43060 36274 43060 36275 43061 36276 43061 36157 43061 36157 43062 36276 43062 36288 43062 36157 43063 36288 43063 36277 43063 36277 43064 36288 43064 36279 43064 36277 43065 36279 43065 36278 43065 36278 43066 36279 43066 36286 43066 36278 43067 36286 43067 36270 43067 36270 43068 36286 43068 36280 43068 36270 43069 36280 43069 36282 43069 36284 43070 35869 43070 36280 43070 36280 43071 35869 43071 36281 43071 36280 43072 36281 43072 36282 43072 36283 43073 36284 43073 36132 43073 36132 43074 36284 43074 36280 43074 36132 43075 36280 43075 36285 43075 36285 43076 36280 43076 36286 43076 36285 43077 36286 43077 36292 43077 36292 43078 36286 43078 36279 43078 36292 43079 36279 43079 36287 43079 36287 43080 36279 43080 36288 43080 36287 43081 36288 43081 36290 43081 36290 43082 36288 43082 36276 43082 36290 43083 36276 43083 36289 43083 36290 43084 36301 43084 36287 43084 36287 43085 36301 43085 36291 43085 36287 43086 36291 43086 36292 43086 36292 43087 36291 43087 36298 43087 36292 43088 36298 43088 36285 43088 36285 43089 36298 43089 36295 43089 36285 43090 36295 43090 36132 43090 36132 43091 36295 43091 36293 43091 36132 43092 36293 43092 35872 43092 35875 43093 35874 43093 36293 43093 36293 43094 35874 43094 36294 43094 36293 43095 36294 43095 35872 43095 35876 43096 35875 43097 36131 43098 36131 43099 35875 43099 36293 43099 36131 43100 36293 43100 36296 43100 36296 43101 36293 43101 36295 43101 36296 43102 36295 43102 36297 43102 36297 43103 36295 43103 36298 43103 36297 43104 36298 43104 36299 43104 36299 43105 36298 43105 36291 43105 36299 43106 36291 43106 36300 43106 36300 43107 36291 43107 36301 43107 36302 43108 36303 43109 36304 43110 36304 43111 36303 43111 36131 43111 36304 43112 36131 43112 36307 43112 36307 43113 36131 43113 36296 43113 36307 43114 36296 43114 36305 43114 36305 43115 36296 43115 36297 43115 36305 43116 36297 43116 36154 43116 36154 43117 36297 43117 36299 43117 36154 43118 36299 43118 36306 43118 36306 43119 36299 43119 36156 43119 35878 43120 36130 43120 36129 43120 36129 43121 36130 43121 36304 43121 36129 43122 36304 43122 36312 43122 36312 43123 36304 43123 36307 43123 36312 43124 36307 43124 36308 43124 36308 43125 36307 43125 36305 43125 36308 43126 36305 43126 36446 43126 36446 43127 36305 43127 36151 43127 36309 43128 36310 43128 36128 43128 36128 43129 36310 43129 36129 43129 36128 43130 36129 43130 36311 43130 36311 43131 36129 43131 36312 43131 36311 43132 36312 43132 36329 43132 36329 43133 36312 43133 36308 43133 36126 43134 36127 43134 36313 43134 36313 43135 36127 43135 36128 43135 36313 43136 36128 43136 36314 43136 36314 43137 36128 43137 36311 43137 36314 43138 36311 43138 36315 43138 36315 43139 36311 43139 36329 43139 36316 43140 35886 43140 36318 43140 36318 43141 35886 43141 35883 43141 35883 43142 36317 43142 36318 43142 36318 43143 36317 43143 36313 43143 36318 43144 36313 43144 36319 43144 36319 43145 36313 43145 36314 43145 36319 43146 36314 43146 36320 43146 36320 43147 36314 43147 36315 43147 36125 43148 36316 43148 36324 43148 36324 43149 36316 43149 36318 43149 36324 43150 36318 43150 36326 43150 36326 43151 36318 43151 36319 43151 36326 43152 36319 43152 36321 43152 36321 43153 36319 43153 36320 43153 35890 43154 35889 43154 36336 43154 36336 43155 35889 43155 36322 43155 36322 43156 36323 43156 36336 43156 36336 43157 36323 43157 36324 43157 36336 43158 36324 43158 36334 43158 36334 43159 36324 43159 36326 43159 36334 43160 36326 43160 36325 43160 36325 43161 36326 43161 36321 43161 36325 43162 36321 43162 36149 43162 36149 43163 36321 43163 36320 43163 36149 43164 36320 43164 36327 43164 36327 43165 36320 43165 36315 43165 36327 43166 36315 43166 36328 43166 36328 43167 36315 43167 36329 43167 36328 43168 36329 43168 36330 43168 36330 43169 36329 43169 36308 43169 36330 43170 36308 43170 36331 43170 36331 43171 36308 43171 36446 43171 36332 43172 36148 43172 36325 43172 36325 43173 36148 43173 36333 43173 36325 43174 36333 43174 36334 43174 36334 43175 36333 43175 36335 43175 36334 43176 36335 43176 36336 43176 36336 43177 36335 43177 36337 43177 36336 43178 36337 43178 35890 43178 35893 43179 35892 43179 36337 43179 36337 43180 35892 43180 35891 43180 36337 43181 35891 43181 35890 43181 35894 43182 35893 43182 36124 43182 36124 43183 35893 43183 36337 43183 36124 43184 36337 43184 36338 43184 36338 43185 36337 43185 36335 43185 36338 43186 36335 43186 36344 43186 36344 43187 36335 43187 36333 43187 36344 43188 36333 43188 36339 43188 36339 43189 36333 43189 36148 43189 36339 43190 36148 43190 36340 43190 36340 43191 36148 43191 36341 43191 36342 43192 36343 43192 36339 43192 36339 43193 36343 43193 36353 43193 36339 43194 36353 43194 36344 43194 36344 43195 36353 43195 36352 43195 36344 43196 36352 43196 36338 43196 36338 43197 36352 43197 36350 43197 36338 43198 36350 43198 36124 43198 36124 43199 36350 43199 36349 43199 36124 43200 36349 43200 36347 43200 35898 43201 36345 43201 36349 43201 36349 43202 36345 43202 36346 43202 36349 43203 36346 43203 36347 43203 35901 43204 35898 43204 36348 43204 36348 43205 35898 43205 36349 43205 36348 43206 36349 43206 36360 43206 36360 43207 36349 43207 36350 43207 36360 43208 36350 43208 36351 43208 36351 43209 36350 43209 36352 43209 36351 43210 36352 43210 36356 43210 36356 43211 36352 43211 36353 43211 36356 43212 36353 43212 36355 43212 36355 43213 36353 43213 36343 43213 36355 43214 36343 43214 36354 43214 36355 43215 36357 43215 36356 43215 36356 43216 36357 43216 36358 43216 36356 43217 36358 43217 36351 43217 36351 43218 36358 43218 36359 43218 36351 43219 36359 43219 36360 43219 36360 43220 36359 43220 36361 43220 36360 43221 36361 43221 36348 43221 36348 43222 36361 43222 36362 43222 36348 43223 36362 43223 36363 43223 35906 43224 35904 43224 36362 43224 36362 43225 35904 43225 35902 43225 36362 43226 35902 43226 36363 43226 35907 43227 35906 43228 36364 43229 36364 43230 35906 43230 36362 43230 36364 43231 36362 43231 36365 43231 36365 43232 36362 43232 36361 43232 36365 43233 36361 43233 36370 43233 36370 43234 36361 43234 36359 43234 36370 43235 36359 43235 36366 43235 36366 43236 36359 43236 36358 43236 36366 43237 36358 43237 36367 43237 36367 43238 36358 43238 36357 43238 35908 43239 36368 43239 36123 43239 36123 43240 36368 43240 36364 43240 36123 43241 36364 43241 36374 43241 36374 43242 36364 43242 36365 43242 36374 43243 36365 43243 36369 43243 36369 43244 36365 43244 36370 43244 36369 43245 36370 43245 36371 43245 36371 43246 36370 43246 36366 43246 36371 43247 36366 43247 36181 43247 36181 43248 36366 43248 36372 43248 36122 43249 35909 43249 36375 43249 36375 43250 35909 43250 36123 43250 36375 43251 36123 43251 36373 43251 36373 43252 36123 43252 36374 43252 36373 43253 36374 43253 36377 43253 36377 43254 36374 43254 36369 43254 36377 43255 36369 43255 36395 43255 36395 43256 36369 43256 36178 43256 35911 43257 35910 43257 36121 43257 36121 43258 35910 43258 36375 43258 36121 43259 36375 43259 36376 43259 36376 43260 36375 43260 36373 43260 36376 43261 36373 43261 36392 43261 36392 43262 36373 43262 36377 43262 35913 43263 36120 43263 36119 43263 36119 43264 36120 43264 36121 43264 36119 43265 36121 43265 36378 43265 36378 43266 36121 43266 36376 43266 36378 43267 36376 43267 36390 43267 36390 43268 36376 43268 36392 43268 36380 43269 35917 43269 36382 43269 36382 43270 35917 43270 35915 43270 35915 43271 36379 43271 36382 43271 36382 43272 36379 43272 36119 43272 36382 43273 36119 43273 36383 43273 36383 43274 36119 43274 36378 43274 36383 43275 36378 43275 36388 43275 36388 43276 36378 43276 36390 43276 36118 43277 36380 43277 36381 43277 36381 43278 36380 43278 36382 43278 36381 43279 36382 43279 36386 43279 36386 43280 36382 43280 36383 43280 36386 43281 36383 43281 36384 43281 36384 43282 36383 43282 36388 43282 35924 43283 36385 43283 36399 43283 36399 43284 36385 43285 35920 43284 35920 43286 36117 43286 36399 43286 36399 43287 36117 43287 36381 43287 36399 43288 36381 43288 36387 43288 36387 43289 36381 43289 36386 43289 36387 43290 36386 43290 36396 43290 36396 43291 36386 43291 36384 43291 36396 43292 36384 43292 36176 43292 36176 43293 36384 43293 36388 43293 36176 43294 36388 43294 36389 43294 36389 43295 36388 43295 36390 43295 36389 43296 36390 43296 36391 43296 36391 43297 36390 43297 36392 43297 36391 43298 36392 43298 36393 43298 36393 43299 36392 43299 36377 43299 36393 43300 36377 43300 36394 43300 36394 43301 36377 43301 36395 43301 36146 43302 36397 43302 36396 43302 36396 43303 36397 43303 36398 43303 36396 43304 36398 43304 36387 43304 36387 43305 36398 43305 36403 43305 36387 43306 36403 43306 36399 43306 36399 43307 36403 43307 36402 43307 36399 43308 36402 43308 35924 43308 35925 43309 36400 43309 36402 43309 36402 43310 36400 43310 36401 43310 36402 43311 36401 43311 35924 43311 36116 43312 35925 43313 36411 43314 36411 43315 35925 43315 36402 43315 36411 43316 36402 43316 36409 43316 36409 43317 36402 43317 36403 43317 36409 43318 36403 43318 36404 43318 36404 43319 36403 43319 36398 43319 36404 43320 36398 43320 36405 43320 36405 43321 36398 43321 36397 43321 36405 43322 36397 43322 36406 43322 36406 43323 36397 43324 36147 43325 36175 43326 36407 43326 36405 43326 36405 43327 36407 43327 36419 43327 36405 43328 36419 43328 36404 43328 36404 43329 36419 43329 36408 43329 36404 43330 36408 43330 36409 43330 36409 43331 36408 43331 36410 43331 36409 43332 36410 43332 36411 43332 36411 43333 36410 43333 36417 43333 36411 43334 36417 43334 36412 43334 36416 43335 36413 43335 36417 43335 36417 43336 36413 43336 36414 43336 36417 43337 36414 43337 36412 43337 36415 43338 36416 43339 36418 43340 36418 43341 36416 43341 36417 43341 36418 43342 36417 43342 36427 43342 36427 43343 36417 43343 36410 43343 36427 43344 36410 43344 36425 43344 36425 43345 36410 43345 36408 43345 36425 43346 36408 43346 36422 43346 36422 43347 36408 43347 36419 43347 36422 43348 36419 43348 36421 43348 36421 43349 36419 43349 36407 43349 36421 43350 36407 43350 36420 43350 36421 43351 36423 43351 36422 43351 36422 43352 36423 43352 36424 43352 36422 43353 36424 43353 36425 43353 36425 43354 36424 43354 36426 43354 36425 43355 36426 43355 36427 43355 36427 43356 36426 43356 36431 43356 36427 43357 36431 43357 36418 43357 36418 43358 36431 43358 36428 43358 36418 43359 36428 43359 35928 43359 35929 43360 36429 43360 36428 43360 36428 43361 36429 43361 36430 43361 36428 43362 36430 43362 35928 43362 36115 43363 35929 43363 36434 43363 36434 43364 35929 43364 36428 43364 36434 43365 36428 43365 36435 43365 36435 43366 36428 43366 36431 43366 36435 43367 36431 43367 36436 43367 36436 43368 36431 43368 36426 43368 36436 43369 36426 43369 36437 43369 36437 43370 36426 43370 36424 43370 36437 43371 36424 43371 36432 43371 36432 43372 36424 43372 36423 43372 36433 43373 35930 43373 36441 43373 36441 43374 35930 43374 36434 43374 36441 43375 36434 43375 36443 43375 36443 43376 36434 43376 36435 43376 36443 43377 36435 43377 36170 43377 36170 43378 36435 43378 36436 43378 36170 43379 36436 43379 36172 43379 36172 43380 36436 43380 36437 43380 36172 43381 36437 43381 36173 43381 36173 43382 36437 43382 36438 43382 36439 43383 36114 43383 36440 43383 36440 43384 36114 43384 36441 43384 36440 43385 36441 43385 36442 43385 36442 43386 36441 43386 36443 43386 36442 43387 36443 43387 36184 43387 36184 43388 36443 43388 36170 43388 36184 43389 36170 43389 35780 43389 35780 43390 36170 43390 36168 43390 36444 43391 36445 43391 36446 43391 36446 43392 36445 43392 36447 43392 36446 43393 36447 43394 36331 43395 36448 43396 36449 43396 36450 43396 36450 43397 36449 43397 36332 43397 36450 43398 36332 43398 36149 43398 36149 43399 36327 43399 36450 43399 36450 43400 36327 43400 36328 43400 36450 43401 36328 43401 36447 43401 36447 43402 36328 43402 36330 43402 36447 43403 36330 43403 36331 43403 36451 43404 36523 43404 36525 43404 36525 43405 36698 43405 36451 43405 36451 43406 36698 43406 36452 43406 36451 43407 36452 43407 36453 43407 36452 39473 36700 39473 36453 39473 36453 39474 36700 39474 36702 39474 36453 43408 36702 43408 36454 43408 36702 43409 36455 43409 36454 43409 36454 39477 36455 39477 36456 39477 36454 43410 36456 43410 36457 43410 36456 43411 36704 43411 36457 43411 36457 43412 36704 43412 36458 43412 36457 43413 36458 43413 36459 43413 36458 39482 36707 39482 36459 39482 36459 39483 36707 39483 36708 39483 36459 43414 36708 43414 36460 43414 36708 39485 36461 39485 36460 39485 36460 39486 36461 39486 36462 39486 36460 43415 36462 43415 36463 43415 36462 39488 36711 39488 36463 39488 36463 43416 36711 43416 36464 43416 36463 43417 36464 43417 36465 43417 36464 43418 36466 43418 36465 43418 36465 43419 36466 43419 36467 43419 36465 43420 36467 43420 36468 43420 36467 43421 36715 43421 36468 43421 36468 39495 36715 39495 36469 39495 36468 43422 36469 43422 36471 43422 36469 39497 36470 39497 36471 39497 36471 39498 36470 39498 36716 39498 36471 43423 36716 43423 36472 43423 36716 43424 36473 43424 36472 43424 36472 39501 36473 39501 36474 39501 36472 43425 36474 43425 36475 43425 36474 39503 36718 39503 36475 39503 36475 50 36718 50 36476 50 36475 43426 36476 43426 36477 43426 36476 39505 36721 39505 36477 39505 36477 39506 36721 39506 36478 39506 36477 43427 36478 43427 36479 43427 36478 43428 36724 43428 36479 43428 36479 39509 36724 39509 36726 39509 36479 39510 36726 39510 36480 39510 36726 39511 36481 39511 36480 39511 36480 43429 36481 43429 36727 43429 36480 43430 36727 43430 36482 43430 36727 43431 36729 43431 36482 43431 36482 43432 36729 43432 36483 43432 36482 43433 36483 43433 36484 43433 36483 39517 36485 39517 36484 39517 36484 43434 36485 43434 36730 43434 36484 43435 36730 43435 36486 43435 36730 39520 36731 39520 36486 39520 36486 39521 36731 39521 36733 39521 36486 43436 36733 43436 36487 43436 36733 43437 36488 43437 36487 43437 36487 39524 36488 39524 36489 39524 36487 43438 36489 43438 36491 43438 36489 43439 36737 43439 36491 43439 36491 43440 36737 43440 36490 43440 36491 43441 36490 43441 36492 43441 36490 39417 36738 39417 36492 39417 36492 39418 36738 39418 36739 39418 36492 43442 36739 43442 36493 43442 36739 43443 36741 43443 36493 43443 36493 39421 36741 39421 36744 39421 36493 43444 36744 43444 36494 43444 36744 43445 36745 43445 36494 43445 36494 43446 36745 43446 36495 43446 36494 43447 36495 43447 36496 43447 36495 39426 36497 39426 36496 39426 36496 39427 36497 39427 36498 39427 36496 43448 36498 43448 36499 43448 36498 39429 36500 39429 36499 39429 36499 39430 36500 39430 36747 39430 36499 43449 36747 43449 36501 43449 36747 39432 36502 39432 36501 39432 36501 43450 36502 43450 36749 43450 36501 43451 36749 43451 36503 43451 36749 43452 36750 43452 36503 43452 36503 43453 36750 43453 36504 43453 36503 43454 36504 43454 36505 43454 36504 43455 36752 43455 36505 43455 36505 39439 36752 39439 36753 39439 36505 43456 36753 43456 36506 43456 36753 39441 36507 39441 36506 39441 36506 39442 36507 39442 36756 39442 36506 43457 36756 43457 36509 43457 36756 43458 36508 43458 36509 43458 36509 39445 36508 39445 36757 39445 36509 43459 36757 43459 36510 43459 36757 39447 36759 39447 36510 39447 36510 49 36759 49 36511 49 36510 43460 36511 43460 36512 43460 36511 39449 36761 39449 36512 39449 36512 39450 36761 39450 36513 39450 36512 43461 36513 43461 36514 43461 36513 43462 36515 43462 36514 43462 36514 39453 36515 39453 36516 39453 36514 39454 36516 39454 36517 39454 36516 39455 36763 39455 36517 39455 36517 43463 36763 43463 36765 43463 36517 43464 36765 43464 36518 43464 36765 43465 36767 43465 36518 43465 36518 43466 36767 43466 36519 43466 36518 43467 36519 43467 36520 43467 36519 39461 36769 39461 36520 39461 36520 43468 36769 43468 36521 43468 36520 43469 36521 43469 36522 43469 36521 39464 36772 39464 36522 39464 36522 39465 36772 39465 36773 39465 36522 43470 36773 43470 36523 43470 36523 43471 36773 43471 36524 43471 36523 39468 36524 39468 36525 39468 36619 43472 36526 43472 36623 43472 36619 43473 36792 43473 36526 43473 36526 43474 36792 43474 36917 43474 36526 43475 36917 43475 36527 43475 36527 43476 36917 43476 36529 43476 36527 43477 36529 43477 36528 43477 36529 43478 36916 43478 36528 43478 36528 43479 36916 43479 36791 43479 36528 43480 36791 43480 36625 43480 36791 43481 36924 43482 36625 43483 36625 43484 36924 43484 36923 43484 36625 43485 36923 43485 36627 43485 36627 43486 36923 43487 36922 43488 36627 43489 36922 43489 36628 43489 36628 43490 36922 43490 36941 43490 36628 43491 36941 43491 36630 43491 36630 43492 36941 43492 36530 43492 36530 43493 36939 43493 36630 43493 36630 43494 36939 43494 36938 43494 36630 43495 36938 43495 36531 43495 36531 43496 36938 43496 36532 43496 36531 43497 36532 43497 36631 43497 36631 43498 36532 43498 36951 43498 36631 43499 36951 43499 36633 43499 36633 43500 36951 43500 36954 43500 36954 43501 36953 43501 36633 43501 36633 43502 36953 43502 36952 43502 36633 43503 36952 43503 36533 43503 36533 43504 36952 43504 36534 43504 36533 43505 36534 43505 36535 43505 36535 43506 36534 43506 36790 43506 36535 43507 36790 43507 36635 43507 36635 39681 36790 39681 36536 39681 36536 43508 36537 43508 36635 43508 36635 43509 36537 43510 36538 43511 36635 43512 36538 43512 36539 43512 36539 43513 36538 43514 36540 43515 36539 43516 36540 43516 36636 43516 36636 43517 36540 43517 36971 43517 36636 43518 36971 43519 36638 43520 36638 43521 36971 43521 36970 43521 36970 43522 36541 43522 36638 43522 36638 43523 36541 43523 36542 43523 36638 43524 36542 43524 36639 43524 36639 43525 36542 43525 36543 43525 36639 43526 36543 43526 36544 43526 36544 43527 36543 43527 36788 43527 36544 39698 36788 39698 36642 39698 36788 43528 36545 43528 36642 43528 36642 43529 36545 43529 36546 43529 36642 43530 36546 43530 36548 43530 36546 43531 36547 43531 36548 43531 36548 43532 36547 43532 36549 43532 36548 43533 36549 43533 36644 43533 36644 43534 36549 43534 36983 43534 36644 43535 36983 43535 36551 43535 36983 43536 36550 43537 36551 43538 36551 43539 36550 43539 36988 43539 36551 43540 36988 43540 36552 43540 36988 43541 36786 43541 36552 43541 36552 43542 36786 43542 36553 43542 36552 43543 36553 43543 36647 43543 36647 43544 36553 43544 36554 43544 36647 43545 36554 43546 36648 43547 36648 43548 36554 43548 36555 43548 36648 39720 36555 39720 36557 39720 36557 43549 36555 43550 37007 43551 37007 43552 37006 43552 36557 43552 36557 39723 37006 39723 36556 39723 36557 43553 36556 43553 36558 43553 36558 43554 36556 43554 36560 43554 36558 43555 36560 43555 36559 43555 36559 39728 36560 39728 37016 39728 36559 43556 37016 43556 36651 43556 36651 43557 37016 43557 37017 43557 37017 43558 36561 43558 36651 43558 36651 43559 36561 43559 37019 43559 36651 43560 37019 43560 36562 43560 36562 43561 37019 43562 37018 43563 36562 43564 37018 43565 36652 43566 36652 43567 37018 43567 36784 43567 36652 43568 36784 43568 36654 43568 36654 43569 36784 43569 37030 43569 37030 43570 36563 43570 36654 43570 36654 43571 36563 43571 37029 43571 36654 43572 37029 43572 36564 43572 36564 43573 37029 43573 36782 43573 36564 43574 36782 43574 36657 43574 36657 43575 36782 43575 36565 43575 36657 43576 36565 43576 36659 43576 36659 43577 36565 43577 36781 43577 36781 43578 36780 43578 36659 43578 36659 43579 36780 43579 37040 43579 36659 43580 37040 43580 36660 43580 36660 39753 37040 39753 36779 39753 36660 43581 36779 43581 36566 43581 36566 43582 36779 43582 36567 43582 36566 43583 36567 43583 36568 43583 36567 43584 36778 43584 36568 43584 36568 43585 36778 43585 36569 43585 36568 43586 36569 43586 36570 43586 36569 43587 37051 43587 36570 43587 36570 43588 37051 43588 37050 43588 36570 43589 37050 43589 36663 43589 36663 43590 37050 43590 37049 43590 36663 43591 37049 43591 36664 43591 37049 43592 36571 43592 36664 43592 36664 43593 36571 43593 36573 43593 36664 43594 36573 43594 36572 43594 36573 43595 36574 43595 36572 43595 36572 43596 36574 43596 37059 43596 36572 43597 37059 43597 36666 43597 36666 43598 37059 43598 37058 43598 36666 43599 37058 43599 36667 43599 36667 43600 37058 43600 37074 43600 36667 43601 37074 43601 36577 43601 36577 43602 37074 43602 36575 43602 36575 43603 36576 43603 36577 43603 36577 43604 36576 43604 37073 43604 36577 43605 37073 43605 36669 43605 36669 43606 37073 43607 36578 43608 36669 43609 36578 43609 36670 43609 36670 43610 36578 43610 36777 43610 36670 43611 36777 43611 36579 43611 36579 43612 36777 43612 37084 43612 37084 43613 36580 43613 36579 43613 36579 43614 36580 43614 36582 43614 36579 43615 36582 43615 36581 43615 36581 43616 36582 43616 36583 43616 36581 43617 36583 43617 36584 43617 36584 43618 36583 43618 37098 43618 36584 43619 37098 43619 36674 43619 36674 39561 37098 39561 36585 39561 36585 43620 36586 43620 36674 43620 36674 43621 36586 43621 37097 43621 36674 43622 37097 43622 36587 43622 36587 43623 37097 43624 36588 43625 36587 43626 36588 43626 36677 43626 36677 43627 36588 43627 36589 43627 36677 43628 36589 43628 36679 43628 36679 43629 36589 43629 36775 43629 36775 43630 36590 43630 36679 43630 36679 43631 36590 43631 36591 43631 36679 43632 36591 43632 36680 43632 36680 43633 36591 43633 36592 43633 36680 43634 36592 43634 36593 43634 36593 43635 36592 43635 36802 43635 36593 39582 36802 39582 36595 39582 36802 43636 36844 43636 36595 43636 36595 43637 36844 43637 36594 43637 36595 43638 36594 43639 36596 43640 36594 43641 36847 43641 36596 43641 36596 43642 36847 43642 36598 43642 36596 43643 36598 43643 36597 43643 36597 43644 36598 43644 36599 43644 36597 43645 36599 43645 36600 43645 36599 43646 36848 43646 36600 43646 36600 43647 36848 43647 36601 43647 36600 43648 36601 43648 36603 43648 36601 43649 36602 43650 36603 43651 36603 43652 36602 43652 36604 43652 36603 43653 36604 43653 36605 43653 36605 43654 36604 43654 36606 43654 36605 43655 36606 43655 36685 43655 36685 43656 36606 43656 36854 43656 36685 39604 36854 39604 36686 39604 36686 43657 36854 43657 36798 43657 36798 43658 36869 43658 36686 43658 36686 39609 36869 39609 36607 39609 36686 43659 36607 43659 36608 43659 36608 43660 36607 43660 36609 43661 36608 43662 36609 43662 36688 43662 36688 43663 36609 43663 36868 43663 36688 43664 36868 43664 36691 43664 36691 43665 36868 43666 36610 43667 36610 43668 36611 43668 36691 43668 36691 43669 36611 43669 36878 43669 36691 43670 36878 43670 36692 43670 36692 43671 36878 43671 36612 43671 36692 43672 36612 43673 36614 43672 36614 43674 36612 43674 36613 43674 36614 43675 36613 43675 36615 43675 36615 43676 36613 43676 36893 43676 36893 43677 36892 43677 36615 43677 36615 43678 36892 43678 36895 43678 36615 43679 36895 43679 36616 43679 36616 43680 36895 43680 36894 43680 36616 43681 36894 43681 36694 43681 36694 43682 36894 43682 36617 43682 36694 43683 36617 43683 36695 43683 36695 43684 36617 43684 36796 43684 36796 43685 36906 43685 36695 43685 36695 43686 36906 43686 36905 43686 36695 43687 36905 43687 36696 43687 36696 39641 36905 39641 36618 39641 36696 43688 36618 43688 36621 43688 36621 43689 36618 43689 36795 43689 36621 43690 36795 43690 36623 43690 36623 43691 36795 43691 36794 43691 36623 43692 36794 43692 36619 43692 36774 39844 36696 39844 36620 39844 36620 43693 36696 43693 36621 43693 36620 43694 36621 43694 36697 43694 36697 43695 36621 43695 36623 43695 36697 43696 36623 43696 36622 43696 36622 39849 36623 39849 36526 39849 36622 43697 36526 43697 36624 43697 36624 43698 36526 43698 36527 43698 36624 39852 36527 39852 36699 39852 36699 43699 36527 43699 36528 43699 36699 43700 36528 43700 36701 43700 36701 43701 36528 43701 36625 43701 36701 43702 36625 43702 36626 43702 36626 43703 36625 43703 36627 43703 36626 43704 36627 43704 36703 43704 36703 43705 36627 43705 36628 43705 36703 43706 36628 43706 36629 43706 36629 43707 36628 43707 36630 43707 36629 39862 36630 39862 36705 39862 36705 43708 36630 43708 36531 43708 36705 39864 36531 39864 36706 39864 36706 43709 36531 43709 36631 43709 36706 43710 36631 43710 36632 43710 36632 43711 36631 43711 36633 43711 36632 43712 36633 43712 36634 43712 36634 43713 36633 43713 36533 43713 36634 43714 36533 43714 36709 43714 36709 43715 36533 43715 36535 43715 36709 43716 36535 43716 36710 43716 36710 43717 36535 43717 36635 43717 36710 43718 36635 43718 36712 43718 36712 43719 36635 43719 36539 43719 36712 43720 36539 43720 36713 43720 36713 43721 36539 43721 36636 43721 36713 43722 36636 43722 36637 43722 36637 43723 36636 43723 36638 43723 36637 43724 36638 43724 36714 43724 36714 43725 36638 43725 36639 43725 36714 43726 36639 43726 36640 43726 36640 43727 36639 43727 36544 43727 36640 43728 36544 43728 36641 43728 36641 39889 36544 39889 36642 39889 36641 43729 36642 43729 36643 43729 36643 43730 36642 43730 36548 43730 36643 43731 36548 43731 36717 43731 36717 43732 36548 43732 36644 43732 36717 43733 36644 43733 36645 43733 36645 43734 36644 43735 36551 43736 36645 43737 36551 43737 36646 43737 36646 43738 36551 43738 36552 43738 36646 43739 36552 43739 36719 43739 36719 43740 36552 43740 36647 43740 36719 43741 36647 43742 36720 43743 36720 43744 36647 43744 36648 43744 36720 43745 36648 43745 36722 43745 36722 43746 36648 43747 36557 43748 36722 43749 36557 43749 36723 43749 36723 39920 36557 39920 36558 39920 36723 43750 36558 43750 36725 43750 36725 39922 36558 39922 36559 39922 36725 43751 36559 43751 36649 43751 36649 39924 36559 39924 36651 39924 36649 43752 36651 43752 36650 43752 36650 43753 36651 43753 36562 43753 36650 43754 36562 43754 36728 43754 36728 39928 36562 39928 36652 39928 36728 43755 36652 43755 36653 43755 36653 43756 36652 43756 36654 43756 36653 43757 36654 43757 36655 43757 36655 39934 36654 39934 36564 39934 36655 43758 36564 43759 36656 43758 36656 43760 36564 43760 36657 43760 36656 43761 36657 43761 36658 43761 36658 43762 36657 43763 36659 43764 36658 43765 36659 43765 36732 43765 36732 43766 36659 43766 36660 43766 36732 39759 36660 39759 36734 39759 36734 43767 36660 43767 36566 43767 36734 43768 36566 43768 36735 43768 36735 43769 36566 43769 36568 43769 36735 43770 36568 43770 36736 43770 36736 39764 36568 39764 36570 39764 36736 43771 36570 43771 36661 43771 36661 43772 36570 43772 36663 43772 36661 39767 36663 39767 36662 39767 36662 43773 36663 43773 36664 43773 36662 43774 36664 43774 36740 43774 36740 43775 36664 43775 36572 43775 36740 43776 36572 43776 36665 43776 36665 43777 36572 43777 36666 43777 36665 43778 36666 43778 36742 43778 36742 43779 36666 43779 36667 43779 36742 43780 36667 43780 36743 43780 36743 43781 36667 43781 36577 43781 36743 39777 36577 39777 36668 39777 36668 43782 36577 43782 36669 43782 36668 39779 36669 39779 36746 39779 36746 43783 36669 43783 36670 43783 36746 43784 36670 43784 36671 43784 36671 43785 36670 43785 36579 43785 36671 43786 36579 43786 36672 43786 36672 43787 36579 43787 36581 43787 36672 43788 36581 43788 36673 43788 36673 43789 36581 43789 36584 43789 36673 43790 36584 43790 36748 43790 36748 43791 36584 43792 36674 43793 36748 43794 36674 43795 36675 43796 36675 43797 36674 43797 36587 43797 36675 43798 36587 43798 36676 43798 36676 43799 36587 43799 36677 43799 36676 43800 36677 43800 36678 43800 36678 43801 36677 43801 36679 43801 36678 43802 36679 43802 36751 43802 36751 43803 36679 43803 36680 43803 36751 43804 36680 43804 36681 43804 36681 43805 36680 43805 36593 43805 36681 43806 36593 43806 36754 43806 36754 39800 36593 39800 36595 39800 36754 43807 36595 43808 36755 43809 36755 43810 36595 43810 36596 43810 36755 43811 36596 43812 36682 43813 36682 39804 36596 39804 36597 39804 36682 39805 36597 39805 36758 39805 36758 43814 36597 43814 36600 43814 36758 43815 36600 43815 36760 43816 36760 43817 36600 43818 36603 43819 36760 43820 36603 43821 36683 43822 36683 43823 36603 43824 36605 43825 36683 43826 36605 43826 36684 43826 36684 43827 36605 43827 36685 43827 36684 43828 36685 43829 36762 43830 36762 43831 36685 43832 36686 43833 36762 43834 36686 43834 36687 43834 36687 39822 36686 39822 36608 39822 36687 43835 36608 43835 36689 43835 36689 39824 36608 39824 36688 39824 36689 43836 36688 43836 36690 43836 36690 39826 36688 39826 36691 39826 36690 43837 36691 43837 36764 43837 36764 43838 36691 43838 36692 43838 36764 43839 36692 43839 36766 43839 36766 39830 36692 39830 36614 39830 36766 43840 36614 43841 36693 43842 36693 43843 36614 43843 36615 43843 36693 43844 36615 43844 36768 43844 36768 39834 36615 39834 36616 39834 36768 43845 36616 43845 36770 43845 36770 43846 36616 43846 36694 43846 36770 43847 36694 43847 36771 43847 36771 43848 36694 43848 36695 43848 36771 43849 36695 43849 36774 43849 36774 43850 36695 43850 36696 43850 36773 43851 36620 43851 36524 43851 36524 43852 36620 43852 36697 43852 36524 43853 36697 43853 36525 43853 36525 43854 36697 43854 36622 43854 36525 43855 36622 43855 36698 43855 36698 43856 36622 43856 36624 43856 36698 43857 36624 43857 36452 43857 36452 43858 36624 43858 36699 43858 36452 43859 36699 43859 36700 43859 36700 40047 36699 40047 36701 40047 36700 43860 36701 43860 36702 43860 36702 43861 36701 43861 36626 43861 36702 43862 36626 43862 36455 43862 36455 43863 36626 43863 36703 43863 36455 43864 36703 43864 36456 43864 36456 43865 36703 43865 36629 43865 36456 43866 36629 43866 36704 43866 36704 40055 36629 40055 36705 40055 36704 43867 36705 43867 36458 43867 36458 43868 36705 43868 36706 43868 36458 43869 36706 43869 36707 43869 36707 43870 36706 43870 36632 43870 36707 43871 36632 43871 36708 43871 36708 43872 36632 43872 36634 43872 36708 43873 36634 43873 36461 43873 36461 43874 36634 43874 36709 43874 36461 43875 36709 43875 36462 43875 36462 43876 36709 43876 36710 43876 36462 43877 36710 43877 36711 43877 36711 43878 36710 43878 36712 43878 36711 43879 36712 43879 36464 43879 36464 43880 36712 43881 36713 43882 36464 43883 36713 43883 36466 43883 36466 43884 36713 43884 36637 43884 36466 43885 36637 43886 36467 43887 36467 43888 36637 43889 36714 43890 36467 43891 36714 43891 36715 43891 36715 43892 36714 43892 36640 43892 36715 43893 36640 43893 36469 43893 36469 43894 36640 43894 36641 43894 36469 43895 36641 43896 36470 43897 36470 43898 36641 43898 36643 43898 36470 43899 36643 43899 36716 43899 36716 43900 36643 43900 36717 43900 36716 43901 36717 43901 36473 43901 36473 43902 36717 43903 36645 43904 36473 43905 36645 43905 36474 43905 36474 40091 36645 40091 36646 40091 36474 43906 36646 43906 36718 43906 36718 43907 36646 43907 36719 43907 36718 43908 36719 43908 36476 43908 36476 43909 36719 43909 36720 43909 36476 43910 36720 43910 36721 43910 36721 43911 36720 43911 36722 43911 36721 43912 36722 43912 36478 43912 36478 43913 36722 43913 36723 43914 36478 43915 36723 43915 36724 43915 36724 43916 36723 43917 36725 43918 36724 43919 36725 43919 36726 43919 36726 43920 36725 43921 36649 43922 36726 43923 36649 43923 36481 43923 36481 43924 36649 43924 36650 43924 36481 43925 36650 43925 36727 43925 36727 40111 36650 40111 36728 40111 36727 43926 36728 43927 36729 43928 36729 43929 36728 43930 36653 43931 36729 43932 36653 43932 36483 43932 36483 40117 36653 40117 36655 40117 36483 43933 36655 43933 36485 43933 36485 43934 36655 43934 36656 43934 36485 43935 36656 43935 36730 43935 36730 43936 36656 43936 36658 43936 36730 43937 36658 43938 36731 43939 36731 43940 36658 43940 36732 43940 36731 43941 36732 43941 36733 43941 36733 40125 36732 40125 36734 40125 36733 43942 36734 43942 36488 43942 36488 43943 36734 43943 36735 43943 36488 43944 36735 43944 36489 43944 36489 43945 36735 43945 36736 43945 36489 43946 36736 43946 36737 43946 36737 43947 36736 43947 36661 43947 36737 43948 36661 43948 36490 43948 36490 43949 36661 43949 36662 43949 36490 43950 36662 43950 36738 43950 36738 39950 36662 39950 36740 39950 36738 43951 36740 43951 36739 43951 36739 43952 36740 43952 36665 43952 36739 43953 36665 43953 36741 43953 36741 43954 36665 43954 36742 43954 36741 43955 36742 43955 36744 43955 36744 43956 36742 43956 36743 43956 36744 43957 36743 43957 36745 43957 36745 39958 36743 39958 36668 39958 36745 43958 36668 43958 36495 43958 36495 43959 36668 43959 36746 43959 36495 43960 36746 43960 36497 43960 36497 43961 36746 43961 36671 43961 36497 43962 36671 43962 36498 43962 36498 43963 36671 43963 36672 43963 36498 43964 36672 43964 36500 43964 36500 43965 36672 43965 36673 43965 36500 43966 36673 43966 36747 43966 36747 43967 36673 43967 36748 43967 36747 43968 36748 43969 36502 43970 36502 43971 36748 43971 36675 43971 36502 43972 36675 43973 36749 43974 36749 43975 36675 43975 36676 43975 36749 43976 36676 43976 36750 43976 36750 43977 36676 43977 36678 43977 36750 43978 36678 43978 36504 43978 36504 43979 36678 43979 36751 43979 36504 43980 36751 43980 36752 43980 36752 43981 36751 43981 36681 43981 36752 43982 36681 43982 36753 43982 36753 43983 36681 43983 36754 43983 36753 43984 36754 43984 36507 43984 36507 43985 36754 43985 36755 43985 36507 43986 36755 43986 36756 43986 36756 43987 36755 43987 36682 43987 36756 43988 36682 43989 36508 43990 36508 43991 36682 43991 36758 43991 36508 43992 36758 43992 36757 43992 36757 39998 36758 39998 36760 39998 36757 43993 36760 43993 36759 43993 36759 43994 36760 43994 36683 43994 36759 43995 36683 43995 36511 43995 36511 43996 36683 43996 36684 43996 36511 43997 36684 43997 36761 43997 36761 43998 36684 43999 36762 44000 36761 44001 36762 44001 36513 44001 36513 44002 36762 44002 36687 44002 36513 44003 36687 44003 36515 44003 36515 44004 36687 44004 36689 44004 36515 44005 36689 44005 36516 44005 36516 44006 36689 44007 36690 44008 36516 44009 36690 44009 36763 44009 36763 44010 36690 44010 36764 44010 36763 44011 36764 44011 36765 44011 36765 40019 36764 40019 36766 40019 36765 44012 36766 44012 36767 44012 36767 44013 36766 44014 36693 44015 36767 44016 36693 44016 36519 44016 36519 40027 36693 40027 36768 40027 36519 44017 36768 44017 36769 44017 36769 44018 36768 44018 36770 44018 36769 44019 36770 44019 36521 44019 36521 44020 36770 44020 36771 44020 36521 44021 36771 44021 36772 44021 36772 44022 36771 44022 36774 44022 36772 44023 36774 44023 36773 44023 36773 40037 36774 40037 36620 40037 36590 40146 36775 40146 37103 40146 36589 44024 36588 44024 36776 44024 37098 44025 36583 44025 37096 44025 36777 44026 36578 44026 37083 44026 36574 44027 36573 44027 37054 44027 37051 44028 36569 44029 37046 44030 36778 40154 36567 40154 37043 40154 36779 40155 37040 40155 37044 40155 36780 44031 36781 44031 37034 44031 36565 44032 36782 44032 36783 44032 36784 44033 37018 44033 36785 44033 37016 40159 36560 40159 37015 40159 36786 44034 36988 44034 36991 44034 36547 44035 36546 44035 36787 44035 36545 44036 36788 44036 36980 44036 36543 44037 36542 44037 36977 44037 36541 40126 36970 40126 36978 40126 36971 44038 36540 44038 36789 44038 36790 44039 36534 44039 36966 44039 36951 44040 36532 44040 36942 44040 36924 44041 36791 44041 36920 44041 36792 44042 36619 44043 36793 44044 36794 40136 36795 40136 36911 40136 36618 40137 36905 40137 36912 40137 36906 44045 36796 44045 36907 44045 36617 44046 36894 44046 36896 44046 36613 44047 36612 44047 36797 44047 36869 44048 36798 44048 36799 44048 36602 44049 36601 44049 36800 44049 36847 44050 36594 44050 36801 44050 36844 44051 36802 44051 36803 44051 36592 44052 36591 44052 37108 44052 37070 44053 36804 44053 37077 44053 36934 44054 36805 44054 36946 44054 36806 44055 36807 44055 37002 44055 36808 44056 36809 44056 37010 44056 36993 44057 36806 44058 36992 44059 36813 44060 36811 44061 36810 44062 36810 44063 36811 44063 36812 44063 36810 44064 36812 44064 36975 44064 36813 40201 36810 40201 36814 40201 36814 44065 36810 44065 36975 44065 36814 44066 36975 44066 36976 44066 36815 40204 36816 40204 36969 40204 36969 44067 36816 44067 36817 44067 36948 44068 36818 44069 36947 44070 36819 44071 36934 44072 36935 44073 36822 44074 36820 44074 36821 44074 36821 44075 36820 44075 36900 44075 36821 44076 36900 44076 36902 44076 36822 44077 36821 44077 36823 44077 36823 44078 36821 44078 36902 44078 36823 44079 36902 44079 36903 44079 36824 44080 36825 44080 36898 44080 36898 44081 36825 44081 36904 44081 36874 44082 36826 44082 36871 44082 36857 44083 36866 44083 36865 44083 36827 44084 36828 44085 36829 44086 36829 44087 36828 44087 37105 44087 36829 44088 37105 44088 36831 44088 36827 40175 36829 40175 36830 40175 36830 44089 36829 44089 36831 44089 36830 44090 36831 44090 37106 44090 36832 40178 36834 40178 36833 40178 36833 44091 36834 44091 37107 44091 37078 44092 37079 44092 36835 44092 37062 44093 37070 44094 37071 44095 36836 44096 36837 44096 36840 44096 36840 44097 36837 44097 37042 44097 36840 44098 37042 44098 36838 44098 36836 44099 36840 44100 36839 44101 36839 44102 36840 44102 36838 44102 36839 44103 36838 44103 37038 44103 36841 44104 36842 44104 37039 44104 37039 44105 36842 44105 36843 44105 36802 40481 36592 40481 36803 40481 36803 44106 36592 44106 37108 44106 36803 44107 37108 44107 36846 44107 36846 44108 37108 44108 37109 44108 36846 44109 37109 44109 36861 44109 36861 44110 37109 44110 37111 44110 36594 44111 36844 44111 36801 44111 36801 44112 36844 44112 36803 44112 36801 44113 36803 44113 36845 44113 36845 44114 36803 44114 36846 44114 36845 44115 36846 44115 36859 44115 36859 44116 36846 44116 36861 44116 36848 44117 36599 44117 36849 44117 36849 44118 36599 44118 36598 44118 36598 44119 36847 44119 36849 44119 36849 44120 36847 44120 36801 44120 36849 44121 36801 44121 36852 44121 36852 44122 36801 44122 36845 44122 36852 44123 36845 44123 36853 44123 36853 44124 36845 44124 36859 44124 36601 44125 36848 44125 36800 44125 36800 44126 36848 44126 36849 44126 36800 44127 36849 44127 36850 44127 36850 44128 36849 44128 36852 44128 36850 40505 36852 40505 36851 40505 36851 44129 36852 44129 36853 44129 36854 44130 36606 44130 36855 44130 36855 44131 36606 44131 36604 44131 36604 44132 36602 44132 36855 44132 36855 44133 36602 44133 36800 44133 36855 44134 36800 44134 36856 44134 36856 44135 36800 44135 36850 44135 36856 44136 36850 44136 36865 44136 36865 44137 36850 44137 36851 44137 36865 44138 36851 44138 36857 44138 36857 44139 36851 44139 36853 44139 36857 44140 36853 44140 36858 44140 36858 44141 36853 44141 36859 44141 36858 44142 36859 44142 36860 44142 36860 40520 36859 40520 36861 40520 36860 44143 36861 44143 36862 44143 36862 44144 36861 44144 37111 44144 36862 44145 37111 44145 36863 44145 36863 44146 37111 44146 37112 44146 36798 44147 36854 44147 36799 44147 36799 44148 36854 44148 36855 44148 36799 44149 36855 44149 36864 44149 36864 44150 36855 44150 36856 44150 36864 44151 36856 44151 36872 44151 36872 44152 36856 44152 36865 44152 36872 44153 36865 44153 36873 44153 36873 44154 36865 44154 36866 44154 36873 44155 36866 44155 36867 44155 36868 44156 36609 44156 36877 44156 36877 44157 36609 44157 36607 44157 36607 44158 36869 44158 36877 44158 36877 44159 36869 44159 36799 44159 36877 44160 36799 44160 36876 44160 36876 44161 36799 44161 36864 44161 36876 44162 36864 44162 36870 44162 36870 44163 36864 44163 36872 44163 36870 44164 36872 44164 36871 44164 36871 44165 36872 44165 36873 44165 36871 44166 36873 44166 36874 44166 36874 44167 36873 44167 36867 44167 36826 44168 36884 44168 36871 44168 36871 44169 36884 44169 36875 44169 36871 44170 36875 44170 36870 44170 36870 40548 36875 40548 36882 40548 36870 44171 36882 44171 36876 44171 36876 44172 36882 44172 36881 44172 36876 44173 36881 44173 36877 44173 36877 44174 36881 44174 36880 44174 36877 44175 36880 44175 36868 44175 36878 44176 36611 44176 36880 44176 36880 44177 36611 44177 36610 44177 36880 44178 36610 44178 36868 44178 36612 44179 36878 44180 36797 44181 36797 44182 36878 44182 36880 44182 36797 44183 36880 44183 36879 44183 36879 44184 36880 44184 36881 44184 36879 44185 36881 44185 36889 44185 36889 44186 36881 44186 36882 44186 36889 44187 36882 44187 36888 44187 36888 40565 36882 40565 36875 40565 36888 44188 36875 44188 36883 44188 36883 44189 36875 44189 36884 44189 36883 44190 36884 44191 36885 44192 36883 44193 36886 44193 36888 44193 36888 44194 36886 44194 36887 44194 36888 44195 36887 44195 36889 44195 36889 44196 36887 44196 36890 44196 36889 44197 36890 44197 36879 44197 36879 44198 36890 44198 36891 44198 36879 44199 36891 44199 36797 44199 36797 44200 36891 44200 36897 44200 36797 44201 36897 44201 36613 44201 36895 44202 36892 44202 36897 44202 36897 44203 36892 44203 36893 44203 36897 44204 36893 44204 36613 44204 36894 44205 36895 44206 36896 44207 36896 44208 36895 44208 36897 44208 36896 44209 36897 44209 36899 44209 36899 44210 36897 44210 36891 44210 36899 44211 36891 44211 36901 44211 36901 44212 36891 44212 36890 44212 36901 44213 36890 44213 36898 44213 36898 44214 36890 44214 36887 44214 36898 44215 36887 44215 36824 44215 36824 44216 36887 44216 36886 44216 36796 40591 36617 40591 36907 40591 36907 44217 36617 44217 36896 44217 36907 44218 36896 44218 36909 44218 36909 44219 36896 44219 36899 44219 36909 44220 36899 44220 36900 44220 36900 44221 36899 44221 36901 44221 36900 44222 36901 44222 36902 44222 36902 40598 36901 40598 36898 40598 36902 44223 36898 44223 36903 44223 36903 44224 36898 44224 36904 44224 36905 44225 36906 44225 36912 44225 36912 44226 36906 44226 36907 44226 36912 44227 36907 44227 36908 44227 36908 44228 36907 44228 36909 44228 36908 40605 36909 40605 36910 40605 36910 44229 36909 44229 36900 44229 36910 44230 36900 44230 36933 44230 36933 44231 36900 44231 36820 44231 36795 44232 36618 44232 36911 44232 36911 44233 36618 44233 36912 44233 36911 44234 36912 44234 36913 44234 36913 40612 36912 40612 36908 40612 36913 44235 36908 44235 36914 44235 36914 44236 36908 44236 36910 44236 36619 44237 36794 44237 36793 44237 36793 40616 36794 40616 36911 40616 36793 44238 36911 44238 36915 44238 36915 44239 36911 44239 36913 44239 36915 44240 36913 44240 36928 44240 36928 44241 36913 44241 36914 44241 36916 44242 36529 44242 36921 44242 36921 44243 36529 44243 36917 44243 36917 44244 36792 44244 36921 44244 36921 44245 36792 44245 36793 44245 36921 44246 36793 44246 36918 44246 36918 40626 36793 40626 36915 40626 36918 44247 36915 44247 36919 44247 36919 40628 36915 40628 36928 40628 36791 44248 36916 44248 36920 44248 36920 44249 36916 44249 36921 44249 36920 44250 36921 44250 36926 44250 36926 44251 36921 44251 36918 44251 36926 40633 36918 40633 36927 40633 36927 40634 36918 40634 36919 40634 36941 44252 36922 44252 36937 44252 36937 44253 36922 44253 36923 44253 36923 44254 36924 44254 36937 44254 36937 44255 36924 44255 36920 44255 36937 44256 36920 44256 36925 44256 36925 44257 36920 44257 36926 44257 36925 40641 36926 40641 36935 40641 36935 44258 36926 44258 36927 44258 36935 44259 36927 44259 36819 44259 36819 44260 36927 44260 36919 44260 36819 44261 36919 44261 36929 44261 36929 44262 36919 44262 36928 44262 36929 40647 36928 40647 36930 40647 36930 44263 36928 44263 36914 44263 36930 44264 36914 44264 36931 44264 36931 44265 36914 44265 36910 44265 36931 44266 36910 44266 36932 44266 36932 44267 36910 44267 36933 44267 36934 44268 36946 44268 36935 44268 36935 44269 36946 44269 36936 44269 36935 44270 36936 44270 36925 44270 36925 44271 36936 44271 36945 44271 36925 44272 36945 44272 36937 44272 36937 44273 36945 44273 36940 44273 36937 44274 36940 44274 36941 44274 36938 44275 36939 44275 36940 44275 36940 44276 36939 44276 36530 44276 36940 44277 36530 44277 36941 44277 36532 44278 36938 44278 36942 44278 36942 44279 36938 44279 36940 44279 36942 44280 36940 44280 36943 44280 36943 44281 36940 44281 36945 44281 36943 44282 36945 44282 36944 44282 36944 44283 36945 44283 36936 44283 36944 44284 36936 44284 36947 44284 36947 44285 36936 44285 36946 44285 36947 40672 36946 40672 36948 40672 36948 44286 36946 44286 36805 44286 36818 44287 36949 44287 36947 44287 36947 44288 36949 44288 36959 44288 36947 44289 36959 44289 36944 44289 36944 44290 36959 44290 36957 44290 36944 44291 36957 44291 36943 44291 36943 44292 36957 44292 36950 44292 36943 44293 36950 44293 36942 44293 36942 44294 36950 44294 36955 44294 36942 44295 36955 44295 36951 44295 36952 44296 36953 44296 36955 44296 36955 44297 36953 44297 36954 44297 36955 44298 36954 44298 36951 44298 36534 40686 36952 40686 36966 40686 36966 44299 36952 44299 36955 44299 36966 44300 36955 44300 36964 44300 36964 44301 36955 44301 36950 44301 36964 44302 36950 44302 36956 44302 36956 44303 36950 44303 36957 44303 36956 40692 36957 40692 36958 40692 36958 44304 36957 44304 36959 44304 36958 40694 36959 40694 36960 40694 36960 40695 36959 40695 36949 40695 36960 40696 36949 40696 36961 40696 36960 44305 36962 44305 36958 44305 36958 44306 36962 44306 36963 44306 36958 44307 36963 44307 36956 44307 36956 44308 36963 44308 36968 44308 36956 44309 36968 44309 36964 44309 36964 44310 36968 44310 36965 44310 36964 44311 36965 44311 36966 44311 36966 44312 36965 44312 36967 44312 36966 44313 36967 44313 36790 44313 36538 44314 36537 44314 36967 44314 36967 44315 36537 44315 36536 44315 36967 40708 36536 40708 36790 40708 36540 44316 36538 44317 36789 44318 36789 44319 36538 44319 36967 44319 36789 44320 36967 44320 36973 44320 36973 40714 36967 40714 36965 40714 36973 40715 36965 40715 36974 40715 36974 40716 36965 40716 36968 40716 36974 40717 36968 40717 36969 40717 36969 44321 36968 44321 36963 44321 36969 40719 36963 40719 36815 40719 36815 44322 36963 44322 36962 44322 36970 40721 36971 40721 36978 40721 36978 40722 36971 40722 36789 40722 36978 44323 36789 44323 36972 44323 36972 44324 36789 44324 36973 44324 36972 44325 36973 44325 36812 44325 36812 44326 36973 44326 36974 44326 36812 40727 36974 40727 36975 40727 36975 44327 36974 44327 36969 44327 36975 44328 36969 44328 36976 44328 36976 44329 36969 44329 36817 44329 36542 44330 36541 44330 36977 44330 36977 44331 36541 44331 36978 44331 36977 44332 36978 44332 36979 44332 36979 44333 36978 44333 36972 44333 36979 44334 36972 44334 37000 44334 37000 44335 36972 44335 36812 44335 37000 44336 36812 44336 37001 44336 37001 44337 36812 44337 36811 44337 36788 40220 36543 40220 36980 40220 36980 44338 36543 44338 36977 44338 36980 44339 36977 44339 36981 44339 36981 44340 36977 44340 36979 44340 36981 44341 36979 44341 36997 44341 36997 44342 36979 44342 37000 44342 36546 44343 36545 44343 36787 44343 36787 44344 36545 44344 36980 44344 36787 44345 36980 44345 36986 44345 36986 44346 36980 44346 36981 44346 36986 44347 36981 44347 36982 44347 36982 44348 36981 44348 36997 44348 36550 44349 36983 44349 36984 44349 36984 44350 36983 44350 36549 44350 36549 44351 36547 44351 36984 44351 36984 44352 36547 44352 36787 44352 36984 44353 36787 44353 36985 44353 36985 44354 36787 44354 36986 44354 36985 44355 36986 44355 36987 44355 36987 44356 36986 44356 36982 44356 36988 44357 36550 44357 36991 44357 36991 44358 36550 44358 36984 44358 36991 44359 36984 44359 36989 44359 36989 44360 36984 44360 36985 44360 36989 40244 36985 40244 36994 40244 36994 44361 36985 44361 36987 44361 36555 44362 36554 44362 36990 44362 36990 44363 36554 44363 36553 44363 36553 44364 36786 44364 36990 44364 36990 44365 36786 44365 36991 44365 36990 44366 36991 44366 37003 44366 37003 44367 36991 44367 36989 44367 37003 44368 36989 44368 36992 44368 36992 44369 36989 44369 36994 44369 36992 44370 36994 44370 36993 44370 36993 44371 36994 44371 36987 44371 36993 44372 36987 44372 36995 44372 36995 44373 36987 44373 36982 44373 36995 44374 36982 44374 36996 44374 36996 40259 36982 40259 36997 40259 36996 44375 36997 44375 36998 44375 36998 44376 36997 44376 37000 44376 36998 44377 37000 44377 36999 44377 36999 44378 37000 44378 37001 44378 36806 44379 37002 44379 36992 44379 36992 44380 37002 44380 37004 44380 36992 44381 37004 44381 37003 44381 37003 44382 37004 44382 37005 44382 37003 40268 37005 40268 36990 40268 36990 44383 37005 44383 37008 44383 36990 44384 37008 44384 36555 44384 36556 40271 37006 40271 37008 40271 37008 44385 37006 44385 37007 44385 37008 44386 37007 44386 36555 44386 36560 44387 36556 44387 37015 44387 37015 44388 36556 44388 37008 44388 37015 44389 37008 44389 37009 44389 37009 44390 37008 44390 37005 44390 37009 44391 37005 44391 37012 44391 37012 44392 37005 44392 37004 44392 37012 44393 37004 44393 37010 44393 37010 44394 37004 44394 37002 44394 37010 44395 37002 44395 36808 44395 36808 44396 37002 44396 36807 44396 36809 44397 37022 44397 37010 44397 37010 44398 37022 44398 37011 44398 37010 44399 37011 44399 37012 44399 37012 40287 37011 40287 37013 40287 37012 44400 37013 44400 37009 44400 37009 44401 37013 44401 37014 44401 37009 44402 37014 44402 37015 44402 37015 44403 37014 44403 37020 44403 37015 44404 37020 44404 37016 44404 37019 44405 36561 44405 37020 44405 37020 44406 36561 44406 37017 44406 37020 44407 37017 44407 37016 44407 37018 44408 37019 44409 36785 44409 36785 44410 37019 44410 37020 44410 36785 44411 37020 44411 37027 44411 37027 44412 37020 44412 37014 44412 37027 44413 37014 44413 37021 44413 37021 44414 37014 44414 37013 44414 37021 44415 37013 44415 37026 44415 37026 40305 37013 40305 37011 40305 37026 44416 37011 44416 37023 44416 37023 44417 37011 44417 37022 44417 37023 44418 37022 44418 37024 44418 37023 44419 37025 44419 37026 44419 37026 44420 37025 44420 37033 44420 37026 44421 37033 44421 37021 44421 37021 44422 37033 44422 37028 44422 37021 44423 37028 44423 37027 44423 37027 44424 37028 44424 37032 44424 37027 44425 37032 44425 36785 44425 36785 44426 37032 44426 37031 44426 36785 44427 37031 44427 36784 44427 37029 44428 36563 44428 37031 44428 37031 44429 36563 44429 37030 44429 37031 44430 37030 44430 36784 44430 36782 44431 37029 44431 36783 44431 36783 44432 37029 44432 37031 44432 36783 44433 37031 44433 37036 44433 37036 44434 37031 44434 37032 44434 37036 44435 37032 44435 37037 44435 37037 44436 37032 44436 37028 44436 37037 44437 37028 44437 37039 44437 37039 44438 37028 44438 37033 44438 37039 44439 37033 44439 36841 44439 36841 44440 37033 44440 37025 44440 36781 40333 36565 40333 37034 40333 37034 44441 36565 44441 36783 44441 37034 44442 36783 44442 37035 44442 37035 44443 36783 44443 37036 44443 37035 44444 37036 44444 37042 44444 37042 44445 37036 44445 37037 44445 37042 44446 37037 44446 36838 44446 36838 40340 37037 40340 37039 40340 36838 44447 37039 44447 37038 44447 37038 44448 37039 44448 36843 44448 37040 44449 36780 44449 37044 44449 37044 44450 36780 44450 37034 44450 37044 44451 37034 44451 37045 44451 37045 44452 37034 44452 37035 44452 37045 40347 37035 40347 37041 40347 37041 44453 37035 44453 37042 44453 37041 44454 37042 44454 37069 44454 37069 44455 37042 44455 36837 44455 36567 44456 36779 44456 37043 44456 37043 44457 36779 44457 37044 44457 37043 44458 37044 44458 37047 44458 37047 40354 37044 40354 37045 40354 37047 44459 37045 44459 37067 44459 37067 44460 37045 44460 37041 44460 36569 44461 36778 44461 37046 44461 37046 40358 36778 40358 37043 40358 37046 44462 37043 44462 37053 44462 37053 44463 37043 44463 37047 44463 37053 44464 37047 44464 37064 44464 37064 44465 37047 44465 37067 44465 36571 44466 37049 44466 37048 44466 37048 44467 37049 44467 37050 44467 37050 44468 37051 44468 37048 44468 37048 44469 37051 44469 37046 44469 37048 44470 37046 44470 37052 44470 37052 40368 37046 40368 37053 40368 37052 44471 37053 44471 37056 44471 37056 40370 37053 40370 37064 40370 36573 44472 36571 44472 37054 44472 37054 44473 36571 44473 37048 44473 37054 44474 37048 44474 37055 44474 37055 44475 37048 44475 37052 44475 37055 40375 37052 40375 37061 40375 37061 40376 37052 40376 37056 40376 37074 44476 37058 44476 37057 44476 37057 44477 37058 44477 37059 44477 37059 44478 36574 44478 37057 44478 37057 44479 36574 44479 37054 44479 37057 44480 37054 44480 37060 44480 37060 44481 37054 44481 37055 44481 37060 40383 37055 40383 37071 40383 37071 44482 37055 44482 37061 44482 37071 44483 37061 44483 37062 44483 37062 44484 37061 44484 37056 44484 37062 44485 37056 44485 37063 44485 37063 44486 37056 44486 37064 44486 37063 40389 37064 40389 37065 40389 37065 44487 37064 44487 37067 44487 37065 44488 37067 44488 37066 44488 37066 44489 37067 44489 37041 44489 37066 44490 37041 44490 37068 44490 37068 44491 37041 44491 37069 44491 37070 44492 37077 44492 37071 44492 37071 44493 37077 44493 37072 44493 37071 44494 37072 44494 37060 44494 37060 44495 37072 44495 37076 44495 37060 44496 37076 44496 37057 44496 37057 44497 37076 44497 37075 44497 37057 44498 37075 44498 37074 44498 37073 44499 36576 44499 37075 44499 37075 44500 36576 44501 36575 44502 37075 44503 36575 44503 37074 44503 36578 44504 37073 44504 37083 44504 37083 44505 37073 44505 37075 44505 37083 44506 37075 44506 37082 44506 37082 44507 37075 44507 37076 44507 37082 44508 37076 44508 37081 44508 37081 44509 37076 44509 37072 44509 37081 44510 37072 44510 36835 44510 36835 44511 37072 44511 37077 44511 36835 40414 37077 40414 37078 40414 37078 44512 37077 44512 36804 44512 37079 44513 37091 44513 36835 44513 36835 44514 37091 44514 37080 44514 36835 44515 37080 44515 37081 44515 37081 44516 37080 44516 37088 44516 37081 44517 37088 44517 37082 44517 37082 44518 37088 44518 37087 44518 37082 44519 37087 44519 37083 44519 37083 44520 37087 44520 37086 44520 37083 44521 37086 44521 36777 44521 36582 44522 36580 44522 37086 44522 37086 44523 36580 44523 37084 44523 37086 44524 37084 44524 36777 44524 36583 40428 36582 40428 37096 40428 37096 44525 36582 44525 37086 44525 37096 44526 37086 44526 37085 44526 37085 44527 37086 44527 37087 44527 37085 44528 37087 44528 37089 44528 37089 44529 37087 44529 37088 44529 37089 40434 37088 40434 37090 40434 37090 44530 37088 44530 37080 44530 37090 40436 37080 40436 37093 40436 37093 40437 37080 40437 37091 40437 37093 40438 37091 40438 37092 40438 37093 44531 37102 44531 37090 44531 37090 44532 37102 44532 37094 44532 37090 44533 37094 44533 37089 44533 37089 44534 37094 44534 37101 44534 37089 44535 37101 44535 37085 44535 37085 44536 37101 44536 37095 44536 37085 44537 37095 44537 37096 44537 37096 44538 37095 44538 37099 44538 37096 44539 37099 44539 37098 44539 37097 44540 36586 44540 37099 44540 37099 44541 36586 44541 36585 44541 37099 40450 36585 40450 37098 40450 36588 44542 37097 44543 36776 44544 36776 44545 37097 44545 37099 44545 36776 44546 37099 44546 37104 44546 37104 40456 37099 40456 37095 40456 37104 40457 37095 40457 37100 40457 37100 40458 37095 40458 37101 40458 37100 40459 37101 40459 36833 40459 36833 44547 37101 44547 37094 44547 36833 40461 37094 40461 36832 40461 36832 44548 37094 44548 37102 44548 36775 40463 36589 40463 37103 40463 37103 40464 36589 40464 36776 40464 37103 44549 36776 44549 37110 44549 37110 44550 36776 44550 37104 44550 37110 44551 37104 44551 37105 44551 37105 44552 37104 44552 37100 44552 37105 40469 37100 40469 36831 40469 36831 44553 37100 44553 36833 44553 36831 44554 36833 44554 37106 44554 37106 44555 36833 44555 37107 44555 36591 44556 36590 44556 37108 44556 37108 44557 36590 44557 37103 44557 37108 44558 37103 44558 37109 44558 37109 44559 37103 44559 37110 44559 37109 44560 37110 44560 37111 44560 37111 44561 37110 44561 37105 44561 37111 44562 37105 44562 37112 44562 37112 44563 37105 44563 36828 44563 37113 44564 37115 44565 37114 44566 37114 44567 37115 44567 37116 44567 37114 44568 37116 44568 37117 44568 37117 44569 37116 44569 37699 44569 37117 44570 37699 44570 37491 44570 37491 44571 37118 44572 37117 44573 37117 44574 37118 44574 37119 44574 37117 44575 37119 44575 37494 44575 37191 44576 37121 44576 37120 44576 37191 44577 37362 44577 37121 44577 37121 44578 37362 44578 37364 44578 37121 44579 37364 44579 37122 44579 37364 44580 37366 44580 37122 44580 37122 40814 37366 40814 37367 40814 37122 44581 37367 44581 37123 44581 37367 44582 37124 44582 37123 44582 37123 44583 37124 44583 37369 44583 37123 44584 37369 44584 37125 44584 37369 44585 37370 44585 37125 44585 37125 44586 37370 44586 37126 44586 37125 44587 37126 44587 37127 44587 37126 44588 37128 44588 37127 44588 37127 40823 37128 40823 37129 40823 37127 44589 37129 44589 37131 44589 37129 40825 37130 40825 37131 40825 37131 44590 37130 44590 37373 44590 37131 44591 37373 44591 37133 44591 37373 44592 37132 44592 37133 44592 37133 44593 37132 44593 37374 44593 37133 44594 37374 44594 37134 44594 37374 44595 37376 44596 37134 44597 37134 44598 37376 44598 37378 44598 37134 44599 37378 44599 37135 44599 37378 44600 37379 44600 37135 44600 37135 44601 37379 44601 37380 44601 37135 44602 37380 44602 37137 44602 37380 44603 37382 44603 37137 44603 37137 44604 37382 44604 37136 44604 37137 44605 37136 44605 37138 44605 37136 44606 37139 44606 37138 44606 37138 44607 37139 44607 37384 44607 37138 44608 37384 44608 37140 44608 37384 44609 37141 44609 37140 44609 37140 44610 37141 44610 37386 44610 37140 44611 37386 44611 37142 44611 37386 44612 37388 44612 37142 44612 37142 44613 37388 44613 37143 44613 37142 44614 37143 44614 37144 44614 37143 44615 37391 44615 37144 44615 37144 40850 37391 40850 37145 40850 37144 44616 37145 44616 37146 44616 37145 40852 37395 40852 37146 40852 37146 44617 37395 44617 37147 44617 37146 44618 37147 44618 37149 44618 37147 44619 37148 44619 37149 44619 37149 44620 37148 44620 37151 44620 37149 44621 37151 44621 37150 44621 37151 40858 37152 40858 37150 40858 37150 44622 37152 44622 37153 44622 37150 44623 37153 44623 37154 44623 37153 44624 37399 44624 37154 44624 37154 44625 37399 44625 37401 44625 37154 44626 37401 44626 37156 44626 37401 44627 37155 44627 37156 44627 37156 44628 37155 44628 37403 44628 37156 44629 37403 44629 37158 44629 37403 44630 37157 44630 37158 44630 37158 44631 37157 44631 37406 44631 37158 44632 37406 44632 37159 44632 37406 44633 37407 44633 37159 44633 37159 40755 37407 40755 37409 40755 37159 44634 37409 44634 37160 44634 37409 44635 37410 44635 37160 44635 37160 44636 37410 44636 37413 44636 37160 44637 37413 44637 37161 44637 37413 44638 37415 44638 37161 44638 37161 44639 37415 44639 37416 44639 37161 44640 37416 44640 37162 44640 37416 44641 37417 44641 37162 44641 37162 40764 37417 40764 37163 40764 37162 44642 37163 44642 37165 44642 37163 40766 37164 40766 37165 40766 37165 44643 37164 44643 37166 44643 37165 44644 37166 44644 37167 44644 37166 44645 37420 44645 37167 44645 37167 44646 37420 44646 37168 44646 37167 44647 37168 44647 37169 44647 37168 44648 37422 44648 37169 44648 37169 44649 37422 44649 37171 44649 37169 44650 37171 44650 37170 44650 37171 44651 37424 44651 37170 44651 37170 44652 37424 44652 37172 44652 37170 44653 37172 44653 37173 44653 37172 44654 37426 44654 37173 44654 37173 44655 37426 44655 37174 44655 37173 44656 37174 44656 37176 44656 37174 44657 37175 44657 37176 44657 37176 44658 37175 44658 37178 44658 37176 44659 37178 44659 37177 44659 37178 44660 37431 44660 37177 44660 37177 44661 37431 44661 37432 44661 37177 44662 37432 44662 37179 44662 37432 44663 37434 44663 37179 44663 37179 44664 37434 44664 37180 44664 37179 44665 37180 44665 37181 44665 37180 44666 37438 44666 37181 44666 37181 40793 37438 40793 37439 40793 37181 44667 37439 44667 37183 44667 37439 40795 37182 40795 37183 40795 37183 44668 37182 44668 37441 44668 37183 44669 37441 44669 37185 44669 37441 44670 37184 44670 37185 44670 37185 44671 37184 44671 37187 44671 37185 44672 37187 44672 37186 44672 37187 40801 37188 40801 37186 40801 37186 44673 37188 44673 37443 44673 37186 44674 37443 44674 37189 44674 37443 44675 37190 44675 37189 44675 37189 44676 37190 44676 37359 44676 37189 44677 37359 44677 37120 44677 37120 44678 37359 44678 37360 44678 37120 44679 37360 44679 37191 44679 37293 44680 37298 44680 37297 44680 37293 44681 37455 44682 37298 44683 37298 44684 37455 44684 37192 44684 37298 44685 37192 44685 37299 44685 37299 44686 37192 44687 37564 44688 37299 44689 37564 44689 37300 44689 37564 44690 37570 44690 37300 44690 37300 44691 37570 44691 37193 44691 37300 44692 37193 44692 37194 44692 37193 44693 37572 44693 37194 44693 37194 44694 37572 44694 37195 44694 37194 44695 37195 44695 37197 44695 37197 44696 37195 44696 37196 44696 37197 44697 37196 44697 37198 44697 37198 44698 37196 44698 37199 44698 37198 44699 37199 44699 37200 44699 37200 44700 37199 44700 37201 44700 37201 44701 37586 44701 37200 44701 37200 44702 37586 44702 37202 44702 37200 44703 37202 44703 37305 44703 37305 44704 37202 44704 37203 44704 37305 44705 37203 44705 37306 44705 37306 44706 37203 44707 37599 44708 37306 44709 37599 44709 37205 44709 37205 44710 37599 44710 37204 44710 37204 44711 37598 44711 37205 44711 37205 44712 37598 44712 37602 44712 37205 44713 37602 44713 37206 44713 37206 44714 37602 44714 37600 44714 37206 44715 37600 44715 37207 44715 37207 44716 37600 44716 37208 44716 37207 44717 37208 44717 37310 44717 37310 44718 37208 44718 37615 44718 37615 44719 37209 44719 37310 44719 37310 44720 37209 44720 37210 44720 37310 44721 37210 44721 37312 44721 37312 44722 37210 44722 37211 44722 37312 44723 37211 44723 37212 44723 37212 44724 37211 44724 37623 44724 37212 44725 37623 44725 37213 44725 37213 44726 37623 44726 37622 44726 37622 44727 37453 44727 37213 44727 37213 44728 37453 44728 37452 44728 37213 44729 37452 44729 37214 44729 37214 44730 37452 44730 37215 44730 37214 44731 37215 44731 37314 44731 37314 44732 37215 44732 37451 44732 37314 44733 37451 44733 37317 44733 37451 44734 37633 44734 37317 44734 37317 44735 37633 44735 37216 44735 37317 44736 37216 44736 37318 44736 37216 44737 37450 44737 37318 44737 37318 44738 37450 44738 37217 44738 37318 44739 37217 44739 37319 44739 37319 44740 37217 44740 37218 44740 37319 44741 37218 44741 37219 44741 37218 44742 37640 44742 37219 44742 37219 44743 37640 44743 37449 44743 37219 44744 37449 44744 37321 44744 37449 44745 37220 44745 37321 44745 37321 44746 37220 44746 37644 44746 37321 44747 37644 44747 37221 44747 37221 44748 37644 44748 37643 44748 37221 44749 37643 44749 37322 44749 37322 44750 37643 44750 37222 44750 37322 44751 37222 44751 37323 44751 37323 44752 37222 44752 37657 44752 37657 44753 37223 44754 37323 44755 37323 44756 37223 44756 37224 44756 37323 44757 37224 44757 37225 44757 37225 44758 37224 44758 37226 44758 37225 44759 37226 44759 37227 44759 37227 44760 37226 44760 37448 44760 37227 44761 37448 44761 37228 44761 37228 44762 37448 44763 37668 44764 37668 44765 37667 44765 37228 44765 37228 44766 37667 44766 37669 44766 37228 44767 37669 44767 37324 44767 37324 44768 37669 44769 37229 44770 37324 44771 37229 44771 37326 44771 37326 44772 37229 44772 37683 44772 37326 44773 37683 44773 37230 44773 37230 44774 37683 44774 37231 44774 37231 44775 37682 44775 37230 44775 37230 44776 37682 44776 37232 44776 37230 44777 37232 44777 37328 44777 37328 44778 37232 44779 37233 44780 37328 44781 37233 44781 37234 44781 37234 44782 37233 44782 37688 44782 37234 44783 37688 44783 37235 44783 37235 44784 37688 44784 37236 44784 37236 44785 37694 44785 37235 44785 37235 44786 37694 44786 37237 44786 37235 44787 37237 44787 37238 44787 37238 44788 37237 44788 37701 44788 37238 44789 37701 44789 37330 44789 37330 41088 37701 41088 37700 41088 37330 44790 37700 44790 37240 44790 37700 44791 37239 44791 37240 44791 37240 44792 37239 44792 37241 44792 37240 44793 37241 44793 37242 44793 37241 44794 37708 44795 37242 44796 37242 44797 37708 44797 37707 44797 37242 44798 37707 44799 37243 44799 37243 44800 37707 44800 37706 44800 37243 44801 37706 44801 37244 44801 37706 44802 37245 44802 37244 44802 37244 44803 37245 44803 37247 44803 37244 44804 37247 44804 37246 44804 37247 44805 37447 44806 37246 44807 37246 44808 37447 44808 37713 44808 37246 44809 37713 44809 37248 44809 37248 44810 37713 44810 37250 44810 37248 44811 37250 44811 37249 44811 37249 44812 37250 44812 37251 44812 37249 44813 37251 44813 37254 44813 37254 44814 37251 44814 37252 44814 37252 44815 37446 44815 37254 44815 37254 44816 37446 44816 37253 44816 37254 44817 37253 44817 37334 44817 37334 44818 37253 44819 37255 44820 37334 44821 37255 44821 37256 44821 37256 44822 37255 44822 37257 44822 37256 44823 37257 44823 37335 44823 37335 44824 37257 44824 37743 44824 37743 44825 37741 44825 37335 44825 37335 44826 37741 44826 37258 44826 37335 44827 37258 44827 37259 44827 37259 44828 37258 44828 37744 44828 37259 44829 37744 44829 37338 44829 37338 44830 37744 44830 37755 44830 37338 44831 37755 44831 37261 44831 37261 44832 37755 44832 37756 44832 37756 44833 37260 44833 37261 44833 37261 44834 37260 44834 37758 44834 37261 44835 37758 44835 37340 44835 37340 44836 37758 44837 37757 44838 37340 44839 37757 44839 37342 44839 37342 44840 37757 44840 37263 44840 37342 44841 37263 44841 37262 44841 37262 44842 37263 44842 37445 44842 37445 44843 37770 44843 37262 44843 37262 44844 37770 44844 37264 44844 37262 44845 37264 44845 37265 44845 37265 44846 37264 44846 37266 44846 37265 44847 37266 44847 37344 44847 37344 44848 37266 44848 37495 44848 37344 44849 37495 44850 37345 44851 37495 44852 37463 44852 37345 44852 37345 44853 37463 44853 37267 44853 37345 44854 37267 44854 37346 44854 37267 44855 37462 44855 37346 44855 37346 44856 37462 44856 37501 44856 37346 44857 37501 44857 37268 44857 37268 44858 37501 44858 37269 44858 37268 44859 37269 44859 37347 44859 37269 44860 37270 44861 37347 44861 37347 44862 37270 44862 37461 44862 37347 44863 37461 44863 37348 44863 37461 44864 37271 44864 37348 44864 37348 44865 37271 44865 37506 44865 37348 44866 37506 44866 37350 44866 37350 44867 37506 44867 37273 44867 37350 44868 37273 44868 37272 44868 37272 44869 37273 44869 37505 44869 37272 44870 37505 44870 37274 44870 37274 44871 37505 44871 37275 44871 37275 44872 37522 44872 37274 44872 37274 44873 37522 44873 37276 44873 37274 44874 37276 44874 37277 44874 37277 44875 37276 44875 37279 44875 37277 44876 37279 44876 37278 44876 37278 44877 37279 44877 37534 44877 37278 44878 37534 44878 37281 44878 37281 44879 37534 44879 37533 44879 37533 44880 37532 44880 37281 44880 37281 44881 37532 44881 37280 44881 37281 44882 37280 44882 37282 44882 37282 44883 37280 44883 37284 44883 37282 44884 37284 44884 37283 44884 37283 44885 37284 44885 37544 44885 37283 44886 37544 44886 37285 44886 37285 44887 37544 44887 37286 44887 37286 44888 37287 44888 37285 44888 37285 44889 37287 44889 37546 44889 37285 44890 37546 44890 37355 44890 37355 44891 37546 44891 37288 44891 37355 44892 37288 44892 37356 44892 37356 44893 37288 44893 37460 44893 37356 44894 37460 44894 37358 44894 37358 44895 37460 44895 37289 44895 37289 44896 37557 44896 37358 44896 37358 44897 37557 44897 37458 44897 37358 44898 37458 44898 37290 44898 37290 44899 37458 44899 37457 44899 37290 44900 37457 44900 37291 44900 37291 40976 37457 40976 37292 40976 37291 44901 37292 44901 37297 44901 37297 44902 37292 44902 37456 44902 37297 44903 37456 44903 37293 44903 37294 44904 37290 44904 37295 44904 37295 44905 37290 44905 37291 44905 37295 44906 37291 44906 37296 44906 37296 44907 37291 44907 37297 44907 37296 44908 37297 44908 37361 44908 37361 44909 37297 44909 37298 44909 37361 44910 37298 44910 37363 44910 37363 44911 37298 44911 37299 44911 37363 44912 37299 44912 37365 44912 37365 44913 37299 44913 37300 44913 37365 44914 37300 44914 37301 44914 37301 44915 37300 44915 37194 44915 37301 44916 37194 44916 37302 44916 37302 44917 37194 44917 37197 44917 37302 44918 37197 44918 37368 44918 37368 44919 37197 44919 37198 44919 37368 44920 37198 44920 37303 44920 37303 44921 37198 44921 37200 44921 37303 44922 37200 44922 37304 44922 37304 44923 37200 44923 37305 44923 37304 44924 37305 44924 37371 44924 37371 44925 37305 44925 37306 44925 37371 44926 37306 44926 37372 44926 37372 44927 37306 44928 37205 44929 37372 44930 37205 44930 37307 44930 37307 44931 37205 44931 37206 44931 37307 44932 37206 44932 37308 44932 37308 44933 37206 44933 37207 44933 37308 44934 37207 44934 37309 44934 37309 44935 37207 44935 37310 44935 37309 44936 37310 44936 37311 44936 37311 44937 37310 44937 37312 44937 37311 44938 37312 44938 37375 44938 37375 44939 37312 44939 37212 44939 37375 44940 37212 44940 37377 44940 37377 44941 37212 44941 37213 44941 37377 44942 37213 44942 37313 44942 37313 44943 37213 44943 37214 44943 37313 44944 37214 44944 37381 44944 37381 44945 37214 44945 37314 44945 37381 44946 37314 44946 37315 44946 37315 44947 37314 44947 37317 44947 37315 44948 37317 44948 37316 44948 37316 44949 37317 44949 37318 44949 37316 44950 37318 44950 37383 44950 37383 44951 37318 44951 37319 44951 37383 44952 37319 44952 37320 44952 37320 44953 37319 44953 37219 44953 37320 44954 37219 44954 37385 44954 37385 44955 37219 44955 37321 44955 37385 44956 37321 44956 37387 44956 37387 44957 37321 44957 37221 44957 37387 44958 37221 44958 37389 44958 37389 44959 37221 44959 37322 44959 37389 44960 37322 44960 37390 44960 37390 44961 37322 44961 37323 44961 37390 44962 37323 44962 37392 44962 37392 44963 37323 44963 37225 44963 37392 44964 37225 44964 37393 44964 37393 44965 37225 44965 37227 44965 37393 44966 37227 44966 37394 44966 37394 44967 37227 44967 37228 44967 37394 44968 37228 44968 37396 44968 37396 44969 37228 44969 37324 44969 37396 44970 37324 44970 37325 44970 37325 44971 37324 44971 37326 44971 37325 44972 37326 44972 37397 44972 37397 44973 37326 44973 37230 44973 37397 44974 37230 44974 37327 44974 37327 44975 37230 44975 37328 44975 37327 44976 37328 44976 37398 44976 37398 44977 37328 44977 37234 44977 37398 44978 37234 44978 37329 44978 37329 44979 37234 44979 37235 44979 37329 44980 37235 44980 37400 44980 37400 44981 37235 44981 37238 44981 37400 44982 37238 44982 37402 44982 37402 44983 37238 44983 37330 44983 37402 44984 37330 44984 37404 44984 37404 44985 37330 44985 37240 44985 37404 44986 37240 44986 37405 44986 37405 44987 37240 44987 37242 44987 37405 44988 37242 44988 37331 44988 37331 44989 37242 44989 37243 44989 37331 44990 37243 44990 37332 44990 37332 44991 37243 44991 37244 44991 37332 44992 37244 44992 37408 44992 37408 44993 37244 44994 37246 44995 37408 44996 37246 44996 37333 44996 37333 44997 37246 44997 37248 44997 37333 44998 37248 44999 37411 44998 37411 45000 37248 45000 37249 45000 37411 45001 37249 45002 37412 45001 37412 45003 37249 45003 37254 45003 37412 45004 37254 45004 37414 45004 37414 45005 37254 45005 37334 45005 37414 45006 37334 45006 37418 45006 37418 45007 37334 45007 37256 45007 37418 45008 37256 45008 37419 45008 37419 45009 37256 45009 37335 45009 37419 45010 37335 45010 37336 45010 37336 45011 37335 45011 37259 45011 37336 45012 37259 45012 37337 45012 37337 45013 37259 45013 37338 45013 37337 45014 37338 45014 37339 45014 37339 45015 37338 45015 37261 45015 37339 45016 37261 45016 37421 45016 37421 45017 37261 45017 37340 45017 37421 45018 37340 45018 37423 45018 37423 45019 37340 45019 37342 45019 37423 45020 37342 45020 37341 45020 37341 45021 37342 45021 37262 45021 37341 45022 37262 45022 37425 45022 37425 45023 37262 45023 37265 45023 37425 45024 37265 45024 37343 45024 37343 45025 37265 45025 37344 45025 37343 45026 37344 45026 37427 45026 37427 45027 37344 45027 37345 45027 37427 45028 37345 45028 37428 45028 37428 45029 37345 45029 37346 45029 37428 45030 37346 45030 37429 45030 37429 45031 37346 45031 37268 45031 37429 45032 37268 45033 37430 45032 37430 45034 37268 45034 37347 45034 37430 45035 37347 45035 37349 45035 37349 45036 37347 45036 37348 45036 37349 45037 37348 45037 37433 45037 37433 45038 37348 45038 37350 45038 37433 45039 37350 45039 37435 45039 37435 45040 37350 45040 37272 45040 37435 45041 37272 45041 37436 45041 37436 45042 37272 45042 37274 45042 37436 45043 37274 45043 37437 45043 37437 45044 37274 45044 37277 45044 37437 45045 37277 45045 37351 45045 37351 45046 37277 45046 37278 45046 37351 45047 37278 45047 37440 45047 37440 45048 37278 45048 37281 45048 37440 45049 37281 45049 37352 45049 37352 45050 37281 45050 37282 45050 37352 45051 37282 45051 37442 45051 37442 45052 37282 45052 37283 45052 37442 45053 37283 45053 37353 45053 37353 45054 37283 45054 37285 45054 37353 45055 37285 45055 37354 45055 37354 45056 37285 45056 37355 45056 37354 45057 37355 45057 37444 45057 37444 45058 37355 45058 37356 45058 37444 45059 37356 45059 37357 45059 37357 45060 37356 45060 37358 45060 37357 45061 37358 45061 37294 45061 37294 45062 37358 45062 37290 45062 37359 45063 37295 45063 37360 45063 37360 45064 37295 45064 37296 45064 37360 45065 37296 45065 37191 45065 37191 45066 37296 45066 37361 45066 37191 45067 37361 45067 37362 45067 37362 45068 37361 45068 37363 45068 37362 45069 37363 45069 37364 45069 37364 45070 37363 45070 37365 45070 37364 45071 37365 45071 37366 45071 37366 45072 37365 45072 37301 45072 37366 45073 37301 45073 37367 45073 37367 45074 37301 45074 37302 45074 37367 45075 37302 45075 37124 45075 37124 45076 37302 45076 37368 45076 37124 45077 37368 45077 37369 45077 37369 45078 37368 45079 37303 45080 37369 45081 37303 45081 37370 45081 37370 45082 37303 45082 37304 45082 37370 45083 37304 45083 37126 45083 37126 45084 37304 45084 37371 45084 37126 45085 37371 45086 37128 45087 37128 45088 37371 45088 37372 45088 37128 45089 37372 45089 37129 45089 37129 45090 37372 45090 37307 45090 37129 45091 37307 45091 37130 45091 37130 45092 37307 45092 37308 45092 37130 45093 37308 45093 37373 45093 37373 45094 37308 45094 37309 45094 37373 45095 37309 45095 37132 45095 37132 45096 37309 45096 37311 45096 37132 45097 37311 45097 37374 45097 37374 45098 37311 45098 37375 45098 37374 45099 37375 45099 37376 45099 37376 45100 37375 45100 37377 45100 37376 45101 37377 45101 37378 45101 37378 45102 37377 45103 37313 45104 37378 45105 37313 45105 37379 45105 37379 45106 37313 45106 37381 45106 37379 45107 37381 45107 37380 45107 37380 45108 37381 45108 37315 45108 37380 45109 37315 45109 37382 45109 37382 45110 37315 45110 37316 45110 37382 45111 37316 45111 37136 45111 37136 45112 37316 45112 37383 45112 37136 45113 37383 45113 37139 45113 37139 45114 37383 45114 37320 45114 37139 45115 37320 45115 37384 45115 37384 45116 37320 45116 37385 45116 37384 45117 37385 45117 37141 45117 37141 45118 37385 45118 37387 45118 37141 45119 37387 45119 37386 45119 37386 45120 37387 45121 37389 45122 37386 45123 37389 45123 37388 45123 37388 45124 37389 45125 37390 45126 37388 45127 37390 45128 37143 45129 37143 45130 37390 45130 37392 45130 37143 45131 37392 45131 37391 45131 37391 45132 37392 45132 37393 45132 37391 45133 37393 45133 37145 45133 37145 45134 37393 45134 37394 45134 37145 45135 37394 45135 37395 45135 37395 45136 37394 45136 37396 45136 37395 45137 37396 45137 37147 45137 37147 45138 37396 45138 37325 45138 37147 45139 37325 45139 37148 45139 37148 45140 37325 45140 37397 45140 37148 45141 37397 45141 37151 45141 37151 45142 37397 45142 37327 45142 37151 45143 37327 45143 37152 45143 37152 45144 37327 45144 37398 45144 37152 45145 37398 45145 37153 45145 37153 45146 37398 45146 37329 45146 37153 45147 37329 45147 37399 45147 37399 45148 37329 45148 37400 45148 37399 45149 37400 45149 37401 45149 37401 45150 37400 45150 37402 45150 37401 45151 37402 45151 37155 45151 37155 45152 37402 45152 37404 45152 37155 45153 37404 45153 37403 45153 37403 45154 37404 45154 37405 45154 37403 45155 37405 45155 37157 45155 37157 45156 37405 45156 37331 45156 37157 45157 37331 45157 37406 45157 37406 45158 37331 45158 37332 45158 37406 45159 37332 45159 37407 45159 37407 45160 37332 45160 37408 45160 37407 45161 37408 45161 37409 45161 37409 45162 37408 45162 37333 45162 37409 45163 37333 45164 37410 45165 37410 45166 37333 45166 37411 45166 37410 45167 37411 45167 37413 45167 37413 45168 37411 45168 37412 45168 37413 45169 37412 45169 37415 45169 37415 45170 37412 45170 37414 45170 37415 45171 37414 45171 37416 45171 37416 45172 37414 45172 37418 45172 37416 45173 37418 45173 37417 45173 37417 45174 37418 45174 37419 45174 37417 45175 37419 45175 37163 45175 37163 45176 37419 45176 37336 45176 37163 45177 37336 45177 37164 45177 37164 45178 37336 45178 37337 45178 37164 45179 37337 45179 37166 45179 37166 45180 37337 45180 37339 45180 37166 45181 37339 45181 37420 45181 37420 45182 37339 45182 37421 45182 37420 45183 37421 45183 37168 45183 37168 45184 37421 45184 37423 45184 37168 45185 37423 45185 37422 45185 37422 45186 37423 45186 37341 45186 37422 45187 37341 45187 37171 45187 37171 45188 37341 45188 37425 45188 37171 45189 37425 45189 37424 45189 37424 45190 37425 45190 37343 45190 37424 45191 37343 45191 37172 45191 37172 45192 37343 45192 37427 45192 37172 45193 37427 45193 37426 45193 37426 45194 37427 45194 37428 45194 37426 45195 37428 45195 37174 45195 37174 45196 37428 45196 37429 45196 37174 45197 37429 45197 37175 45197 37175 45198 37429 45198 37430 45198 37175 45199 37430 45199 37178 45199 37178 45200 37430 45200 37349 45200 37178 45201 37349 45201 37431 45201 37431 45202 37349 45202 37433 45202 37431 45203 37433 45203 37432 45203 37432 45204 37433 45204 37435 45204 37432 45205 37435 45205 37434 45205 37434 45206 37435 45206 37436 45206 37434 45207 37436 45207 37180 45207 37180 45208 37436 45208 37437 45208 37180 45209 37437 45209 37438 45209 37438 45210 37437 45210 37351 45210 37438 45211 37351 45211 37439 45211 37439 45212 37351 45212 37440 45212 37439 45213 37440 45213 37182 45213 37182 45214 37440 45214 37352 45214 37182 45215 37352 45215 37441 45215 37441 45216 37352 45216 37442 45216 37441 45217 37442 45217 37184 45217 37184 45218 37442 45218 37353 45218 37184 45219 37353 45219 37187 45219 37187 45220 37353 45221 37354 45222 37187 45223 37354 45223 37188 45223 37188 45224 37354 45224 37444 45224 37188 45225 37444 45225 37443 45225 37443 45226 37444 45226 37357 45226 37443 45227 37357 45227 37190 45227 37190 45228 37357 45228 37294 45228 37190 45229 37294 45230 37359 45231 37359 45232 37294 45232 37295 45232 37770 45233 37445 45233 37763 45233 37263 45234 37757 45234 37759 45234 37755 45235 37744 45235 37745 45235 37446 45236 37252 45236 37725 45236 37447 45237 37247 45238 37715 45239 37708 45240 37241 45241 37709 45242 37239 45243 37700 45243 37704 45243 37701 45244 37237 45244 37702 45244 37694 45245 37236 45245 37695 45245 37688 45246 37233 45246 37689 45246 37683 45247 37229 45247 37680 45247 37448 45248 37226 45248 37658 45248 37220 45249 37449 45249 37641 45249 37450 45250 37216 45250 37634 45250 37633 45251 37451 45251 37628 45251 37215 45252 37452 45252 37629 45252 37453 45253 37622 45253 37454 45253 37623 45254 37211 45254 37616 45254 37208 45255 37600 45255 37601 45255 37586 45256 37201 45257 37587 45258 37572 45259 37193 45259 37569 45259 37455 45260 37293 45261 37566 45262 37456 45263 37292 45263 37560 45263 37457 45264 37458 45264 37459 45264 37557 45265 37289 45265 37552 45265 37460 45266 37288 45266 37545 45266 37544 45267 37284 45267 37535 45267 37534 45268 37279 45268 37529 45268 37271 45269 37461 45270 37507 45271 37462 45272 37267 45272 37502 45272 37463 45273 37495 45274 37496 45275 37266 45276 37264 45276 37769 45276 37778 45277 37782 45277 37526 45277 37653 45278 37464 45278 37465 45278 37663 45279 37466 45279 37662 45279 37648 45280 37653 45281 37654 45282 37467 45283 37627 45283 37469 45283 37469 45284 37627 45284 37624 45284 37469 41497 37624 41497 37470 41497 37467 45285 37469 45286 37468 45287 37468 45288 37469 45288 37470 45288 37468 41500 37470 41500 37471 41500 37472 45289 37473 45289 37620 45289 37620 45290 37473 45290 37474 45290 37589 45291 37592 45291 37593 45291 37575 45292 37475 45292 37585 45292 37477 45293 37559 45293 37476 45293 37476 45294 37559 45295 37555 45296 37476 45297 37555 45297 37556 45297 37477 45298 37476 45298 37478 45298 37478 45299 37476 45299 37556 45299 37478 45300 37556 45300 37479 45300 37550 45301 37480 45301 37481 45301 37481 45302 37480 45302 37482 45302 37781 45303 37780 45303 37483 45303 37510 45304 37778 45304 37517 45304 37484 45305 37485 45305 37486 45305 37486 45306 37485 45307 37774 45308 37486 41471 37774 41471 37765 41471 37484 45309 37486 45309 37487 45309 37487 45310 37486 45310 37765 45310 37487 41476 37765 41476 37766 41476 37488 45311 37489 45311 37767 45311 37767 45312 37489 45312 37768 45312 37733 45313 37734 45313 37735 45313 37490 45314 37728 45314 37717 45314 37491 45315 37699 45315 37492 45315 37492 45316 37699 45316 37698 45316 37492 45317 37698 45317 37691 45317 37491 45318 37492 45319 37118 45320 37118 45321 37492 45321 37691 45321 37118 45322 37691 45322 37119 45322 37686 45323 37493 45323 37693 45323 37693 45324 37493 45324 37494 45324 37495 45325 37266 45325 37496 45325 37496 45326 37266 45326 37769 45326 37496 45327 37769 45327 37497 45327 37497 45328 37769 45328 37771 45328 37497 45329 37771 45329 37513 45329 37513 45330 37771 45330 37773 45330 37267 45331 37463 45331 37502 45331 37502 45332 37463 45332 37496 45332 37502 45333 37496 45333 37498 45333 37498 45334 37496 45334 37497 45334 37498 45335 37497 45335 37499 45335 37499 45336 37497 45336 37513 45336 37270 45337 37269 45337 37500 45337 37500 45338 37269 45338 37501 45338 37501 45339 37462 45339 37500 45339 37500 45340 37462 45340 37502 45340 37500 45341 37502 45341 37503 45341 37503 45342 37502 45342 37498 45342 37503 45343 37498 45343 37504 45343 37504 45344 37498 45344 37499 45344 37461 45345 37270 45345 37507 45345 37507 45346 37270 45346 37500 45346 37507 45347 37500 45347 37508 45347 37508 45348 37500 45348 37503 45348 37508 45349 37503 45349 37509 45349 37509 45350 37503 45350 37504 45350 37505 45351 37273 45351 37520 45351 37520 45352 37273 45352 37506 45352 37506 45353 37271 45353 37520 45353 37520 45354 37271 45354 37507 45354 37520 45355 37507 45355 37519 45355 37519 45356 37507 45356 37508 45356 37519 45357 37508 45357 37517 45357 37517 45358 37508 45358 37509 45358 37517 45359 37509 45359 37510 45359 37510 45360 37509 45360 37504 45360 37510 45361 37504 45361 37511 45361 37511 45362 37504 45362 37499 45362 37511 45363 37499 45363 37512 45363 37512 45364 37499 45364 37513 45364 37512 45365 37513 45365 37514 45365 37514 45366 37513 45366 37773 45366 37514 45367 37773 45367 37515 45367 37515 45368 37773 45368 37516 45368 37778 45369 37526 45369 37517 45369 37517 45370 37526 45370 37518 45370 37517 45371 37518 45371 37519 45371 37519 45372 37518 45372 37524 45372 37519 45373 37524 45373 37520 45373 37520 45374 37524 45374 37521 45374 37520 45375 37521 45375 37505 45375 37276 45376 37522 45376 37521 45376 37521 45377 37522 45377 37275 45377 37521 45378 37275 45378 37505 45378 37279 45379 37276 45379 37529 45379 37529 45380 37276 45380 37521 45380 37529 45381 37521 45381 37523 45381 37523 45382 37521 45382 37524 45382 37523 45383 37524 45383 37525 45383 37525 45384 37524 45384 37518 45384 37525 45385 37518 45385 37483 45385 37483 45386 37518 45386 37526 45386 37483 45387 37526 45387 37781 45387 37781 45388 37526 45389 37782 45390 37780 45391 37527 45391 37483 45391 37483 45392 37527 45392 37528 45392 37483 45393 37528 45393 37525 45393 37525 45394 37528 45394 37538 45394 37525 45395 37538 45395 37523 45395 37523 45396 37538 45396 37530 45396 37523 45397 37530 45397 37529 45397 37529 45398 37530 45398 37531 45398 37529 45399 37531 45399 37534 45399 37280 45400 37532 45400 37531 45400 37531 45401 37532 45401 37533 45401 37531 45402 37533 45402 37534 45402 37284 45403 37280 45403 37535 45403 37535 45404 37280 45404 37531 45404 37535 45405 37531 45405 37536 45405 37536 45406 37531 45406 37530 45406 37536 45407 37530 45407 37537 45407 37537 45408 37530 45408 37538 45408 37537 45409 37538 45409 37539 45409 37539 45410 37538 45410 37528 45410 37539 45411 37528 45411 37540 45411 37540 45412 37528 45412 37527 45412 37540 45413 37527 45413 37541 45413 37540 45414 37551 45414 37539 45414 37539 45415 37551 45415 37542 45415 37539 45416 37542 45416 37537 45416 37537 45417 37542 45417 37543 45417 37537 45418 37543 45418 37536 45418 37536 45419 37543 45419 37548 45419 37536 45420 37548 45420 37535 45420 37535 45421 37548 45421 37547 45421 37535 45422 37547 45422 37544 45422 37546 45423 37287 45423 37547 45423 37547 45424 37287 45424 37286 45424 37547 45425 37286 45425 37544 45425 37288 45426 37546 45427 37545 45428 37545 45429 37546 45429 37547 45429 37545 45430 37547 45430 37554 45430 37554 45431 37547 45431 37548 45431 37554 45432 37548 45432 37549 45432 37549 45433 37548 45433 37543 45433 37549 45434 37543 45434 37481 45434 37481 45435 37543 45435 37542 45435 37481 45436 37542 45436 37550 45436 37550 45437 37542 45437 37551 45437 37289 45438 37460 45438 37552 45438 37552 45439 37460 45439 37545 45439 37552 45440 37545 45440 37553 45440 37553 45441 37545 45441 37554 45441 37553 45442 37554 45442 37555 45442 37555 45443 37554 45443 37549 45443 37555 45444 37549 45444 37556 45444 37556 45445 37549 45445 37481 45445 37556 45446 37481 45446 37479 45446 37479 45447 37481 45447 37482 45447 37458 45448 37557 45448 37459 45448 37459 45449 37557 45449 37552 45449 37459 45450 37552 45450 37558 45450 37558 45451 37552 45451 37553 45451 37558 45452 37553 45452 37562 45452 37562 45453 37553 45453 37555 45453 37562 45454 37555 45454 37582 45454 37582 45455 37555 45455 37559 45455 37292 45456 37457 45456 37560 45456 37560 45457 37457 45457 37459 45457 37560 45458 37459 45458 37561 45458 37561 45459 37459 45459 37558 45459 37561 45460 37558 45460 37579 45460 37579 45461 37558 45461 37562 45461 37293 45462 37456 45462 37566 45462 37566 45463 37456 45463 37560 45463 37566 45464 37560 45464 37563 45464 37563 45465 37560 45465 37561 45465 37563 45466 37561 45466 37568 45466 37568 45467 37561 45467 37579 45467 37570 45468 37564 45468 37565 45468 37565 45469 37564 45469 37192 45469 37192 45470 37455 45470 37565 45470 37565 45471 37455 45471 37566 45471 37565 45472 37566 45472 37571 45472 37571 45473 37566 45473 37563 45473 37571 45474 37563 45474 37567 45474 37567 45475 37563 45475 37568 45475 37193 45476 37570 45476 37569 45476 37569 45477 37570 45477 37565 45477 37569 45478 37565 45478 37574 45478 37574 45479 37565 45479 37571 45479 37574 45480 37571 45480 37576 45480 37576 45481 37571 45481 37567 45481 37199 45482 37196 45482 37573 45482 37573 45483 37196 45483 37195 45483 37195 45484 37572 45484 37573 45484 37573 45485 37572 45485 37569 45485 37573 45486 37569 45486 37584 45486 37584 45487 37569 45487 37574 45487 37584 45488 37574 45488 37585 45488 37585 45489 37574 45489 37576 45489 37585 45490 37576 45490 37575 45490 37575 45491 37576 45491 37567 45491 37575 45492 37567 45492 37577 45492 37577 45493 37567 45493 37568 45493 37577 45494 37568 45494 37578 45494 37578 45495 37568 45495 37579 45495 37578 45496 37579 45496 37580 45496 37580 45497 37579 45497 37562 45497 37580 45498 37562 45498 37581 45498 37581 45499 37562 45500 37582 45501 37201 45502 37199 45502 37587 45502 37587 45503 37199 45503 37573 45503 37587 45504 37573 45504 37583 45504 37583 45505 37573 45505 37584 45505 37583 45506 37584 45506 37588 45506 37588 45507 37584 45507 37585 45507 37588 45508 37585 45508 37590 45508 37590 45509 37585 45509 37475 45509 37590 45510 37475 45511 37591 45512 37599 45513 37203 45513 37597 45513 37597 45514 37203 45514 37202 45514 37202 45515 37586 45515 37597 45515 37597 45516 37586 45516 37587 45516 37597 45517 37587 45517 37595 45517 37595 45518 37587 45518 37583 45518 37595 45519 37583 45519 37594 45519 37594 45520 37583 45520 37588 45520 37594 45521 37588 45521 37593 45521 37593 45522 37588 45522 37590 45522 37593 45523 37590 45523 37589 45523 37589 45524 37590 45524 37591 45524 37592 45525 37610 45525 37593 45525 37593 45526 37610 45526 37609 45526 37593 45527 37609 45527 37594 45527 37594 45528 37609 45528 37606 45528 37594 45529 37606 45529 37595 45529 37595 45530 37606 45530 37604 45530 37595 45531 37604 45531 37597 45531 37597 45532 37604 45532 37596 45532 37597 45533 37596 45533 37599 45533 37602 45534 37598 45534 37596 45534 37596 45535 37598 45535 37204 45535 37596 45536 37204 45536 37599 45536 37600 45537 37602 45538 37601 45539 37601 45540 37602 45540 37596 45540 37601 41994 37596 41994 37603 41994 37603 45541 37596 45541 37604 45541 37603 45542 37604 45542 37605 45542 37605 45543 37604 45543 37606 45543 37605 45544 37606 45544 37607 45544 37607 45545 37606 45545 37609 45545 37607 45546 37609 45546 37608 45546 37608 45547 37609 45547 37610 45547 37608 45548 37610 45548 37611 45548 37608 45549 37621 45549 37607 45549 37607 45550 37621 45550 37612 45550 37607 45551 37612 45551 37605 45551 37605 45552 37612 45552 37619 45552 37605 45553 37619 45553 37603 45553 37603 45554 37619 45554 37613 45554 37603 45555 37613 45555 37601 45555 37601 45556 37613 45556 37614 45556 37601 45557 37614 45557 37208 45557 37210 45558 37209 45558 37614 45558 37614 45559 37209 45559 37615 45559 37614 45560 37615 45560 37208 45560 37211 45561 37210 45561 37616 45561 37616 45562 37210 45562 37614 45562 37616 45563 37614 45563 37617 45563 37617 45564 37614 45564 37613 45564 37617 45565 37613 45565 37618 45565 37618 45566 37613 45566 37619 45566 37618 45567 37619 45567 37620 45567 37620 45568 37619 45568 37612 45568 37620 45569 37612 45569 37472 45569 37472 45570 37612 45570 37621 45570 37622 45571 37623 45571 37454 45571 37454 45572 37623 45572 37616 45572 37454 45573 37616 45573 37625 45573 37625 45574 37616 45574 37617 45574 37625 45575 37617 45575 37624 45575 37624 45576 37617 45576 37618 45576 37624 45577 37618 45577 37470 45577 37470 45578 37618 45578 37620 45578 37470 45579 37620 45579 37471 45579 37471 45580 37620 45580 37474 45580 37452 45581 37453 45581 37629 45581 37629 45582 37453 45582 37454 45582 37629 45583 37454 45583 37631 45583 37631 45584 37454 45584 37625 45584 37631 45585 37625 45585 37632 45585 37632 45586 37625 45586 37624 45586 37632 45587 37624 45587 37626 45587 37626 45588 37624 45588 37627 45588 37451 45589 37215 45589 37628 45589 37628 45590 37215 45590 37629 45590 37628 45591 37629 45591 37636 45591 37636 45592 37629 45592 37631 45592 37636 45593 37631 45593 37630 45593 37630 45594 37631 45594 37632 45594 37216 45595 37633 45595 37634 45595 37634 45596 37633 45596 37628 45596 37634 45597 37628 45597 37635 45597 37635 45598 37628 45598 37636 45598 37635 45599 37636 45599 37637 45599 37637 45600 37636 45600 37630 45600 37640 45601 37218 45601 37642 45601 37642 45602 37218 45602 37217 45602 37217 45603 37450 45603 37642 45603 37642 45604 37450 45604 37634 45604 37642 45605 37634 45605 37638 45605 37638 45606 37634 45606 37635 45606 37638 45607 37635 45607 37639 45607 37639 45608 37635 45608 37637 45608 37449 45609 37640 45609 37641 45609 37641 45610 37640 45610 37642 45610 37641 45611 37642 45611 37646 45611 37646 45612 37642 45612 37638 45612 37646 45613 37638 45613 37647 45613 37647 45614 37638 45614 37639 45614 37222 45615 37643 45615 37645 45615 37645 45616 37643 45616 37644 45616 37644 45617 37220 45617 37645 45617 37645 45618 37220 45618 37641 45618 37645 45619 37641 45619 37655 45619 37655 45620 37641 45620 37646 45620 37655 45621 37646 45621 37654 45621 37654 45622 37646 45622 37647 45622 37654 45623 37647 45623 37648 45623 37648 45624 37647 45624 37639 45624 37648 45625 37639 45625 37649 45625 37649 45626 37639 45626 37637 45626 37649 45627 37637 45627 37650 45627 37650 45628 37637 45628 37630 45628 37650 45629 37630 45629 37651 45629 37651 45630 37630 45630 37632 45630 37651 45631 37632 45631 37652 45631 37652 45632 37632 45632 37626 45632 37653 45633 37465 45633 37654 45633 37654 45634 37465 45634 37656 45634 37654 45635 37656 45635 37655 45635 37655 45636 37656 45636 37661 45636 37655 45637 37661 45637 37645 45637 37645 45638 37661 45638 37660 45638 37645 45639 37660 45639 37222 45639 37224 45640 37223 45640 37660 45640 37660 45641 37223 45642 37657 45643 37660 45644 37657 45644 37222 45644 37226 45645 37224 45645 37658 45645 37658 45646 37224 45646 37660 45646 37658 45647 37660 45647 37659 45647 37659 45648 37660 45648 37661 45648 37659 45649 37661 45649 37665 45649 37665 45650 37661 45650 37656 45650 37665 45651 37656 45651 37662 45651 37662 45652 37656 45652 37465 45652 37662 45653 37465 45653 37663 45653 37663 45654 37465 45655 37464 45656 37466 45657 37664 45657 37662 45657 37662 45658 37664 45658 37674 45658 37662 45659 37674 45659 37665 45659 37665 45660 37674 45660 37672 45660 37665 45661 37672 45661 37659 45661 37659 45662 37672 45662 37666 45662 37659 45663 37666 45663 37658 45663 37658 45664 37666 45664 37670 45664 37658 45665 37670 45665 37448 45665 37669 45666 37667 45666 37670 45666 37670 45667 37667 45667 37668 45667 37670 45668 37668 45668 37448 45668 37229 45669 37669 45669 37680 45669 37680 45670 37669 45670 37670 45670 37680 45671 37670 45671 37671 45671 37671 45672 37670 45672 37666 45672 37671 45673 37666 45673 37677 45673 37677 45674 37666 45674 37672 45674 37677 45675 37672 45675 37673 45675 37673 45676 37672 45676 37674 45676 37673 45677 37674 45677 37675 45677 37675 45678 37674 45678 37664 45678 37675 45679 37664 45679 37676 45679 37675 45680 37687 45680 37673 45680 37673 45681 37687 45681 37685 45681 37673 45682 37685 45682 37677 45682 37677 45683 37685 45683 37678 45683 37677 45684 37678 45684 37671 45684 37671 45685 37678 45685 37679 45685 37671 45686 37679 45686 37680 45686 37680 45687 37679 45687 37681 45687 37680 45688 37681 45688 37683 45688 37232 45689 37682 45689 37681 45689 37681 45690 37682 45690 37231 45690 37681 45691 37231 45691 37683 45691 37233 45692 37232 45693 37689 45694 37689 45695 37232 45695 37681 45695 37689 45696 37681 45696 37684 45696 37684 45697 37681 45697 37679 45697 37684 45698 37679 45698 37692 45698 37692 45699 37679 45699 37678 45699 37692 45700 37678 45700 37693 45700 37693 45701 37678 45701 37685 45701 37693 45702 37685 45702 37686 45702 37686 45703 37685 45703 37687 45703 37236 45704 37688 45704 37695 45704 37695 45705 37688 45705 37689 45705 37695 45706 37689 45706 37690 45706 37690 45707 37689 45707 37684 45707 37690 45708 37684 45708 37698 45708 37698 45709 37684 45709 37692 45709 37698 45710 37692 45710 37691 45710 37691 45711 37692 45711 37693 45711 37691 45712 37693 45712 37119 45712 37119 45713 37693 45713 37494 45713 37237 45714 37694 45714 37702 45714 37702 45715 37694 45715 37695 45715 37702 45716 37695 45716 37696 45716 37696 45717 37695 45717 37690 45717 37696 45718 37690 45718 37697 45718 37697 45719 37690 45719 37698 45719 37697 45720 37698 45720 37116 45720 37116 45721 37698 45721 37699 45721 37700 45722 37701 45722 37704 45723 37704 45724 37701 45724 37702 45724 37704 45725 37702 45725 37703 45725 37703 45726 37702 45726 37696 45726 37703 45727 37696 45727 37722 45727 37722 45728 37696 45728 37697 45728 37241 45729 37239 45729 37709 45729 37709 45730 37239 45730 37704 45730 37709 45731 37704 45731 37705 45731 37705 45732 37704 45732 37703 45732 37705 45733 37703 45733 37721 45733 37721 45734 37703 45734 37722 45734 37245 45735 37706 45735 37711 45735 37711 45736 37706 45736 37707 45736 37707 45737 37708 45737 37711 45737 37711 45738 37708 45738 37709 45738 37711 45739 37709 45739 37710 45739 37710 45740 37709 45740 37705 45740 37710 45741 37705 45741 37718 45741 37718 45742 37705 45742 37721 45742 37247 45743 37245 45743 37715 45743 37715 45744 37245 45744 37711 45744 37715 45745 37711 45745 37716 45745 37716 45746 37711 45746 37710 45746 37716 45747 37710 45747 37712 45747 37712 45748 37710 45748 37718 45748 37251 45749 37250 45749 37714 45749 37714 45750 37250 45750 37713 45750 37713 45751 37447 45751 37714 45751 37714 45752 37447 45752 37715 45752 37714 45753 37715 45753 37727 45753 37727 45754 37715 45754 37716 45754 37727 45755 37716 45755 37717 45755 37717 45756 37716 45756 37712 45756 37717 45757 37712 45757 37490 45757 37490 45758 37712 45758 37718 45758 37490 45759 37718 45759 37719 45759 37719 45760 37718 45760 37721 45760 37719 45761 37721 45761 37720 45761 37720 45762 37721 45762 37722 45762 37720 45763 37722 45763 37723 45763 37723 45764 37722 45764 37697 45764 37723 45765 37697 45765 37724 45765 37724 45766 37697 45766 37116 45766 37252 45767 37251 45767 37725 45767 37725 45768 37251 45768 37714 45768 37725 45769 37714 45769 37726 45769 37726 45770 37714 45770 37727 45770 37726 45771 37727 45771 37731 45771 37731 45772 37727 45772 37717 45772 37731 45773 37717 45773 37732 45773 37732 45774 37717 45774 37728 45774 37732 45775 37728 45775 37729 45775 37257 45776 37255 45776 37730 45776 37730 45777 37255 45777 37253 45777 37253 45778 37446 45778 37730 45778 37730 45779 37446 45779 37725 45779 37730 45780 37725 45780 37739 45780 37739 45781 37725 45781 37726 45781 37739 45782 37726 45782 37738 45782 37738 45783 37726 45783 37731 45783 37738 45784 37731 45784 37735 45784 37735 45785 37731 45785 37732 45785 37735 45786 37732 45786 37733 45786 37733 45787 37732 45787 37729 45787 37734 45788 37736 45788 37735 45788 37735 45789 37736 45789 37737 45789 37735 45790 37737 45790 37738 45790 37738 45791 37737 45791 37747 45791 37738 45792 37747 45792 37739 45792 37739 45793 37747 45793 37740 45793 37739 45794 37740 45794 37730 45794 37730 45795 37740 45795 37742 45795 37730 45796 37742 45796 37257 45796 37258 45797 37741 45797 37742 45797 37742 45798 37741 45798 37743 45798 37742 45799 37743 45799 37257 45799 37744 45800 37258 45800 37745 45800 37745 45801 37258 45801 37742 45801 37745 41733 37742 41733 37753 41733 37753 45802 37742 45802 37740 45802 37753 45803 37740 45803 37746 45803 37746 45804 37740 45804 37747 45804 37746 45805 37747 45805 37752 45805 37752 45806 37747 45806 37737 45806 37752 45807 37737 45807 37748 45807 37748 45808 37737 45808 37736 45808 37748 45809 37736 45810 37749 45811 37748 45812 37750 45812 37752 45812 37752 45813 37750 45813 37751 45813 37752 45814 37751 45814 37746 45814 37746 45815 37751 45815 37762 45815 37746 45816 37762 45816 37753 45816 37753 45817 37762 45817 37761 45817 37753 45818 37761 45818 37745 45818 37745 45819 37761 45819 37754 45819 37745 45820 37754 45820 37755 45820 37758 45821 37260 45821 37754 45821 37754 45822 37260 45822 37756 45822 37754 45823 37756 45823 37755 45823 37757 45824 37758 45825 37759 45826 37759 45827 37758 45827 37754 45827 37759 45828 37754 45828 37760 45828 37760 45829 37754 45829 37761 45829 37760 45830 37761 45830 37764 45830 37764 45831 37761 45831 37762 45831 37764 45832 37762 45832 37767 45832 37767 45833 37762 45833 37751 45833 37767 45834 37751 45834 37488 45834 37488 45835 37751 45835 37750 45835 37445 45836 37263 45836 37763 45836 37763 45837 37263 45837 37759 45837 37763 45838 37759 45838 37772 45838 37772 45839 37759 45839 37760 45839 37772 45840 37760 45840 37774 45840 37774 45841 37760 45841 37764 45841 37774 45842 37764 45842 37765 45842 37765 45843 37764 45843 37767 45843 37765 45844 37767 45844 37766 45844 37766 45845 37767 45845 37768 45845 37264 45846 37770 45846 37769 45846 37769 45847 37770 45847 37763 45847 37769 45848 37763 45848 37771 45848 37771 45849 37763 45849 37772 45849 37771 45850 37772 45850 37773 45850 37773 45851 37772 45851 37774 45851 37773 45852 37774 45852 37516 45852 37516 45853 37774 45853 37485 45853 37778 45854 37775 45854 37776 45854 37776 45855 37777 45855 37778 45855 37778 45856 37777 45856 37779 45856 37778 45857 37779 45857 37782 45857 37779 45858 37541 45859 37527 45860 37527 45861 37780 45861 37779 45861 37779 45862 37780 45862 37781 45862 37779 45863 37781 45863 37782 45863 37784 45864 37834 45864 37783 45864 37783 45865 37834 45865 37858 45865 37783 45866 37855 45866 37784 45866 37784 45867 37855 45867 37785 45867 37784 45868 37785 45868 37786 45868 37786 45869 37785 45869 37862 45869 37786 45870 37862 45870 37787 45870 37787 45871 37862 45871 37861 45871 37787 45872 37861 45872 37788 45872 37788 45873 37861 45873 37790 45873 37788 45874 37790 45874 37789 45874 37789 45875 37790 45875 37791 45875 37789 45876 37791 45876 37792 45876 37792 45877 37791 45877 37794 45877 37792 45878 37794 45878 37793 45878 37793 45879 37794 45879 37869 45879 37793 45880 37869 45880 37796 45880 37796 45881 37869 45881 37795 45881 37796 45882 37795 45882 37797 45882 37797 45883 37795 45883 37868 45883 37797 45884 37868 45884 37798 45884 37798 45885 37868 45885 37799 45885 37798 45886 37799 45886 37800 45886 37800 45887 37799 45887 37801 45887 37800 45888 37801 45888 37802 45888 37802 45889 37801 45889 37803 45889 37802 45890 37803 45890 37804 45890 37804 45891 37803 45891 37867 45891 37804 45892 37867 45892 37805 45892 37805 45893 37867 45893 37806 45893 37805 45894 37806 45894 37807 45894 37807 45895 37806 45895 37808 45895 37807 45896 37808 45896 37809 45896 37809 45897 37808 45897 37811 45897 37809 45898 37811 45898 37810 45898 37810 45899 37811 45899 37848 45899 37810 45900 37848 45900 37812 45900 37812 45901 37848 45901 37847 45901 37812 45902 37847 45902 37813 45902 37813 45903 37847 45903 37814 45903 37813 45904 37814 45904 37815 45904 37815 45905 37814 45905 37853 45905 37815 45906 37853 45906 37816 45906 37816 45907 37853 45907 37852 45907 37816 45908 37852 45908 37817 45908 37817 45909 37852 45909 37818 45909 37817 45910 37818 45910 37819 45910 37819 45911 37818 45911 37849 45911 37819 45912 37849 45912 37820 45912 37820 45913 37849 45913 37837 45913 37820 45914 37837 45914 37821 45914 37821 45915 37837 45915 37836 45915 37821 45916 37836 45916 37822 45916 37822 45917 37836 45917 37835 45917 37822 45918 37835 45918 37823 45918 37823 45919 37835 45919 37840 45919 37823 45920 37840 45920 37824 45920 37824 45921 37840 45921 37825 45921 37824 45922 37825 45922 37826 45922 37826 45923 37825 45923 37839 45923 37826 45924 37839 45924 37827 45924 37827 45925 37839 45925 37828 45925 37827 45926 37828 45926 37829 45926 37829 45927 37828 45927 37845 45927 37829 45928 37845 45928 37830 45928 37830 45929 37845 45929 37842 45929 37830 45930 37842 45930 37831 45930 37831 45931 37842 45931 37841 45931 37831 45932 37841 45932 37832 45932 37832 45933 37841 45933 37858 45933 37832 45934 37858 45934 37833 45934 37833 45935 37858 45935 37834 45935 37875 590 37835 590 37878 590 37878 45936 37835 45936 37836 45936 37878 590 37836 590 37880 590 37880 45937 37836 45937 37837 45937 37880 45938 37837 45938 37850 45938 37846 590 37839 590 37838 590 37838 45939 37839 45939 37825 45939 37838 590 37825 590 37875 590 37875 45940 37825 45940 37840 45940 37875 45941 37840 45941 37835 45941 37857 45942 37841 45942 37843 45942 37843 45943 37841 45943 37842 45943 37843 590 37842 590 37844 590 37844 45944 37842 45944 37845 45944 37844 45945 37845 45945 37846 45945 37846 45946 37845 45946 37828 45946 37846 45947 37828 45947 37839 45947 37883 45948 37814 45948 37884 45948 37884 590 37814 590 37847 590 37884 45949 37847 45949 37887 45949 37887 45950 37847 45950 37848 45950 37887 590 37848 590 37865 590 37837 590 37849 590 37850 590 37850 590 37849 590 37818 590 37850 45951 37818 45951 37851 45951 37851 590 37818 590 37852 590 37851 590 37852 590 37883 590 37883 590 37852 590 37853 590 37883 45952 37853 45952 37814 45952 37863 45953 37785 45953 37854 45953 37854 45954 37785 45954 37855 45954 37854 590 37855 590 37856 590 37856 45955 37855 45955 37783 45955 37856 45956 37783 45956 37857 45956 37857 45957 37783 45957 37858 45957 37857 45958 37858 45958 37841 45958 37859 590 37791 590 37901 590 37901 590 37791 590 37790 590 37901 590 37790 590 37860 590 37860 590 37790 590 37861 590 37860 590 37861 590 37863 590 37863 590 37861 590 37862 590 37863 590 37862 590 37785 590 37891 590 37803 590 37864 590 37864 45959 37803 45959 37801 45959 37864 45960 37801 45960 37894 45960 37894 45961 37801 45961 37799 45961 37894 590 37799 590 37896 590 37848 590 37811 590 37865 590 37865 590 37811 590 37808 590 37865 590 37808 590 37866 590 37866 590 37808 590 37806 590 37866 590 37806 590 37891 590 37891 45962 37806 45962 37867 45962 37891 45963 37867 45963 37803 45963 37799 45964 37868 45964 37896 45964 37896 45965 37868 45965 37795 45965 37896 590 37795 590 37899 590 37899 45966 37795 45966 37869 45966 37899 590 37869 590 37859 590 37859 590 37869 590 37794 590 37859 590 37794 590 37791 590 37870 45967 37906 45967 37856 45967 37856 45968 37906 45968 37854 45968 37856 45969 37857 45969 37870 45969 37870 45970 37857 45970 37843 45970 37870 45971 37843 45971 37871 45971 37871 45972 37843 45972 37844 45972 37871 45973 37844 45973 37872 45973 37872 45974 37844 45974 37846 45974 37872 45975 37846 45975 37873 45975 37873 45976 37846 45976 37838 45976 37873 45977 37838 45977 37874 45977 37874 45978 37838 45978 37875 45978 37874 45978 37875 45978 37876 45978 37876 45979 37875 45979 37878 45979 37876 45980 37878 45980 37877 45980 37877 45981 37878 45981 37880 45981 37877 45982 37880 45982 37879 45982 37879 45983 37880 45983 37850 45983 37879 45984 37850 45984 37881 45984 37881 45985 37850 45985 37851 45985 37881 45986 37851 45986 37882 45986 37882 45987 37851 45987 37883 45987 37882 45988 37883 45988 37885 45988 37885 45989 37883 45989 37884 45989 37885 45990 37884 45990 37886 45990 37886 45991 37884 45991 37887 45991 37886 45992 37887 45992 37888 45992 37888 45993 37887 45993 37865 45993 37888 45994 37865 45994 37889 45994 37889 45995 37865 45995 37866 45995 37889 45996 37866 45996 37890 45996 37890 45997 37866 45997 37891 45997 37890 45998 37891 45998 37892 45998 37892 45999 37891 45999 37864 45999 37892 46000 37864 46000 37893 46000 37893 46001 37864 46001 37894 46001 37893 46002 37894 46002 37895 46002 37895 46003 37894 46003 37896 46003 37895 46004 37896 46004 37897 46004 37897 46005 37896 46005 37899 46005 37897 46005 37899 46005 37898 46005 37898 46006 37899 46006 37859 46006 37898 46007 37859 46007 37900 46007 37900 46008 37859 46008 37901 46008 37900 46009 37901 46009 37902 46009 37902 46010 37901 46010 37860 46010 37902 46011 37860 46011 37903 46011 37903 46012 37860 46012 37863 46012 37903 46013 37863 46013 37904 46013 37904 46014 37863 46014 37854 46014 37904 46015 37854 46016 37905 46017 37905 46018 37854 46018 37906 46018 37908 46019 37958 46019 37907 46019 37907 49 37958 49 37957 49 37907 46020 37975 46020 37908 46020 37908 46021 37975 46021 37909 46021 37908 46022 37909 46022 37910 46022 37910 46023 37909 46023 37973 46023 37910 46024 37973 46024 37911 46024 37911 46025 37973 46025 37969 46025 37911 46026 37969 46026 37912 46026 37912 46027 37969 46027 37914 46027 37912 46028 37914 46028 37913 46028 37913 46029 37914 46029 37983 46029 37913 46029 37983 46029 37915 46029 37915 46030 37983 46030 37916 46030 37915 46031 37916 46031 37917 46031 37917 46032 37916 46032 37982 46032 37917 46033 37982 46033 37919 46033 37919 46034 37982 46034 37918 46034 37919 46035 37918 46035 37920 46035 37920 46036 37918 46036 37921 46036 37920 46037 37921 46037 37922 46037 37922 46038 37921 46038 37988 46038 37922 46039 37988 46039 37923 46039 37923 46040 37988 46040 37986 46040 37923 46041 37986 46041 37924 46041 37924 46042 37986 46042 37925 46042 37924 46043 37925 46043 37926 46043 37926 46044 37925 46044 37984 46044 37926 46045 37984 46045 37927 46045 37927 46046 37984 46046 37960 46046 37927 46047 37960 46047 37928 46047 37928 46048 37960 46048 37959 46048 37928 46049 37959 46049 37929 46049 37929 46050 37959 46050 37965 46050 37929 46051 37965 46051 37930 46051 37930 46052 37965 46052 37964 46052 37930 46053 37964 46053 37932 46053 37932 46054 37964 46054 37931 46054 37932 46055 37931 46055 37933 46055 37933 46056 37931 46056 37935 46056 37933 46057 37935 46057 37934 46057 37934 46058 37935 46058 37968 46058 37934 46059 37968 46059 37936 46059 37936 46060 37968 46060 37966 46060 37936 46061 37966 46061 37938 46061 37938 46062 37966 46062 37937 46062 37938 46063 37937 46063 37939 46063 37939 46064 37937 46064 37940 46064 37939 46065 37940 46065 37941 46065 37941 46066 37940 46066 37994 46066 37941 46067 37994 46067 37942 46067 37942 46068 37994 46068 37943 46068 37942 46069 37943 46069 37944 46069 37944 46070 37943 46070 37991 46070 37944 46071 37991 46071 37945 46071 37945 46072 37991 46072 37946 46072 37945 46073 37946 46073 37947 46073 37947 46074 37946 46074 37990 46074 37947 46074 37990 46074 37948 46074 37948 46075 37990 46075 37980 46075 37948 46076 37980 46076 37949 46076 37949 46077 37980 46077 37978 46077 37949 46078 37978 46078 37950 46078 37950 46079 37978 46079 37952 46079 37950 46080 37952 46080 37951 46080 37951 46081 37952 46081 37953 46081 37951 46082 37953 46082 37954 46082 37954 46083 37953 46083 37971 46083 37954 46084 37971 46084 37955 46084 37955 46085 37971 46085 37957 46085 37955 46086 37957 46086 37956 46086 37956 49 37957 49 37958 49 37963 590 37959 590 38013 590 38013 46087 37959 46087 37960 46087 38013 590 37960 590 37985 590 38008 46088 37935 46088 37961 46088 37961 46089 37935 46089 37931 46089 37961 46090 37931 46090 37962 46090 37962 46091 37931 46091 37964 46091 37962 590 37964 590 37963 590 37963 46092 37964 46092 37965 46092 37963 46093 37965 46093 37959 46093 38005 590 37937 590 37967 590 37967 590 37937 590 37966 590 37967 590 37966 590 38008 590 38008 46094 37966 46094 37968 46094 38008 46095 37968 46095 37935 46095 38023 46096 37983 46096 38024 46096 38024 590 37983 590 37914 590 38024 46097 37914 46097 37970 46097 37970 46098 37914 46098 37969 46098 37970 46099 37969 46099 38028 46099 37977 590 37971 590 37996 590 37996 46100 37971 46100 37953 46100 37996 590 37953 590 37972 590 37972 46101 37953 46101 37952 46101 37972 590 37952 590 37979 590 37969 590 37973 590 38028 590 38028 46102 37973 46102 37909 46102 38028 46103 37909 46103 37974 46103 37974 892 37909 892 37975 892 37974 46104 37975 46104 37976 46104 37976 46105 37975 46105 37907 46105 37976 46106 37907 46106 37977 46106 37977 590 37907 590 37957 590 37977 590 37957 590 37971 590 37952 46107 37978 46107 37979 46107 37979 46108 37978 46108 37980 46108 37979 590 37980 590 37981 590 37981 46109 37980 46109 37990 46109 37981 590 37990 590 38002 590 37989 46110 37918 46110 38020 46110 38020 590 37918 590 37982 590 38020 46111 37982 46111 38023 46111 38023 46112 37982 46112 37916 46112 38023 46113 37916 46113 37983 46113 37960 590 37984 590 37985 590 37985 46114 37984 46114 37925 46114 37985 590 37925 590 38016 590 38016 590 37925 590 37986 590 38016 590 37986 590 37987 590 37987 590 37986 590 37988 590 37987 590 37988 590 37989 590 37989 590 37988 590 37921 590 37989 590 37921 590 37918 590 37990 46115 37946 46115 38002 46115 38002 46116 37946 46116 37991 46116 38002 46117 37991 46117 37992 46117 37992 590 37991 590 37943 590 37992 46118 37943 46118 37993 46118 37993 590 37943 590 37994 590 37993 46119 37994 46119 38005 46119 38005 590 37994 590 37940 590 38005 590 37940 590 37937 590 37995 46120 38030 46120 37976 46120 37976 46121 38030 46121 37974 46121 37976 46122 37977 46122 37995 46122 37995 46123 37977 46123 37996 46123 37995 46124 37996 46124 37997 46124 37997 46125 37996 46125 37972 46125 37997 46126 37972 46126 37998 46126 37998 46127 37972 46127 37979 46127 37998 46128 37979 46128 37999 46128 37999 46129 37979 46129 37981 46129 37999 46130 37981 46130 38000 46130 38000 46131 37981 46131 38002 46131 38000 46132 38002 46132 38001 46132 38001 46133 38002 46133 37992 46133 38001 46134 37992 46134 38003 46134 38003 46135 37992 46135 37993 46135 38003 46136 37993 46136 38004 46136 38004 46137 37993 46137 38005 46137 38004 46138 38005 46138 38006 46138 38006 46139 38005 46139 37967 46139 38006 46140 37967 46140 38007 46140 38007 46141 37967 46141 38008 46141 38007 46142 38008 46142 38009 46142 38009 46143 38008 46143 37961 46143 38009 46144 37961 46144 38010 46144 38010 46145 37961 46145 37962 46145 38010 46146 37962 46146 38011 46146 38011 46147 37962 46147 37963 46147 38011 46148 37963 46148 38012 46148 38012 46149 37963 46149 38013 46149 38012 46150 38013 46150 38014 46150 38014 46151 38013 46151 37985 46151 38014 46152 37985 46152 38015 46152 38015 46153 37985 46153 38016 46153 38015 46154 38016 46154 38017 46154 38017 46155 38016 46155 37987 46155 38017 46156 37987 46156 38018 46156 38018 46157 37987 46157 37989 46157 38018 46158 37989 46158 38019 46158 38019 46159 37989 46159 38020 46159 38019 46160 38020 46160 38021 46160 38021 46161 38020 46161 38023 46161 38021 46162 38023 46162 38022 46162 38022 46163 38023 46163 38024 46163 38022 46164 38024 46164 38025 46164 38025 46165 38024 46165 37970 46165 38025 46166 37970 46166 38026 46166 38026 46167 37970 46167 38028 46167 38026 46168 38028 46168 38027 46168 38027 46169 38028 46169 37974 46169 38027 46169 37974 46169 38029 46169 38029 46170 37974 46170 38030 46170 38031 46171 38032 46171 38033 46171 38033 46172 38032 46172 38087 46172 38033 46173 38034 46173 38031 46173 38031 46174 38034 46174 38114 46174 38031 46175 38114 46175 38035 46175 38035 46176 38114 46176 38037 46176 38035 46177 38037 46177 38036 46177 38036 46178 38037 46178 38038 46178 38036 46179 38038 46179 38039 46179 38039 46180 38038 46180 38041 46180 38039 46181 38041 46181 38040 46181 38040 46182 38041 46182 38097 46182 38040 46183 38097 46183 38042 46183 38042 46184 38097 46184 38043 46184 38042 46185 38043 46185 38044 46185 38044 46186 38043 46186 38102 46186 38044 46187 38102 46187 38045 46187 38045 46188 38102 46188 38100 46188 38045 46189 38100 46189 38046 46189 38046 46190 38100 46190 38047 46190 38046 46191 38047 46191 38049 46191 38049 46192 38047 46192 38048 46192 38049 46193 38048 46193 38051 46193 38051 46194 38048 46194 38050 46194 38051 46195 38050 46195 38052 46195 38052 46196 38050 46196 38092 46196 38052 46197 38092 46197 38053 46197 38053 46198 38092 46198 38054 46198 38053 46199 38054 46199 38055 46199 38055 46200 38054 46200 38056 46200 38055 46201 38056 46201 38057 46201 38057 46202 38056 46202 38095 46202 38057 46203 38095 46203 38058 46203 38058 46204 38095 46204 38059 46204 38058 46205 38059 46205 38060 46205 38060 46206 38059 46206 38094 46206 38060 46207 38094 46207 38061 46207 38061 46208 38094 46208 38062 46208 38061 46209 38062 46209 38063 46209 38063 46210 38062 46210 38065 46210 38063 46211 38065 46211 38064 46211 38064 46212 38065 46212 38067 46212 38064 46213 38067 46213 38066 46213 38066 46214 38067 46214 38068 46214 38066 46215 38068 46215 38069 46215 38069 46216 38068 46216 38071 46216 38069 46217 38071 46217 38070 46217 38070 46218 38071 46218 38072 46218 38070 46219 38072 46219 38073 46219 38073 46220 38072 46220 38106 46220 38073 46221 38106 46221 38074 46221 38074 46222 38106 46222 38104 46222 38074 46223 38104 46223 38075 46223 38075 46224 38104 46224 38103 46224 38075 46225 38103 46225 38076 46225 38076 46226 38103 46226 38078 46226 38076 46227 38078 46227 38077 46227 38077 46228 38078 46228 38079 46228 38077 46229 38079 46229 38080 46229 38080 46230 38079 46230 38108 46230 38080 46231 38108 46231 38081 46231 38081 46232 38108 46232 38082 46232 38081 46233 38082 46233 38083 46233 38083 46234 38082 46234 38111 46234 38083 46235 38111 46235 38084 46235 38084 46236 38111 46236 38110 46236 38084 46237 38110 46238 38085 46239 38085 46240 38110 46240 38086 46240 38085 46241 38086 46241 38088 46241 38088 46242 38086 46242 38087 46242 38088 46243 38087 46243 38089 46243 38089 46244 38087 46244 38032 46244 38138 590 38095 590 38139 590 38139 590 38095 590 38056 590 38139 590 38056 590 38090 590 38056 46245 38054 46245 38090 46245 38090 590 38054 590 38092 590 38090 46246 38092 46246 38091 46246 38091 590 38092 590 38050 590 38091 590 38050 590 38144 590 38144 46247 38050 46247 38048 46247 38144 46248 38048 46248 38099 46248 38093 590 38065 590 38134 590 38134 590 38065 590 38062 590 38134 590 38062 590 38136 590 38136 590 38062 590 38094 590 38136 590 38094 590 38138 590 38138 590 38094 590 38059 590 38138 590 38059 590 38095 590 38096 46249 38097 46249 38150 46249 38150 46250 38097 46250 38041 46250 38150 46251 38041 46251 38098 46251 38098 46252 38041 46252 38038 46252 38098 46253 38038 46253 38112 46253 38048 590 38047 590 38099 590 38099 46254 38047 46254 38100 46254 38099 590 38100 590 38101 590 38101 46255 38100 46255 38102 46255 38101 590 38102 590 38096 590 38096 46256 38102 46256 38043 46256 38096 46257 38043 46257 38097 46257 38130 590 38071 590 38131 590 38131 46258 38071 46258 38068 46258 38131 590 38068 590 38093 590 38093 46259 38068 46259 38067 46259 38093 590 38067 590 38065 590 38124 590 38103 590 38127 590 38127 46260 38103 46260 38104 46260 38127 590 38104 590 38105 590 38105 46261 38104 46261 38106 46261 38105 590 38106 590 38130 590 38130 46262 38106 46262 38072 46262 38130 46263 38072 46263 38071 46263 38107 46264 38108 46264 38109 46264 38109 590 38108 590 38079 590 38109 590 38079 590 38124 590 38124 590 38079 590 38078 590 38124 46265 38078 46265 38103 46265 38116 46266 38086 46266 38118 46266 38118 590 38086 590 38110 590 38118 590 38110 590 38120 590 38120 46267 38110 46267 38111 46267 38120 590 38111 590 38107 590 38107 590 38111 590 38082 590 38107 590 38082 590 38108 590 38038 46268 38037 46268 38112 46268 38112 46269 38037 46269 38114 46269 38112 590 38114 590 38113 590 38113 46270 38114 46270 38034 46270 38113 46271 38034 46271 38115 46271 38115 590 38034 590 38033 590 38115 590 38033 590 38116 590 38116 590 38033 590 38087 590 38116 46272 38087 46272 38086 46272 38117 46273 38154 46273 38115 46273 38115 46274 38154 46274 38113 46274 38115 46275 38116 46275 38117 46275 38117 46276 38116 46276 38118 46276 38117 46277 38118 46277 38119 46277 38119 46278 38118 46278 38120 46278 38119 46279 38120 46279 38121 46279 38121 46280 38120 46280 38107 46280 38121 46281 38107 46281 38122 46281 38122 46282 38107 46282 38109 46282 38122 46283 38109 46283 38123 46283 38123 46284 38109 46284 38124 46284 38123 46285 38124 46285 38125 46285 38125 46286 38124 46286 38127 46286 38125 46287 38127 46287 38126 46287 38126 46288 38127 46288 38105 46288 38126 46289 38105 46289 38128 46289 38128 46290 38105 46290 38130 46290 38128 46290 38130 46290 38129 46290 38129 46291 38130 46291 38131 46291 38129 46292 38131 46292 38132 46292 38132 46293 38131 46293 38093 46293 38132 46294 38093 46294 38133 46294 38133 46295 38093 46295 38134 46295 38133 46296 38134 46296 38135 46296 38135 46297 38134 46297 38136 46297 38135 46298 38136 46298 38137 46298 38137 46299 38136 46299 38138 46299 38137 46300 38138 46300 38140 46300 38140 46301 38138 46301 38139 46301 38140 46302 38139 46302 38141 46302 38141 46303 38139 46303 38090 46303 38141 46304 38090 46304 38142 46304 38142 46305 38090 46305 38091 46305 38142 46306 38091 46306 38143 46306 38143 46307 38091 46307 38144 46307 38143 46308 38144 46308 38145 46308 38145 46309 38144 46309 38099 46309 38145 46310 38099 46310 38146 46310 38146 46311 38099 46311 38101 46311 38146 46312 38101 46312 38147 46312 38147 46313 38101 46313 38096 46313 38147 46314 38096 46314 38148 46314 38148 46315 38096 46315 38150 46315 38148 46315 38150 46315 38149 46315 38149 46316 38150 46316 38098 46316 38149 46317 38098 46317 38151 46317 38151 46318 38098 46318 38112 46318 38151 46319 38112 46319 38152 46319 38152 46320 38112 46320 38113 46320 38152 46321 38113 46321 38153 46321 38153 46322 38113 46323 38154 46324 38157 46325 38155 46325 38239 46325 38239 46326 38155 46326 38240 46326 38239 46327 38156 46327 38157 46327 38157 46328 38156 46328 38236 46328 38157 46329 38236 46329 38158 46329 38158 46330 38236 46330 38160 46330 38158 46331 38160 46331 38159 46331 38159 46332 38160 46332 38226 46332 38159 46333 38226 46333 38161 46333 38161 46334 38226 46334 38162 46334 38161 46335 38162 46335 38163 46335 38163 46336 38162 46336 38224 46336 38163 46337 38224 46337 38165 46337 38165 46338 38224 46338 38164 46338 38165 46339 38164 46339 38166 46339 38166 46340 38164 46340 38167 46340 38166 46341 38167 46341 38168 46341 38168 46342 38167 46342 38233 46342 38168 46343 38233 46343 38169 46343 38169 46344 38233 46344 38170 46344 38169 46345 38170 46345 38171 46345 38171 46346 38170 46346 38222 46346 38171 46347 38222 46347 38172 46347 38172 46348 38222 46348 38221 46348 38172 46349 38221 46349 38174 46349 38174 46350 38221 46350 38173 46350 38174 46351 38173 46351 38175 46351 38175 46352 38173 46352 38176 46352 38175 46353 38176 46353 38177 46353 38177 46354 38176 46354 38215 46354 38177 46355 38215 46355 38178 46355 38178 46356 38215 46356 38180 46356 38178 46357 38180 46357 38179 46357 38179 46358 38180 46358 38213 46358 38179 46359 38213 46359 38181 46359 38181 46360 38213 46360 38182 46360 38181 46361 38182 46361 38183 46361 38183 46362 38182 46362 38185 46362 38183 46363 38185 46363 38184 46363 38184 46364 38185 46364 38210 46364 38184 46365 38210 46365 38186 46365 38186 46366 38210 46366 38217 46366 38186 46367 38217 46367 38187 46367 38187 46368 38217 46368 38188 46368 38187 46369 38188 46369 38189 46369 38189 46370 38188 46370 38190 46370 38189 46371 38190 46371 38191 46371 38191 46372 38190 46372 38219 46372 38191 46373 38219 46373 38192 46373 38192 46374 38219 46374 38193 46374 38192 46375 38193 46375 38194 46375 38194 46376 38193 46376 38218 46376 38194 46377 38218 46377 38195 46377 38195 46378 38218 46378 38231 46378 38195 46379 38231 46379 38197 46379 38197 46380 38231 46380 38196 46380 38197 46381 38196 46381 38198 46381 38198 46382 38196 46382 38230 46382 38198 46383 38230 46383 38199 46383 38199 46384 38230 46384 38229 46384 38199 46385 38229 46385 38201 46385 38201 46386 38229 46386 38200 46386 38201 46387 38200 46387 38203 46387 38203 46388 38200 46388 38202 46388 38203 46389 38202 46389 38204 46389 38204 46390 38202 46390 38206 46390 38204 46391 38206 46391 38205 46391 38205 46392 38206 46392 38241 46392 38205 46393 38241 46393 38207 46393 38207 46394 38241 46394 38240 46394 38207 46395 38240 46395 38208 46395 38208 46396 38240 46396 38155 46396 38209 46397 38210 46397 38260 46397 38260 590 38210 590 38185 590 38260 46398 38185 46398 38211 46398 38211 46399 38185 46399 38182 46399 38211 590 38182 590 38212 590 38182 590 38213 590 38212 590 38212 590 38213 590 38180 590 38212 590 38180 590 38214 590 38214 590 38180 590 38215 590 38214 590 38215 590 38264 590 38256 46400 38190 46400 38216 46400 38216 590 38190 590 38188 590 38216 590 38188 590 38209 590 38209 590 38188 590 38217 590 38209 46401 38217 46401 38210 46401 38250 590 38231 590 38251 590 38251 46402 38231 46402 38218 46402 38251 590 38218 590 38254 590 38254 46403 38218 46403 38193 46403 38254 46404 38193 46404 38256 46404 38256 590 38193 590 38219 590 38256 590 38219 590 38190 590 38215 590 38176 590 38264 590 38264 46405 38176 46405 38173 46405 38264 590 38173 590 38220 590 38220 46406 38173 46406 38221 46406 38220 46407 38221 46407 38268 46407 38268 46408 38221 46408 38222 46408 38268 590 38222 590 38232 590 38238 46409 38241 46409 38245 46409 38245 46410 38241 46410 38206 46410 38245 590 38206 590 38223 590 38223 46411 38206 46411 38202 46411 38223 46412 38202 46412 38227 46412 38235 590 38224 590 38273 590 38273 590 38224 590 38162 590 38273 590 38162 590 38225 590 38225 590 38162 590 38226 590 38225 590 38226 590 38276 590 38202 46413 38200 46413 38227 46413 38227 46414 38200 46414 38229 46414 38227 590 38229 590 38228 590 38228 46415 38229 46415 38230 46415 38228 590 38230 590 38250 590 38250 46416 38230 46416 38196 46416 38250 46417 38196 46417 38231 46417 38222 46418 38170 46418 38232 46418 38232 46419 38170 46419 38233 46419 38232 590 38233 590 38234 590 38234 46420 38233 46420 38167 46420 38234 590 38167 590 38235 590 38235 590 38167 590 38164 590 38235 590 38164 590 38224 590 38226 46421 38160 46421 38276 46421 38276 590 38160 590 38236 590 38276 46422 38236 46422 38237 46422 38237 46423 38236 46423 38156 46423 38237 590 38156 590 38242 590 38242 46424 38156 46424 38239 46424 38242 46425 38239 46425 38238 46425 38238 46426 38239 46426 38240 46426 38238 46427 38240 46427 38241 46427 38244 46428 38243 46428 38242 46428 38242 46429 38243 46429 38237 46429 38242 46430 38238 46430 38244 46430 38244 46431 38238 46431 38245 46431 38244 46432 38245 46432 38246 46432 38246 46433 38245 46433 38223 46433 38246 46434 38223 46434 38247 46434 38247 46435 38223 46435 38227 46435 38247 46436 38227 46436 38248 46436 38248 46437 38227 46437 38228 46437 38248 46438 38228 46438 38249 46438 38249 46439 38228 46439 38250 46439 38249 46439 38250 46439 38252 46439 38252 46440 38250 46440 38251 46440 38252 46441 38251 46441 38253 46441 38253 46442 38251 46442 38254 46442 38253 46443 38254 46443 38255 46443 38255 46444 38254 46444 38256 46444 38255 46445 38256 46445 38257 46445 38257 46446 38256 46446 38216 46446 38257 46447 38216 46447 38258 46447 38258 46448 38216 46448 38209 46448 38258 46449 38209 46449 38259 46449 38259 46450 38209 46450 38260 46450 38259 46451 38260 46451 38261 46451 38261 46452 38260 46452 38211 46452 38261 46453 38211 46453 38262 46453 38262 46454 38211 46454 38212 46454 38262 46455 38212 46455 38263 46455 38263 46456 38212 46456 38214 46456 38263 46457 38214 46457 38265 46457 38265 46458 38214 46458 38264 46458 38265 46459 38264 46459 38266 46459 38266 46460 38264 46460 38220 46460 38266 46461 38220 46461 38267 46461 38267 46462 38220 46462 38268 46462 38267 46463 38268 46463 38269 46463 38269 46464 38268 46464 38232 46464 38269 46465 38232 46465 38270 46465 38270 46466 38232 46466 38234 46466 38270 46466 38234 46466 38271 46466 38271 46467 38234 46467 38235 46467 38271 46468 38235 46468 38272 46468 38272 46469 38235 46469 38273 46469 38272 46470 38273 46470 38274 46470 38274 46471 38273 46471 38225 46471 38274 46472 38225 46472 38275 46472 38275 46473 38225 46473 38276 46473 38275 46474 38276 46474 38277 46474 38277 46475 38276 46475 38237 46475 38277 46476 38237 46477 38278 46478 38278 46479 38237 46479 38243 46479 38281 46480 38279 46480 38280 46480 38280 50 38279 50 38327 50 38280 46481 38351 46481 38281 46481 38281 46482 38351 46482 38283 46482 38281 46483 38283 46483 38282 46483 38282 46484 38283 46484 38349 46484 38282 46485 38349 46485 38284 46485 38284 46486 38349 46486 38285 46486 38284 46487 38285 46487 38286 46487 38286 46488 38285 46488 38338 46488 38286 46489 38338 46489 38287 46489 38287 46490 38338 46490 38335 46490 38287 46490 38335 46490 38288 46490 38288 46491 38335 46491 38289 46491 38288 46492 38289 46492 38291 46492 38291 46493 38289 46493 38290 46493 38291 46494 38290 46494 38292 46494 38292 46495 38290 46495 38339 46495 38292 46496 38339 46496 38293 46496 38293 46497 38339 46497 38345 46497 38293 46498 38345 46498 38294 46498 38294 46499 38345 46499 38295 46499 38294 46500 38295 46500 38296 46500 38296 46501 38295 46501 38343 46501 38296 46502 38343 46502 38297 46502 38297 46503 38343 46503 38342 46503 38297 46504 38342 46504 38298 46504 38298 46505 38342 46505 38341 46505 38298 46506 38341 46506 38299 46506 38299 46507 38341 46507 38300 46507 38299 46508 38300 46508 38301 46508 38301 46509 38300 46509 38333 46509 38301 46510 38333 46510 38302 46510 38302 46511 38333 46511 38332 46511 38302 46512 38332 46512 38303 46512 38303 46513 38332 46513 38304 46513 38303 46514 38304 46514 38305 46514 38305 46515 38304 46515 38330 46515 38305 46516 38330 46516 38306 46516 38306 46517 38330 46517 38329 46517 38306 46518 38329 46518 38307 46518 38307 46519 38329 46519 38362 46519 38307 46520 38362 46520 38308 46520 38308 46521 38362 46521 38361 46521 38308 46522 38361 46522 38309 46522 38309 46523 38361 46523 38310 46523 38309 46524 38310 46524 38311 46524 38311 46525 38310 46525 38360 46525 38311 46526 38360 46526 38312 46526 38312 46527 38360 46527 38356 46527 38312 46528 38356 46528 38313 46528 38313 46529 38356 46529 38355 46529 38313 46530 38355 46530 38314 46530 38314 46531 38355 46531 38359 46531 38314 46532 38359 46532 38315 46532 38315 46533 38359 46533 38316 46533 38315 46534 38316 46534 38317 46534 38317 46535 38316 46535 38318 46535 38317 46535 38318 46535 38320 46535 38320 46536 38318 46536 38319 46536 38320 46537 38319 46537 38321 46537 38321 46538 38319 46538 38357 46538 38321 46539 38357 46539 38322 46539 38322 46540 38357 46540 38348 46540 38322 46541 38348 46541 38324 46541 38324 46542 38348 46542 38323 46542 38324 46543 38323 46543 38325 46543 38325 46544 38323 46544 38346 46544 38325 46545 38346 46545 38326 46545 38326 46546 38346 46546 38327 46546 38326 46547 38327 46547 38328 46547 38328 50 38327 50 38279 50 38331 590 38333 590 38387 590 38387 46548 38333 46548 38300 46548 38387 590 38300 590 38389 590 38379 46549 38329 46549 38382 46549 38382 46550 38329 46550 38330 46550 38382 46551 38330 46551 38384 46551 38384 46552 38330 46552 38304 46552 38384 590 38304 590 38331 590 38331 46553 38304 46553 38332 46553 38331 46554 38332 46554 38333 46554 38334 46266 38335 46266 38336 46266 38336 590 38335 590 38338 590 38336 46555 38338 46555 38337 46555 38337 46556 38338 46556 38285 46556 38337 46557 38285 46557 38350 46557 38393 46558 38339 46558 38340 46558 38340 590 38339 590 38290 590 38340 46559 38290 46559 38334 46559 38334 46560 38290 46560 38289 46560 38334 46561 38289 46561 38335 46561 38300 590 38341 590 38389 590 38389 46562 38341 46562 38342 46562 38389 590 38342 590 38391 590 38391 590 38342 590 38343 590 38391 590 38343 590 38344 590 38344 590 38343 590 38295 590 38344 590 38295 590 38393 590 38393 590 38295 590 38345 590 38393 590 38345 590 38339 590 38364 590 38346 590 38347 590 38347 46563 38346 46563 38323 46563 38347 590 38323 590 38367 590 38367 46564 38323 46564 38348 46564 38367 590 38348 590 38369 590 38285 590 38349 590 38350 590 38350 46565 38349 46565 38283 46565 38350 46566 38283 46566 38401 46566 38401 610 38283 610 38351 610 38401 46567 38351 46567 38352 46567 38352 46568 38351 46568 38280 46568 38352 46569 38280 46569 38364 46569 38364 590 38280 590 38327 590 38364 590 38327 590 38346 590 38358 46570 38359 46570 38353 46570 38353 590 38359 590 38355 590 38353 46571 38355 46571 38354 46571 38354 590 38355 590 38356 590 38354 46572 38356 46572 38376 46572 38348 46573 38357 46573 38369 46573 38369 46574 38357 46574 38319 46574 38369 590 38319 590 38371 590 38371 46575 38319 46575 38318 46575 38371 590 38318 590 38358 590 38358 46576 38318 46576 38316 46576 38358 46577 38316 46577 38359 46577 38356 590 38360 590 38376 590 38376 590 38360 590 38310 590 38376 590 38310 590 38378 590 38378 590 38310 590 38361 590 38378 590 38361 590 38379 590 38379 46578 38361 46578 38362 46578 38379 46579 38362 46579 38329 46579 38365 46580 38363 46580 38352 46580 38352 46581 38363 46581 38401 46581 38352 46582 38364 46582 38365 46582 38365 46583 38364 46583 38347 46583 38365 46584 38347 46584 38366 46584 38366 46585 38347 46585 38367 46585 38366 46586 38367 46586 38368 46586 38368 46587 38367 46587 38369 46587 38368 46588 38369 46588 38370 46588 38370 46589 38369 46589 38371 46589 38370 46590 38371 46590 38372 46590 38372 46591 38371 46591 38358 46591 38372 46592 38358 46592 38373 46592 38373 46593 38358 46593 38353 46593 38373 46594 38353 46594 38374 46594 38374 46595 38353 46595 38354 46595 38374 46596 38354 46596 38375 46596 38375 46597 38354 46597 38376 46597 38375 46598 38376 46598 38377 46598 38377 46599 38376 46599 38378 46599 38377 46600 38378 46600 38380 46600 38380 46601 38378 46601 38379 46601 38380 46602 38379 46602 38381 46602 38381 46603 38379 46603 38382 46603 38381 46604 38382 46604 38383 46604 38383 46605 38382 46605 38384 46605 38383 46606 38384 46606 38385 46606 38385 46607 38384 46607 38331 46607 38385 46608 38331 46608 38386 46608 38386 46609 38331 46609 38387 46609 38386 46610 38387 46610 38388 46610 38388 46611 38387 46611 38389 46611 38388 46612 38389 46612 38390 46612 38390 46613 38389 46613 38391 46613 38390 46614 38391 46614 38392 46614 38392 46615 38391 46615 38344 46615 38392 46616 38344 46616 38394 46616 38394 46617 38344 46617 38393 46617 38394 46618 38393 46618 38395 46618 38395 46619 38393 46619 38340 46619 38395 46620 38340 46620 38396 46620 38396 46621 38340 46621 38334 46621 38396 46622 38334 46622 38397 46622 38397 46623 38334 46623 38336 46623 38397 46624 38336 46624 38398 46624 38398 46625 38336 46625 38337 46625 38398 46626 38337 46626 38399 46626 38399 46627 38337 46627 38350 46627 38399 46628 38350 46628 38400 46628 38400 46629 38350 46629 38401 46629 38400 46629 38401 46629 38402 46629 38402 46630 38401 46630 38363 46630 38403 46631 38460 46631 38473 46631 38473 46632 38460 46632 38459 46632 38473 46633 38404 46633 38403 46633 38403 46634 38404 46634 38405 46634 38403 46635 38405 46635 38406 46635 38406 46636 38405 46636 38408 46636 38406 46637 38408 46637 38407 46637 38407 46638 38408 46638 38476 46638 38407 46639 38476 46639 38409 46639 38409 46640 38476 46640 38410 46640 38409 46641 38410 46641 38411 46641 38411 46642 38410 46642 38412 46642 38411 46643 38412 46643 38413 46643 38413 46644 38412 46644 38415 46644 38413 46645 38415 46645 38414 46645 38414 46646 38415 46646 38416 46646 38414 46647 38416 46647 38417 46647 38417 46648 38416 46648 38477 46648 38417 46649 38477 46649 38418 46649 38418 46650 38477 46650 38482 46650 38418 46651 38482 46651 38419 46651 38419 46652 38482 46652 38420 46652 38419 46653 38420 46653 38421 46653 38421 46654 38420 46654 38480 46654 38421 46655 38480 46655 38422 46655 38422 46656 38480 46656 38423 46656 38422 46657 38423 46657 38424 46657 38424 46658 38423 46658 38425 46658 38424 46659 38425 46659 38426 46659 38426 46660 38425 46660 38492 46660 38426 46661 38492 46661 38427 46661 38427 46662 38492 46662 38491 46662 38427 46663 38491 46663 38428 46663 38428 46664 38491 46664 38429 46664 38428 46665 38429 46665 38430 46665 38430 46666 38429 46666 38432 46666 38430 46667 38432 46667 38431 46667 38431 46668 38432 46668 38433 46668 38431 46669 38433 46669 38434 46669 38434 46670 38433 46670 38435 46670 38434 46671 38435 46671 38436 46671 38436 46672 38435 46672 38437 46672 38436 46673 38437 46673 38439 46673 38439 46674 38437 46674 38438 46674 38439 46675 38438 46675 38440 46675 38440 46676 38438 46676 38488 46676 38440 46677 38488 46677 38441 46677 38441 46678 38488 46678 38485 46678 38441 46679 38485 46679 38442 46679 38442 46680 38485 46680 38444 46680 38442 46681 38444 46681 38443 46681 38443 46682 38444 46682 38463 46682 38443 46683 38463 46683 38445 46683 38445 46684 38463 46684 38446 46684 38445 46685 38446 46685 38447 46685 38447 46686 38446 46686 38448 46686 38447 46687 38448 46687 38449 46687 38449 46688 38448 46688 38471 46688 38449 46689 38471 46689 38450 46689 38450 46690 38471 46690 38452 46690 38450 46691 38452 46691 38451 46691 38451 46692 38452 46692 38469 46692 38451 46693 38469 46693 38453 46693 38453 46694 38469 46694 38455 46694 38453 46695 38455 46695 38454 46695 38454 46696 38455 46696 38466 46696 38454 46697 38466 46697 38456 46697 38456 46698 38466 46698 38464 46698 38456 46699 38464 46699 38457 46699 38457 46700 38464 46700 38459 46700 38457 46701 38459 46701 38458 46701 38458 46702 38459 46702 38460 46702 38500 46703 38446 46703 38461 46703 38461 46704 38446 46704 38463 46704 38461 46705 38463 46705 38462 46705 38462 46706 38463 46706 38444 46706 38462 590 38444 590 38486 590 38474 590 38464 590 38465 590 38465 590 38464 590 38466 590 38465 46707 38466 46707 38467 46707 38467 46399 38466 46399 38455 46399 38467 590 38455 590 38468 590 38455 590 38469 590 38468 590 38468 46708 38469 46708 38452 46708 38468 590 38452 590 38470 590 38470 46709 38452 46709 38471 46709 38470 46710 38471 46710 38500 46710 38500 46711 38471 46711 38448 46711 38500 46712 38448 46712 38446 46712 38524 590 38405 590 38495 590 38495 46713 38405 46713 38404 46713 38495 590 38404 590 38472 590 38472 46714 38404 46714 38473 46714 38472 590 38473 590 38474 590 38474 46715 38473 46715 38459 46715 38474 590 38459 590 38464 590 38478 590 38412 590 38521 590 38521 46716 38412 46716 38410 46716 38521 590 38410 590 38475 590 38475 46717 38410 46717 38476 46717 38475 590 38476 590 38524 590 38524 590 38476 590 38408 590 38524 590 38408 590 38405 590 38481 590 38477 590 38518 590 38518 46718 38477 46718 38416 46718 38518 590 38416 590 38478 590 38478 46719 38416 46719 38415 46719 38478 46720 38415 46720 38412 46720 38513 590 38423 590 38514 590 38514 46721 38423 46721 38480 46721 38514 590 38480 590 38479 590 38479 590 38480 590 38420 590 38479 590 38420 590 38481 590 38481 590 38420 590 38482 590 38481 46722 38482 46722 38477 46722 38489 590 38435 590 38483 590 38483 590 38435 590 38433 590 38483 590 38433 590 38484 590 38484 590 38433 590 38432 590 38484 590 38432 590 38490 590 38444 590 38485 590 38486 590 38486 590 38485 590 38488 590 38486 590 38488 590 38487 590 38487 590 38488 590 38438 590 38487 590 38438 590 38489 590 38489 590 38438 590 38437 590 38489 590 38437 590 38435 590 38432 46723 38429 46723 38490 46723 38490 590 38429 590 38491 590 38490 46724 38491 46724 38511 46724 38511 590 38491 590 38492 590 38511 46725 38492 46725 38513 46725 38513 46726 38492 46726 38425 46726 38513 590 38425 590 38423 590 38493 46727 38494 46727 38472 46727 38472 46728 38494 46728 38495 46728 38472 46729 38474 46729 38493 46729 38493 46730 38474 46730 38465 46730 38493 46731 38465 46731 38496 46731 38496 46732 38465 46732 38467 46732 38496 46733 38467 46733 38497 46733 38497 46734 38467 46734 38468 46734 38497 46735 38468 46735 38498 46735 38498 46736 38468 46736 38470 46736 38498 46737 38470 46737 38499 46737 38499 46738 38470 46738 38500 46738 38499 46739 38500 46739 38501 46739 38501 46740 38500 46740 38461 46740 38501 46741 38461 46741 38502 46741 38502 46742 38461 46742 38462 46742 38502 46743 38462 46743 38503 46743 38503 46744 38462 46744 38486 46744 38503 46745 38486 46745 38504 46745 38504 46746 38486 46746 38487 46746 38504 46747 38487 46747 38505 46747 38505 46748 38487 46748 38489 46748 38505 46749 38489 46749 38506 46749 38506 46750 38489 46750 38483 46750 38506 46751 38483 46751 38507 46751 38507 46752 38483 46752 38484 46752 38507 46753 38484 46753 38508 46753 38508 46754 38484 46754 38490 46754 38508 46755 38490 46755 38509 46755 38509 46756 38490 46756 38511 46756 38509 46757 38511 46757 38510 46757 38510 46758 38511 46758 38513 46758 38510 46759 38513 46759 38512 46759 38512 46760 38513 46760 38514 46760 38512 46761 38514 46761 38515 46761 38515 46762 38514 46762 38479 46762 38515 46763 38479 46763 38516 46763 38516 46764 38479 46764 38481 46764 38516 46765 38481 46765 38517 46765 38517 46766 38481 46766 38518 46766 38517 46767 38518 46767 38519 46767 38519 46768 38518 46768 38478 46768 38519 46768 38478 46768 38520 46768 38520 46769 38478 46769 38521 46769 38520 46770 38521 46770 38522 46770 38522 46771 38521 46771 38475 46771 38522 46772 38475 46772 38523 46772 38523 46773 38475 46773 38524 46773 38523 46774 38524 46774 38525 46774 38525 46775 38524 46775 38495 46775 38525 46776 38495 46776 38526 46776 38526 46777 38495 46777 38494 46777 38529 46778 38527 46778 38528 46778 38528 46779 38527 46779 38583 46779 38528 46780 38608 46780 38529 46780 38529 46781 38608 46781 38531 46781 38529 46782 38531 46782 38530 46782 38530 46783 38531 46783 38532 46783 38530 46783 38532 46783 38533 46783 38533 46784 38532 46784 38594 46784 38533 46785 38594 46785 38534 46785 38534 46786 38594 46786 38535 46786 38534 46787 38535 46787 38536 46787 38536 46788 38535 46788 38537 46788 38536 46789 38537 46789 38538 46789 38538 46790 38537 46790 38539 46790 38538 46790 38539 46790 38540 46790 38540 46791 38539 46791 38593 46791 38540 46792 38593 46792 38541 46792 38541 46793 38593 46793 38542 46793 38541 46794 38542 46794 38543 46794 38543 46795 38542 46795 38544 46795 38543 46796 38544 46796 38545 46796 38545 46797 38544 46797 38586 46797 38545 46797 38586 46797 38546 46797 38546 46798 38586 46798 38547 46798 38546 46799 38547 46799 38548 46799 38548 46800 38547 46800 38550 46800 38548 46801 38550 46801 38549 46801 38549 46802 38550 46802 38551 46802 38549 46803 38551 46803 38552 46803 38552 46804 38551 46804 38553 46804 38552 46805 38553 46805 38554 46805 38554 46806 38553 46806 38556 46806 38554 46807 38556 46807 38555 46807 38555 46808 38556 46808 38603 46808 38555 46809 38603 46809 38557 46809 38557 46810 38603 46810 38601 46810 38557 46811 38601 46811 38558 46811 38558 46812 38601 46812 38599 46812 38558 46813 38599 46813 38559 46813 38559 46814 38599 46814 38605 46814 38559 46815 38605 46815 38560 46815 38560 46816 38605 46816 38561 46816 38560 46817 38561 46817 38562 46817 38562 46818 38561 46818 38563 46818 38562 46819 38563 46819 38564 46819 38564 46820 38563 46820 38604 46820 38564 46821 38604 46821 38565 46821 38565 46822 38604 46822 38607 46822 38565 46823 38607 46823 38566 46823 38566 46824 38607 46824 38606 46824 38566 46825 38606 46825 38567 46825 38567 46826 38606 46826 38568 46826 38567 46827 38568 46827 38569 46827 38569 46828 38568 46828 38571 46828 38569 46829 38571 46829 38570 46829 38570 46830 38571 46830 38572 46830 38570 46831 38572 46831 38573 46831 38573 46832 38572 46832 38592 46832 38573 46833 38592 46833 38574 46833 38574 46834 38592 46834 38590 46834 38574 46835 38590 46835 38575 46835 38575 46836 38590 46836 38576 46836 38575 46837 38576 46837 38577 46837 38577 46838 38576 46838 38578 46838 38577 46839 38578 46839 38579 46839 38579 46840 38578 46840 38597 46840 38579 46841 38597 46841 38580 46841 38580 46842 38597 46842 38595 46842 38580 46843 38595 46843 38581 46843 38581 46844 38595 46844 38583 46844 38581 46845 38583 46845 38582 46845 38582 46846 38583 46846 38527 46846 38589 590 38550 590 38584 590 38584 46847 38550 46847 38547 46847 38584 590 38547 590 38585 590 38585 46848 38547 46848 38586 46848 38585 590 38586 590 38587 590 38602 46849 38556 46849 38588 46849 38588 46850 38556 46850 38553 46850 38588 590 38553 590 38589 590 38589 46851 38553 46851 38551 46851 38589 46852 38551 46852 38550 46852 38598 590 38590 590 38591 590 38591 46853 38590 46853 38592 46853 38591 590 38592 590 38618 590 38586 590 38544 590 38587 590 38587 590 38544 590 38542 590 38587 590 38542 590 38640 590 38640 590 38542 590 38593 590 38640 590 38593 590 38642 590 38593 590 38539 590 38642 590 38642 46854 38539 46854 38537 46854 38642 46855 38537 46855 38643 46855 38643 590 38537 590 38535 590 38643 590 38535 590 38646 590 38646 590 38535 590 38594 590 38646 46856 38594 46856 38647 46856 38609 46857 38595 46857 38596 46857 38596 46565 38595 46565 38597 46565 38596 590 38597 590 38615 590 38615 590 38597 590 38578 590 38615 590 38578 590 38598 590 38598 46858 38578 46858 38576 46858 38598 46859 38576 46859 38590 46859 38628 46860 38605 46860 38630 46860 38630 46861 38605 46861 38599 46861 38630 590 38599 590 38600 590 38600 46862 38599 46862 38601 46862 38600 590 38601 590 38602 590 38602 46863 38601 46863 38603 46863 38602 46864 38603 46864 38556 46864 38624 46865 38604 46865 38626 46865 38626 46866 38604 46866 38563 46866 38626 590 38563 590 38628 590 38628 590 38563 590 38561 590 38628 590 38561 590 38605 590 38592 46867 38572 46867 38618 46867 38618 46868 38572 46868 38571 46868 38618 46703 38571 46703 38619 46703 38619 46869 38571 46869 38568 46869 38619 590 38568 590 38623 590 38623 46870 38568 46870 38606 46870 38623 590 38606 590 38624 590 38624 590 38606 590 38607 590 38624 590 38607 590 38604 590 38594 590 38532 590 38647 590 38647 46871 38532 46871 38531 46871 38647 46872 38531 46872 38650 46872 38650 590 38531 590 38608 590 38650 590 38608 590 38611 590 38611 46873 38608 46873 38528 46873 38611 590 38528 590 38609 590 38609 46874 38528 46874 38583 46874 38609 46875 38583 46875 38595 46875 38612 46876 38610 46876 38611 46876 38611 46877 38610 46877 38650 46877 38611 46878 38609 46878 38612 46878 38612 46879 38609 46879 38596 46879 38612 46880 38596 46880 38613 46880 38613 46881 38596 46881 38615 46881 38613 46882 38615 46882 38614 46882 38614 46883 38615 46883 38598 46883 38614 46883 38598 46883 38616 46883 38616 46884 38598 46884 38591 46884 38616 46885 38591 46885 38617 46885 38617 46886 38591 46886 38618 46886 38617 46887 38618 46887 38620 46887 38620 46888 38618 46888 38619 46888 38620 46889 38619 46889 38621 46889 38621 46890 38619 46890 38623 46890 38621 46891 38623 46891 38622 46891 38622 46892 38623 46892 38624 46892 38622 46893 38624 46893 38625 46893 38625 46894 38624 46894 38626 46894 38625 46895 38626 46895 38627 46895 38627 46896 38626 46896 38628 46896 38627 46896 38628 46896 38629 46896 38629 46897 38628 46897 38630 46897 38629 46898 38630 46898 38631 46898 38631 46899 38630 46899 38600 46899 38631 46900 38600 46900 38632 46900 38632 46901 38600 46901 38602 46901 38632 46902 38602 46902 38633 46902 38633 46903 38602 46903 38588 46903 38633 46904 38588 46904 38634 46904 38634 46905 38588 46905 38589 46905 38634 46906 38589 46906 38635 46906 38635 46907 38589 46907 38584 46907 38635 46908 38584 46908 38636 46908 38636 46909 38584 46909 38585 46909 38636 46910 38585 46910 38637 46910 38637 46911 38585 46911 38587 46911 38637 46912 38587 46912 38638 46912 38638 46913 38587 46913 38640 46913 38638 46914 38640 46914 38639 46914 38639 46915 38640 46915 38642 46915 38639 46915 38642 46915 38641 46915 38641 46916 38642 46916 38643 46916 38641 46917 38643 46917 38644 46917 38644 46918 38643 46918 38646 46918 38644 46919 38646 46919 38645 46919 38645 46920 38646 46920 38647 46920 38645 46921 38647 46921 38648 46921 38648 46922 38647 46922 38650 46922 38648 46923 38650 46923 38649 46923 38649 46924 38650 46924 38610 46924 38652 46925 38651 46925 38728 46925 38728 46926 38651 46926 38729 46926 38728 46927 38727 46927 38652 46927 38652 46928 38727 46928 38725 46928 38652 46929 38725 46929 38653 46929 38653 46930 38725 46930 38654 46930 38653 46931 38654 46931 38655 46931 38655 46932 38654 46932 38724 46932 38655 46933 38724 46933 38656 46933 38656 46934 38724 46934 38703 46934 38656 46935 38703 46935 38657 46935 38657 46936 38703 46936 38659 46936 38657 46937 38659 46937 38658 46937 38658 46938 38659 46938 38708 46938 38658 46939 38708 46939 38660 46939 38660 46940 38708 46940 38706 46940 38660 46941 38706 46941 38661 46941 38661 46942 38706 46942 38716 46942 38661 46943 38716 46943 38663 46943 38663 46944 38716 46944 38662 46944 38663 46945 38662 46945 38664 46945 38664 46946 38662 46946 38665 46946 38664 46947 38665 46947 38667 46947 38667 46948 38665 46948 38666 46948 38667 46949 38666 46949 38668 46949 38668 46950 38666 46950 38714 46950 38668 46951 38714 46951 38670 46951 38670 46952 38714 46952 38669 46952 38670 46953 38669 46953 38671 46953 38671 46954 38669 46954 38673 46954 38671 46955 38673 46955 38672 46955 38672 46956 38673 46956 38674 46956 38672 46956 38674 46956 38675 46956 38675 46957 38674 46957 38732 46957 38675 46958 38732 46958 38676 46958 38676 46959 38732 46959 38677 46959 38676 46959 38677 46959 38678 46959 38678 46960 38677 46960 38679 46960 38678 46961 38679 46961 38680 46961 38680 46962 38679 46962 38730 46962 38680 46963 38730 46963 38681 46963 38681 46964 38730 46964 38738 46964 38681 46965 38738 46965 38682 46965 38682 46966 38738 46966 38737 46966 38682 46967 38737 46967 38683 46967 38683 46968 38737 46968 38684 46968 38683 46969 38684 46969 38685 46969 38685 46970 38684 46970 38735 46970 38685 46971 38735 46971 38686 46971 38686 46972 38735 46972 38734 46972 38686 46973 38734 46973 38687 46973 38687 46974 38734 46974 38718 46974 38687 46975 38718 46975 38688 46975 38688 46976 38718 46976 38717 46976 38688 46976 38717 46976 38689 46976 38689 46977 38717 46977 38690 46977 38689 46978 38690 46978 38691 46978 38691 46979 38690 46979 38723 46979 38691 46980 38723 46980 38692 46980 38692 46981 38723 46981 38721 46981 38692 46982 38721 46982 38693 46982 38693 46983 38721 46983 38695 46983 38693 46984 38695 46984 38694 46984 38694 46985 38695 46985 38696 46985 38694 46986 38696 46986 38697 46986 38697 46987 38696 46987 38712 46987 38697 46988 38712 46988 38698 46988 38698 46989 38712 46989 38710 46989 38698 46990 38710 46990 38699 46990 38699 46991 38710 46991 38729 46991 38699 46992 38729 46992 38700 46992 38700 46993 38729 46993 38651 46993 38707 46994 38659 46994 38701 46994 38701 46995 38659 46995 38703 46995 38701 590 38703 590 38702 590 38702 46996 38703 46996 38724 46996 38702 46997 38724 46997 38704 46997 38767 590 38716 590 38705 590 38705 46998 38716 46998 38706 46998 38705 590 38706 590 38707 590 38707 46999 38706 46999 38708 46999 38707 47000 38708 47000 38659 47000 38709 590 38710 590 38711 590 38711 47001 38710 47001 38712 47001 38711 590 38712 590 38713 590 38713 47002 38712 47002 38696 47002 38713 47003 38696 47003 38720 47003 38733 47004 38714 47004 38763 47004 38763 590 38714 590 38666 590 38763 590 38666 590 38715 590 38715 590 38666 590 38665 590 38715 47005 38665 47005 38767 47005 38767 47006 38665 47006 38662 47006 38767 590 38662 590 38716 590 38745 590 38717 590 38748 590 38748 590 38717 590 38718 590 38748 47007 38718 47007 38719 47007 38719 590 38718 590 38734 590 38719 590 38734 590 38736 590 38696 590 38695 590 38720 590 38720 47008 38695 47008 38721 47008 38720 590 38721 590 38722 590 38722 590 38721 590 38723 590 38722 590 38723 590 38745 590 38745 47009 38723 47009 38690 47009 38745 590 38690 590 38717 590 38724 590 38654 590 38704 590 38704 47010 38654 47010 38725 47010 38704 590 38725 590 38773 590 38773 47011 38725 47011 38727 47011 38773 590 38727 590 38726 590 38726 47012 38727 47012 38728 47012 38726 590 38728 590 38709 590 38709 47013 38728 47013 38729 47013 38709 47014 38729 47014 38710 47014 38753 590 38730 590 38755 590 38755 47015 38730 47015 38679 47015 38755 590 38679 590 38757 590 38757 47016 38679 47016 38677 47016 38757 47017 38677 47017 38731 47017 38677 590 38732 590 38731 590 38731 47018 38732 47018 38674 47018 38731 590 38674 590 38760 590 38760 590 38674 590 38673 590 38760 590 38673 590 38733 590 38733 47019 38673 47019 38669 47019 38733 590 38669 590 38714 590 38734 590 38735 590 38736 590 38736 47020 38735 47020 38684 47020 38736 590 38684 590 38752 590 38752 47021 38684 47021 38737 47021 38752 590 38737 590 38753 590 38753 47022 38737 47022 38738 47022 38753 47023 38738 47023 38730 47023 38740 47024 38739 47024 38726 47024 38726 47025 38739 47025 38773 47025 38726 47026 38709 47026 38740 47026 38740 47027 38709 47027 38711 47027 38740 47027 38711 47027 38741 47027 38741 47028 38711 47028 38713 47028 38741 47029 38713 47029 38742 47029 38742 47030 38713 47030 38720 47030 38742 47031 38720 47031 38743 47031 38743 47032 38720 47032 38722 47032 38743 47033 38722 47033 38744 47033 38744 47034 38722 47034 38745 47034 38744 47035 38745 47035 38746 47035 38746 47036 38745 47036 38748 47036 38746 47037 38748 47037 38747 47037 38747 47038 38748 47038 38719 47038 38747 47039 38719 47039 38749 47039 38749 47040 38719 47040 38736 47040 38749 47041 38736 47041 38750 47041 38750 47042 38736 47042 38752 47042 38750 47043 38752 47043 38751 47043 38751 47044 38752 47044 38753 47044 38751 47045 38753 47045 38754 47045 38754 47046 38753 47046 38755 47046 38754 47047 38755 47047 38756 47047 38756 47048 38755 47048 38757 47048 38756 47049 38757 47049 38758 47049 38758 47050 38757 47050 38731 47050 38758 47051 38731 47051 38759 47051 38759 47052 38731 47052 38760 47052 38759 47053 38760 47053 38761 47053 38761 47054 38760 47054 38733 47054 38761 47055 38733 47055 38762 47055 38762 47056 38733 47056 38763 47056 38762 47057 38763 47057 38764 47057 38764 47058 38763 47058 38715 47058 38764 47059 38715 47059 38765 47059 38765 47060 38715 47060 38767 47060 38765 47061 38767 47061 38766 47061 38766 47062 38767 47062 38705 47062 38766 47063 38705 47063 38768 47063 38768 47064 38705 47064 38707 47064 38768 47065 38707 47065 38769 47065 38769 47066 38707 47066 38701 47066 38769 47067 38701 47067 38770 47067 38770 47068 38701 47068 38702 47068 38770 47069 38702 47069 38771 47069 38771 47070 38702 47070 38704 47070 38771 47071 38704 47071 38772 47071 38772 47072 38704 47072 38773 47072 38772 47073 38773 47073 38774 47073 38774 47074 38773 47074 38739 47074 38775 47075 38828 47075 38776 47075 38776 47076 38828 47076 38845 47076 38776 47077 38777 47077 38775 47077 38775 47078 38777 47078 38779 47078 38775 47079 38779 47079 38778 47079 38778 47080 38779 47080 38844 47080 38778 47081 38844 47081 38780 47081 38780 47082 38844 47082 38781 47082 38780 47083 38781 47083 38782 47083 38782 47084 38781 47084 38833 47084 38782 47085 38833 47085 38783 47085 38783 47086 38833 47086 38784 47086 38783 47087 38784 47087 38785 47087 38785 47088 38784 47088 38786 47088 38785 47089 38786 47089 38787 47089 38787 47090 38786 47090 38831 47090 38787 47091 38831 47091 38788 47091 38788 47092 38831 47092 38790 47092 38788 47093 38790 47093 38789 47093 38789 47094 38790 47094 38852 47094 38789 47095 38852 47095 38791 47095 38791 47096 38852 47096 38851 47096 38791 47097 38851 47097 38792 47097 38792 47098 38851 47098 38849 47098 38792 47099 38849 47099 38793 47099 38793 47100 38849 47100 38794 47100 38793 47101 38794 47101 38795 47101 38795 47102 38794 47102 38846 47102 38795 47103 38846 47103 38796 47103 38796 47104 38846 47104 38797 47104 38796 47105 38797 47105 38798 47105 38798 47106 38797 47106 38835 47106 38798 47107 38835 47107 38799 47107 38799 47108 38835 47108 38800 47108 38799 47109 38800 47109 38801 47109 38801 47110 38800 47110 38840 47110 38801 47111 38840 47111 38802 47111 38802 47112 38840 47112 38803 47112 38802 47113 38803 47113 38804 47113 38804 47114 38803 47114 38806 47114 38804 47115 38806 47115 38805 47115 38805 47116 38806 47116 38836 47116 38805 47117 38836 47117 38808 47117 38808 47118 38836 47118 38807 47118 38808 47119 38807 47119 38810 47119 38810 47120 38807 47120 38809 47120 38810 47121 38809 47121 38811 47121 38811 47122 38809 47122 38812 47122 38811 47123 38812 47123 38814 47123 38814 47124 38812 47124 38813 47124 38814 47125 38813 47125 38815 47125 38815 47126 38813 47126 38816 47126 38815 47127 38816 47127 38817 47127 38817 47128 38816 47128 38855 47128 38817 47129 38855 47129 38818 47129 38818 47130 38855 47130 38854 47130 38818 47131 38854 47131 38819 47131 38819 47132 38854 47132 38853 47132 38819 47133 38853 47133 38820 47133 38820 47134 38853 47134 38842 47134 38820 47135 38842 47135 38821 47135 38821 47136 38842 47136 38841 47136 38821 47137 38841 47137 38822 47137 38822 47138 38841 47138 38823 47138 38822 47139 38823 47139 38824 47139 38824 47140 38823 47140 38830 47140 38824 47141 38830 47141 38825 47141 38825 47142 38830 47142 38829 47142 38825 47143 38829 47143 38826 47143 38826 47144 38829 47144 38845 47144 38826 47145 38845 47145 38827 47145 38827 47146 38845 47146 38828 47146 38889 590 38790 590 38892 590 38892 47147 38790 47147 38831 47147 38892 590 38831 590 38832 590 38875 590 38809 590 38877 590 38877 590 38809 590 38807 590 38877 590 38807 590 38837 590 38862 590 38829 590 38864 590 38864 590 38829 590 38830 590 38864 47148 38830 47148 38865 47148 38865 45950 38830 45950 38823 45950 38865 590 38823 590 38867 590 38831 590 38786 590 38832 590 38832 47149 38786 47149 38784 47149 38832 590 38784 590 38894 590 38894 47150 38784 47150 38833 47150 38894 590 38833 590 38834 590 38834 47151 38833 47151 38781 47151 38834 590 38781 590 38843 590 38882 47152 38835 47152 38884 47152 38884 590 38835 590 38797 590 38884 47153 38797 47153 38847 47153 38807 590 38836 590 38837 590 38837 590 38836 590 38806 590 38837 590 38806 590 38838 590 38838 590 38806 590 38803 590 38838 590 38803 590 38839 590 38839 590 38803 590 38840 590 38839 590 38840 590 38882 590 38882 590 38840 590 38800 590 38882 590 38800 590 38835 590 38823 590 38841 590 38867 590 38867 47154 38841 47154 38842 47154 38867 590 38842 590 38869 590 38869 47155 38842 47155 38853 47155 38869 47156 38853 47156 38870 47156 38781 590 38844 590 38843 590 38843 590 38844 590 38779 590 38843 590 38779 590 38861 590 38861 47157 38779 47157 38777 47157 38861 590 38777 590 38859 590 38859 47158 38777 47158 38776 47158 38859 590 38776 590 38862 590 38862 47159 38776 47159 38845 47159 38862 590 38845 590 38829 590 38797 47160 38846 47160 38847 47160 38847 590 38846 590 38794 590 38847 590 38794 590 38848 590 38848 47161 38794 47161 38849 47161 38848 590 38849 590 38850 590 38850 590 38849 590 38851 590 38850 590 38851 590 38889 590 38889 590 38851 590 38852 590 38889 47162 38852 47162 38790 47162 38853 590 38854 590 38870 590 38870 47163 38854 47163 38855 47163 38870 47164 38855 47164 38856 47164 38856 47165 38855 47165 38816 47165 38856 47166 38816 47166 38857 47166 38857 47167 38816 47167 38813 47167 38857 590 38813 590 38875 590 38875 47168 38813 47168 38812 47168 38875 590 38812 590 38809 590 38858 47169 38860 47169 38859 47169 38859 47170 38860 47170 38861 47170 38859 47171 38862 47171 38858 47171 38858 47172 38862 47172 38864 47172 38858 47173 38864 47173 38863 47173 38863 47174 38864 47174 38865 47174 38863 47175 38865 47175 38866 47175 38866 47176 38865 47176 38867 47176 38866 47177 38867 47177 38868 47177 38868 47178 38867 47178 38869 47178 38868 47179 38869 47179 38871 47179 38871 47180 38869 47180 38870 47180 38871 47181 38870 47181 38872 47181 38872 47182 38870 47182 38856 47182 38872 47183 38856 47183 38873 47183 38873 47184 38856 47184 38857 47184 38873 47185 38857 47185 38874 47185 38874 47186 38857 47186 38875 47186 38874 47187 38875 47187 38876 47187 38876 47188 38875 47188 38877 47188 38876 47189 38877 47189 38878 47189 38878 47190 38877 47190 38837 47190 38878 47191 38837 47191 38879 47191 38879 47192 38837 47192 38838 47192 38879 47193 38838 47193 38880 47193 38880 47194 38838 47194 38839 47194 38880 47195 38839 47195 38881 47195 38881 47196 38839 47196 38882 47196 38881 47197 38882 47197 38883 47197 38883 47198 38882 47198 38884 47198 38883 47199 38884 47199 38885 47199 38885 47200 38884 47200 38847 47200 38885 47201 38847 47201 38886 47201 38886 47202 38847 47202 38848 47202 38886 47203 38848 47203 38887 47203 38887 47204 38848 47204 38850 47204 38887 47205 38850 47205 38888 47205 38888 47206 38850 47206 38889 47206 38888 47207 38889 47207 38890 47207 38890 47208 38889 47208 38892 47208 38890 47209 38892 47209 38891 47209 38891 47210 38892 47210 38832 47210 38891 47210 38832 47210 38893 47210 38893 47211 38832 47211 38894 47211 38893 47212 38894 47212 38895 47212 38895 47213 38894 47213 38834 47213 38895 47214 38834 47214 38896 47214 38896 47215 38834 47215 38843 47215 38896 47216 38843 47216 38897 47216 38897 47217 38843 47217 38861 47217 38897 47218 38861 47218 38898 47218 38898 47219 38861 47219 38860 47219 38900 47220 38899 47220 38987 47220 38987 47221 38899 47221 38949 47221 38987 47222 38986 47222 38900 47222 38900 47223 38986 47223 38984 47223 38900 47224 38984 47224 38901 47224 38901 47225 38984 47225 38983 47225 38901 47225 38983 47225 38902 47225 38902 47226 38983 47226 38962 47226 38902 47227 38962 47227 38903 47227 38903 47228 38962 47228 38960 47228 38903 47229 38960 47229 38904 47229 38904 47230 38960 47230 38905 47230 38904 47231 38905 47231 38906 47231 38906 47232 38905 47232 38907 47232 38906 47232 38907 47232 38908 47232 38908 47233 38907 47233 38909 47233 38908 47234 38909 47234 38910 47234 38910 47235 38909 47235 38965 47235 38910 47236 38965 47236 38911 47236 38911 47237 38965 47237 38912 47237 38911 47238 38912 47238 38913 47238 38913 47239 38912 47239 38964 47239 38913 47239 38964 47239 38914 47239 38914 47240 38964 47240 38915 47240 38914 47241 38915 47241 38916 47241 38916 47242 38915 47242 38954 47242 38916 47243 38954 47243 38917 47243 38917 47244 38954 47244 38953 47244 38917 47245 38953 47245 38918 47245 38918 47246 38953 47246 38919 47246 38918 47247 38919 47247 38921 47247 38921 47248 38919 47248 38920 47248 38921 47249 38920 47249 38922 47249 38922 47250 38920 47250 38970 47250 38922 47251 38970 47251 38923 47251 38923 47252 38970 47252 38968 47252 38923 47253 38968 47253 38924 47253 38924 47254 38968 47254 38967 47254 38924 47255 38967 47255 38925 47255 38925 47256 38967 47256 38926 47256 38925 47257 38926 47257 38927 47257 38927 47258 38926 47258 38928 47258 38927 47259 38928 47259 38929 47259 38929 47260 38928 47260 38971 47260 38929 47261 38971 47261 38930 47261 38930 47262 38971 47262 38931 47262 38930 47263 38931 47263 38932 47263 38932 47264 38931 47264 38977 47264 38932 47265 38977 47265 38933 47265 38933 47266 38977 47266 38975 47266 38933 47267 38975 47267 38934 47267 38934 47268 38975 47268 38935 47268 38934 47269 38935 47269 38936 47269 38936 47270 38935 47270 38972 47270 38936 47271 38972 47271 38938 47271 38938 47272 38972 47272 38937 47272 38938 47273 38937 47273 38939 47273 38939 47274 38937 47274 38940 47274 38939 47275 38940 47275 38941 47275 38941 47276 38940 47276 38958 47276 38941 47277 38958 47277 38942 47277 38942 47278 38958 47278 38982 47278 38942 47279 38982 47279 38943 47279 38943 47280 38982 47280 38944 47280 38943 47281 38944 47281 38945 47281 38945 47282 38944 47282 38979 47282 38945 47283 38979 47283 38947 47283 38947 47284 38979 47284 38946 47284 38947 47285 38946 47285 38948 47285 38948 47286 38946 47286 38949 47286 38948 47287 38949 47287 38950 47287 38950 47288 38949 47288 38899 47288 38951 47289 38920 47289 39010 47289 39010 47290 38920 47290 38919 47290 39010 590 38919 590 38952 590 38919 590 38953 590 38952 590 38952 47291 38953 47291 38954 47291 38952 590 38954 590 38955 590 38955 47292 38954 47292 38915 47292 38955 590 38915 590 38956 590 38956 47293 38915 47293 38964 47293 38956 590 38964 590 38957 590 38981 590 38958 590 38995 590 38995 47294 38958 47294 38940 47294 38995 590 38940 590 38997 590 38966 47295 38905 47295 38959 47295 38959 590 38905 590 38960 590 38959 590 38960 590 38961 590 38961 590 38960 590 38962 590 38961 47296 38962 47296 38963 47296 38964 590 38912 590 38957 590 38957 590 38912 590 38965 590 38957 590 38965 590 39016 590 39016 590 38965 590 38909 590 39016 590 38909 590 38966 590 38966 590 38909 590 38907 590 38966 47297 38907 47297 38905 47297 39004 47298 38926 47298 39007 47298 39007 47299 38926 47299 38967 47299 39007 590 38967 590 38969 590 38969 47300 38967 47300 38968 47300 38969 590 38968 590 38951 590 38951 47301 38968 47301 38970 47301 38951 47302 38970 47302 38920 47302 38976 47303 38931 47303 39002 47303 39002 47304 38931 47304 38971 47304 39002 590 38971 590 39004 590 39004 590 38971 590 38928 590 39004 590 38928 590 38926 590 38940 47305 38937 47305 38997 47305 38997 47306 38937 47306 38972 47306 38997 47164 38972 47164 38973 47164 38973 47307 38972 47307 38935 47307 38973 590 38935 590 38974 590 38974 47308 38935 47308 38975 47308 38974 590 38975 590 38976 590 38976 590 38975 590 38977 590 38976 590 38977 590 38931 590 38978 47309 38946 47309 38992 47309 38992 46102 38946 46102 38979 46102 38992 590 38979 590 38980 590 38980 590 38979 590 38944 590 38980 590 38944 590 38981 590 38981 47310 38944 47310 38982 47310 38981 47311 38982 47311 38958 47311 38962 590 38983 590 38963 590 38963 47312 38983 47312 38984 47312 38963 47313 38984 47313 38985 47313 38985 590 38984 590 38986 590 38985 590 38986 590 38989 590 38989 47314 38986 47314 38987 47314 38989 590 38987 590 38978 590 38978 47315 38987 47315 38949 47315 38978 47316 38949 47316 38946 47316 38990 47317 38988 47317 38989 47317 38989 47318 38988 47318 38985 47318 38989 47319 38978 47319 38990 47319 38990 47320 38978 47320 38992 47320 38990 47321 38992 47321 38991 47321 38991 47322 38992 47322 38980 47322 38991 47323 38980 47323 38993 47323 38993 47324 38980 47324 38981 47324 38993 47324 38981 47324 38994 47324 38994 47325 38981 47325 38995 47325 38994 47326 38995 47326 38996 47326 38996 47327 38995 47327 38997 47327 38996 47328 38997 47328 38998 47328 38998 47329 38997 47329 38973 47329 38998 47330 38973 47330 38999 47330 38999 47331 38973 47331 38974 47331 38999 47332 38974 47332 39000 47332 39000 47333 38974 47333 38976 47333 39000 47334 38976 47334 39001 47334 39001 47335 38976 47335 39002 47335 39001 47336 39002 47336 39003 47336 39003 47337 39002 47337 39004 47337 39003 47337 39004 47337 39005 47337 39005 47338 39004 47338 39007 47338 39005 47339 39007 47339 39006 47339 39006 47340 39007 47340 38969 47340 39006 47341 38969 47341 39008 47341 39008 47342 38969 47342 38951 47342 39008 47343 38951 47343 39009 47343 39009 47344 38951 47344 39010 47344 39009 47345 39010 47345 39011 47345 39011 47346 39010 47346 38952 47346 39011 47347 38952 47347 39012 47347 39012 47348 38952 47348 38955 47348 39012 47349 38955 47349 39013 47349 39013 47350 38955 47350 38956 47350 39013 47351 38956 47351 39014 47351 39014 47352 38956 47352 38957 47352 39014 47353 38957 47353 39015 47353 39015 47354 38957 47354 39016 47354 39015 47355 39016 47355 39017 47355 39017 47356 39016 47356 38966 47356 39017 47356 38966 47356 39018 47356 39018 47357 38966 47357 38959 47357 39018 47358 38959 47358 39019 47358 39019 47359 38959 47359 38961 47359 39019 47360 38961 47360 39020 47360 39020 47361 38961 47361 38963 47361 39020 47362 38963 47362 39021 47362 39021 47363 38963 47363 38985 47363 39021 47364 38985 47364 39022 47364 39022 47365 38985 47365 38988 47365 39023 960 39039 960 39041 960 39024 47366 39025 47366 39029 47366 39029 47367 39025 47367 39026 47367 39029 47368 39026 47368 39027 47368 39027 960 39028 960 39029 960 39029 47369 39028 47369 39031 47369 39029 47370 39031 47370 39034 47370 39045 47371 39030 47371 39031 47371 39030 960 39032 960 39031 960 39031 47372 39032 47372 39033 47372 39031 47373 39033 47373 39034 47373 39024 960 39029 960 39041 960 39041 47374 39029 47374 39035 47374 39041 47375 39035 47375 39023 47375 39036 960 39055 960 39046 960 39037 960 39038 960 39041 960 39041 47376 39038 47376 39043 47376 39039 47377 39040 47377 39041 47377 39041 47378 39040 47378 39042 47378 39041 47379 39042 47379 39037 47379 39043 47380 39044 47380 39041 47380 39041 960 39044 960 39053 960 39041 47381 39053 47381 39054 47381 39045 960 39031 960 39046 960 39046 47382 39031 47382 39047 47382 39046 47383 39047 47383 39036 47383 39048 960 39053 960 39049 960 39049 47384 39053 47384 39050 47384 39048 47385 39051 47385 39053 47385 39053 47386 39051 47386 39052 47386 39053 47387 39052 47387 39054 47387 39055 960 39056 960 39046 960 39046 47388 39056 47388 39057 47388 39046 960 39057 960 39058 960 39058 960 39059 960 39046 960 39046 960 39059 960 39060 960 39046 960 39060 960 39061 960 39062 47389 39063 47389 39064 47389 39064 47390 39063 47390 39070 47390 39064 47391 39070 47391 39071 47391 39065 47392 39066 47393 39068 47394 39068 47395 39066 47395 39425 47395 39068 47396 39425 47396 39481 47396 39481 47397 39067 47397 39068 47397 39068 47398 39067 47398 39069 47398 39068 47399 39069 47399 39070 47399 39070 47400 39069 47400 39484 47400 39070 47401 39484 47401 39071 47401 39072 47402 39074 47402 39151 47402 39072 47403 39341 47403 39074 47403 39074 47404 39341 47404 39073 47404 39074 47405 39073 47405 39075 47405 39073 47406 39344 47406 39075 47406 39075 47407 39344 47407 39076 47407 39075 47408 39076 47408 39078 47408 39076 47409 39347 47409 39078 47409 39078 47410 39347 47410 39077 47410 39078 47411 39077 47411 39079 47411 39077 47412 39350 47412 39079 47412 39079 47413 39350 47413 39081 47413 39079 47414 39081 47414 39080 47414 39081 47415 39351 47415 39080 47415 39080 47416 39351 47416 39082 47416 39080 47417 39082 47417 39083 47417 39082 47418 39352 47418 39083 47418 39083 47419 39352 47419 39084 47419 39083 47420 39084 47420 39085 47420 39084 47421 39354 47421 39085 47421 39085 47422 39354 47422 39086 47422 39085 47423 39086 47423 39088 47423 39086 47424 39087 47424 39088 47424 39088 47425 39087 47425 39089 47425 39088 47426 39089 47426 39090 47426 39089 47427 39091 47427 39090 47427 39090 47428 39091 47428 39092 47428 39090 47429 39092 47429 39094 47429 39092 47430 39093 47430 39094 47430 39094 47431 39093 47431 39095 47431 39094 47432 39095 47432 39096 47432 39095 47433 39097 47433 39096 47433 39096 47434 39097 47434 39359 47434 39096 47435 39359 47435 39098 47435 39359 47436 39099 47436 39098 47436 39098 47437 39099 47437 39100 47437 39098 47438 39100 47438 39101 47438 39100 47439 39360 47439 39101 47439 39101 47440 39360 47440 39362 47440 39101 47441 39362 47441 39102 47441 39362 47442 39363 47442 39102 47442 39102 47443 39363 47443 39104 47443 39102 47444 39104 47444 39103 47444 39104 47445 39105 47445 39103 47445 39103 47446 39105 47446 39365 47446 39103 47447 39365 47447 39106 47447 39365 47448 39366 47448 39106 47448 39106 47449 39366 47449 39367 47449 39106 47450 39367 47450 39107 47450 39367 47451 39370 47451 39107 47451 39107 47452 39370 47452 39371 47452 39107 47453 39371 47453 39108 47453 39371 47454 39373 47454 39108 47454 39108 47455 39373 47455 39109 47455 39108 47456 39109 47456 39111 47456 39109 47457 39110 47457 39111 47457 39111 47458 39110 47458 39112 47458 39111 47459 39112 47459 39113 47459 39112 47460 39374 47460 39113 47460 39113 47461 39374 47461 39375 47461 39113 47462 39375 47462 39114 47462 39375 47463 39115 47463 39114 47463 39114 47464 39115 47464 39117 47464 39114 47465 39117 47465 39116 47465 39117 47466 39118 47466 39116 47466 39116 47467 39118 47467 39119 47467 39116 47468 39119 47468 39121 47468 39119 47469 39120 47469 39121 47469 39121 47470 39120 47470 39122 47470 39121 47471 39122 47471 39123 47471 39122 47472 39378 47472 39123 47472 39123 47473 39378 47473 39379 47473 39123 47474 39379 47474 39124 47474 39379 47475 39125 47475 39124 47475 39124 47476 39125 47476 39126 47476 39124 47477 39126 47477 39127 47477 39126 47478 39382 47478 39127 47478 39127 47479 39382 47479 39384 47479 39127 47480 39384 47480 39128 47480 39384 47481 39129 47481 39128 47481 39128 47482 39129 47482 39387 47482 39128 47483 39387 47483 39131 47483 39387 47484 39130 47484 39131 47484 39131 47485 39130 47485 39388 47485 39131 47486 39388 47486 39133 47486 39388 47487 39392 47487 39133 47487 39133 47488 39392 47488 39132 47488 39133 47489 39132 47489 39134 47489 39132 47490 39135 47490 39134 47490 39134 47491 39135 47491 39395 47491 39134 47492 39395 47492 39136 47492 39395 47493 39397 47493 39136 47493 39136 47494 39397 47494 39137 47494 39136 47495 39137 47495 39139 47495 39137 47496 39138 47496 39139 47496 39139 47497 39138 47497 39141 47497 39139 47498 39141 47498 39140 47498 39141 47499 39142 47499 39140 47499 39140 47500 39142 47500 39144 47500 39140 47501 39144 47501 39143 47501 39144 47502 39401 47502 39143 47502 39143 47503 39401 47503 39145 47503 39143 47504 39145 47504 39147 47504 39145 47505 39146 47505 39147 47505 39147 47506 39146 47506 39404 47506 39147 47507 39404 47507 39148 47507 39404 47508 39405 47508 39148 47508 39148 47509 39405 47509 39406 47509 39148 47510 39406 47510 39149 47510 39406 47511 39150 47511 39149 47511 39149 47512 39150 47512 39336 47512 39149 47513 39336 47513 39151 47513 39151 47514 39336 47514 39338 47514 39151 47515 39338 47515 39072 47515 39417 47516 39152 47516 39262 47516 39417 47517 39416 47518 39152 47519 39152 47520 39416 47520 39153 47520 39152 47521 39153 47521 39154 47521 39154 47522 39153 47522 39155 47522 39154 47523 39155 47523 39157 47523 39155 47524 39156 47525 39157 47526 39157 47527 39156 47527 39158 47527 39157 47528 39158 47528 39159 47528 39158 47529 39540 47529 39159 47529 39159 47530 39540 47530 39160 47530 39159 47531 39160 47531 39264 47531 39264 47532 39160 47532 39161 47532 39264 47533 39161 47533 39265 47533 39265 47534 39161 47534 39162 47534 39265 47535 39162 47535 39164 47535 39164 47536 39162 47536 39415 47536 39415 47537 39163 47537 39164 47537 39164 47538 39163 47538 39558 47538 39164 47539 39558 47539 39266 47539 39266 47540 39558 47540 39557 47540 39266 47541 39557 47541 39268 47541 39268 47542 39557 47542 39165 47542 39268 47543 39165 47543 39270 47543 39270 47544 39165 47544 39569 47544 39569 47545 39567 47545 39270 47545 39270 47546 39567 47546 39166 47546 39270 47547 39166 47547 39168 47547 39168 47548 39166 47549 39167 47550 39168 47551 39167 47551 39273 47551 39273 47552 39167 47552 39414 47552 39273 47553 39414 47553 39274 47553 39274 47554 39414 47554 39169 47554 39169 47555 39581 47555 39274 47555 39274 47556 39581 47556 39580 47556 39274 47557 39580 47557 39170 47557 39170 47558 39580 47558 39172 47558 39170 47559 39172 47559 39171 47559 39171 47560 39172 47560 39173 47560 39171 47561 39173 47561 39174 47561 39174 47562 39173 47562 39175 47562 39175 47563 39176 47563 39174 47563 39174 47564 39176 47565 39177 47566 39174 47567 39177 47567 39277 47567 39277 47568 39177 47568 39178 47568 39277 47569 39178 47569 39278 47569 39278 47570 39178 47570 39179 47570 39278 47571 39179 47571 39279 47571 39179 47572 39180 47572 39279 47572 39279 47573 39180 47573 39181 47573 39279 47574 39181 47574 39182 47574 39181 47575 39183 47575 39182 47575 39182 47576 39183 47576 39184 47576 39182 47577 39184 47577 39283 47577 39283 47578 39184 47578 39185 47578 39283 47579 39185 47579 39186 47579 39185 47580 39602 47580 39186 47580 39186 47581 39602 47581 39187 47581 39186 47582 39187 47582 39284 47582 39187 47583 39610 47583 39284 47583 39284 47584 39610 47584 39609 47584 39284 47585 39609 47586 39188 47587 39188 47588 39609 47588 39607 47588 39188 47589 39607 47589 39189 47589 39189 47590 39607 47590 39606 47590 39189 47591 39606 47591 39288 47591 39288 47592 39606 47592 39620 47592 39620 47593 39190 47593 39288 47593 39288 47594 39190 47594 39191 47594 39288 47595 39191 47595 39289 47595 39289 47596 39191 47596 39192 47596 39289 47597 39192 47597 39193 47597 39193 47598 39192 47598 39194 47598 39193 47599 39194 47599 39293 47599 39293 47600 39194 47601 39195 47602 39195 47603 39196 47603 39293 47603 39293 47604 39196 47604 39197 47604 39293 47605 39197 47605 39295 47605 39295 47606 39197 47606 39632 47606 39295 47607 39632 47607 39199 47607 39199 47608 39632 47608 39198 47608 39199 47609 39198 47609 39201 47609 39201 47610 39198 47610 39200 47610 39200 47611 39642 47611 39201 47611 39201 47612 39642 47612 39644 47612 39201 47613 39644 47613 39297 47613 39297 47614 39644 47615 39202 47616 39297 47617 39202 47617 39298 47617 39298 47618 39202 47618 39203 47618 39298 47619 39203 47619 39300 47619 39300 47620 39203 47620 39651 47620 39651 47621 39411 47621 39300 47621 39300 47622 39411 47622 39204 47622 39300 47623 39204 47623 39302 47623 39302 47624 39204 47624 39205 47624 39302 47625 39205 47625 39303 47625 39303 47626 39205 47626 39409 47626 39303 47627 39409 47627 39305 47627 39409 47628 39206 47628 39305 47628 39305 47629 39206 47629 39207 47629 39305 47630 39207 47630 39308 47630 39207 47631 39208 47631 39308 47631 39308 47632 39208 47632 39209 47632 39308 47633 39209 47633 39309 47633 39309 47634 39209 47634 39210 47634 39309 47635 39210 47635 39311 47635 39210 47636 39668 47636 39311 47636 39311 47637 39668 47637 39211 47637 39311 47638 39211 47638 39213 47638 39211 47639 39212 47639 39213 47639 39213 47640 39212 47640 39214 47640 39213 47641 39214 47641 39314 47641 39314 47642 39214 47642 39672 47642 39314 47643 39672 47643 39216 47643 39216 47644 39672 47644 39215 47644 39216 47645 39215 47645 39218 47645 39218 47646 39215 47646 39680 47646 39680 47647 39217 47647 39218 47647 39218 47648 39217 47648 39219 47648 39218 47649 39219 47649 39220 47649 39220 47650 39219 47650 39688 47650 39220 47651 39688 47651 39317 47651 39317 47652 39688 47652 39699 47652 39317 47653 39699 47653 39221 47653 39221 47654 39699 47654 39698 47654 39698 47655 39222 47655 39221 47655 39221 47656 39222 47656 39223 47656 39221 47657 39223 47657 39320 47657 39320 47658 39223 47658 39224 47658 39320 47659 39224 47659 39225 47659 39225 47660 39224 47660 39408 47660 39225 47661 39408 47661 39227 47661 39227 47662 39408 47662 39226 47662 39226 47663 39228 47663 39227 47663 39227 47664 39228 47664 39711 47664 39227 47665 39711 47665 39321 47665 39321 47666 39711 47666 39710 47666 39321 47667 39710 47667 39229 47667 39229 47668 39710 47668 39715 47668 39229 47669 39715 47669 39322 47669 39322 47670 39715 47670 39230 47670 39230 47671 39723 47671 39322 47671 39322 47672 39723 47672 39722 47672 39322 47673 39722 47673 39231 47673 39231 47674 39722 47674 39232 47674 39231 47675 39232 47675 39233 47675 39233 47676 39232 47676 39234 47676 39233 47677 39234 47677 39324 47677 39234 47678 39235 47678 39324 47678 39324 47679 39235 47679 39236 47679 39324 47680 39236 47680 39237 47680 39236 47681 39238 47681 39237 47681 39237 47682 39238 47682 39239 47682 39237 47683 39239 47683 39240 47683 39240 47684 39239 47684 39241 47684 39240 47685 39241 47685 39242 47685 39241 47686 39469 47686 39242 47686 39242 47687 39469 47687 39474 47687 39242 47688 39474 47688 39243 47688 39474 47689 39423 47689 39243 47689 39243 47690 39423 47690 39478 47690 39243 47691 39478 47691 39325 47691 39325 47692 39478 47692 39477 47692 39325 47693 39477 47693 39244 47693 39244 47694 39477 47694 39476 47694 39244 47695 39476 47696 39246 47697 39246 47698 39476 47698 39489 47698 39489 47699 39488 47699 39246 47699 39246 47700 39488 47701 39245 47702 39246 47703 39245 47703 39328 47703 39328 47704 39245 47705 39247 47705 39328 47706 39247 47706 39249 47706 39249 47707 39247 47707 39248 47707 39249 47708 39248 47708 39251 47708 39251 47709 39248 47710 39500 47711 39500 47712 39250 47712 39251 47712 39251 47713 39250 47714 39502 47715 39251 47716 39502 47716 39329 47716 39329 47717 39502 47717 39501 47717 39329 47718 39501 47718 39252 47718 39252 47719 39501 47719 39512 47719 39252 47720 39512 47720 39332 47720 39332 47721 39512 47721 39514 47721 39514 47722 39513 47722 39332 47722 39332 47723 39513 47723 39254 47723 39332 47724 39254 47724 39253 47724 39253 47725 39254 47725 39255 47725 39253 47726 39255 47726 39256 47726 39256 47727 39255 47727 39258 47727 39256 47728 39258 47728 39257 47728 39257 47729 39258 47729 39420 47729 39420 47730 39526 47730 39257 47730 39257 47731 39526 47731 39419 47731 39257 47732 39419 47732 39259 47732 39259 47733 39419 47733 39533 47733 39259 47734 39533 47734 39261 47734 39261 47735 39533 47735 39532 47735 39261 47736 39532 47736 39262 47736 39262 47737 39532 47737 39260 47737 39262 47738 39260 47738 39417 47738 39335 47739 39259 47739 39337 47739 39337 47740 39259 47740 39261 47740 39337 47741 39261 47741 39339 47741 39339 47742 39261 47742 39262 47742 39339 47743 39262 47743 39340 47743 39340 47744 39262 47744 39152 47744 39340 47745 39152 47745 39342 47745 39342 47746 39152 47746 39154 47746 39342 47747 39154 47747 39343 47747 39343 47748 39154 47748 39157 47748 39343 47749 39157 47749 39263 47749 39263 47750 39157 47750 39159 47750 39263 47751 39159 47751 39345 47751 39345 47752 39159 47752 39264 47752 39345 47753 39264 47753 39346 47753 39346 47754 39264 47754 39265 47754 39346 47755 39265 47755 39348 47755 39348 47756 39265 47756 39164 47756 39348 47757 39164 47757 39349 47757 39349 47758 39164 47758 39266 47758 39349 47759 39266 47759 39267 47759 39267 47760 39266 47760 39268 47760 39267 47761 39268 47761 39269 47761 39269 47762 39268 47762 39270 47762 39269 47763 39270 47763 39271 47763 39271 47764 39270 47764 39168 47764 39271 47765 39168 47765 39272 47765 39272 47766 39168 47766 39273 47766 39272 47767 39273 47767 39353 47767 39353 47768 39273 47768 39274 47768 39353 47769 39274 47769 39275 47769 39275 47770 39274 47771 39170 47771 39275 47772 39170 47772 39276 47772 39276 47773 39170 47774 39171 47775 39276 47776 39171 47777 39355 47776 39355 47778 39171 47778 39174 47778 39355 47779 39174 47779 39356 47779 39356 47780 39174 47780 39277 47780 39356 47781 39277 47781 39357 47781 39357 47782 39277 47783 39278 47784 39357 47785 39278 47785 39280 47785 39280 47786 39278 47787 39279 47787 39280 47788 39279 47788 39281 47788 39281 47789 39279 47789 39182 47789 39281 47790 39182 47790 39282 47790 39282 47791 39182 47791 39283 47791 39282 47792 39283 47792 39358 47792 39358 47793 39283 47793 39186 47793 39358 47794 39186 47794 39285 47794 39285 47795 39186 47796 39284 47796 39285 47797 39284 47798 39286 47799 39286 47800 39284 47801 39188 47802 39286 47803 39188 47803 39287 47803 39287 47804 39188 47804 39189 47804 39287 47805 39189 47805 39361 47805 39361 47806 39189 47807 39288 47808 39361 47809 39288 47810 39290 47811 39290 47812 39288 47812 39289 47812 39290 47813 39289 47813 39291 47813 39291 47814 39289 47815 39193 47816 39291 47817 39193 47817 39292 47817 39292 47818 39193 47818 39293 47818 39292 47819 39293 47819 39364 47819 39364 47820 39293 47820 39295 47820 39364 47821 39295 47822 39294 47823 39294 47824 39295 47825 39199 47826 39294 47827 39199 47827 39368 47827 39368 47828 39199 47829 39201 47830 39368 47831 39201 47831 39369 47831 39369 47832 39201 47832 39297 47832 39369 47833 39297 47834 39296 47833 39296 47835 39297 47836 39298 47837 39296 47838 39298 47838 39299 47838 39299 47839 39298 47839 39300 47839 39299 47840 39300 47840 39372 47840 39372 47841 39300 47841 39302 47841 39372 47842 39302 47842 39301 47842 39301 47843 39302 47843 39303 47843 39301 47844 39303 47844 39304 47844 39304 47845 39303 47845 39305 47845 39304 47846 39305 47846 39306 47846 39306 47847 39305 47847 39308 47847 39306 47848 39308 47848 39307 47848 39307 47849 39308 47849 39309 47849 39307 47850 39309 47850 39310 47850 39310 47851 39309 47851 39311 47851 39310 47852 39311 47852 39312 47852 39312 47853 39311 47853 39213 47853 39312 47854 39213 47854 39376 47854 39376 47855 39213 47855 39314 47855 39376 47856 39314 47856 39313 47856 39313 47857 39314 47857 39216 47857 39313 47858 39216 47858 39315 47858 39315 47859 39216 47859 39218 47859 39315 47860 39218 47860 39316 47860 39316 47861 39218 47861 39220 47861 39316 47862 39220 47862 39377 47862 39377 47863 39220 47863 39317 47863 39377 47864 39317 47864 39318 47864 39318 47865 39317 47865 39221 47865 39318 47866 39221 47866 39319 47866 39319 47867 39221 47868 39320 47869 39319 47870 39320 47870 39380 47870 39380 47871 39320 47871 39225 47871 39380 47872 39225 47872 39381 47872 39381 47873 39225 47873 39227 47873 39381 47874 39227 47874 39383 47874 39383 47875 39227 47875 39321 47875 39383 47876 39321 47876 39385 47876 39385 47877 39321 47877 39229 47877 39385 47878 39229 47878 39386 47878 39386 47879 39229 47879 39322 47879 39386 47880 39322 47880 39323 47880 39323 47881 39322 47881 39231 47881 39323 47882 39231 47882 39389 47882 39389 47883 39231 47883 39233 47883 39389 47884 39233 47884 39390 47884 39390 47885 39233 47885 39324 47885 39390 47886 39324 47886 39391 47886 39391 47887 39324 47887 39237 47887 39391 47888 39237 47888 39393 47888 39393 47889 39237 47890 39240 47891 39393 47892 39240 47892 39394 47892 39394 47893 39240 47893 39242 47893 39394 47894 39242 47894 39396 47894 39396 47895 39242 47895 39243 47895 39396 47896 39243 47896 39398 47896 39398 47897 39243 47897 39325 47897 39398 47898 39325 47898 39326 47898 39326 47899 39325 47899 39244 47899 39326 47900 39244 47900 39399 47900 39399 47901 39244 47901 39246 47901 39399 47902 39246 47902 39400 47902 39400 47903 39246 47903 39328 47903 39400 47904 39328 47904 39327 47904 39327 47905 39328 47905 39249 47905 39327 47906 39249 47906 39402 47906 39402 47907 39249 47907 39251 47907 39402 47908 39251 47908 39403 47908 39403 47909 39251 47909 39329 47909 39403 47910 39329 47910 39330 47910 39330 47911 39329 47911 39252 47911 39330 47912 39252 47912 39331 47912 39331 47913 39252 47913 39332 47913 39331 47914 39332 47914 39333 47914 39333 47915 39332 47915 39253 47915 39333 47916 39253 47916 39334 47916 39334 47917 39253 47917 39256 47917 39334 47918 39256 47918 39407 47918 39407 47919 39256 47919 39257 47919 39407 47920 39257 47920 39335 47920 39335 47921 39257 47921 39259 47921 39336 47922 39337 47922 39338 47922 39338 47923 39337 47923 39339 47923 39338 47924 39339 47924 39072 47924 39072 47925 39339 47925 39340 47925 39072 47926 39340 47926 39341 47926 39341 47927 39340 47927 39342 47927 39341 47928 39342 47928 39073 47928 39073 47929 39342 47929 39343 47929 39073 47930 39343 47930 39344 47930 39344 47931 39343 47931 39263 47931 39344 47932 39263 47932 39076 47932 39076 47933 39263 47933 39345 47933 39076 47934 39345 47934 39347 47934 39347 47935 39345 47935 39346 47935 39347 47936 39346 47936 39077 47936 39077 47937 39346 47937 39348 47937 39077 47938 39348 47938 39350 47938 39350 47939 39348 47939 39349 47939 39350 47940 39349 47940 39081 47940 39081 47941 39349 47941 39267 47941 39081 47942 39267 47942 39351 47942 39351 47943 39267 47943 39269 47943 39351 47944 39269 47944 39082 47944 39082 47945 39269 47945 39271 47945 39082 47946 39271 47946 39352 47946 39352 47947 39271 47947 39272 47947 39352 47948 39272 47948 39084 47948 39084 47949 39272 47949 39353 47949 39084 47950 39353 47950 39354 47950 39354 47951 39353 47951 39275 47951 39354 47952 39275 47952 39086 47952 39086 47953 39275 47953 39276 47953 39086 47954 39276 47954 39087 47954 39087 47955 39276 47955 39355 47955 39087 47956 39355 47956 39089 47956 39089 47957 39355 47957 39356 47957 39089 47958 39356 47958 39091 47958 39091 47959 39356 47959 39357 47959 39091 47960 39357 47960 39092 47960 39092 47961 39357 47962 39280 47963 39092 47964 39280 47964 39093 47964 39093 47965 39280 47965 39281 47965 39093 47966 39281 47966 39095 47966 39095 47967 39281 47967 39282 47967 39095 47968 39282 47968 39097 47968 39097 47969 39282 47969 39358 47969 39097 47970 39358 47970 39359 47970 39359 47971 39358 47971 39285 47971 39359 47972 39285 47972 39099 47972 39099 47973 39285 47974 39286 47974 39099 47975 39286 47975 39100 47975 39100 47976 39286 47976 39287 47976 39100 47977 39287 47978 39360 47979 39360 47980 39287 47980 39361 47980 39360 47981 39361 47981 39362 47981 39362 47982 39361 47982 39290 47982 39362 47983 39290 47983 39363 47983 39363 47984 39290 47984 39291 47984 39363 47985 39291 47985 39104 47985 39104 47986 39291 47986 39292 47986 39104 47987 39292 47988 39105 47989 39105 47990 39292 47990 39364 47990 39105 47991 39364 47991 39365 47991 39365 47992 39364 47992 39294 47992 39365 47993 39294 47993 39366 47993 39366 47994 39294 47994 39368 47994 39366 47995 39368 47995 39367 47995 39367 47996 39368 47996 39369 47996 39367 47997 39369 47997 39370 47997 39370 47998 39369 47998 39296 47998 39370 47999 39296 47999 39371 47999 39371 48000 39296 48001 39299 48002 39371 48003 39299 48003 39373 48003 39373 48004 39299 48004 39372 48004 39373 48005 39372 48005 39109 48005 39109 48006 39372 48006 39301 48006 39109 48007 39301 48007 39110 48007 39110 48008 39301 48008 39304 48008 39110 48009 39304 48009 39112 48009 39112 48010 39304 48010 39306 48010 39112 48011 39306 48011 39374 48011 39374 48012 39306 48012 39307 48012 39374 48013 39307 48014 39375 48015 39375 48016 39307 48016 39310 48016 39375 48017 39310 48017 39115 48017 39115 48018 39310 48018 39312 48018 39115 48019 39312 48019 39117 48019 39117 48020 39312 48020 39376 48020 39117 48021 39376 48021 39118 48021 39118 48022 39376 48022 39313 48022 39118 48023 39313 48023 39119 48023 39119 48024 39313 48024 39315 48024 39119 48025 39315 48025 39120 48025 39120 48026 39315 48026 39316 48026 39120 48027 39316 48027 39122 48027 39122 48028 39316 48028 39377 48028 39122 48029 39377 48029 39378 48029 39378 48030 39377 48030 39318 48030 39378 48031 39318 48031 39379 48031 39379 48032 39318 48032 39319 48032 39379 48033 39319 48033 39125 48033 39125 48034 39319 48034 39380 48034 39125 48035 39380 48035 39126 48035 39126 48036 39380 48036 39381 48036 39126 48037 39381 48037 39382 48037 39382 48038 39381 48038 39383 48038 39382 48039 39383 48039 39384 48039 39384 48040 39383 48040 39385 48040 39384 48041 39385 48041 39129 48041 39129 48042 39385 48042 39386 48042 39129 48043 39386 48043 39387 48043 39387 48044 39386 48045 39323 48046 39387 48047 39323 48048 39130 48049 39130 48050 39323 48050 39389 48050 39130 48051 39389 48051 39388 48051 39388 48052 39389 48053 39390 48054 39388 48055 39390 48056 39392 48057 39392 48058 39390 48058 39391 48058 39392 48059 39391 48060 39132 48061 39132 48062 39391 48063 39393 48064 39132 48065 39393 48065 39135 48065 39135 48066 39393 48066 39394 48066 39135 48067 39394 48067 39395 48067 39395 48068 39394 48069 39396 48070 39395 48071 39396 48071 39397 48071 39397 48072 39396 48072 39398 48072 39397 48073 39398 48073 39137 48073 39137 48074 39398 48075 39326 48076 39137 48077 39326 48078 39138 48079 39138 48080 39326 48080 39399 48080 39138 48081 39399 48081 39141 48081 39141 48082 39399 48082 39400 48082 39141 48083 39400 48083 39142 48083 39142 48084 39400 48085 39327 48086 39142 48087 39327 48087 39144 48087 39144 48088 39327 48088 39402 48088 39144 48089 39402 48089 39401 48089 39401 48090 39402 48090 39403 48090 39401 48091 39403 48091 39145 48091 39145 48092 39403 48093 39330 48094 39145 48095 39330 48095 39146 48095 39146 48096 39330 48096 39331 48096 39146 48097 39331 48097 39404 48097 39404 48098 39331 48098 39333 48098 39404 48099 39333 48099 39405 48099 39405 48100 39333 48101 39334 48102 39405 48103 39334 48103 39406 48103 39406 48104 39334 48105 39407 48106 39406 48107 39407 48107 39150 48107 39150 48108 39407 48108 39335 48108 39150 48109 39335 48110 39336 48111 39336 48112 39335 48112 39337 48112 39723 48113 39230 48113 39724 48113 39715 48114 39710 48114 39716 48114 39408 48115 39224 48115 39709 48115 39217 48116 39680 48117 39682 48118 39212 48119 39211 48119 39667 48119 39208 48120 39207 48121 39662 48122 39206 48123 39409 48123 39410 48123 39205 48124 39204 48124 39657 48124 39411 48125 39651 48125 39412 48125 39203 48126 39202 48126 39645 48126 39198 48127 39632 48127 39641 48127 39194 48128 39192 48128 39621 48128 39610 48129 39187 48129 39612 48129 39183 48130 39181 48130 39598 48130 39180 48131 39179 48131 39413 48131 39178 48132 39177 48132 39595 48132 39176 48133 39175 48133 39592 48133 39173 48134 39172 48134 39587 48134 39414 48135 39167 48135 39578 48135 39163 48136 39415 48137 39559 48138 39540 48139 39158 48139 39542 48139 39416 48140 39417 48140 39418 48140 39260 48141 39532 48141 39534 48141 39533 48142 39419 48142 39527 48142 39526 48143 39420 48143 39521 48143 39258 48144 39255 48144 39515 48144 39512 48145 39501 48145 39421 48145 39248 48146 39247 48146 39422 48146 39423 48147 39474 48147 39475 48147 39238 48148 39236 48148 39467 48148 39235 48149 39234 48149 39424 48149 39232 48150 39722 48150 39464 48150 39425 48151 39493 48151 39485 48151 39426 48152 39427 48152 39625 48152 39626 48153 39428 48153 39627 48153 39616 48154 39426 48154 39614 48154 39430 48155 39429 48155 39431 48155 39431 48156 39429 48156 39590 48156 39431 48157 39590 48157 39432 48157 39430 48158 39431 48159 39433 48160 39433 48161 39431 48161 39432 48161 39433 48162 39432 48162 39591 48162 39585 48163 39434 48163 39584 48163 39584 48164 39434 48164 39435 48164 39436 48165 39437 48165 39563 48165 39438 48166 39439 48166 39543 48166 39440 48167 39531 48167 39442 48167 39442 48168 39531 48168 39530 48168 39442 48169 39530 48169 39441 48169 39440 48170 39442 48170 39443 48170 39443 48171 39442 48171 39441 48171 39443 48172 39441 48172 39524 48172 39519 48173 39445 48173 39444 48173 39444 48174 39445 48174 39525 48174 39492 48175 39446 48175 39494 48175 39481 48176 39425 48176 39447 48176 39451 48177 39448 48177 39449 48177 39449 48178 39448 48178 39719 48178 39449 48179 39719 48179 39450 48179 39451 48180 39449 48180 39452 48180 39452 48181 39449 48181 39450 48181 39452 48182 39450 48182 39721 48182 39453 48183 39454 48183 39720 48183 39720 48184 39454 48185 39455 48186 39693 48187 39456 48187 39692 48187 39674 48188 39686 48188 39673 48188 39460 48189 39457 48189 39459 48189 39459 48190 39457 48191 39458 48192 39459 48193 39458 48193 39654 48193 39460 48194 39459 48195 39461 48196 39461 48197 39459 48197 39654 48197 39461 48198 39654 48198 39655 48198 39648 48199 39462 48199 39463 48199 39463 48200 39462 48200 39656 48200 39234 48201 39232 48201 39424 48201 39424 48202 39232 48202 39464 48202 39424 48203 39464 48203 39468 48203 39468 48204 39464 48204 39465 48204 39468 48205 39465 48205 39466 48205 39466 48206 39465 48206 39726 48206 39236 48207 39235 48207 39467 48207 39467 48208 39235 48208 39424 48208 39467 48209 39424 48209 39473 48209 39473 48210 39424 48210 39468 48210 39473 48211 39468 48211 39483 48211 39483 48212 39468 48212 39466 48212 39469 48213 39241 48213 39470 48213 39470 48214 39241 48214 39239 48214 39239 48215 39238 48215 39470 48215 39470 48216 39238 48216 39467 48216 39470 48217 39467 48217 39471 48217 39471 48218 39467 48218 39473 48218 39471 48219 39473 48219 39472 48219 39472 48220 39473 48220 39483 48220 39474 48221 39469 48221 39475 48221 39475 48222 39469 48222 39470 48222 39475 48223 39470 48223 39480 48223 39480 48224 39470 48224 39471 48224 39480 48225 39471 48225 39482 48225 39482 48226 39471 48226 39472 48226 39476 48227 39477 48227 39479 48227 39479 48228 39477 48228 39478 48228 39478 48229 39423 48229 39479 48229 39479 48230 39423 48230 39475 48230 39479 48231 39475 48231 39487 48231 39487 48232 39475 48232 39480 48232 39487 48233 39480 48233 39447 48233 39447 48234 39480 48234 39482 48234 39447 48235 39482 48235 39481 48235 39481 48236 39482 48236 39472 48236 39481 48237 39472 48237 39067 48237 39067 48238 39472 48238 39483 48238 39067 48239 39483 48239 39069 48239 39069 48240 39483 48240 39466 48240 39069 48241 39466 48241 39484 48241 39484 48242 39466 48242 39726 48242 39484 48243 39726 48243 39071 48243 39071 48244 39726 48244 39064 48244 39425 48245 39485 48245 39447 48245 39447 48246 39485 48246 39486 48246 39447 48247 39486 48247 39487 48247 39487 48248 39486 48248 39491 48248 39487 48249 39491 48249 39479 48249 39479 48250 39491 48250 39490 48250 39479 48251 39490 48251 39476 48251 39245 48252 39488 48252 39490 48252 39490 48253 39488 48253 39489 48253 39490 48254 39489 48254 39476 48254 39247 48255 39245 48255 39422 48256 39422 48257 39245 48257 39490 48257 39422 48258 39490 48258 39497 48258 39497 48259 39490 48259 39491 48259 39497 48260 39491 48260 39495 48260 39495 48261 39491 48261 39486 48261 39495 48262 39486 48262 39494 48262 39494 48263 39486 48263 39485 48263 39494 48264 39485 48264 39492 48264 39492 48265 39485 48265 39493 48265 39446 48266 39505 48266 39494 48266 39494 48267 39505 48267 39504 48267 39494 48268 39504 48268 39495 48268 39495 48269 39504 48269 39496 48269 39495 48270 39496 48270 39497 48270 39497 48271 39496 48271 39498 48271 39497 48272 39498 48272 39422 48272 39422 48273 39498 48273 39499 48273 39422 48274 39499 48274 39248 48274 39502 48275 39250 48275 39499 48275 39499 48276 39250 48276 39500 48276 39499 48277 39500 48277 39248 48277 39501 48278 39502 48279 39421 48280 39421 48281 39502 48281 39499 48281 39421 48282 39499 48282 39511 48282 39511 48283 39499 48283 39498 48283 39511 48284 39498 48284 39503 48284 39503 48285 39498 48285 39496 48285 39503 48286 39496 48286 39508 48286 39508 48287 39496 48287 39504 48287 39508 48288 39504 48288 39507 48288 39507 48289 39504 48289 39505 48289 39507 48290 39505 48290 39506 48290 39507 48291 39520 48291 39508 48291 39508 48292 39520 48292 39509 48292 39508 48293 39509 48293 39503 48293 39503 48294 39509 48294 39510 48294 39503 48295 39510 48295 39511 48295 39511 48296 39510 48296 39517 48296 39511 48297 39517 48297 39421 48297 39421 48298 39517 48298 39516 48298 39421 48299 39516 48299 39512 48299 39254 48300 39513 48300 39516 48300 39516 48301 39513 48301 39514 48301 39516 48302 39514 48302 39512 48302 39255 48303 39254 48304 39515 48305 39515 48306 39254 48306 39516 48306 39515 48307 39516 48307 39523 48307 39523 48308 39516 48308 39517 48308 39523 48309 39517 48309 39518 48309 39518 48310 39517 48310 39510 48310 39518 48311 39510 48311 39444 48311 39444 48312 39510 48312 39509 48312 39444 48313 39509 48313 39519 48313 39519 48314 39509 48314 39520 48314 39420 48315 39258 48315 39521 48315 39521 48316 39258 48316 39515 48316 39521 48317 39515 48317 39522 48317 39522 48318 39515 48318 39523 48318 39522 48319 39523 48319 39530 48319 39530 48320 39523 48320 39518 48320 39530 48321 39518 48321 39441 48321 39441 48322 39518 48322 39444 48322 39441 48323 39444 48323 39524 48323 39524 48324 39444 48324 39525 48324 39419 48325 39526 48325 39527 48325 39527 48326 39526 48326 39521 48326 39527 48327 39521 48327 39528 48327 39528 48328 39521 48328 39522 48328 39528 48329 39522 48329 39550 48329 39550 48330 39522 48330 39530 48330 39550 48331 39530 48331 39529 48331 39529 48332 39530 48332 39531 48332 39532 48333 39533 48333 39534 48333 39534 48334 39533 48334 39527 48334 39534 48335 39527 48335 39536 48335 39536 48336 39527 48336 39528 48336 39536 48337 39528 48337 39548 48337 39548 48338 39528 48338 39550 48338 39417 48339 39260 48339 39418 48339 39418 48340 39260 48340 39534 48340 39418 48341 39534 48341 39535 48341 39535 48342 39534 48342 39536 48342 39535 48343 39536 48343 39547 48343 39547 48344 39536 48344 39548 48344 39156 48345 39155 48345 39537 48345 39537 48346 39155 48346 39153 48346 39153 48347 39416 48347 39537 48347 39537 48348 39416 48348 39418 48348 39537 48349 39418 48349 39538 48349 39538 48350 39418 48350 39535 48350 39538 48351 39535 48351 39545 48351 39545 48352 39535 48352 39547 48352 39158 48353 39156 48353 39542 48353 39542 48354 39156 48354 39537 48354 39542 48355 39537 48355 39539 48355 39539 48356 39537 48356 39538 48356 39539 48357 39538 48357 39544 48357 39544 48358 39538 48358 39545 48358 39162 48359 39161 48359 39553 48359 39553 48360 39161 48360 39160 48360 39160 48361 39540 48361 39553 48361 39553 48362 39540 48362 39542 48362 39553 48363 39542 48363 39541 48363 39541 48364 39542 48364 39539 48364 39541 48365 39539 48365 39543 48365 39543 48366 39539 48366 39544 48366 39543 48367 39544 48367 39438 48367 39438 48368 39544 48368 39545 48368 39438 48369 39545 48369 39546 48369 39546 48370 39545 48370 39547 48370 39546 48371 39547 48371 39549 48371 39549 48372 39547 48372 39548 48372 39549 48373 39548 48373 39551 48373 39551 48374 39548 48374 39550 48374 39551 48375 39550 48375 39552 48375 39552 48376 39550 48376 39529 48376 39415 48377 39162 48377 39559 48377 39559 48378 39162 48378 39553 48378 39559 48379 39553 48379 39561 48379 39561 48380 39553 48380 39541 48380 39561 48381 39541 48381 39554 48381 39554 48382 39541 48382 39543 48382 39554 48383 39543 48383 39555 48383 39555 48384 39543 48384 39439 48384 39555 48385 39439 48386 39556 48387 39165 48388 39557 48388 39566 48388 39566 48389 39557 48389 39558 48389 39558 48390 39163 48390 39566 48390 39566 48391 39163 48391 39559 48391 39566 48392 39559 48392 39560 48392 39560 48393 39559 48393 39561 48393 39560 48394 39561 48394 39562 48394 39562 48395 39561 48395 39554 48395 39562 48396 39554 48396 39563 48396 39563 48397 39554 48397 39555 48397 39563 48398 39555 48398 39436 48398 39436 48399 39555 48399 39556 48399 39437 48400 39572 48400 39563 48400 39563 48401 39572 48401 39564 48401 39563 48402 39564 48402 39562 48402 39562 48403 39564 48403 39570 48403 39562 48404 39570 48404 39560 48404 39560 48405 39570 48405 39565 48405 39560 48406 39565 48406 39566 48406 39566 48407 39565 48407 39568 48407 39566 48408 39568 48408 39165 48408 39166 48409 39567 48409 39568 48409 39568 48410 39567 48410 39569 48410 39568 48411 39569 48411 39165 48411 39167 48412 39166 48413 39578 48414 39578 48415 39166 48415 39568 48415 39578 48416 39568 48416 39577 48416 39577 48417 39568 48417 39565 48417 39577 48418 39565 48418 39576 48418 39576 48419 39565 48419 39570 48419 39576 48420 39570 48420 39575 48420 39575 48421 39570 48421 39564 48421 39575 48422 39564 48422 39571 48422 39571 48423 39564 48423 39572 48423 39571 48424 39572 48425 39573 48426 39571 48427 39574 48427 39575 48427 39575 48428 39574 48428 39586 48428 39575 48429 39586 48429 39576 48429 39576 48430 39586 48430 39583 48430 39576 48431 39583 48431 39577 48431 39577 48432 39583 48432 39579 48432 39577 48433 39579 48433 39578 48433 39578 48434 39579 48434 39582 48434 39578 48435 39582 48435 39414 48435 39580 48436 39581 48436 39582 48436 39582 48437 39581 48437 39169 48437 39582 48438 39169 48438 39414 48438 39172 48439 39580 48439 39587 48439 39587 48440 39580 48440 39582 48440 39587 48441 39582 48441 39588 48441 39588 48442 39582 48442 39579 48442 39588 48443 39579 48443 39589 48443 39589 48444 39579 48444 39583 48444 39589 48445 39583 48445 39584 48445 39584 48446 39583 48446 39586 48446 39584 48447 39586 48447 39585 48447 39585 48448 39586 48448 39574 48448 39175 48449 39173 48449 39592 48449 39592 48450 39173 48450 39587 48450 39592 48451 39587 48451 39593 48451 39593 48452 39587 48452 39588 48452 39593 48453 39588 48453 39590 48453 39590 48454 39588 48454 39589 48454 39590 48455 39589 48455 39432 48455 39432 48456 39589 48456 39584 48456 39432 48457 39584 48457 39591 48457 39591 48458 39584 48458 39435 48458 39177 48459 39176 48459 39595 48459 39595 48460 39176 48460 39592 48460 39595 48461 39592 48461 39596 48461 39596 48462 39592 48462 39593 48462 39596 48463 39593 48463 39597 48463 39597 48464 39593 48464 39590 48464 39597 48465 39590 48465 39594 48465 39594 48466 39590 48466 39429 48466 39179 48467 39178 48467 39413 48467 39413 48468 39178 48468 39595 48468 39413 48469 39595 48469 39600 48469 39600 48470 39595 48470 39596 48470 39600 48471 39596 48471 39618 48471 39618 48472 39596 48472 39597 48472 39181 48473 39180 48473 39598 48473 39598 48474 39180 48474 39413 48474 39598 48475 39413 48475 39599 48475 39599 48476 39413 48476 39600 48476 39599 48477 39600 48477 39601 48477 39601 48478 39600 48478 39618 48478 39602 48479 39185 48479 39604 48479 39604 48480 39185 48480 39184 48480 39184 48481 39183 48481 39604 48481 39604 48482 39183 48482 39598 48482 39604 48483 39598 48483 39605 48483 39605 48484 39598 48484 39599 48484 39605 48485 39599 48485 39603 48485 39603 48486 39599 48486 39601 48486 39187 48487 39602 48487 39612 48487 39612 48488 39602 48488 39604 48488 39612 48489 39604 48489 39613 48489 39613 48490 39604 48490 39605 48490 39613 48491 39605 48491 39615 48491 39615 48492 39605 48492 39603 48492 39606 48493 39607 48493 39608 48493 39608 48494 39607 48494 39609 48494 39609 48495 39610 48495 39608 48495 39608 48496 39610 48496 39612 48496 39608 48497 39612 48497 39611 48497 39611 48498 39612 48498 39613 48498 39611 48499 39613 48499 39614 48499 39614 48500 39613 48500 39615 48500 39614 48501 39615 48501 39616 48501 39616 48502 39615 48502 39603 48502 39616 48503 39603 48503 39732 48503 39732 48504 39603 48504 39601 48504 39732 48505 39601 48505 39617 48505 39617 48506 39601 48506 39618 48506 39617 48507 39618 48507 39734 48507 39734 48508 39618 48508 39597 48508 39734 48509 39597 48509 39735 48509 39735 48510 39597 48510 39594 48510 39426 48511 39625 48511 39614 48511 39614 48512 39625 48512 39624 48512 39614 48513 39624 48513 39611 48513 39611 48514 39624 48514 39623 48514 39611 48515 39623 48515 39608 48515 39608 48516 39623 48516 39619 48516 39608 48517 39619 48517 39606 48517 39191 48518 39190 48518 39619 48518 39619 48519 39190 48519 39620 48519 39619 48520 39620 48520 39606 48520 39192 48521 39191 48521 39621 48521 39621 48522 39191 48522 39619 48522 39621 48523 39619 48523 39622 48523 39622 48524 39619 48524 39623 48524 39622 48525 39623 48525 39629 48525 39629 48526 39623 48526 39624 48526 39629 48527 39624 48527 39627 48527 39627 48528 39624 48528 39625 48528 39627 48529 39625 48529 39626 48529 39626 48530 39625 48530 39427 48530 39428 48531 39636 48531 39627 48531 39627 48532 39636 48532 39628 48532 39627 48533 39628 48533 39629 48533 39629 48534 39628 48534 39633 48534 39629 48535 39633 48535 39622 48535 39622 48536 39633 48536 39630 48536 39622 48537 39630 48537 39621 48537 39621 48538 39630 48538 39631 48538 39621 48539 39631 48539 39194 48539 39197 48540 39196 48540 39631 48540 39631 48541 39196 48541 39195 48541 39631 48542 39195 48542 39194 48542 39632 48543 39197 48543 39641 48543 39641 48544 39197 48544 39631 48544 39641 48545 39631 48545 39639 48545 39639 48546 39631 48546 39630 48546 39639 48547 39630 48547 39638 48547 39638 48548 39630 48548 39633 48548 39638 48549 39633 48549 39634 48549 39634 48550 39633 48550 39628 48550 39634 48551 39628 48551 39635 48551 39635 48552 39628 48552 39636 48552 39635 48553 39636 48553 39637 48553 39635 48554 39650 48554 39634 48554 39634 48555 39650 48555 39649 48555 39634 48556 39649 48556 39638 48556 39638 48557 39649 48557 39640 48557 39638 48558 39640 48558 39639 48558 39639 48559 39640 48559 39646 48559 39639 48560 39646 48560 39641 48560 39641 48561 39646 48561 39643 48561 39641 48562 39643 48562 39198 48562 39644 48563 39642 48563 39643 48563 39643 48564 39642 48564 39200 48564 39643 48565 39200 48565 39198 48565 39202 48566 39644 48566 39645 48566 39645 48567 39644 48567 39643 48567 39645 48568 39643 48568 39653 48568 39653 48569 39643 48569 39646 48569 39653 48570 39646 48570 39647 48570 39647 48571 39646 48571 39640 48571 39647 48572 39640 48572 39463 48572 39463 48573 39640 48573 39649 48573 39463 48574 39649 48574 39648 48574 39648 48575 39649 48575 39650 48575 39651 48576 39203 48576 39412 48576 39412 48577 39203 48577 39645 48577 39412 48578 39645 48578 39652 48578 39652 48579 39645 48579 39653 48579 39652 48580 39653 48580 39458 48580 39458 48581 39653 48581 39647 48581 39458 48582 39647 48582 39654 48582 39654 48583 39647 48583 39463 48583 39654 48584 39463 48584 39655 48584 39655 48585 39463 48585 39656 48585 39204 48586 39411 48586 39657 48586 39657 48587 39411 48587 39412 48587 39657 48588 39412 48588 39661 48588 39661 48589 39412 48589 39652 48589 39661 48590 39652 48590 39658 48590 39658 48591 39652 48591 39458 48591 39658 48592 39458 48592 39659 48592 39659 48593 39458 48593 39457 48593 39409 48594 39205 48594 39410 48594 39410 48595 39205 48595 39657 48595 39410 48596 39657 48596 39660 48596 39660 48597 39657 48597 39661 48597 39660 48598 39661 48598 39664 48598 39664 48599 39661 48599 39658 48599 39207 48600 39206 48600 39662 48600 39662 48601 39206 48601 39410 48601 39662 48602 39410 48602 39666 48602 39666 48603 39410 48603 39660 48603 39666 48604 39660 48604 39663 48604 39663 48605 39660 48605 39664 48605 39668 48606 39210 48606 39669 48606 39669 48607 39210 48608 39209 48609 39209 48610 39208 48610 39669 48610 39669 48611 39208 48611 39662 48611 39669 48612 39662 48612 39665 48612 39665 48613 39662 48613 39666 48613 39665 48614 39666 48614 39675 48614 39675 48615 39666 48615 39663 48615 39211 48616 39668 48616 39667 48616 39667 48617 39668 48617 39669 48617 39667 48618 39669 48618 39670 48618 39670 48619 39669 48619 39665 48619 39670 48620 39665 48620 39671 48620 39671 48621 39665 48621 39675 48621 39215 48622 39672 48622 39681 48622 39681 48623 39672 48623 39214 48623 39214 48624 39212 48624 39681 48624 39681 48625 39212 48625 39667 48625 39681 48626 39667 48626 39684 48626 39684 48627 39667 48627 39670 48627 39684 48628 39670 48628 39673 48628 39673 48629 39670 48629 39671 48629 39673 48630 39671 48630 39674 48630 39674 48631 39671 48631 39675 48631 39674 48632 39675 48632 39676 48632 39676 48633 39675 48633 39663 48633 39676 48634 39663 48634 39677 48634 39677 48635 39663 48635 39664 48635 39677 48636 39664 48636 39678 48636 39678 48637 39664 48637 39658 48637 39678 48638 39658 48638 39679 48638 39679 48639 39658 48639 39659 48639 39680 48640 39215 48640 39682 48640 39682 48641 39215 48641 39681 48641 39682 48642 39681 48642 39683 48642 39683 48643 39681 48643 39684 48643 39683 48644 39684 48644 39691 48644 39691 48645 39684 48645 39673 48645 39691 48646 39673 48646 39685 48646 39685 48647 39673 48647 39686 48647 39685 48648 39686 48648 39687 48648 39699 48649 39688 48649 39689 48649 39689 48650 39688 48650 39219 48650 39219 48651 39217 48651 39689 48651 39689 48652 39217 48652 39682 48652 39689 48653 39682 48653 39695 48653 39695 48654 39682 48654 39683 48654 39695 48655 39683 48655 39690 48655 39690 48656 39683 48656 39691 48656 39690 48657 39691 48657 39692 48657 39692 48658 39691 48658 39685 48658 39692 48659 39685 48659 39693 48659 39693 48660 39685 48661 39687 48662 39456 48663 39694 48663 39692 48663 39692 48664 39694 48664 39703 48664 39692 48665 39703 48665 39690 48665 39690 48666 39703 48666 39701 48666 39690 48667 39701 48667 39695 48667 39695 48668 39701 48668 39696 48668 39695 48669 39696 48669 39689 48669 39689 48670 39696 48670 39697 48670 39689 48671 39697 48671 39699 48671 39223 48672 39222 48672 39697 48672 39697 48673 39222 48673 39698 48673 39697 48674 39698 48674 39699 48674 39224 48675 39223 48675 39709 48676 39709 48677 39223 48677 39697 48677 39709 48678 39697 48678 39700 48678 39700 48679 39697 48679 39696 48679 39700 48680 39696 48680 39707 48680 39707 48681 39696 48681 39701 48681 39707 48682 39701 48682 39702 48682 39702 48683 39701 48683 39703 48683 39702 48684 39703 48684 39704 48684 39704 48685 39703 48685 39694 48685 39704 48686 39694 48687 39705 48688 39704 48689 39706 48689 39702 48689 39702 48690 39706 48690 39714 48690 39702 48691 39714 48691 39707 48691 39707 48692 39714 48692 39713 48692 39707 48693 39713 48693 39700 48693 39700 48694 39713 48694 39712 48694 39700 48695 39712 48695 39709 48695 39709 48696 39712 48696 39708 48696 39709 48697 39708 48697 39408 48697 39711 48698 39228 48698 39708 48698 39708 48699 39228 48699 39226 48699 39708 48700 39226 48700 39408 48700 39710 48701 39711 48702 39716 48703 39716 48704 39711 48704 39708 48704 39716 48705 39708 48705 39717 48705 39717 48706 39708 48706 39712 48706 39717 48707 39712 48707 39718 48707 39718 48708 39712 48708 39713 48708 39718 48709 39713 48709 39720 48709 39720 48710 39713 48710 39714 48710 39720 48711 39714 48711 39453 48711 39453 48712 39714 48712 39706 48712 39230 48713 39715 48713 39724 48713 39724 48714 39715 48714 39716 48714 39724 48715 39716 48715 39725 48715 39725 48716 39716 48716 39717 48716 39725 48717 39717 48717 39719 48717 39719 48718 39717 48718 39718 48718 39719 48719 39718 48719 39450 48719 39450 48720 39718 48720 39720 48720 39450 48721 39720 48721 39721 48721 39721 48722 39720 48722 39455 48722 39722 48723 39723 48723 39464 48723 39464 48724 39723 48724 39724 48724 39464 48725 39724 48725 39465 48725 39465 48726 39724 48726 39725 48726 39465 48727 39725 48727 39726 48727 39726 48728 39725 48728 39719 48728 39726 48729 39719 48729 39064 48729 39064 48730 39719 48730 39448 48730 39727 48731 39728 48731 39594 48731 39594 48732 39728 48732 39729 48732 39594 48733 39729 48733 39735 48733 39730 48734 39731 48734 39733 48734 39733 48735 39731 48735 39426 48735 39733 48736 39426 48736 39616 48736 39616 48737 39732 48737 39733 48737 39733 48738 39732 48738 39617 48738 39733 48739 39617 48739 39729 48739 39729 48740 39617 48740 39734 48740 39729 48741 39734 48741 39735 48741 39778 48742 39779 48742 39736 48742 39736 48743 39779 48743 39738 48743 39736 48744 39738 48744 39737 48744 39737 48745 39738 48745 39739 48745 39737 48746 39739 48746 39780 48746 39780 48747 39739 48747 39741 48747 39780 48748 39741 48748 39740 48748 39740 48749 39741 48749 39742 48749 39740 48750 39742 48750 39781 48750 39781 48751 39742 48751 39743 48751 39781 48752 39743 48752 39783 48752 39783 48753 39743 48753 39745 48753 39783 48754 39745 48754 39744 48754 39744 48755 39745 48755 39746 48755 39744 48755 39746 48755 39747 48755 39747 48756 39746 48756 39748 48756 39747 48757 39748 48757 39749 48757 39749 48758 39748 48758 39750 48758 39749 48758 39750 48758 39784 48758 39784 48759 39750 48759 39751 48759 39784 48760 39751 48760 39785 48760 39785 48761 39751 48761 39752 48761 39785 48762 39752 48762 39753 48762 39753 48763 39752 48763 39754 48763 39753 48764 39754 48764 39755 48764 39755 48765 39754 48765 39756 48765 39755 48766 39756 48766 39758 48766 39758 48767 39756 48767 39757 48767 39758 48768 39757 48768 39760 48768 39760 48769 39757 48769 39759 48769 39760 48770 39759 48770 39761 48770 39761 48771 39759 48771 39762 48771 39761 48772 39762 48772 39763 48772 39763 48773 39762 48773 39764 48773 39763 48774 39764 48774 39787 48774 39787 48775 39764 48775 39765 48775 39787 48775 39765 48775 39788 48775 39788 48776 39765 48776 39766 48776 39788 48777 39766 48777 39768 48777 39768 48778 39766 48778 39767 48778 39768 48779 39767 48779 39782 48779 39782 48780 39767 48780 39769 48780 39782 48781 39769 48781 39786 48781 39786 48782 39769 48782 39770 48782 39786 48783 39770 48783 39771 48783 39771 48784 39770 48784 39772 48784 39771 48785 39772 48785 39789 48785 39789 48786 39772 48786 39773 48786 39789 48787 39773 48787 39774 48787 39774 48788 39773 48788 39775 48788 39774 48789 39775 48789 39776 48789 39776 48790 39775 48790 39777 48790 39776 48791 39777 48791 39778 48791 39778 48792 39777 48792 39779 48792 39737 48793 39780 48793 39789 48793 39740 48794 39781 48794 39782 48794 39789 48795 39780 48795 39771 48795 39781 960 39783 960 39782 960 39782 960 39783 960 39744 960 39782 960 39744 960 39768 960 39749 960 39784 960 39785 960 39740 960 39782 960 39780 960 39780 48796 39782 48796 39786 48796 39780 48797 39786 48797 39771 48797 39776 48798 39778 48798 39736 48798 39753 960 39755 960 39744 960 39744 48799 39755 48799 39758 48799 39758 960 39760 960 39744 960 39744 48800 39760 48800 39761 48800 39744 48801 39761 48801 39763 48801 39763 960 39787 960 39744 960 39744 48802 39787 48802 39788 48802 39744 48803 39788 48803 39768 48803 39753 960 39744 960 39785 960 39785 48804 39744 48804 39747 48804 39785 960 39747 960 39749 960 39737 48805 39789 48805 39736 48805 39736 48806 39789 48806 39774 48806 39736 48807 39774 48807 39776 48807 39790 48808 39791 48808 39792 48808 39792 48809 39791 48809 39800 48809 39792 48810 39800 48810 40273 48810 39793 48811 39794 48811 39795 48811 39795 48812 39794 48812 40152 48812 39795 48813 40152 48813 39796 48813 39796 48814 39797 48814 39795 48814 39795 48815 39797 48815 39798 48815 39795 48816 39798 48816 39800 48816 39800 48817 39798 48817 39799 48817 39800 48818 39799 48818 40273 48818 39875 48819 39801 48819 39874 48819 39875 48820 40044 48820 39801 48820 39801 48821 40044 48821 39802 48821 39801 48822 39802 48822 39803 48822 39802 48823 40047 48823 39803 48823 39803 48824 40047 48824 39805 48824 39803 48825 39805 48825 39804 48825 39805 48826 40050 48826 39804 48826 39804 48827 40050 48827 40052 48827 39804 48828 40052 48828 39807 48828 40052 48829 40053 48829 39807 48829 39807 48830 40053 48830 39806 48830 39807 48831 39806 48831 39808 48831 39806 48832 39809 48832 39808 48832 39808 48833 39809 48833 40055 48833 39808 48834 40055 48834 39810 48834 40055 48835 40056 48835 39810 48835 39810 48836 40056 48836 40057 48836 39810 48837 40057 48837 39811 48837 40057 48838 40059 48838 39811 48838 39811 48839 40059 48839 40060 48839 39811 48840 40060 48840 39812 48840 40060 48841 39813 48841 39812 48841 39812 48842 39813 48842 40062 48842 39812 48843 40062 48843 39814 48843 40062 48844 40063 48844 39814 48844 39814 48845 40063 48845 39815 48845 39814 48846 39815 48846 39816 48846 39815 48847 39817 48847 39816 48847 39816 48848 39817 48848 39818 48848 39816 48849 39818 48849 39819 48849 39818 48850 39820 48851 39819 48852 39819 48853 39820 48853 40065 48853 39819 48854 40065 48854 39821 48854 40065 48855 40066 48855 39821 48855 39821 48856 40066 48856 40068 48856 39821 48857 40068 48857 39823 48857 40068 48858 39822 48858 39823 48858 39823 48859 39822 48859 40070 48859 39823 48860 40070 48860 39825 48860 40070 48861 39824 48861 39825 48861 39825 48862 39824 48862 40072 48862 39825 48863 40072 48863 39826 48863 40072 48864 40073 48864 39826 48864 39826 48865 40073 48865 40075 48865 39826 48866 40075 48866 39827 48866 40075 48867 40076 48867 39827 48867 39827 48868 40076 48868 39828 48868 39827 48869 39828 48869 39830 48869 39828 48870 40078 48870 39830 48870 39830 48871 40078 48871 39829 48871 39830 48872 39829 48872 39833 48872 39829 48873 39831 48873 39833 48873 39833 48874 39831 48874 39832 48874 39833 48875 39832 48875 39834 48875 39832 48876 40080 48876 39834 48876 39834 48877 40080 48877 39835 48877 39834 48878 39835 48878 39836 48878 39835 48879 40081 48879 39836 48879 39836 48880 40081 48880 40083 48880 39836 48881 40083 48881 39837 48881 40083 48882 39838 48882 39837 48882 39837 48883 39838 48883 39839 48883 39837 48884 39839 48884 39840 48884 39839 48885 40086 48885 39840 48885 39840 48886 40086 48886 39841 48886 39840 48887 39841 48887 39842 48887 39841 48888 40089 48888 39842 48888 39842 48889 40089 48889 39843 48889 39842 48890 39843 48890 39844 48890 39843 48891 40091 48891 39844 48891 39844 48892 40091 48892 39845 48892 39844 48893 39845 48893 39846 48893 39845 48894 39847 48894 39846 48894 39846 48895 39847 48895 39848 48895 39846 48896 39848 48896 39849 48896 39848 48897 40094 48897 39849 48897 39849 48898 40094 48898 39851 48898 39849 48899 39851 48899 39850 48899 39851 48900 40095 48900 39850 48900 39850 48901 40095 48901 40096 48901 39850 48902 40096 48902 39852 48902 40096 48903 40097 48903 39852 48903 39852 48904 40097 48904 40098 48904 39852 48905 40098 48905 39853 48905 40098 48906 39854 48907 39853 48908 39853 48909 39854 48909 39855 48909 39853 48910 39855 48910 39858 48910 39855 48911 39856 48911 39858 48911 39858 48912 39856 48912 39857 48912 39858 48913 39857 48913 39860 48913 39857 48914 39859 48914 39860 48914 39860 48915 39859 48915 39861 48915 39860 48916 39861 48916 39862 48916 39861 48917 40103 48917 39862 48917 39862 48918 40103 48918 39863 48918 39862 48919 39863 48919 39864 48919 39863 48920 40106 48920 39864 48920 39864 48921 40106 48921 40107 48921 39864 48922 40107 48922 39866 48922 40107 48923 39865 48923 39866 48923 39866 48924 39865 48924 40110 48924 39866 48925 40110 48925 39867 48925 40110 48926 39868 48926 39867 48926 39867 48927 39868 48927 39869 48927 39867 48928 39869 48928 39871 48928 39869 48929 39870 48929 39871 48929 39871 48930 39870 48930 40113 48930 39871 48931 40113 48931 39872 48931 40113 48932 40116 48932 39872 48932 39872 48933 40116 48933 40117 48933 39872 48934 40117 48934 39874 48934 39874 48935 40117 48935 39873 48935 39874 48936 39873 48936 39875 48936 39962 48937 39965 48937 39961 48937 39962 48938 39876 48939 39965 48940 39965 48941 39876 48941 39877 48941 39965 48942 39877 48942 39878 48942 39878 48943 39877 48943 40260 48943 39878 48944 40260 48944 39966 48944 40260 48945 40259 48945 39966 48945 39966 48946 40259 48946 40263 48946 39966 48947 40263 48947 39967 48947 40263 48948 40135 48948 39967 48948 39967 48949 40135 48949 39879 48949 39967 48950 39879 48950 39968 48950 39968 48951 39879 48951 39880 48951 39968 48952 39880 48952 39881 48952 39881 48953 39880 48953 40278 48953 39881 48954 40278 48954 39971 48954 39971 48955 40278 48955 39882 48955 39882 48956 40276 48957 39971 48958 39971 48959 40276 48959 40275 48959 39971 48960 40275 48960 39883 48960 39883 48961 40275 48962 40279 48963 39883 48964 40279 48964 39884 48964 39884 48965 40279 48965 40134 48965 39884 48966 40134 48966 39887 48966 39887 48967 40134 48967 40288 48967 40288 48968 39885 48969 39887 48970 39887 48971 39885 48971 39886 48971 39887 48972 39886 48972 39975 48972 39975 48973 39886 48973 40289 48973 39975 48974 40289 48974 39889 48974 39889 48975 40289 48975 39888 48975 39889 48976 39888 48976 39977 48976 39977 48977 39888 48977 39890 48977 39890 48978 39891 48978 39977 48978 39977 48979 39891 48979 40301 48979 39977 48980 40301 48980 39892 48980 39892 48981 40301 48982 40133 48983 39892 48984 40133 48984 39980 48984 39980 48985 40133 48985 40132 48985 39980 48986 40132 48986 39894 48986 39894 48987 40132 48987 40131 48987 40131 48988 39893 48988 39894 48988 39894 48989 39893 48989 40129 48989 39894 48990 40129 48990 39895 48990 39895 48991 40129 48991 40317 48991 39895 48992 40317 48992 39983 48992 39983 48993 40317 48993 39896 48993 39983 48994 39896 48994 39985 48994 39896 48995 40127 48996 39985 48997 39985 48998 40127 48998 39897 48998 39985 48999 39897 48999 39988 48999 39897 49000 40323 49001 39988 49002 39988 49003 40323 49003 39899 49003 39988 49004 39899 49004 39898 49004 39898 49005 39899 49005 39900 49005 39898 49006 39900 49006 39990 49006 39900 49007 40322 49007 39990 49007 39990 49008 40322 49008 40126 49008 39990 49009 40126 49009 39901 49009 40126 49010 39902 49010 39901 49010 39901 49011 39902 49011 39903 49011 39901 49012 39903 49012 39991 49012 39991 49013 39903 49013 40329 49013 39991 49014 40329 49014 39905 49014 39905 49015 40329 49015 39904 49015 39905 49016 39904 49016 39993 49016 39993 49017 39904 49017 39906 49017 39906 49018 40343 49018 39993 49018 39993 49019 40343 49019 40342 49019 39993 49020 40342 49020 39995 49020 39995 49021 40342 49021 39907 49021 39995 49022 39907 49022 39908 49022 39908 49023 39907 49023 40125 49023 39908 49024 40125 49024 39909 49024 39909 49025 40125 49025 39910 49025 39910 49026 40353 49026 39909 49026 39909 49027 40353 49027 40352 49027 39909 49028 40352 49028 39998 49028 39998 49029 40352 49029 40124 49029 39998 49030 40124 49030 39999 49030 39999 49031 40124 49031 40364 49031 39999 49032 40364 49032 39911 49032 39911 49033 40364 49033 40367 49033 40367 49034 40366 49034 39911 49034 39911 49035 40366 49035 40365 49035 39911 49036 40365 49036 39912 49036 39912 49037 40365 49037 39913 49037 39912 49038 39913 49038 40003 49038 40003 49039 39913 49039 40373 49039 40003 49040 40373 49040 40004 49040 40004 49041 40373 49041 39914 49041 39914 49042 39915 49042 40004 49042 40004 49043 39915 49043 39916 49043 40004 49044 39916 49044 39917 49044 39917 49045 39916 49045 40383 49045 39917 49046 40383 49046 39918 49046 39918 49047 40383 49047 39919 49047 39918 49048 39919 49048 39921 49048 39919 49049 39920 49049 39921 49049 39921 49050 39920 49050 39922 49050 39921 49051 39922 49051 39923 49051 39922 49052 39924 49053 39923 49054 39923 49055 39924 49055 39925 49055 39923 49056 39925 49056 40008 49056 40008 49057 39925 49057 39926 49057 40008 49058 39926 49058 40009 49058 39926 49059 40389 49059 40009 49059 40009 49060 40389 49060 40388 49060 40009 49061 40388 49061 40010 49061 40388 49062 39927 49062 40010 49062 40010 49063 39927 49063 39928 49063 40010 49064 39928 49064 40011 49064 40011 49065 39928 49065 39929 49065 40011 49066 39929 49066 40012 49066 40012 49067 39929 49067 40407 49067 40012 49068 40407 49068 39930 49068 39930 49069 40407 49069 40409 49069 40409 49070 39931 49070 39930 49070 39930 49071 39931 49071 40408 49071 39930 49072 40408 49072 40014 49072 40014 49073 40408 49073 40410 49073 40014 49074 40410 49074 40015 49074 40015 49075 40410 49075 40424 49075 40015 49076 40424 49076 39932 49076 39932 49077 40424 49077 40423 49077 40423 49078 40422 49078 39932 49078 39932 49079 40422 49079 40420 49079 39932 49080 40420 49080 40018 49080 40018 49081 40420 49081 40425 49081 40018 49082 40425 49082 39933 49082 39933 49083 40425 49083 40121 49083 39933 49084 40121 49084 40020 49084 40020 49085 40121 49086 40437 49087 40437 49088 40436 49088 40020 49088 40020 49089 40436 49089 40438 49089 40020 49090 40438 49090 39934 49090 39934 49091 40438 49092 39935 49093 39934 49094 39935 49094 40023 49094 40023 49095 39935 49095 39936 49095 40023 49096 39936 49096 40026 49096 40026 49097 39936 49097 40118 49097 40118 49098 40449 49098 40026 49098 40026 49099 40449 49099 40139 49099 40026 49100 40139 49100 39937 49100 39937 49101 40139 49101 40138 49101 39937 49102 40138 49102 40028 49102 40028 49103 40138 49103 40179 49103 40028 49104 40179 49104 40030 49104 40179 49105 40137 49105 40030 49105 40030 49106 40137 49106 40181 49106 40030 49107 40181 49107 39938 49107 40181 49108 40136 49109 39938 49110 39938 49111 40136 49111 40186 49111 39938 49112 40186 49112 40032 49112 40032 49113 40186 49114 39940 49115 40032 49116 39940 49116 39939 49116 39940 49117 40188 49117 39939 49117 39939 49118 40188 49118 39941 49118 39939 49119 39941 49119 39942 49119 39941 49120 40190 49121 39942 49122 39942 49123 40190 49123 39943 49123 39942 49124 39943 49124 39945 49124 39945 49125 39943 49125 39944 49125 39945 49126 39944 49126 40035 49126 40035 49127 39944 49127 39946 49127 40035 49128 39946 49128 39948 49128 39948 49129 39946 49129 39947 49129 39947 49130 40205 49130 39948 49130 39948 49131 40205 49131 39949 49131 39948 49132 39949 49132 40036 49132 40036 49133 39949 49133 40207 49133 40036 49134 40207 49134 40037 49134 40037 49135 40207 49135 40218 49135 40037 49136 40218 49136 39951 49136 39951 49137 40218 49137 40219 49137 40219 49138 39950 49138 39951 49138 39951 49139 39950 49139 39952 49139 39951 49140 39952 49140 40038 49140 40038 49141 39952 49142 39953 49143 40038 49144 39953 49144 40040 49144 40040 49145 39953 49145 39954 49145 40040 49146 39954 49146 39955 49146 39955 49147 39954 49147 40233 49147 40233 49148 40231 49148 39955 49148 39955 49149 40231 49149 39956 49149 39955 49150 39956 49150 39957 49150 39957 49151 39956 49151 40234 49151 39957 49152 40234 49152 40041 49152 40041 49153 40234 49153 40242 49153 40041 49154 40242 49154 39958 49154 39958 49155 40242 49155 40241 49155 40241 49156 40247 49156 39958 49156 39958 49157 40247 49157 39959 49157 39958 49158 39959 49158 39963 49158 39963 49159 39959 49159 40253 49159 39963 49160 40253 49160 39960 49160 39960 49161 40253 49161 40251 49161 39960 49162 40251 49162 39961 49162 39961 49163 40251 49163 40257 49163 39961 49164 40257 49164 39962 49164 40042 49165 39963 49165 40043 49165 40043 49166 39963 49166 39960 49166 40043 49167 39960 49167 39964 49167 39964 49168 39960 49168 39961 49168 39964 49169 39961 49169 40045 49169 40045 49170 39961 49170 39965 49170 40045 49171 39965 49171 40046 49171 40046 49172 39965 49172 39878 49172 40046 49173 39878 49173 40048 49173 40048 49174 39878 49174 39966 49174 40048 49175 39966 49175 40049 49175 40049 49176 39966 49176 39967 49176 40049 49177 39967 49177 40051 49177 40051 49178 39967 49178 39968 49178 40051 49179 39968 49179 39969 49179 39969 49180 39968 49180 39881 49180 39969 49181 39881 49181 39970 49181 39970 49182 39881 49183 39971 49184 39970 49185 39971 49185 39972 49185 39972 49186 39971 49186 39883 49186 39972 49187 39883 49187 39973 49187 39973 49188 39883 49189 39884 49190 39973 49191 39884 49191 40054 49191 40054 49192 39884 49192 39887 49192 40054 49193 39887 49193 39974 49193 39974 49194 39887 49194 39975 49194 39974 49195 39975 49195 39976 49195 39976 49196 39975 49196 39889 49196 39976 49197 39889 49197 40058 49197 40058 49198 39889 49198 39977 49198 40058 49199 39977 49199 39978 49199 39978 49200 39977 49200 39892 49200 39978 49201 39892 49201 39979 49201 39979 49202 39892 49202 39980 49202 39979 49203 39980 49203 40061 49203 40061 49204 39980 49204 39894 49204 40061 49205 39894 49205 39981 49205 39981 49206 39894 49206 39895 49206 39981 49207 39895 49207 39982 49207 39982 49208 39895 49208 39983 49208 39982 49209 39983 49209 39984 49209 39984 49210 39983 49210 39985 49210 39984 49211 39985 49211 39986 49211 39986 49212 39985 49212 39988 49212 39986 49213 39988 49213 39987 49213 39987 49214 39988 49214 39898 49214 39987 49215 39898 49215 40064 49215 40064 49216 39898 49216 39990 49216 40064 49217 39990 49217 39989 49217 39989 49218 39990 49218 39901 49218 39989 49219 39901 49219 40067 49219 40067 49220 39901 49220 39991 49220 40067 49221 39991 49221 40069 49221 40069 49222 39991 49222 39905 49222 40069 49223 39905 49223 39992 49223 39992 49224 39905 49224 39993 49224 39992 49225 39993 49225 40071 49225 40071 49226 39993 49226 39995 49226 40071 49227 39995 49227 39994 49227 39994 49228 39995 49228 39908 49228 39994 49229 39908 49229 39996 49229 39996 49230 39908 49230 39909 49230 39996 49231 39909 49231 40074 49231 40074 49232 39909 49232 39998 49232 40074 49233 39998 49233 39997 49233 39997 49234 39998 49234 39999 49234 39997 49235 39999 49235 40077 49235 40077 49236 39999 49236 39911 49236 40077 49237 39911 49237 40000 49237 40000 49238 39911 49238 39912 49238 40000 49239 39912 49239 40001 49239 40001 49240 39912 49240 40003 49240 40001 49241 40003 49241 40002 49241 40002 49242 40003 49242 40004 49242 40002 49243 40004 49243 40079 49243 40079 49244 40004 49244 39917 49244 40079 49245 39917 49245 40005 49245 40005 49246 39917 49246 39918 49246 40005 49247 39918 49248 40006 49249 40006 49250 39918 49250 39921 49250 40006 49251 39921 49251 40007 49251 40007 49252 39921 49252 39923 49252 40007 49253 39923 49253 40082 49253 40082 49254 39923 49254 40008 49254 40082 49255 40008 49255 40084 49255 40084 49256 40008 49256 40009 49256 40084 49257 40009 49257 40085 49257 40085 49258 40009 49258 40010 49258 40085 49259 40010 49259 40087 49259 40087 49260 40010 49260 40011 49260 40087 49261 40011 49261 40088 49261 40088 49262 40011 49262 40012 49262 40088 49263 40012 49263 40013 49263 40013 49264 40012 49265 39930 49265 40013 49266 39930 49266 40090 49266 40090 49267 39930 49267 40014 49267 40090 49268 40014 49268 40092 49268 40092 49269 40014 49269 40015 49269 40092 49270 40015 49270 40093 49270 40093 49271 40015 49271 39932 49271 40093 49272 39932 49272 40016 49272 40016 49273 39932 49273 40018 49273 40016 49274 40018 49274 40017 49274 40017 49275 40018 49275 39933 49275 40017 49276 39933 49276 40019 49276 40019 49277 39933 49277 40020 49277 40019 49278 40020 49278 40021 49278 40021 49279 40020 49279 39934 49279 40021 49280 39934 49280 40022 49280 40022 49281 39934 49281 40023 49281 40022 49282 40023 49282 40024 49282 40024 49283 40023 49283 40026 49283 40024 49284 40026 49284 40025 49284 40025 49285 40026 49285 39937 49285 40025 49286 39937 49286 40027 49286 40027 49287 39937 49287 40028 49287 40027 49288 40028 49288 40029 49288 40029 49289 40028 49289 40030 49289 40029 49290 40030 49290 40099 49290 40099 49291 40030 49291 39938 49291 40099 49292 39938 49292 40031 49292 40031 49293 39938 49293 40032 49293 40031 49294 40032 49294 40100 49294 40100 49295 40032 49295 39939 49295 40100 49296 39939 49296 40101 49296 40101 49297 39939 49297 39942 49297 40101 49298 39942 49298 40033 49298 40033 49299 39942 49299 39945 49299 40033 49300 39945 49300 40034 49300 40034 49301 39945 49301 40035 49301 40034 49302 40035 49302 40102 49302 40102 49303 40035 49304 39948 49305 40102 49306 39948 49306 40104 49306 40104 49307 39948 49307 40036 49307 40104 49308 40036 49308 40105 49308 40105 49309 40036 49309 40037 49309 40105 49310 40037 49310 40108 49310 40108 49311 40037 49311 39951 49311 40108 49312 39951 49312 40109 49312 40109 49313 39951 49313 40038 49313 40109 49314 40038 49314 40039 49314 40039 49315 40038 49315 40040 49315 40039 49316 40040 49316 40111 49316 40111 49317 40040 49317 39955 49317 40111 49318 39955 49318 40112 49318 40112 49319 39955 49319 39957 49319 40112 49320 39957 49320 40114 49320 40114 49321 39957 49321 40041 49321 40114 49322 40041 49322 40115 49322 40115 49323 40041 49323 39958 49323 40115 49324 39958 49324 40042 49324 40042 49325 39958 49325 39963 49325 40117 49326 40043 49326 39873 49326 39873 49327 40043 49327 39964 49327 39873 49328 39964 49328 39875 49328 39875 49329 39964 49329 40045 49329 39875 49330 40045 49330 40044 49330 40044 49331 40045 49331 40046 49331 40044 49332 40046 49332 39802 49332 39802 49333 40046 49333 40048 49333 39802 49334 40048 49334 40047 49334 40047 49335 40048 49336 40049 49337 40047 49338 40049 49338 39805 49338 39805 49339 40049 49339 40051 49339 39805 49340 40051 49340 40050 49340 40050 49341 40051 49341 39969 49341 40050 49342 39969 49342 40052 49342 40052 49343 39969 49343 39970 49343 40052 49344 39970 49344 40053 49344 40053 49345 39970 49345 39972 49345 40053 49346 39972 49346 39806 49346 39806 49347 39972 49347 39973 49347 39806 49348 39973 49348 39809 49348 39809 49349 39973 49349 40054 49349 39809 49350 40054 49350 40055 49350 40055 49351 40054 49351 39974 49351 40055 49352 39974 49352 40056 49352 40056 49353 39974 49353 39976 49353 40056 49354 39976 49354 40057 49354 40057 49355 39976 49355 40058 49355 40057 49356 40058 49356 40059 49356 40059 49357 40058 49357 39978 49357 40059 49358 39978 49358 40060 49358 40060 49359 39978 49359 39979 49359 40060 49360 39979 49360 39813 49360 39813 49361 39979 49361 40061 49361 39813 49362 40061 49362 40062 49362 40062 49363 40061 49364 39981 49365 40062 49366 39981 49366 40063 49366 40063 49367 39981 49367 39982 49367 40063 49368 39982 49368 39815 49368 39815 49369 39982 49369 39984 49369 39815 49370 39984 49370 39817 49370 39817 49371 39984 49371 39986 49371 39817 49372 39986 49372 39818 49372 39818 49373 39986 49373 39987 49373 39818 49374 39987 49374 39820 49374 39820 49375 39987 49375 40064 49375 39820 49376 40064 49376 40065 49376 40065 49377 40064 49377 39989 49377 40065 49378 39989 49378 40066 49378 40066 49379 39989 49379 40067 49379 40066 49380 40067 49380 40068 49380 40068 49381 40067 49381 40069 49381 40068 49382 40069 49382 39822 49382 39822 49383 40069 49383 39992 49383 39822 49384 39992 49384 40070 49384 40070 49385 39992 49385 40071 49385 40070 49386 40071 49386 39824 49386 39824 49387 40071 49387 39994 49387 39824 49388 39994 49389 40072 49390 40072 49391 39994 49391 39996 49391 40072 49392 39996 49392 40073 49392 40073 49393 39996 49393 40074 49393 40073 49394 40074 49394 40075 49394 40075 49395 40074 49395 39997 49395 40075 49396 39997 49396 40076 49396 40076 49397 39997 49397 40077 49397 40076 49398 40077 49398 39828 49398 39828 49399 40077 49399 40000 49399 39828 49400 40000 49400 40078 49400 40078 49401 40000 49401 40001 49401 40078 49402 40001 49402 39829 49402 39829 49403 40001 49403 40002 49403 39829 49404 40002 49404 39831 49404 39831 49405 40002 49405 40079 49405 39831 49406 40079 49406 39832 49406 39832 49407 40079 49407 40005 49407 39832 49408 40005 49408 40080 49408 40080 49409 40005 49409 40006 49409 40080 49410 40006 49410 39835 49410 39835 49411 40006 49411 40007 49411 39835 49412 40007 49412 40081 49412 40081 49413 40007 49413 40082 49413 40081 49414 40082 49414 40083 49414 40083 49415 40082 49415 40084 49415 40083 49416 40084 49416 39838 49416 39838 49417 40084 49417 40085 49417 39838 49418 40085 49418 39839 49418 39839 49419 40085 49419 40087 49419 39839 49420 40087 49421 40086 49422 40086 49423 40087 49423 40088 49423 40086 49424 40088 49424 39841 49424 39841 49425 40088 49425 40013 49425 39841 49426 40013 49426 40089 49426 40089 49427 40013 49427 40090 49427 40089 49428 40090 49428 39843 49428 39843 49429 40090 49429 40092 49429 39843 49430 40092 49430 40091 49430 40091 49431 40092 49431 40093 49431 40091 49432 40093 49432 39845 49432 39845 49433 40093 49433 40016 49433 39845 49434 40016 49434 39847 49434 39847 49435 40016 49435 40017 49435 39847 49436 40017 49436 39848 49436 39848 49437 40017 49437 40019 49437 39848 49438 40019 49438 40094 49438 40094 49439 40019 49439 40021 49439 40094 49440 40021 49440 39851 49440 39851 49441 40021 49441 40022 49441 39851 49442 40022 49443 40095 49444 40095 49445 40022 49445 40024 49445 40095 49446 40024 49446 40096 49446 40096 49447 40024 49447 40025 49447 40096 49448 40025 49449 40097 49450 40097 49451 40025 49451 40027 49451 40097 49452 40027 49452 40098 49452 40098 49453 40027 49454 40029 49455 40098 49456 40029 49456 39854 49456 39854 49457 40029 49457 40099 49457 39854 49458 40099 49458 39855 49458 39855 49459 40099 49459 40031 49459 39855 49460 40031 49460 39856 49460 39856 49461 40031 49461 40100 49461 39856 49462 40100 49462 39857 49462 39857 49463 40100 49463 40101 49463 39857 49464 40101 49464 39859 49464 39859 49465 40101 49465 40033 49465 39859 49466 40033 49466 39861 49466 39861 49467 40033 49467 40034 49467 39861 49468 40034 49468 40103 49468 40103 49469 40034 49469 40102 49469 40103 49470 40102 49470 39863 49470 39863 49471 40102 49471 40104 49471 39863 49472 40104 49472 40106 49472 40106 49473 40104 49473 40105 49473 40106 49474 40105 49474 40107 49474 40107 49475 40105 49475 40108 49475 40107 49476 40108 49476 39865 49476 39865 49477 40108 49477 40109 49477 39865 49478 40109 49478 40110 49478 40110 49479 40109 49479 40039 49479 40110 49480 40039 49480 39868 49480 39868 49481 40039 49482 40111 49483 39868 49484 40111 49484 39869 49484 39869 49485 40111 49485 40112 49485 39869 49486 40112 49487 39870 49488 39870 49489 40112 49489 40114 49489 39870 49490 40114 49490 40113 49490 40113 49491 40114 49491 40115 49491 40113 49492 40115 49492 40116 49492 40116 49493 40115 49493 40042 49493 40116 49494 40042 49494 40117 49494 40117 49495 40042 49496 40043 49497 40449 49498 40118 49498 40119 49498 39936 49499 39935 49499 40120 49499 40121 49500 40425 49500 40435 49500 40424 49501 40410 49501 40419 49501 39927 49502 40388 49502 40122 49502 39924 49503 39922 49504 40387 49505 39920 49506 39919 49506 40382 49506 40383 49507 39916 49507 40377 49507 39915 49508 39914 49508 40123 49508 40373 49509 39913 49509 40374 49509 40364 49510 40124 49510 40354 49510 40125 49511 39907 49511 40344 49511 39902 49512 40126 49513 40330 49514 40323 49515 39897 49516 40324 49517 40127 49518 39896 49518 40128 49518 40317 49519 40129 49519 40130 49519 39893 49520 40131 49520 40307 49520 40132 49521 40133 49521 40308 49521 39888 49522 40289 49522 40299 49522 40134 49523 40279 49523 40280 49523 40135 49524 40263 49524 40264 49524 39876 49525 39962 49525 40262 49525 40257 49526 40251 49526 40252 49526 40253 49527 39959 49527 40254 49527 40247 49528 40241 49528 40243 49528 40242 49529 40234 49529 40235 49529 39954 49530 39953 49530 40230 49530 40218 49531 40207 49531 40217 49531 40190 49532 39941 49533 40192 49534 40136 49535 40181 49536 40187 49537 40137 49538 40179 49538 40182 49538 40138 49539 40139 49539 40450 49539 40171 49540 40140 49540 40413 49540 40161 49541 40212 49542 40141 49543 40152 49544 40142 49544 40143 49544 40453 49545 40461 49545 40144 49545 40460 49546 40459 49546 40349 49546 40145 49547 40453 49547 40333 49547 40147 49548 40316 49549 40146 49550 40146 49551 40316 49551 40309 49551 40146 49552 40309 49552 40311 49552 40147 49553 40146 49554 40148 49555 40148 49556 40146 49556 40311 49556 40148 49557 40311 49557 40313 49557 40305 49558 40149 49558 40312 49558 40312 49559 40149 49559 40150 49559 40282 49560 40283 49560 40151 49560 39796 49561 40152 49561 40269 49561 40156 49562 40153 49563 40154 49564 40154 49565 40153 49565 40155 49565 40154 49566 40155 49566 40244 49566 40156 49567 40154 49567 40157 49567 40157 49568 40154 49568 40244 49568 40157 49569 40244 49569 40245 49569 40158 49570 40159 49570 40239 49570 40239 49571 40159 49571 40246 49571 40211 49572 40213 49572 40160 49572 40196 49573 40161 49573 40162 49573 40165 49574 40163 49574 40164 49574 40164 49575 40163 49576 40452 49577 40164 49578 40452 49578 40446 49578 40165 49579 40164 49579 40166 49579 40166 49580 40164 49580 40446 49580 40166 49581 40446 49581 40167 49581 40168 49582 40169 49582 40447 49582 40447 49583 40169 49584 40448 49585 40414 49586 40415 49586 40412 49586 40170 49587 40171 49587 40404 49587 40172 49588 40381 49589 40173 49590 40173 49591 40381 49591 40380 49591 40173 49592 40380 49592 40174 49592 40172 49593 40173 49593 40175 49593 40175 49594 40173 49594 40174 49594 40175 49595 40174 49595 40176 49595 40371 49596 40177 49596 40376 49596 40376 49597 40177 49597 40178 49597 40179 49598 40138 49598 40182 49598 40182 49599 40138 49599 40450 49599 40182 49600 40450 49600 40180 49600 40180 49601 40450 49601 40451 49601 40180 49602 40451 49602 40200 49602 40200 49603 40451 49603 40202 49603 40181 49604 40137 49604 40187 49604 40187 49605 40137 49605 40182 49605 40187 49606 40182 49606 40183 49606 40183 49607 40182 49607 40180 49607 40183 49608 40180 49608 40184 49608 40184 49609 40180 49609 40200 49609 40188 49610 39940 49610 40185 49610 40185 49611 39940 49611 40186 49611 40186 49612 40136 49612 40185 49612 40185 49613 40136 49613 40187 49613 40185 49614 40187 49614 40189 49614 40189 49615 40187 49615 40183 49615 40189 49616 40183 49616 40197 49616 40197 49617 40183 49617 40184 49617 39941 49618 40188 49618 40192 49618 40192 49619 40188 49619 40185 49619 40192 49620 40185 49620 40194 49620 40194 49621 40185 49621 40189 49621 40194 49622 40189 49622 40195 49622 40195 49623 40189 49623 40197 49623 39946 49624 39944 49624 40191 49624 40191 49625 39944 49625 39943 49625 39943 49626 40190 49626 40191 49626 40191 49627 40190 49627 40192 49627 40191 49628 40192 49628 40193 49628 40193 49629 40192 49629 40194 49629 40193 49630 40194 49630 40162 49630 40162 49631 40194 49631 40195 49631 40162 49632 40195 49632 40196 49632 40196 49633 40195 49633 40197 49633 40196 49634 40197 49634 40198 49634 40198 49635 40197 49635 40184 49635 40198 49636 40184 49636 40199 49636 40199 49637 40184 49637 40200 49637 40199 49638 40200 49638 40201 49638 40201 49639 40200 49639 40202 49639 40201 49640 40202 49640 40203 49640 40203 49641 40202 49641 40204 49641 40161 49642 40141 49642 40162 49642 40162 49643 40141 49643 40210 49643 40162 49644 40210 49644 40193 49644 40193 49645 40210 49645 40209 49645 40193 49646 40209 49646 40191 49646 40191 49647 40209 49647 40206 49647 40191 49648 40206 49648 39946 49648 39949 49649 40205 49649 40206 49649 40206 49650 40205 49650 39947 49650 40206 49651 39947 49651 39946 49651 40207 49652 39949 49652 40217 49652 40217 49653 39949 49653 40206 49653 40217 49654 40206 49654 40208 49654 40208 49655 40206 49655 40209 49655 40208 49656 40209 49656 40216 49656 40216 49657 40209 49657 40210 49657 40216 49658 40210 49658 40160 49658 40160 49659 40210 49659 40141 49659 40160 49660 40141 49660 40211 49660 40211 49661 40141 49661 40212 49661 40213 49662 40224 49662 40160 49662 40160 49663 40224 49663 40214 49663 40160 49664 40214 49664 40216 49664 40216 49665 40214 49665 40215 49665 40216 49666 40215 49666 40208 49666 40208 49667 40215 49667 40221 49667 40208 49668 40221 49668 40217 49668 40217 49669 40221 49669 40220 49669 40217 49670 40220 49670 40218 49670 39952 49671 39950 49671 40220 49671 40220 49672 39950 49672 40219 49672 40220 49673 40219 49673 40218 49673 39953 49674 39952 49675 40230 49676 40230 49677 39952 49677 40220 49677 40230 49678 40220 49678 40228 49678 40228 49679 40220 49679 40221 49679 40228 49680 40221 49680 40222 49680 40222 49681 40221 49681 40215 49681 40222 49682 40215 49682 40227 49682 40227 49683 40215 49683 40214 49683 40227 49684 40214 49684 40223 49684 40223 49685 40214 49685 40224 49685 40223 49686 40224 49687 40225 49688 40223 49689 40240 49689 40227 49689 40227 49690 40240 49690 40226 49690 40227 49691 40226 49691 40222 49691 40222 49692 40226 49692 40238 49692 40222 49693 40238 49693 40228 49693 40228 49694 40238 49694 40229 49694 40228 49695 40229 49695 40230 49695 40230 49696 40229 49696 40232 49696 40230 49697 40232 49697 39954 49697 39956 49698 40231 49698 40232 49698 40232 49699 40231 49699 40233 49699 40232 49700 40233 49700 39954 49700 40234 49701 39956 49702 40235 49703 40235 49704 39956 49704 40232 49704 40235 49705 40232 49705 40236 49705 40236 49706 40232 49706 40229 49706 40236 49707 40229 49707 40237 49707 40237 49708 40229 49708 40238 49708 40237 49709 40238 49709 40239 49709 40239 49710 40238 49710 40226 49710 40239 49711 40226 49711 40158 49711 40158 49712 40226 49712 40240 49712 40241 49713 40242 49713 40243 49713 40243 49714 40242 49714 40235 49714 40243 49715 40235 49715 40250 49715 40250 49716 40235 49716 40236 49716 40250 49717 40236 49717 40155 49717 40155 49718 40236 49718 40237 49718 40155 49719 40237 49719 40244 49719 40244 49720 40237 49720 40239 49720 40244 49721 40239 49721 40245 49721 40245 49722 40239 49722 40246 49722 39959 49723 40247 49723 40254 49723 40254 49724 40247 49724 40243 49724 40254 49725 40243 49725 40248 49725 40248 49726 40243 49726 40250 49726 40248 49727 40250 49727 40249 49727 40249 49728 40250 49728 40155 49728 40249 49729 40155 49729 39792 49729 39792 49730 40155 49730 40153 49730 40251 49731 40253 49731 40252 49731 40252 49732 40253 49732 40254 49732 40252 49733 40254 49733 40255 49733 40255 49734 40254 49734 40248 49734 40255 49735 40248 49735 40256 49735 40256 49736 40248 49736 40249 49736 39962 49737 40257 49737 40262 49737 40262 49738 40257 49738 40252 49738 40262 49739 40252 49739 40258 49739 40258 49740 40252 49740 40255 49740 40258 49741 40255 49741 40272 49741 40272 49742 40255 49742 40256 49742 40259 49743 40260 49743 40261 49743 40261 49744 40260 49744 39877 49744 39877 49745 39876 49745 40261 49745 40261 49746 39876 49746 40262 49746 40261 49747 40262 49747 40266 49747 40266 49748 40262 49748 40258 49748 40266 49749 40258 49749 40271 49749 40271 49750 40258 49750 40272 49750 40263 49751 40259 49751 40264 49751 40264 49752 40259 49752 40261 49752 40264 49753 40261 49753 40265 49753 40265 49754 40261 49754 40266 49754 40265 49755 40266 49755 40270 49755 40270 49756 40266 49756 40271 49756 40278 49757 39880 49757 40267 49757 40267 49758 39880 49758 39879 49758 39879 49759 40135 49759 40267 49759 40267 49760 40135 49760 40264 49760 40267 49761 40264 49761 40268 49761 40268 49762 40264 49762 40265 49762 40268 49763 40265 49763 40269 49763 40269 49764 40265 49764 40270 49764 40269 49765 40270 49765 39796 49765 39796 49766 40270 49766 40271 49766 39796 49767 40271 49767 39797 49767 39797 49768 40271 49768 40272 49768 39797 49769 40272 49769 39798 49769 39798 49770 40272 49770 40256 49770 39798 49771 40256 49771 39799 49771 39799 49772 40256 49772 40249 49772 39799 49773 40249 49773 40273 49773 40273 49774 40249 49774 39792 49774 40152 49775 40143 49775 40269 49775 40269 49776 40143 49776 40274 49776 40269 49777 40274 49777 40268 49777 40268 49778 40274 49778 40281 49778 40268 49779 40281 49779 40267 49779 40267 49780 40281 49780 40277 49780 40267 49781 40277 49781 40278 49781 40275 49782 40276 49782 40277 49782 40277 49783 40276 49784 39882 49785 40277 49786 39882 49786 40278 49786 40279 49787 40275 49788 40280 49789 40280 49790 40275 49790 40277 49790 40280 49791 40277 49791 40287 49791 40287 49792 40277 49792 40281 49792 40287 49793 40281 49793 40285 49793 40285 49794 40281 49794 40274 49794 40285 49795 40274 49795 40151 49795 40151 49796 40274 49796 40143 49796 40151 49797 40143 49797 40282 49797 40282 49798 40143 49798 40142 49798 40283 49799 40293 49799 40151 49799 40151 49800 40293 49800 40284 49800 40151 49801 40284 49801 40285 49801 40285 49802 40284 49802 40286 49802 40285 49803 40286 49803 40287 49803 40287 49804 40286 49804 40291 49804 40287 49805 40291 49805 40280 49805 40280 49806 40291 49806 40290 49806 40280 49807 40290 49807 40134 49807 39886 49808 39885 49808 40290 49808 40290 49809 39885 49809 40288 49809 40290 49810 40288 49810 40134 49810 40289 49811 39886 49811 40299 49811 40299 49812 39886 49812 40290 49812 40299 49813 40290 49813 40298 49813 40298 49814 40290 49814 40291 49814 40298 49815 40291 49815 40292 49815 40292 49816 40291 49816 40286 49816 40292 49817 40286 49817 40297 49817 40297 49818 40286 49818 40284 49818 40297 49819 40284 49819 40295 49819 40295 49820 40284 49820 40293 49820 40295 49821 40293 49821 40294 49821 40295 49822 40296 49822 40297 49822 40297 49823 40296 49823 40306 49823 40297 49824 40306 49824 40292 49824 40292 49825 40306 49825 40304 49825 40292 49826 40304 49826 40298 49826 40298 49827 40304 49827 40303 49827 40298 49828 40303 49828 40299 49828 40299 49829 40303 49829 40300 49829 40299 49830 40300 49830 39888 49830 40301 49831 39891 49831 40300 49831 40300 49832 39891 49832 39890 49832 40300 49833 39890 49833 39888 49833 40133 49834 40301 49835 40308 49836 40308 49837 40301 49837 40300 49837 40308 49838 40300 49838 40302 49838 40302 49839 40300 49839 40303 49839 40302 49840 40303 49840 40310 49840 40310 49841 40303 49841 40304 49841 40310 49842 40304 49842 40312 49842 40312 49843 40304 49843 40306 49843 40312 49844 40306 49844 40305 49844 40305 49845 40306 49845 40296 49845 40131 49846 40132 49846 40307 49846 40307 49847 40132 49847 40308 49847 40307 49848 40308 49848 40314 49848 40314 49849 40308 49849 40302 49849 40314 49850 40302 49850 40309 49850 40309 49851 40302 49851 40310 49851 40309 49852 40310 49852 40311 49852 40311 49853 40310 49853 40312 49853 40311 49854 40312 49854 40313 49854 40313 49855 40312 49855 40150 49855 40129 49856 39893 49856 40130 49856 40130 49857 39893 49857 40307 49857 40130 49858 40307 49858 40319 49858 40319 49859 40307 49859 40314 49859 40319 49860 40314 49860 40315 49860 40315 49861 40314 49861 40309 49861 40315 49862 40309 49862 40340 49862 40340 49863 40309 49863 40316 49863 39896 49864 40317 49864 40128 49864 40128 49865 40317 49865 40130 49865 40128 49866 40130 49866 40318 49866 40318 49867 40130 49867 40319 49867 40318 49868 40319 49868 40336 49868 40336 49869 40319 49869 40315 49869 39897 49870 40127 49870 40324 49870 40324 49871 40127 49871 40128 49871 40324 49872 40128 49872 40320 49872 40320 49873 40128 49873 40318 49873 40320 49874 40318 49874 40321 49874 40321 49875 40318 49875 40336 49875 40322 49876 39900 49876 40327 49876 40327 49877 39900 49877 39899 49877 39899 49878 40323 49878 40327 49878 40327 49879 40323 49879 40324 49879 40327 49880 40324 49880 40325 49880 40325 49881 40324 49881 40320 49881 40325 49882 40320 49882 40326 49882 40326 49883 40320 49883 40321 49883 40126 49884 40322 49884 40330 49884 40330 49885 40322 49885 40327 49885 40330 49886 40327 49886 40332 49886 40332 49887 40327 49887 40325 49887 40332 49888 40325 49888 40334 49888 40334 49889 40325 49889 40326 49889 39904 49890 40329 49890 40328 49890 40328 49891 40329 49891 39903 49891 39903 49892 39902 49892 40328 49892 40328 49893 39902 49893 40330 49893 40328 49894 40330 49894 40331 49894 40331 49895 40330 49895 40332 49895 40331 49896 40332 49896 40333 49896 40333 49897 40332 49897 40334 49897 40333 49898 40334 49898 40145 49898 40145 49899 40334 49899 40326 49899 40145 49900 40326 49900 40335 49900 40335 49901 40326 49901 40321 49901 40335 49902 40321 49902 40337 49902 40337 49903 40321 49903 40336 49903 40337 49904 40336 49904 40338 49904 40338 49905 40336 49905 40315 49905 40338 49906 40315 49906 40339 49906 40339 49907 40315 49907 40340 49907 40453 49908 40144 49908 40333 49908 40333 49909 40144 49909 40348 49909 40333 49910 40348 49910 40331 49910 40331 49911 40348 49911 40345 49911 40331 49912 40345 49912 40328 49912 40328 49913 40345 49913 40341 49913 40328 49914 40341 49914 39904 49914 40342 49915 40343 49915 40341 49915 40341 49916 40343 49916 39906 49916 40341 49917 39906 49917 39904 49917 39907 49918 40342 49918 40344 49918 40344 49919 40342 49919 40341 49919 40344 49920 40341 49920 40346 49920 40346 49921 40341 49921 40345 49921 40346 49922 40345 49922 40347 49922 40347 49923 40345 49923 40348 49923 40347 49924 40348 49924 40349 49924 40349 49925 40348 49925 40144 49925 40349 49926 40144 49926 40460 49926 40460 49927 40144 49927 40461 49927 40459 49928 40458 49928 40349 49928 40349 49929 40458 49929 40350 49929 40349 49930 40350 49930 40347 49930 40347 49931 40350 49931 40351 49931 40347 49932 40351 49932 40346 49932 40346 49933 40351 49933 40356 49933 40346 49934 40356 49934 40344 49934 40344 49935 40356 49935 40355 49935 40344 49936 40355 49936 40125 49936 40352 49937 40353 49937 40355 49937 40355 49938 40353 49938 39910 49938 40355 49939 39910 49939 40125 49939 40124 49940 40352 49941 40354 49942 40354 49943 40352 49943 40355 49943 40354 49944 40355 49944 40357 49944 40357 49945 40355 49945 40356 49945 40357 49946 40356 49946 40358 49946 40358 49947 40356 49947 40351 49947 40358 49948 40351 49948 40361 49948 40361 49949 40351 49949 40350 49949 40361 49950 40350 49950 40359 49950 40359 49951 40350 49951 40458 49951 40359 49952 40458 49952 40360 49952 40359 49953 40372 49953 40361 49953 40361 49954 40372 49954 40362 49954 40361 49955 40362 49955 40358 49955 40358 49956 40362 49956 40363 49956 40358 49957 40363 49957 40357 49957 40357 49958 40363 49958 40370 49958 40357 49959 40370 49959 40354 49959 40354 49960 40370 49960 40368 49960 40354 49961 40368 49961 40364 49961 40365 49962 40366 49962 40368 49962 40368 49963 40366 49963 40367 49963 40368 49964 40367 49964 40364 49964 39913 49965 40365 49966 40374 49967 40374 49968 40365 49968 40368 49968 40374 49969 40368 49969 40369 49969 40369 49970 40368 49970 40370 49970 40369 49971 40370 49971 40375 49971 40375 49972 40370 49972 40363 49972 40375 49973 40363 49973 40376 49973 40376 49974 40363 49974 40362 49974 40376 49975 40362 49975 40371 49975 40371 49976 40362 49976 40372 49976 39914 49977 40373 49977 40123 49977 40123 49978 40373 49978 40374 49978 40123 49979 40374 49979 40378 49979 40378 49980 40374 49980 40369 49980 40378 49981 40369 49981 40380 49981 40380 49982 40369 49982 40375 49982 40380 49983 40375 49983 40174 49983 40174 49984 40375 49984 40376 49984 40174 49985 40376 49985 40176 49985 40176 49986 40376 49986 40178 49986 39916 49987 39915 49987 40377 49987 40377 49988 39915 49988 40123 49988 40377 49989 40123 49989 40384 49989 40384 49990 40123 49990 40378 49990 40384 49991 40378 49991 40402 49991 40402 49992 40378 49992 40380 49992 40402 49993 40380 49993 40379 49993 40379 49994 40380 49994 40381 49994 39919 49995 40383 49995 40382 49995 40382 49996 40383 49996 40377 49996 40382 49997 40377 49997 40385 49997 40385 49998 40377 49998 40384 49998 40385 49999 40384 49999 40399 49999 40399 50000 40384 50000 40402 50000 39922 50001 39920 50001 40387 50001 40387 50002 39920 50002 40382 50002 40387 50003 40382 50003 40386 50003 40386 50004 40382 50004 40385 50004 40386 50005 40385 50005 40398 50005 40398 50006 40385 50006 40399 50006 40389 50007 39926 50007 40390 50007 40390 50008 39926 50008 39925 50008 39925 50009 39924 50009 40390 50009 40390 50010 39924 50010 40387 50010 40390 50011 40387 50011 40391 50011 40391 50012 40387 50012 40386 50012 40391 50013 40386 50013 40396 50013 40396 50014 40386 50014 40398 50014 40388 50015 40389 50015 40122 50015 40122 50016 40389 50016 40390 50016 40122 50017 40390 50017 40394 50017 40394 50018 40390 50018 40391 50018 40394 50019 40391 50019 40395 50019 40395 50020 40391 50020 40396 50020 40407 50021 39929 50021 40392 50021 40392 50022 39929 50022 39928 50022 39928 50023 39927 50023 40392 50023 40392 50024 39927 50024 40122 50024 40392 50025 40122 50025 40393 50025 40393 50026 40122 50026 40394 50026 40393 50027 40394 50027 40404 50027 40404 50028 40394 50028 40395 50028 40404 50029 40395 50029 40170 50029 40170 50030 40395 50030 40396 50030 40170 50031 40396 50031 40397 50031 40397 50032 40396 50032 40398 50032 40397 50033 40398 50033 40400 50033 40400 50034 40398 50034 40399 50034 40400 50035 40399 50035 40401 50035 40401 50036 40399 50036 40402 50036 40401 50037 40402 50037 40403 50037 40403 50038 40402 50038 40379 50038 40171 50039 40413 50039 40404 50039 40404 50040 40413 50040 40411 50040 40404 50041 40411 50041 40393 50041 40393 50042 40411 50042 40405 50042 40393 50043 40405 50043 40392 50043 40392 50044 40405 50044 40406 50044 40392 50045 40406 50045 40407 50045 40408 50046 39931 50046 40406 50046 40406 50047 39931 50047 40409 50047 40406 50048 40409 50048 40407 50048 40410 50049 40408 50049 40419 50049 40419 50050 40408 50050 40406 50050 40419 50051 40406 50051 40418 50051 40418 50052 40406 50052 40405 50052 40418 50053 40405 50053 40416 50053 40416 50054 40405 50054 40411 50054 40416 50055 40411 50055 40412 50055 40412 50056 40411 50056 40413 50056 40412 50057 40413 50057 40414 50057 40414 50058 40413 50059 40140 50060 40415 50061 40431 50061 40412 50061 40412 50062 40431 50062 40430 50062 40412 50063 40430 50063 40416 50063 40416 50064 40430 50064 40428 50064 40416 50065 40428 50065 40418 50065 40418 50066 40428 50066 40417 50066 40418 50067 40417 50067 40419 50067 40419 50068 40417 50068 40421 50068 40419 50069 40421 50069 40424 50069 40420 50070 40422 50070 40421 50070 40421 50071 40422 50071 40423 50071 40421 50072 40423 50072 40424 50072 40425 50073 40420 50073 40435 50073 40435 50074 40420 50074 40421 50074 40435 50075 40421 50075 40426 50075 40426 50076 40421 50076 40417 50076 40426 50077 40417 50077 40434 50077 40434 50078 40417 50078 40428 50078 40434 50079 40428 50079 40427 50079 40427 50080 40428 50080 40430 50080 40427 50081 40430 50081 40429 50081 40429 50082 40430 50082 40431 50082 40429 50083 40431 50083 40432 50083 40429 50084 40433 50084 40427 50084 40427 50085 40433 50085 40442 50085 40427 50086 40442 50086 40434 50086 40434 50087 40442 50087 40441 50087 40434 50088 40441 50088 40426 50088 40426 50089 40441 50089 40440 50089 40426 50090 40440 50090 40435 50090 40435 50091 40440 50091 40439 50091 40435 50092 40439 50092 40121 50092 40438 50093 40436 50093 40439 50093 40439 50094 40436 50094 40437 50094 40439 50095 40437 50095 40121 50095 39935 50096 40438 50096 40120 50096 40120 50097 40438 50097 40439 50097 40120 50098 40439 50098 40443 50098 40443 50099 40439 50099 40440 50099 40443 50100 40440 50100 40445 50100 40445 50101 40440 50101 40441 50101 40445 50102 40441 50102 40447 50102 40447 50103 40441 50103 40442 50103 40447 50104 40442 50104 40168 50104 40168 50105 40442 50105 40433 50105 40118 50106 39936 50106 40119 50106 40119 50107 39936 50107 40120 50107 40119 50108 40120 50108 40444 50108 40444 50109 40120 50109 40443 50109 40444 50110 40443 50110 40452 50110 40452 50111 40443 50111 40445 50111 40452 50112 40445 50112 40446 50112 40446 50113 40445 50113 40447 50113 40446 50114 40447 50114 40167 50114 40167 50115 40447 50115 40448 50115 40139 50116 40449 50116 40450 50116 40450 50117 40449 50117 40119 50117 40450 50118 40119 50118 40451 50118 40451 50119 40119 50119 40444 50119 40451 50120 40444 50120 40202 50120 40202 50121 40444 50121 40452 50121 40202 50122 40452 50122 40204 50122 40204 50123 40452 50123 40163 50123 40453 50124 40454 50124 40455 50124 40455 50125 40456 50125 40453 50125 40453 50126 40456 50126 40457 50126 40453 50127 40457 50127 40461 50127 40457 50128 40360 50128 40458 50128 40458 50129 40459 50129 40457 50129 40457 50130 40459 50131 40460 50132 40457 50133 40460 50134 40461 50135 40462 50136 40824 50137 40463 50138 40463 50139 40824 50140 40905 50141 40463 50142 40905 50143 40464 50144 40465 50145 40840 50146 40466 50147 40466 50148 40840 50149 40467 50150 40466 50151 40467 50151 40462 50151 40462 50152 40467 50152 40906 50152 40462 50153 40906 50153 40824 50153 40468 50154 40469 50154 41086 50154 41086 50155 40469 50155 40470 50155 41086 50156 40470 50156 40476 50156 40471 50157 40472 50157 40474 50157 40474 50158 40472 50158 40473 50158 40474 50159 40473 50160 41080 50161 41080 50162 41082 50162 40474 50162 40474 50163 41082 50163 40475 50163 40474 50164 40475 50164 40470 50164 40470 50165 40475 50166 41084 50167 40470 50168 41084 50168 40476 50168 40720 50169 40478 50169 40549 50169 40720 50170 40477 50170 40478 50170 40478 50171 40477 50171 40479 50171 40478 50172 40479 50172 40481 50172 40479 50173 40480 50173 40481 50173 40481 50174 40480 50174 40723 50174 40481 50175 40723 50175 40482 50175 40723 50176 40725 50176 40482 50176 40482 50177 40725 50177 40484 50177 40482 50178 40484 50178 40483 50178 40484 50179 40728 50179 40483 50179 40483 50180 40728 50180 40485 50180 40483 50181 40485 50181 40486 50181 40485 50182 40729 50182 40486 50182 40486 50183 40729 50183 40487 50183 40486 50184 40487 50184 40488 50184 40487 50185 40731 50185 40488 50185 40488 50186 40731 50186 40489 50186 40488 50187 40489 50187 40491 50187 40489 50188 40733 50188 40491 50188 40491 50189 40733 50189 40490 50189 40491 50190 40490 50190 40492 50190 40490 50191 40736 50191 40492 50191 40492 50192 40736 50192 40738 50192 40492 50193 40738 50193 40493 50193 40738 50194 40739 50194 40493 50194 40493 50195 40739 50195 40742 50195 40493 50196 40742 50196 40495 50196 40742 50197 40494 50197 40495 50197 40495 50198 40494 50198 40496 50198 40495 50199 40496 50199 40497 50199 40496 50200 40744 50200 40497 50200 40497 50201 40744 50201 40498 50201 40497 50202 40498 50202 40499 50202 40498 50203 40748 50203 40499 50203 40499 50204 40748 50204 40749 50204 40499 50205 40749 50205 40500 50205 40749 50206 40750 50206 40500 50206 40500 50207 40750 50207 40752 50207 40500 50208 40752 50208 40501 50208 40752 50209 40502 50209 40501 50209 40501 50210 40502 50210 40755 50210 40501 50211 40755 50211 40504 50211 40755 50212 40503 50212 40504 50212 40504 50213 40503 50213 40506 50213 40504 50214 40506 50214 40505 50214 40506 50215 40507 50215 40505 50215 40505 50216 40507 50216 40760 50216 40505 50217 40760 50217 40508 50217 40760 50218 40761 50218 40508 50218 40508 50219 40761 50219 40762 50219 40508 50220 40762 50220 40511 50220 40762 50221 40509 50221 40511 50221 40511 50222 40509 50222 40510 50222 40511 50223 40510 50223 40513 50223 40510 50224 40765 50224 40513 50224 40513 50225 40765 50225 40512 50225 40513 50226 40512 50226 40515 50226 40512 50227 40514 50227 40515 50227 40515 50228 40514 50228 40769 50228 40515 50229 40769 50229 40517 50229 40769 50230 40516 50230 40517 50230 40517 50231 40516 50231 40519 50231 40517 50232 40519 50232 40518 50232 40519 50233 40772 50233 40518 50233 40518 50234 40772 50234 40774 50234 40518 50235 40774 50235 40520 50235 40774 50236 40776 50236 40520 50236 40520 50237 40776 50237 40521 50237 40520 50238 40521 50238 40522 50238 40521 50239 40778 50239 40522 50239 40522 50240 40778 50240 40523 50240 40522 50241 40523 50241 40524 50241 40523 50242 40779 50242 40524 50242 40524 50243 40779 50243 40780 50243 40524 50244 40780 50244 40525 50244 40780 50245 40782 50245 40525 50245 40525 50246 40782 50246 40527 50246 40525 50247 40527 50247 40526 50247 40527 50248 40528 50248 40526 50248 40526 50249 40528 50249 40529 50249 40526 50250 40529 50250 40530 50250 40529 50251 40784 50251 40530 50251 40530 50252 40784 50252 40785 50252 40530 50253 40785 50253 40531 50253 40785 50254 40786 50254 40531 50254 40531 50255 40786 50255 40532 50255 40531 50256 40532 50256 40533 50256 40532 50257 40534 50257 40533 50257 40533 50258 40534 50258 40535 50258 40533 50259 40535 50259 40536 50259 40535 50260 40789 50260 40536 50260 40536 50261 40789 50261 40790 50261 40536 50262 40790 50262 40537 50262 40790 50263 40793 50263 40537 50263 40537 50264 40793 50264 40539 50264 40537 50265 40539 50265 40538 50265 40539 50266 40794 50266 40538 50266 40538 50267 40794 50267 40796 50267 40538 50268 40796 50268 40540 50268 40796 50269 40798 50269 40540 50269 40540 50270 40798 50270 40799 50270 40540 50271 40799 50271 40542 50271 40799 50272 40541 50272 40542 50272 40542 50273 40541 50273 40543 50273 40542 50274 40543 50274 40544 50274 40543 50275 40545 50275 40544 50275 40544 50276 40545 50276 40546 50276 40544 50277 40546 50277 40547 50277 40546 50278 40804 50278 40547 50278 40547 50279 40804 50280 40548 50281 40547 50282 40548 50282 40549 50282 40549 50283 40548 50283 40550 50283 40549 50284 40550 50284 40720 50284 40551 50285 40552 50285 40659 50285 40551 50286 40817 50287 40552 50288 40552 50289 40817 50289 40553 50289 40552 50290 40553 50290 40554 50290 40554 50291 40553 50291 40555 50291 40554 50292 40555 50292 40661 50292 40555 50293 40556 50293 40661 50293 40661 50294 40556 50294 40816 50294 40661 50295 40816 50295 40558 50295 40816 50296 40557 50296 40558 50296 40558 50297 40557 50297 40941 50297 40558 50298 40941 50298 40559 50298 40559 50299 40941 50299 40939 50299 40559 50300 40939 50300 40663 50300 40663 50301 40939 50301 40560 50301 40663 50302 40560 50302 40664 50302 40664 50303 40560 50303 40561 50303 40561 50304 40562 50304 40664 50304 40664 50305 40562 50305 40563 50305 40664 50306 40563 50306 40666 50306 40666 50307 40563 50307 40953 50307 40666 50308 40953 50308 40564 50308 40564 50309 40953 50309 40565 50309 40564 50310 40565 50310 40669 50310 40669 50311 40565 50311 40966 50311 40966 50312 40566 50312 40669 50312 40669 50313 40566 50313 40568 50313 40669 50314 40568 50314 40567 50314 40567 50315 40568 50316 40569 50317 40567 50318 40569 50318 40570 50318 40570 50319 40569 50319 40571 50319 40570 50320 40571 50320 40671 50320 40671 50321 40571 50321 40978 50321 40978 50322 40572 50322 40671 50322 40671 50323 40572 50323 40573 50323 40671 50324 40573 50324 40672 50324 40672 50325 40573 50325 40574 50325 40672 50326 40574 50326 40673 50326 40673 50327 40574 50327 40985 50327 40673 50328 40985 50328 40575 50328 40575 50329 40985 50329 40984 50329 40984 50330 40991 50330 40575 50330 40575 50331 40991 50331 40576 50331 40575 50332 40576 50332 40577 50332 40577 50333 40576 50333 40578 50333 40577 50334 40578 50334 40579 50334 40579 50335 40578 50335 40580 50335 40579 50336 40580 50336 40674 50336 40580 50337 40581 50337 40674 50337 40674 50338 40581 50338 40582 50338 40674 50339 40582 50339 40583 50339 40582 50340 41001 50341 40583 50342 40583 50343 41001 50344 41000 50345 40583 50346 41000 50346 40584 50346 40584 50347 41000 50347 40585 50347 40584 50348 40585 50348 40586 50348 40585 50349 40998 50349 40586 50349 40586 50350 40998 50350 41004 50350 40586 50351 41004 50351 40677 50351 41004 50352 40813 50353 40677 50354 40677 50355 40813 50355 41006 50355 40677 50356 41006 50356 40678 50356 40678 50357 41006 50358 40588 50359 40678 50360 40588 50360 40587 50360 40587 50361 40588 50361 41021 50361 40587 50362 41021 50362 40589 50362 40589 50363 41021 50363 40590 50363 40590 50364 40591 50364 40589 50364 40589 50365 40591 50365 41023 50365 40589 50366 41023 50366 40592 50366 40592 50367 41023 50367 40593 50367 40592 50368 40593 50368 40595 50368 40595 50369 40593 50370 40594 50371 40595 50372 40594 50372 40596 50372 40596 50373 40594 50373 41033 50373 41033 50374 41032 50374 40596 50374 40596 50375 41032 50375 41034 50375 40596 50376 41034 50376 40597 50376 40597 50377 41034 50378 40598 50379 40597 50380 40598 50380 40599 50380 40599 50381 40598 50381 40812 50381 40599 50382 40812 50382 40681 50382 40681 50383 40812 50383 40600 50383 40600 50384 41046 50384 40681 50384 40681 50385 41046 50385 40602 50385 40681 50386 40602 50387 40601 50388 40601 50389 40602 50390 40811 50391 40601 50392 40811 50392 40603 50392 40603 50393 40811 50393 41052 50393 40603 50394 41052 50394 40604 50394 40604 50395 41052 50395 40810 50395 40810 50396 41059 50396 40604 50396 40604 50397 41059 50397 40605 50397 40604 50398 40605 50398 40606 50398 40606 50399 40605 50399 41061 50399 40606 50400 41061 50400 40684 50400 40684 50401 41061 50401 40607 50401 40684 50402 40607 50402 40608 50402 40607 50403 40809 50403 40608 50403 40608 50404 40809 50404 41065 50404 40608 50405 41065 50405 40686 50405 41065 50406 40609 50407 40686 50408 40686 50409 40609 50409 40610 50409 40686 50410 40610 50410 40687 50410 40687 50411 40610 50411 40611 50411 40687 50412 40611 50412 40612 50412 40611 50413 41071 50413 40612 50413 40612 50414 41071 50414 40613 50414 40612 50415 40613 50415 40614 50415 40613 50416 41076 50416 40614 50416 40614 50417 41076 50417 41075 50417 40614 50418 41075 50418 40615 50418 40615 50419 41075 50419 40616 50419 40615 50420 40616 50420 40617 50420 40617 50421 40616 50421 41074 50421 40617 50422 41074 50422 40618 50422 40618 50423 41074 50423 40808 50423 40808 50424 40619 50424 40618 50424 40618 50425 40619 50425 40620 50425 40618 50426 40620 50426 40688 50426 40688 50427 40620 50427 41093 50427 40688 50428 41093 50428 40690 50428 40690 50429 41093 50429 40621 50429 40690 50430 40621 50430 40693 50430 40693 50431 40621 50431 40622 50431 40622 50432 40623 50432 40693 50432 40693 50433 40623 50433 41102 50433 40693 50434 41102 50434 40694 50434 40694 50435 41102 50436 40624 50437 40694 50438 40624 50438 40696 50438 40696 50439 40624 50439 40807 50439 40696 50440 40807 50440 40626 50440 40626 50441 40807 50441 41112 50441 41112 50442 41111 50442 40626 50442 40626 50443 41111 50443 40625 50443 40626 50444 40625 50444 40627 50444 40627 50445 40625 50445 41113 50445 40627 50446 41113 50446 40628 50446 40628 50447 41113 50447 41120 50447 40628 50448 41120 50448 40630 50448 40630 50449 41120 50449 40629 50449 40629 50450 41125 50450 40630 50450 40630 50451 41125 50451 40631 50451 40630 50452 40631 50452 40701 50452 40701 50453 40631 50453 40632 50453 40701 50454 40632 50454 40702 50454 40702 50455 40632 50455 40633 50455 40702 50456 40633 50456 40705 50456 40633 50457 40822 50457 40705 50457 40705 50458 40822 50458 40821 50458 40705 50459 40821 50459 40706 50459 40821 50460 40820 50461 40706 50462 40706 50463 40820 50463 40634 50463 40706 50464 40634 50464 40707 50464 40707 50465 40634 50465 40866 50465 40707 50466 40866 50466 40635 50466 40866 50467 40871 50467 40635 50467 40635 50468 40871 50468 40636 50468 40635 50469 40636 50469 40709 50469 40636 50470 40637 50470 40709 50470 40709 50471 40637 50471 40874 50471 40709 50472 40874 50472 40638 50472 40638 50473 40874 50473 40639 50473 40638 50474 40639 50474 40711 50474 40711 50475 40639 50475 40873 50475 40711 50476 40873 50476 40640 50476 40640 50477 40873 50477 40889 50477 40889 50478 40641 50478 40640 50478 40640 50479 40641 50479 40887 50479 40640 50480 40887 50480 40642 50480 40642 50481 40887 50481 40644 50481 40642 50482 40644 50482 40643 50482 40643 50483 40644 50483 40645 50483 40643 50484 40645 50484 40648 50484 40648 50485 40645 50485 40646 50485 40646 50486 40647 50486 40648 50486 40648 50487 40647 50487 40898 50487 40648 50488 40898 50488 40713 50488 40713 50489 40898 50489 40819 50489 40713 50490 40819 50490 40649 50490 40649 50491 40819 50492 40911 50493 40649 50494 40911 50494 40715 50494 40715 50495 40911 50495 40650 50495 40650 50496 40910 50496 40715 50496 40715 50497 40910 50497 40651 50497 40715 50498 40651 50498 40652 50498 40652 50499 40651 50500 40653 50501 40652 50502 40653 50502 40717 50502 40717 50503 40653 50503 40919 50503 40717 50504 40919 50504 40718 50504 40718 50505 40919 50506 40917 50506 40917 50507 40923 50508 40718 50509 40718 50510 40923 50510 40818 50510 40718 50511 40818 50511 40654 50511 40654 50512 40818 50512 40655 50512 40654 50513 40655 50513 40658 50513 40658 50514 40655 50514 40656 50514 40658 50515 40656 50515 40659 50515 40659 50516 40656 50516 40657 50516 40659 50517 40657 50517 40551 50517 40805 50518 40654 50518 40806 50518 40806 50519 40654 50519 40658 50519 40806 50520 40658 50520 40719 50520 40719 50521 40658 50521 40659 50521 40719 50522 40659 50522 40721 50522 40721 50523 40659 50523 40552 50523 40721 50524 40552 50524 40722 50524 40722 50525 40552 50525 40554 50525 40722 50526 40554 50526 40660 50526 40660 50527 40554 50527 40661 50527 40660 50528 40661 50528 40662 50528 40662 50529 40661 50530 40558 50531 40662 50532 40558 50532 40724 50532 40724 50533 40558 50533 40559 50533 40724 50534 40559 50534 40726 50534 40726 50535 40559 50535 40663 50535 40726 50536 40663 50536 40727 50536 40727 50537 40663 50537 40664 50537 40727 50538 40664 50538 40665 50538 40665 50539 40664 50539 40666 50539 40665 50540 40666 50540 40667 50540 40667 50541 40666 50541 40564 50541 40667 50542 40564 50542 40668 50542 40668 50543 40564 50543 40669 50543 40668 50544 40669 50544 40730 50544 40730 50545 40669 50545 40567 50545 40730 50546 40567 50546 40670 50546 40670 50547 40567 50547 40570 50547 40670 50548 40570 50548 40732 50548 40732 50549 40570 50549 40671 50549 40732 50550 40671 50550 40734 50550 40734 50551 40671 50551 40672 50551 40734 50552 40672 50552 40735 50552 40735 50553 40672 50553 40673 50553 40735 50554 40673 50554 40737 50554 40737 50555 40673 50555 40575 50555 40737 50556 40575 50556 40740 50556 40740 50557 40575 50557 40577 50557 40740 50558 40577 50558 40741 50558 40741 50559 40577 50559 40579 50559 40741 50560 40579 50560 40675 50560 40675 50561 40579 50561 40674 50561 40675 50562 40674 50562 40743 50562 40743 50563 40674 50563 40583 50563 40743 50564 40583 50564 40745 50564 40745 50565 40583 50565 40584 50565 40745 50566 40584 50566 40676 50566 40676 50567 40584 50567 40586 50567 40676 50568 40586 50568 40746 50568 40746 50569 40586 50569 40677 50569 40746 50570 40677 50570 40747 50570 40747 50571 40677 50571 40678 50571 40747 50572 40678 50572 40751 50572 40751 50573 40678 50573 40587 50573 40751 50574 40587 50574 40753 50574 40753 50575 40587 50575 40589 50575 40753 50576 40589 50576 40754 50576 40754 50577 40589 50577 40592 50577 40754 50578 40592 50578 40679 50578 40679 50579 40592 50579 40595 50579 40679 50580 40595 50580 40756 50580 40756 50581 40595 50581 40596 50581 40756 50582 40596 50582 40757 50582 40757 50583 40596 50583 40597 50583 40757 50584 40597 50584 40758 50584 40758 50585 40597 50585 40599 50585 40758 50586 40599 50586 40759 50586 40759 50587 40599 50587 40681 50587 40759 50588 40681 50588 40680 50588 40680 50589 40681 50589 40601 50589 40680 50590 40601 50590 40682 50590 40682 50591 40601 50591 40603 50591 40682 50592 40603 50592 40763 50592 40763 50593 40603 50593 40604 50593 40763 50594 40604 50594 40683 50594 40683 50595 40604 50595 40606 50595 40683 50596 40606 50596 40764 50596 40764 50597 40606 50598 40684 50599 40764 50600 40684 50600 40766 50600 40766 50601 40684 50601 40608 50602 40766 50603 40608 50603 40685 50603 40685 50604 40608 50604 40686 50604 40685 50605 40686 50605 40767 50605 40767 50606 40686 50606 40687 50606 40767 50607 40687 50607 40768 50607 40768 50608 40687 50608 40612 50608 40768 50609 40612 50609 40770 50609 40770 50610 40612 50611 40614 50612 40770 50613 40614 50613 40771 50613 40771 50614 40614 50614 40615 50614 40771 50615 40615 50615 40773 50615 40773 50616 40615 50617 40617 50618 40773 50619 40617 50619 40775 50619 40775 50620 40617 50620 40618 50620 40775 50621 40618 50621 40777 50621 40777 50622 40618 50622 40688 50622 40777 50623 40688 50624 40689 50625 40689 50626 40688 50626 40690 50626 40689 50627 40690 50628 40691 50629 40691 50630 40690 50630 40693 50630 40691 50631 40693 50631 40692 50631 40692 50632 40693 50632 40694 50632 40692 50633 40694 50633 40695 50633 40695 50634 40694 50634 40696 50634 40695 50635 40696 50635 40781 50635 40781 50636 40696 50636 40626 50636 40781 50637 40626 50637 40783 50637 40783 50638 40626 50638 40627 50638 40783 50639 40627 50639 40697 50639 40697 50640 40627 50640 40628 50640 40697 50641 40628 50641 40698 50641 40698 50642 40628 50643 40630 50644 40698 50645 40630 50645 40699 50645 40699 50646 40630 50646 40701 50646 40699 50647 40701 50647 40700 50647 40700 50648 40701 50648 40702 50648 40700 50649 40702 50649 40703 50649 40703 50650 40702 50650 40705 50650 40703 50651 40705 50651 40704 50651 40704 50652 40705 50653 40706 50652 40704 50654 40706 50654 40787 50654 40787 50655 40706 50655 40707 50655 40787 50656 40707 50656 40708 50656 40708 50657 40707 50657 40635 50657 40708 50658 40635 50658 40788 50658 40788 50659 40635 50659 40709 50659 40788 50660 40709 50660 40791 50660 40791 50661 40709 50661 40638 50661 40791 50662 40638 50663 40792 50664 40792 50665 40638 50665 40711 50665 40792 50666 40711 50666 40710 50666 40710 50667 40711 50667 40640 50667 40710 50668 40640 50668 40712 50668 40712 50669 40640 50669 40642 50669 40712 50670 40642 50670 40795 50670 40795 50671 40642 50671 40643 50671 40795 50672 40643 50672 40797 50672 40797 50673 40643 50673 40648 50673 40797 50674 40648 50674 40800 50674 40800 50675 40648 50675 40713 50675 40800 50676 40713 50676 40714 50676 40714 50677 40713 50677 40649 50677 40714 50678 40649 50678 40801 50678 40801 50679 40649 50679 40715 50679 40801 50680 40715 50680 40716 50680 40716 50681 40715 50681 40652 50681 40716 50682 40652 50682 40802 50682 40802 50683 40652 50683 40717 50683 40802 50684 40717 50684 40803 50684 40803 50685 40717 50685 40718 50685 40803 50686 40718 50686 40805 50686 40805 50687 40718 50687 40654 50687 40548 50688 40806 50688 40550 50688 40550 50689 40806 50689 40719 50689 40550 50690 40719 50690 40720 50690 40720 50691 40719 50691 40721 50691 40720 50692 40721 50692 40477 50692 40477 50693 40721 50693 40722 50693 40477 50694 40722 50694 40479 50694 40479 50695 40722 50695 40660 50695 40479 50696 40660 50696 40480 50696 40480 50697 40660 50698 40662 50699 40480 50700 40662 50701 40723 50702 40723 50703 40662 50703 40724 50703 40723 50704 40724 50704 40725 50704 40725 50705 40724 50705 40726 50705 40725 50706 40726 50706 40484 50706 40484 50707 40726 50707 40727 50707 40484 50708 40727 50708 40728 50708 40728 50709 40727 50709 40665 50709 40728 50710 40665 50710 40485 50710 40485 50711 40665 50711 40667 50711 40485 50712 40667 50712 40729 50712 40729 50713 40667 50713 40668 50713 40729 50714 40668 50714 40487 50714 40487 50715 40668 50715 40730 50715 40487 50716 40730 50716 40731 50716 40731 50717 40730 50717 40670 50717 40731 50718 40670 50718 40489 50718 40489 50719 40670 50719 40732 50719 40489 50720 40732 50720 40733 50720 40733 50721 40732 50721 40734 50721 40733 50722 40734 50722 40490 50722 40490 50723 40734 50723 40735 50723 40490 50724 40735 50724 40736 50724 40736 50725 40735 50726 40737 50727 40736 50728 40737 50728 40738 50728 40738 50729 40737 50729 40740 50729 40738 50730 40740 50730 40739 50730 40739 50731 40740 50731 40741 50731 40739 50732 40741 50732 40742 50732 40742 50733 40741 50733 40675 50733 40742 50734 40675 50734 40494 50734 40494 50735 40675 50735 40743 50735 40494 50736 40743 50736 40496 50736 40496 50737 40743 50737 40745 50737 40496 50738 40745 50738 40744 50738 40744 50739 40745 50739 40676 50739 40744 50740 40676 50740 40498 50741 40498 50742 40676 50742 40746 50742 40498 50743 40746 50743 40748 50743 40748 50744 40746 50744 40747 50744 40748 50745 40747 50745 40749 50745 40749 50746 40747 50746 40751 50746 40749 50747 40751 50748 40750 50749 40750 50750 40751 50750 40753 50750 40750 50751 40753 50751 40752 50751 40752 50752 40753 50753 40754 50754 40752 50755 40754 50755 40502 50755 40502 50756 40754 50757 40679 50758 40502 50759 40679 50759 40755 50759 40755 50760 40679 50760 40756 50760 40755 50761 40756 50761 40503 50761 40503 50762 40756 50763 40757 50764 40503 50765 40757 50765 40506 50765 40506 50766 40757 50766 40758 50766 40506 50767 40758 50768 40507 50769 40507 50770 40758 50770 40759 50770 40507 50771 40759 50771 40760 50771 40760 50772 40759 50772 40680 50772 40760 50773 40680 50773 40761 50773 40761 50774 40680 50775 40682 50776 40761 50777 40682 50777 40762 50777 40762 50778 40682 50778 40763 50778 40762 50779 40763 50779 40509 50779 40509 50780 40763 50780 40683 50780 40509 50781 40683 50781 40510 50781 40510 50782 40683 50782 40764 50782 40510 50783 40764 50783 40765 50783 40765 50784 40764 50784 40766 50784 40765 50785 40766 50785 40512 50785 40512 50786 40766 50786 40685 50786 40512 50787 40685 50787 40514 50787 40514 50788 40685 50788 40767 50788 40514 50789 40767 50789 40769 50789 40769 50790 40767 50791 40768 50792 40769 50793 40768 50793 40516 50793 40516 50794 40768 50794 40770 50794 40516 50795 40770 50795 40519 50795 40519 50796 40770 50796 40771 50796 40519 50797 40771 50797 40772 50797 40772 50798 40771 50798 40773 50798 40772 50799 40773 50799 40774 50799 40774 50800 40773 50800 40775 50800 40774 50801 40775 50801 40776 50801 40776 50802 40775 50802 40777 50802 40776 50803 40777 50803 40521 50803 40521 50804 40777 50804 40689 50804 40521 50805 40689 50805 40778 50805 40778 50806 40689 50806 40691 50806 40778 50807 40691 50807 40523 50807 40523 50808 40691 50809 40692 50810 40523 50811 40692 50811 40779 50811 40779 50812 40692 50812 40695 50812 40779 50813 40695 50813 40780 50813 40780 50814 40695 50814 40781 50814 40780 50815 40781 50815 40782 50815 40782 50816 40781 50816 40783 50816 40782 50817 40783 50817 40527 50817 40527 50818 40783 50818 40697 50818 40527 50819 40697 50819 40528 50819 40528 50820 40697 50820 40698 50820 40528 50821 40698 50821 40529 50821 40529 50822 40698 50823 40699 50823 40529 50824 40699 50824 40784 50824 40784 50825 40699 50825 40700 50825 40784 50826 40700 50826 40785 50826 40785 50827 40700 50827 40703 50827 40785 50828 40703 50828 40786 50828 40786 50829 40703 50829 40704 50829 40786 50830 40704 50830 40532 50830 40532 50831 40704 50831 40787 50831 40532 50832 40787 50832 40534 50832 40534 50833 40787 50833 40708 50833 40534 50834 40708 50834 40535 50834 40535 50835 40708 50835 40788 50835 40535 50836 40788 50836 40789 50836 40789 50837 40788 50837 40791 50837 40789 50838 40791 50838 40790 50838 40790 50839 40791 50839 40792 50839 40790 50840 40792 50840 40793 50840 40793 50841 40792 50841 40710 50841 40793 50842 40710 50842 40539 50842 40539 50843 40710 50843 40712 50843 40539 50844 40712 50845 40794 50846 40794 50847 40712 50847 40795 50847 40794 50848 40795 50849 40796 50850 40796 50851 40795 50851 40797 50851 40796 50852 40797 50852 40798 50852 40798 50853 40797 50853 40800 50853 40798 50854 40800 50854 40799 50854 40799 50855 40800 50855 40714 50855 40799 50856 40714 50856 40541 50856 40541 50857 40714 50857 40801 50857 40541 50858 40801 50858 40543 50858 40543 50859 40801 50859 40716 50859 40543 50860 40716 50860 40545 50860 40545 50861 40716 50861 40802 50861 40545 50862 40802 50862 40546 50862 40546 50863 40802 50863 40803 50863 40546 50864 40803 50864 40804 50864 40804 50865 40803 50865 40805 50865 40804 50866 40805 50866 40548 50866 40548 50867 40805 50867 40806 50867 41125 50868 40629 50868 41127 50868 41120 50869 41113 50869 41114 50869 40807 50870 40624 50870 41101 50870 40619 50871 40808 50871 41094 50871 41076 50872 40613 50873 41078 50874 40609 50875 41065 50876 41069 50877 40809 50878 40607 50878 41062 50878 41061 50879 40605 50879 41063 50879 41059 50880 40810 50880 41054 50880 41052 50881 40811 50881 41053 50881 40812 50882 40598 50882 41045 50882 40594 50883 40593 50883 41022 50883 40813 50884 41004 50884 40814 50884 41001 50885 40582 50886 40996 50887 40581 50888 40580 50888 40992 50888 40578 50889 40576 50889 40990 50889 40991 50890 40984 50890 40815 50890 40985 50891 40574 50891 40979 50891 40571 50892 40569 50892 40976 50892 40562 50893 40561 50893 40955 50893 40557 50894 40816 50894 40936 50894 40817 50895 40551 50895 40932 50895 40657 50896 40656 50896 40928 50896 40655 50897 40818 50897 40922 50897 40923 50898 40917 50898 40918 50898 40919 50899 40653 50899 40912 50899 40911 50900 40819 50900 40899 50900 40645 50901 40644 50902 40897 50903 40637 50904 40636 50904 40877 50904 40820 50905 40821 50905 40867 50905 40822 50906 40633 50906 40823 50906 40632 50907 40631 50907 41126 50907 40905 50908 40824 50908 40907 50908 40825 50909 40893 50910 40892 50911 41015 50912 40826 50913 41016 50914 40827 50915 41029 50915 41028 50915 41008 50916 41015 50917 41017 50918 41136 50919 40828 50919 40829 50919 40829 50920 40828 50920 40830 50920 40829 50921 40830 50921 40987 50921 41136 50922 40829 50923 41137 50924 41137 50925 40829 50925 40987 50925 41137 50926 40987 50926 40831 50926 40983 50927 40832 50927 40989 50927 40989 50928 40832 50928 40833 50928 40960 50929 40962 50929 40958 50929 40834 50930 40952 50931 40951 50932 40837 50933 40836 50933 40835 50933 40835 50934 40836 50934 40927 50934 40835 50935 40927 50935 40839 50935 40837 50936 40835 50937 40838 50938 40838 50939 40835 50939 40839 50939 40838 50940 40839 50940 40921 50940 40467 50941 40840 50941 40916 50941 40916 50942 40840 50943 40465 50944 40841 50945 40842 50945 40843 50945 40844 50946 40825 50946 40879 50946 40845 50947 41130 50947 40847 50947 40847 50948 41130 50948 41122 50948 40847 50949 41122 50949 40848 50949 40845 50950 40847 50951 40846 50952 40846 50953 40847 50953 40848 50953 40846 50954 40848 50954 40849 50954 41117 50955 40850 50955 40851 50955 40851 50956 40850 50956 41124 50956 40852 50957 41096 50957 40853 50957 41080 50958 40473 50958 40854 50958 40858 50959 41060 50959 40855 50959 40855 50960 41060 50961 40856 50962 40855 50963 40856 50963 40857 50963 40858 50964 40855 50964 40859 50964 40859 50965 40855 50965 40857 50965 40859 50966 40857 50966 41058 50966 41051 50967 40860 50967 41057 50967 41057 50968 40860 50968 40861 50968 40633 50969 40632 50969 40823 50969 40823 50970 40632 50970 41126 50970 40823 50971 41126 50971 40864 50971 40864 50972 41126 50972 40862 50972 40864 50973 40862 50973 40883 50973 40883 50974 40862 50974 40863 50974 40821 50975 40822 50975 40867 50975 40867 50976 40822 50976 40823 50976 40867 50977 40823 50977 40869 50977 40869 50978 40823 50978 40864 50978 40869 50979 40864 50979 40870 50979 40870 50980 40864 50980 40883 50980 40871 50981 40866 50981 40865 50981 40865 50982 40866 50982 40634 50982 40634 50983 40820 50983 40865 50983 40865 50984 40820 50984 40867 50984 40865 50985 40867 50985 40868 50985 40868 50986 40867 50986 40869 50986 40868 50987 40869 50987 40881 50987 40881 50988 40869 50988 40870 50988 40636 50989 40871 50989 40877 50989 40877 50990 40871 50990 40865 50990 40877 50991 40865 50991 40872 50991 40872 50992 40865 50992 40868 50992 40872 50993 40868 50993 40878 50993 40878 50994 40868 50994 40881 50994 40873 50995 40639 50995 40875 50995 40875 50996 40639 50996 40874 50996 40874 50997 40637 50997 40875 50997 40875 50998 40637 50998 40877 50998 40875 50999 40877 50999 40876 50999 40876 51000 40877 51000 40872 51000 40876 51001 40872 51001 40879 51001 40879 51002 40872 51002 40878 51002 40879 51003 40878 51003 40844 51003 40844 51004 40878 51004 40881 51004 40844 51005 40881 51005 40880 51005 40880 51006 40881 51006 40870 51006 40880 51007 40870 51007 40882 51007 40882 51008 40870 51008 40883 51008 40882 51009 40883 51009 40884 51009 40884 51010 40883 51010 40863 51010 40884 51011 40863 51011 40885 51011 40885 51012 40863 51012 41129 51012 40825 51013 40892 51013 40879 51013 40879 51014 40892 51014 40886 51014 40879 51015 40886 51015 40876 51015 40876 51016 40886 51016 40891 51016 40876 51017 40891 51017 40875 51017 40875 51018 40891 51018 40888 51018 40875 51019 40888 51019 40873 51019 40887 51020 40641 51020 40888 51020 40888 51021 40641 51021 40889 51021 40888 51022 40889 51022 40873 51022 40644 51023 40887 51023 40897 51023 40897 51024 40887 51024 40888 51024 40897 51025 40888 51025 40890 51025 40890 51026 40888 51026 40891 51026 40890 51027 40891 51027 40895 51027 40895 51028 40891 51028 40886 51028 40895 51029 40886 51029 40843 51029 40843 51030 40886 51030 40892 51030 40843 51031 40892 51031 40841 51031 40841 51032 40892 51032 40893 51032 40842 51033 40894 51033 40843 51033 40843 51034 40894 51034 40896 51034 40843 51035 40896 51035 40895 51035 40895 51036 40896 51036 40904 51036 40895 51037 40904 51037 40890 51037 40890 51038 40904 51038 40903 51038 40890 51039 40903 51039 40897 51039 40897 51040 40903 51040 40900 51040 40897 51041 40900 51041 40645 51041 40898 51042 40647 51042 40900 51042 40900 51043 40647 51043 40646 51043 40900 51044 40646 51044 40645 51044 40819 51045 40898 51046 40899 51047 40899 51048 40898 51048 40900 51048 40899 51049 40900 51049 40901 51049 40901 51050 40900 51050 40903 51050 40901 51051 40903 51051 40902 51051 40902 51052 40903 51052 40904 51052 40902 51053 40904 51053 40907 51053 40907 51054 40904 51054 40896 51054 40907 51055 40896 51055 40905 51055 40905 51056 40896 51056 40894 51056 40905 51057 40894 51058 40464 51059 40824 51060 40906 51060 40907 51060 40907 51061 40906 51061 40908 51061 40907 51062 40908 51062 40902 51062 40902 51063 40908 51063 40909 51063 40902 51064 40909 51064 40901 51064 40901 51065 40909 51065 40914 51065 40901 51066 40914 51066 40899 51066 40899 51067 40914 51067 40913 51067 40899 51068 40913 51068 40911 51068 40651 51069 40910 51069 40913 51069 40913 51070 40910 51070 40650 51070 40913 51071 40650 51071 40911 51071 40653 51072 40651 51072 40912 51072 40912 51073 40651 51073 40913 51073 40912 51074 40913 51074 40920 51074 40920 51075 40913 51075 40914 51075 40920 51076 40914 51076 40915 51076 40915 51077 40914 51077 40909 51077 40915 51078 40909 51078 40916 51078 40916 51079 40909 51079 40908 51079 40916 51080 40908 51080 40467 51080 40467 51081 40908 51081 40906 51081 40917 51082 40919 51082 40918 51082 40918 51083 40919 51083 40912 51083 40918 51084 40912 51084 40925 51084 40925 51085 40912 51085 40920 51085 40925 51086 40920 51086 40927 51086 40927 51087 40920 51087 40915 51087 40927 51088 40915 51088 40839 51088 40839 51089 40915 51089 40916 51089 40839 51090 40916 51090 40921 51090 40921 51091 40916 51091 40465 51091 40818 51092 40923 51092 40922 51092 40922 51093 40923 51093 40918 51093 40922 51094 40918 51094 40924 51094 40924 51095 40918 51095 40925 51095 40924 51096 40925 51096 40926 51096 40926 51097 40925 51097 40927 51097 40926 51098 40927 51098 40948 51098 40948 51099 40927 51099 40836 51099 40656 51100 40655 51101 40928 51102 40928 51103 40655 51103 40922 51103 40928 51104 40922 51105 40929 51106 40929 51107 40922 51107 40924 51107 40929 51108 40924 51108 40930 51108 40930 51109 40924 51109 40926 51109 40551 51110 40657 51110 40932 51110 40932 51111 40657 51111 40928 51111 40932 51112 40928 51112 40934 51112 40934 51113 40928 51113 40929 51113 40934 51114 40929 51114 40935 51114 40935 51115 40929 51115 40930 51115 40556 51116 40555 51116 40931 51116 40931 51117 40555 51118 40553 51119 40553 51120 40817 51120 40931 51120 40931 51121 40817 51121 40932 51121 40931 51122 40932 51122 40937 51122 40937 51123 40932 51123 40934 51123 40937 51124 40934 51124 40933 51124 40933 51125 40934 51125 40935 51125 40816 51126 40556 51126 40936 51126 40936 51127 40556 51127 40931 51127 40936 51128 40931 51128 40943 51128 40943 51129 40931 51129 40937 51129 40943 51130 40937 51130 40938 51130 40938 51131 40937 51131 40933 51131 40560 51132 40939 51132 40940 51132 40940 51133 40939 51133 40941 51133 40941 51134 40557 51134 40940 51134 40940 51135 40557 51135 40936 51135 40940 51136 40936 51136 40942 51136 40942 51137 40936 51137 40943 51137 40942 51138 40943 51138 40951 51138 40951 51139 40943 51139 40938 51139 40951 51140 40938 51140 40834 51140 40834 51141 40938 51141 40933 51141 40834 51142 40933 51142 40944 51142 40944 51143 40933 51143 40935 51143 40944 51144 40935 51144 40945 51144 40945 51145 40935 51145 40930 51145 40945 51146 40930 51146 40946 51146 40946 51147 40930 51147 40926 51147 40946 51148 40926 51148 40947 51148 40947 51149 40926 51149 40948 51149 40561 51150 40560 51150 40955 51150 40955 51151 40560 51151 40940 51151 40955 51152 40940 51152 40949 51152 40949 51153 40940 51153 40942 51153 40949 51154 40942 51154 40950 51154 40950 51155 40942 51155 40951 51155 40950 51156 40951 51156 40959 51156 40959 51157 40951 51157 40952 51157 40959 51158 40952 51159 40961 51160 40565 51161 40953 51161 40954 51161 40954 51162 40953 51162 40563 51162 40563 51163 40562 51163 40954 51163 40954 51164 40562 51164 40955 51164 40954 51165 40955 51165 40956 51165 40956 51166 40955 51166 40949 51166 40956 51167 40949 51167 40957 51167 40957 51168 40949 51168 40950 51168 40957 51169 40950 51169 40958 51169 40958 51170 40950 51170 40959 51170 40958 51171 40959 51171 40960 51171 40960 51172 40959 51172 40961 51172 40962 51173 40963 51173 40958 51173 40958 51174 40963 51174 40968 51174 40958 51175 40968 51175 40957 51175 40957 51176 40968 51176 40964 51176 40957 51177 40964 51177 40956 51177 40956 51178 40964 51178 40965 51178 40956 51179 40965 51179 40954 51179 40954 51180 40965 51180 40967 51180 40954 51181 40967 51181 40565 51181 40568 51182 40566 51182 40967 51182 40967 51183 40566 51183 40966 51183 40967 51184 40966 51184 40565 51184 40569 51185 40568 51185 40976 51185 40976 51186 40568 51186 40967 51186 40976 51187 40967 51187 40974 51187 40974 51188 40967 51188 40965 51188 40974 51189 40965 51189 40973 51189 40973 51190 40965 51190 40964 51190 40973 51191 40964 51191 40969 51191 40969 51192 40964 51192 40968 51192 40969 51193 40968 51193 40970 51193 40970 51194 40968 51194 40963 51194 40970 51195 40963 51196 40971 51197 40970 51198 40972 51198 40969 51198 40969 51199 40972 51199 40982 51199 40969 51200 40982 51200 40973 51200 40973 51201 40982 51201 40981 51201 40973 51202 40981 51202 40974 51202 40974 51203 40981 51203 40975 51203 40974 51204 40975 51204 40976 51204 40976 51205 40975 51205 40977 51205 40976 51206 40977 51206 40571 51206 40573 51207 40572 51207 40977 51207 40977 51208 40572 51208 40978 51208 40977 51209 40978 51209 40571 51209 40574 51210 40573 51210 40979 51210 40979 51211 40573 51211 40977 51211 40979 51212 40977 51212 40980 51212 40980 51213 40977 51213 40975 51213 40980 51214 40975 51214 40988 51214 40988 51215 40975 51215 40981 51215 40988 51216 40981 51216 40989 51216 40989 51217 40981 51217 40982 51217 40989 51218 40982 51218 40983 51218 40983 51219 40982 51219 40972 51219 40984 51220 40985 51220 40815 51220 40815 51221 40985 51221 40979 51221 40815 51222 40979 51222 40986 51222 40986 51223 40979 51223 40980 51223 40986 51224 40980 51224 40830 51224 40830 51225 40980 51225 40988 51225 40830 51226 40988 51226 40987 51226 40987 51227 40988 51227 40989 51227 40987 51228 40989 51228 40831 51228 40831 51229 40989 51229 40833 51229 40576 51230 40991 51230 40990 51230 40990 51231 40991 51231 40815 51231 40990 51232 40815 51232 40994 51232 40994 51233 40815 51233 40986 51233 40994 51234 40986 51234 41012 51234 41012 51235 40986 51235 40830 51235 41012 51236 40830 51236 41135 51236 41135 51237 40830 51237 40828 51237 40580 51238 40578 51238 40992 51238 40992 51239 40578 51239 40990 51239 40992 51240 40990 51240 40993 51240 40993 51241 40990 51241 40994 51241 40993 51242 40994 51242 40995 51242 40995 51243 40994 51243 41012 51243 40582 51244 40581 51244 40996 51244 40996 51245 40581 51245 40992 51245 40996 51246 40992 51246 40997 51246 40997 51247 40992 51247 40993 51247 40997 51248 40993 51248 41003 51248 41003 51249 40993 51249 40995 51249 40998 51250 40585 51250 40999 51250 40999 51251 40585 51251 41000 51251 41000 51252 41001 51252 40999 51252 40999 51253 41001 51253 40996 51253 40999 51254 40996 51254 41002 51254 41002 51255 40996 51255 40997 51255 41002 51256 40997 51256 41010 51256 41010 36548 40997 36548 41003 36548 41004 51257 40998 51257 40814 51257 40814 51258 40998 51258 40999 51258 40814 51259 40999 51259 41005 51259 41005 51260 40999 51260 41002 51260 41005 51261 41002 51261 41007 51261 41007 51262 41002 51262 41010 51262 41021 51263 40588 51263 41020 51263 41020 51264 40588 51264 41006 51264 41006 51265 40813 51265 41020 51265 41020 51266 40813 51266 40814 51266 41020 51267 40814 51267 41019 51267 41019 51268 40814 51268 41005 51268 41019 51269 41005 51269 41017 51269 41017 51270 41005 51270 41007 51270 41017 51271 41007 51271 41008 51271 41008 51272 41007 51272 41010 51272 41008 51273 41010 51273 41009 51273 41009 51274 41010 51274 41003 51274 41009 51275 41003 51275 41011 51275 41011 51276 41003 51276 40995 51276 41011 51277 40995 51277 41013 51277 41013 51278 40995 51278 41012 51278 41013 51279 41012 51279 41014 51279 41014 51280 41012 51280 41135 51280 41015 51281 41016 51281 41017 51281 41017 51282 41016 51282 41018 51282 41017 51283 41018 51283 41019 51283 41019 51284 41018 51284 41025 51284 41019 51285 41025 51285 41020 51285 41020 51286 41025 51286 41024 51286 41020 51287 41024 51287 41021 51287 41023 51288 40591 51288 41024 51288 41024 51289 40591 51289 40590 51289 41024 51290 40590 51290 41021 51290 40593 51291 41023 51291 41022 51291 41022 51292 41023 51292 41024 51292 41022 51293 41024 51293 41026 51293 41026 51294 41024 51294 41025 51294 41026 51295 41025 51295 41027 51295 41027 51296 41025 51296 41018 51296 41027 51297 41018 51297 41028 51297 41028 51298 41018 51298 41016 51298 41028 51299 41016 51299 40827 51299 40827 51300 41016 51300 40826 51300 41029 51301 41030 51301 41028 51301 41028 51302 41030 51302 41031 51302 41028 51303 41031 51303 41027 51303 41027 51304 41031 51304 41039 51304 41027 51305 41039 51305 41026 51305 41026 51306 41039 51306 41037 51306 41026 51307 41037 51307 41022 51307 41022 51308 41037 51308 41035 51308 41022 51309 41035 51309 40594 51309 41034 51310 41032 51310 41035 51310 41035 51311 41032 51311 41033 51311 41035 51312 41033 51312 40594 51312 40598 51313 41034 51313 41045 51313 41045 51314 41034 51314 41035 51314 41045 51315 41035 51315 41036 51315 41036 51316 41035 51316 41037 51316 41036 51317 41037 51317 41043 51317 41043 51318 41037 51318 41039 51318 41043 51319 41039 51319 41038 51319 41038 51320 41039 51320 41031 51320 41038 51321 41031 51321 41040 51321 41040 51322 41031 51322 41030 51322 41040 51323 41030 51323 41041 51323 41040 51324 41042 51324 41038 51324 41038 51325 41042 51325 41044 51325 41038 51326 41044 51326 41043 51326 41043 51327 41044 51327 41050 51327 41043 51328 41050 51328 41036 51328 41036 51329 41050 51329 41049 51329 41036 51330 41049 51330 41045 51330 41045 51331 41049 51331 41047 51331 41045 51332 41047 51332 40812 51332 40602 51333 41046 51333 41047 51333 41047 51334 41046 51334 40600 51334 41047 51335 40600 51335 40812 51335 40811 51336 40602 51337 41053 51338 41053 51339 40602 51339 41047 51339 41053 51340 41047 51340 41056 51340 41056 51341 41047 51341 41049 51341 41056 51342 41049 51342 41048 51342 41048 51343 41049 51343 41050 51343 41048 51344 41050 51344 41057 51344 41057 51345 41050 51345 41044 51345 41057 51346 41044 51346 41051 51346 41051 51347 41044 51347 41042 51347 40810 51348 41052 51348 41054 51348 41054 51349 41052 51349 41053 51349 41054 51350 41053 51350 41055 51350 41055 51351 41053 51351 41056 51351 41055 51352 41056 51352 40856 51352 40856 51353 41056 51353 41048 51353 40856 51354 41048 51354 40857 51354 40857 51355 41048 51355 41057 51355 40857 51356 41057 51356 41058 51356 41058 51357 41057 51357 40861 51357 40605 51358 41059 51358 41063 51358 41063 51359 41059 51359 41054 51359 41063 51360 41054 51360 41064 51360 41064 51361 41054 51361 41055 51361 41064 51362 41055 51362 41085 51362 41085 51363 41055 51363 40856 51363 41085 51364 40856 51364 41086 51364 41086 51365 40856 51365 41060 51365 40607 51366 41061 51366 41062 51366 41062 51367 41061 51367 41063 51367 41062 51368 41063 51368 41066 51368 41066 51369 41063 51369 41064 51369 41066 51370 41064 51370 41067 51370 41067 51371 41064 51371 41085 51371 41065 51372 40809 51372 41069 51372 41069 51373 40809 51373 41062 51373 41069 51374 41062 51374 41070 51374 41070 51375 41062 51375 41066 51375 41070 51376 41066 51376 41083 51376 41083 51377 41066 51377 41067 51377 41071 51378 40611 51378 41068 51378 41068 51379 40611 51379 40610 51379 40610 51380 40609 51380 41068 51380 41068 51381 40609 51381 41069 51381 41068 51382 41069 51382 41072 51382 41072 51383 41069 51383 41070 51383 41072 51384 41070 51384 41073 51384 41073 51385 41070 51385 41083 51385 40613 51386 41071 51386 41078 51386 41078 51387 41071 51387 41068 51387 41078 51388 41068 51388 41079 51388 41079 51389 41068 51389 41072 51389 41079 51390 41072 51390 41081 51390 41081 51391 41072 51391 41073 51391 41074 51392 40616 51392 41087 51392 41087 51393 40616 51393 41075 51393 41075 51394 41076 51394 41087 51394 41087 51395 41076 51395 41078 51395 41087 51396 41078 51396 41077 51396 41077 51397 41078 51397 41079 51397 41077 51398 41079 51398 40854 51398 40854 51399 41079 51399 41081 51399 40854 51400 41081 51400 41080 51400 41080 51401 41081 51401 41073 51401 41080 51402 41073 51402 41082 51402 41082 51403 41073 51403 41083 51403 41082 51404 41083 51404 40475 51404 40475 51405 41083 51405 41067 51405 40475 51406 41067 51406 41084 51406 41084 51407 41067 51407 41085 51407 41084 51408 41085 51408 40476 51408 40476 51409 41085 51409 41086 51409 40808 51410 41074 51410 41094 51410 41094 51411 41074 51411 41087 51411 41094 51412 41087 51412 41088 51412 41088 51413 41087 51413 41077 51413 41088 51414 41077 51414 41089 51414 41089 51415 41077 51415 40854 51415 41089 51416 40854 51416 41090 51416 41090 51417 40854 51417 40473 51417 41090 51418 40473 51419 41091 51420 40621 51421 41093 51421 41092 51421 41092 51422 41093 51422 40620 51422 40620 51423 40619 51423 41092 51423 41092 51424 40619 51424 41094 51424 41092 51425 41094 51425 41099 51425 41099 51426 41094 51426 41088 51426 41099 51427 41088 51427 41095 51427 41095 51428 41088 51428 41089 51428 41095 51429 41089 51429 40853 51429 40853 51430 41089 51430 41090 51430 40853 51431 41090 51431 40852 51431 40852 51432 41090 51432 41091 51432 41096 51433 41108 51433 40853 51433 40853 51434 41108 51434 41105 51434 40853 51435 41105 51435 41095 51435 41095 51436 41105 51436 41097 51436 41095 51437 41097 51437 41099 51437 41099 51438 41097 51438 41098 51438 41099 51439 41098 51439 41092 51439 41092 51440 41098 51440 41100 51440 41092 51441 41100 51441 40621 51441 41102 51442 40623 51442 41100 51442 41100 51443 40623 51443 40622 51443 41100 51444 40622 51444 40621 51444 40624 51445 41102 51446 41101 51447 41101 51448 41102 51448 41100 51448 41101 51449 41100 51449 41103 51449 41103 51450 41100 51450 41098 51450 41103 51451 41098 51451 41104 51451 41104 51452 41098 51452 41097 51452 41104 51453 41097 51453 41106 51453 41106 51454 41097 51454 41105 51454 41106 51455 41105 51455 41107 51455 41107 51456 41105 51456 41108 51456 41107 51457 41108 51458 41109 51459 41107 51460 41119 51460 41106 51460 41106 51461 41119 51461 41118 51461 41106 51462 41118 51462 41104 51462 41104 51463 41118 51463 41116 51463 41104 51464 41116 51464 41103 51464 41103 51465 41116 51465 41110 51465 41103 51466 41110 51466 41101 51466 41101 51467 41110 51467 41115 51467 41101 51468 41115 51468 40807 51468 40625 51469 41111 51469 41115 51469 41115 51470 41111 51470 41112 51470 41115 51471 41112 51471 40807 51471 41113 51472 40625 51472 41114 51472 41114 51473 40625 51473 41115 51473 41114 51474 41115 51474 41121 51474 41121 51475 41115 51475 41110 51475 41121 51476 41110 51476 41123 51476 41123 51477 41110 51477 41116 51477 41123 51478 41116 51478 40851 51478 40851 51479 41116 51479 41118 51479 40851 51480 41118 51480 41117 51480 41117 51481 41118 51481 41119 51481 40629 51482 41120 51482 41127 51482 41127 51483 41120 51483 41114 51483 41127 51484 41114 51484 41128 51484 41128 51485 41114 51485 41121 51485 41128 51486 41121 51486 41122 51486 41122 51487 41121 51487 41123 51487 41122 51488 41123 51488 40848 51488 40848 51489 41123 51489 40851 51489 40848 51490 40851 51490 40849 51490 40849 51491 40851 51491 41124 51491 40631 51492 41125 51492 41126 51492 41126 51493 41125 51493 41127 51493 41126 51494 41127 51494 40862 51494 40862 51495 41127 51495 41128 51495 40862 51496 41128 51496 40863 51496 40863 51497 41128 51497 41122 51497 40863 51498 41122 51498 41129 51498 41129 51499 41122 51499 41130 51499 41131 51500 41132 51500 41133 51500 41133 51501 41132 51501 41135 51501 41133 51502 41135 51502 41134 51502 41134 51503 41135 51503 40828 51503 41134 51504 40828 51505 41136 51506 41136 51507 41137 51508 41134 51509 41134 51510 41137 51510 40831 51510 41134 51511 40831 51511 40833 51511 41138 51512 41191 51512 41139 51512 41139 51513 41191 51513 41141 51513 41139 51514 41141 51514 41140 51514 41140 51515 41141 51515 41142 51515 41140 51516 41142 51516 41143 51516 41143 51517 41142 51517 41144 51517 41143 51518 41144 51518 41145 51518 41145 51519 41144 51519 41147 51519 41145 51520 41147 51520 41146 51520 41146 51521 41147 51521 41148 51521 41146 51522 41148 51522 41149 51522 41149 51523 41148 51523 41150 51523 41149 51523 41150 51523 41152 51523 41152 51524 41150 51524 41151 51524 41152 51525 41151 51525 41153 51525 41153 51526 41151 51526 41155 51526 41153 51527 41155 51527 41154 51527 41154 51528 41155 51528 41156 51528 41154 51529 41156 51529 41158 51529 41158 51530 41156 51530 41157 51530 41158 51531 41157 51531 41159 51531 41159 51532 41157 51532 41160 51532 41159 51533 41160 51533 41161 51533 41161 51534 41160 51534 41162 51534 41161 51534 41162 51534 41163 51534 41163 51535 41162 51535 41164 51535 41163 51536 41164 51536 41166 51536 41166 51537 41164 51537 41165 51537 41166 51538 41165 51538 41167 51538 41167 51539 41165 51539 41168 51539 41167 51540 41168 51540 41170 51540 41170 51541 41168 51541 41169 51541 41170 51542 41169 51542 41171 51542 41171 51543 41169 51543 41172 51543 41171 51544 41172 51544 41173 51544 41173 51545 41172 51545 41174 51545 41173 51546 41174 51546 41175 51546 41175 51547 41174 51547 41176 51547 41175 51548 41176 51548 41177 51548 41177 51549 41176 51549 41178 51549 41177 51550 41178 51550 41179 51550 41179 51551 41178 51551 41180 51551 41179 51552 41180 51552 41181 51552 41181 51553 41180 51553 41182 51553 41181 51554 41182 51554 41183 51554 41183 51555 41182 51555 41184 51555 41183 51556 41184 51556 41186 51556 41186 51557 41184 51557 41185 51557 41186 51558 41185 51558 41187 51558 41187 51559 41185 51559 41188 51559 41187 51560 41188 51560 41189 51560 41189 51561 41188 51561 41190 51561 41189 51561 41190 51561 41138 51561 41138 51562 41190 51562 41191 51562 41192 51563 41193 51563 41659 51563 41659 51564 41193 51564 41199 51564 41659 51565 41199 51565 41194 51565 41195 51566 41196 51566 41197 51566 41197 51567 41196 51567 41684 51567 41197 51568 41684 51569 41680 51570 41680 51571 41198 51571 41197 51571 41197 51572 41198 51572 41681 51572 41197 51573 41681 51573 41199 51573 41199 51574 41681 51574 41200 51574 41199 51575 41200 51575 41194 51575 41861 51576 41201 51576 41202 51576 41202 51577 41201 51577 41203 51577 41202 51578 41203 51579 41204 51580 41203 51581 41847 51581 41204 51581 41204 51582 41847 51582 41845 51582 41204 51583 41845 51583 41205 51583 41205 51584 41845 51584 41843 51584 41205 51585 41843 51586 41844 51587 41206 51588 41207 51588 41208 51588 41208 51589 41207 51589 41821 51589 41208 51590 41821 51590 41209 51590 41209 51591 41821 51591 41586 51591 41209 51592 41586 51593 41587 51594 41587 51595 41589 51595 41209 51595 41209 51596 41589 51596 41590 51596 41209 51597 41590 51597 41210 51597 41211 51598 41282 51598 41453 51598 41453 51599 41212 51599 41211 51599 41211 51600 41212 51601 41213 51602 41211 51603 41213 51603 41214 51603 41213 51604 41215 51604 41214 51604 41214 51605 41215 51605 41456 51605 41214 51606 41456 51606 41216 51606 41456 51607 41217 51607 41216 51607 41216 51608 41217 51608 41458 51608 41216 51609 41458 51609 41220 51609 41458 51610 41218 51610 41220 51610 41220 51611 41218 51611 41219 51611 41220 51612 41219 51612 41222 51612 41219 35573 41221 35573 41222 35573 41222 51613 41221 51613 41462 51613 41222 51614 41462 51614 41223 51614 41462 51615 41464 51615 41223 51615 41223 51616 41464 51616 41224 51616 41223 51617 41224 51617 41225 51617 41224 51618 41465 51618 41225 51618 41225 51619 41465 51619 41227 51619 41225 51620 41227 51620 41226 51620 41227 51621 41228 51621 41226 51621 41226 51622 41228 51622 41466 51622 41226 51623 41466 51623 41230 51623 41466 51624 41229 51624 41230 51624 41230 51625 41229 51625 41470 51625 41230 51626 41470 51626 41231 51626 41470 51627 41471 51627 41231 51627 41231 51628 41471 51628 41473 51628 41231 51629 41473 51629 41232 51629 41473 51630 41474 51630 41232 51630 41232 51631 41474 51631 41475 51631 41232 51632 41475 51632 41233 51632 41475 51633 41477 51633 41233 51633 41233 35595 41477 35595 41478 35595 41233 51634 41478 51634 41234 51634 41478 51635 41479 51635 41234 51635 41234 35598 41479 35598 41481 35598 41234 51636 41481 51636 41235 51636 41481 51637 41482 51637 41235 51637 41235 51638 41482 51638 41236 51638 41235 51639 41236 51639 41238 51639 41236 51640 41237 51640 41238 51640 41238 51641 41237 51641 41239 51641 41238 51642 41239 51642 41240 51642 41239 51643 41484 51643 41240 51643 41240 51644 41484 51644 41486 51644 41240 51645 41486 51645 41241 51645 41486 51646 41487 51646 41241 51646 41241 51647 41487 51647 41489 51647 41241 51648 41489 51648 41242 51648 41489 35612 41491 35612 41242 35612 41242 51649 41491 51649 41492 51649 41242 51650 41492 51650 41243 51650 41492 51651 41495 51651 41243 51651 41243 51652 41495 51652 41498 51652 41243 51653 41498 51653 41244 51653 41498 51654 41499 51654 41244 51654 41244 51655 41499 51655 41501 51655 41244 51656 41501 51656 41245 51656 41501 51657 41246 51657 41245 51657 41245 51658 41246 51658 41247 51658 41245 51659 41247 51659 41249 51659 41247 51660 41248 51660 41249 51660 41249 51661 41248 51661 41504 51661 41249 51662 41504 51662 41250 51662 41504 51663 41505 51663 41250 51663 41250 51664 41505 51664 41251 51664 41250 51665 41251 51665 41253 51665 41251 51666 41252 51666 41253 51666 41253 51667 41252 51667 41255 51667 41253 51668 41255 51668 41254 51668 41255 51669 41510 51669 41254 51669 41254 51670 41510 51670 41256 51670 41254 51671 41256 51671 41257 51671 41256 51672 41512 51672 41257 51672 41257 35523 41512 35523 41513 35523 41257 51673 41513 51673 41259 51673 41513 51674 41258 51674 41259 51674 41259 51675 41258 51675 41260 51675 41259 51676 41260 51676 41261 51676 41260 51677 41262 51677 41261 51677 41261 51678 41262 51678 41517 51678 41261 51679 41517 51679 41264 51679 41517 51680 41263 51680 41264 51680 41264 51681 41263 51681 41519 51681 41264 51682 41519 51682 41265 51682 41519 51683 41521 51683 41265 51683 41265 51684 41521 51684 41266 51684 41265 51685 41266 51685 41267 51685 41266 51686 41524 51686 41267 51686 41267 51687 41524 51687 41525 51687 41267 51688 41525 51688 41269 51688 41525 51689 41268 51689 41269 51689 41269 35541 41268 35541 41270 35541 41269 51690 41270 51690 41271 51690 41270 51691 41272 51691 41271 51691 41271 51692 41272 51692 41273 51692 41271 51693 41273 51693 41275 51693 41273 51694 41274 51694 41275 51694 41275 51695 41274 51695 41276 51695 41275 51696 41276 51696 41278 51696 41276 51697 41531 51697 41278 51697 41278 35550 41531 35550 41277 35550 41278 51698 41277 51698 41279 51698 41277 51699 41533 51699 41279 51699 41279 51700 41533 51700 41535 51700 41279 51701 41535 51701 41280 51701 41535 35555 41281 35555 41280 35555 41280 51702 41281 51702 41536 51702 41280 51703 41536 51703 41282 51703 41282 51704 41536 51704 41451 51704 41282 51705 41451 51705 41453 51705 41283 51706 41373 51706 41370 51706 41283 51707 41549 51708 41373 51709 41373 51710 41549 51710 41670 51710 41373 51711 41670 51711 41375 51711 41375 51712 41670 51712 41284 51712 41375 51713 41284 51713 41376 51713 41284 51714 41285 51714 41376 51714 41376 51715 41285 51715 41672 51715 41376 51716 41672 51716 41377 51716 41672 51717 41676 51717 41377 51717 41377 51718 41676 51718 41675 51718 41377 51719 41675 51719 41286 51719 41286 51720 41675 51720 41287 51720 41286 51721 41287 51721 41288 51721 41288 51722 41287 51722 41289 51722 41288 51723 41289 51723 41379 51723 41379 51724 41289 51724 41290 51724 41290 51725 41547 51725 41379 51725 41379 51726 41547 51726 41291 51726 41379 51727 41291 51727 41292 51727 41292 51728 41291 51728 41685 51728 41292 51729 41685 51729 41293 51729 41293 51730 41685 51730 41294 51730 41293 51731 41294 51731 41382 51731 41382 51732 41294 51732 41699 51732 41699 51733 41698 51733 41382 51733 41382 51734 41698 51734 41295 51734 41382 51735 41295 51735 41296 51735 41296 51736 41295 51737 41297 51738 41296 51739 41297 51739 41298 51739 41298 51740 41297 51740 41299 51740 41298 51741 41299 51741 41385 51741 41385 51742 41299 51742 41300 51742 41300 51743 41301 51743 41385 51743 41385 51744 41301 51744 41710 51744 41385 51745 41710 51745 41388 51745 41388 51746 41710 51746 41302 51746 41388 51747 41302 51747 41390 51747 41390 51748 41302 51748 41716 51748 41390 51749 41716 51749 41391 51749 41391 51750 41716 51750 41303 51750 41303 51751 41721 51751 41391 51751 41391 51752 41721 51752 41720 51752 41391 51753 41720 51753 41392 51753 41392 51754 41720 51754 41305 51754 41392 51755 41305 51755 41304 51755 41304 51756 41305 51756 41544 51756 41304 51757 41544 51757 41306 51757 41544 51758 41307 51758 41306 51758 41306 51759 41307 51759 41308 51759 41306 51760 41308 51761 41393 51762 41308 51763 41732 51764 41393 51765 41393 51766 41732 51766 41730 51766 41393 51767 41730 51767 41395 51767 41395 51768 41730 51768 41309 51768 41395 51769 41309 51769 41397 51769 41309 51770 41310 51770 41397 51770 41397 51771 41310 51771 41311 51771 41397 51772 41311 51772 41398 51772 41311 51773 41543 51774 41398 51775 41398 51776 41543 51776 41313 51776 41398 51777 41313 51777 41312 51777 41312 51778 41313 51778 41737 51778 41312 51779 41737 51779 41401 51779 41401 51780 41737 51780 41753 51780 41401 51781 41753 51781 41402 51781 41402 51782 41753 51782 41314 51782 41314 51783 41315 51783 41402 51783 41402 51784 41315 51784 41752 51784 41402 51785 41752 51785 41316 51785 41316 51786 41752 51786 41317 51786 41316 51787 41317 51787 41405 51787 41405 51788 41317 51788 41318 51788 41405 51789 41318 51789 41319 51789 41319 51790 41318 51790 41766 51790 41766 51791 41765 51792 41319 51793 41319 51794 41765 51794 41768 51794 41319 51795 41768 51795 41320 51795 41320 51796 41768 51796 41542 51796 41320 51797 41542 51797 41408 51797 41408 51798 41542 51798 41321 51798 41408 51799 41321 51799 41322 51799 41322 51800 41321 51800 41781 51800 41781 51801 41779 51801 41322 51801 41322 51802 41779 51802 41323 51802 41322 51803 41323 51803 41409 51803 41409 51804 41323 51804 41325 51804 41409 51805 41325 51805 41324 51805 41324 51806 41325 51806 41786 51806 41324 51807 41786 51807 41326 51807 41326 51808 41786 51808 41327 51808 41327 51809 41792 51809 41326 51809 41326 51810 41792 51810 41791 51810 41326 51811 41791 51811 41411 51811 41411 51812 41791 51812 41541 51812 41411 51813 41541 51813 41412 51813 41412 51814 41541 51814 41328 51814 41412 51815 41328 51815 41329 51815 41328 51816 41540 51816 41329 51816 41329 51817 41540 51817 41330 51817 41329 51818 41330 51818 41413 51818 41330 51819 41331 51819 41413 51819 41413 51820 41331 51820 41802 51820 41413 51821 41802 51821 41414 51821 41414 51822 41802 51822 41332 51822 41414 51823 41332 51823 41333 51823 41332 51824 41805 51824 41333 51824 41333 51825 41805 51825 41804 51825 41333 51826 41804 51826 41415 51826 41804 51827 41334 51827 41415 51827 41415 51828 41334 51828 41335 51828 41415 51829 41335 51829 41336 51829 41336 51830 41335 51830 41337 51830 41336 51831 41337 51831 41418 51831 41418 51832 41337 51832 41338 51832 41418 51833 41338 51833 41420 51833 41420 51834 41338 51834 41339 51834 41339 51835 41340 51835 41420 51835 41420 51836 41340 51836 41341 51836 41420 51837 41341 51837 41421 51837 41421 51838 41341 51838 41342 51838 41421 51839 41342 51839 41422 51839 41422 51840 41342 51840 41826 51840 41422 51841 41826 51841 41423 51841 41423 51842 41826 51842 41838 51842 41838 51843 41837 51843 41423 51843 41423 51844 41837 51844 41839 51844 41423 51845 41839 51845 41343 51845 41343 51846 41839 51847 41344 51848 41343 51849 41344 51849 41425 51849 41425 51850 41344 51850 41345 51850 41425 51851 41345 51851 41426 51851 41426 51852 41345 51852 41852 51852 41852 51853 41346 51853 41426 51853 41426 51854 41346 51854 41347 51854 41426 51855 41347 51855 41428 51855 41428 51856 41347 51856 41853 51856 41428 51857 41853 51857 41348 51857 41348 51858 41853 51858 41349 51858 41348 51859 41349 51859 41350 51859 41350 51860 41349 51860 41351 51860 41351 51861 41863 51861 41350 51862 41350 51863 41863 51863 41862 51863 41350 51864 41862 51864 41352 51864 41352 51865 41862 51865 41353 51865 41352 51866 41353 51866 41431 51866 41431 51867 41353 51867 41592 51867 41431 51868 41592 51868 41355 51868 41592 51869 41354 51869 41355 51869 41355 51870 41354 51870 41556 51870 41355 51871 41556 51871 41432 51871 41556 51872 41555 51873 41432 51874 41432 51875 41555 51875 41598 51875 41432 51876 41598 51876 41433 51876 41433 51877 41598 51877 41597 51877 41433 51878 41597 51878 41434 51878 41597 51879 41356 51879 41434 51879 41434 51880 41356 51880 41357 51880 41434 51881 41357 51881 41435 51881 41357 51882 41604 51882 41435 51882 41435 51883 41604 51883 41358 51883 41435 51884 41358 51884 41436 51884 41436 51885 41358 51885 41603 51885 41436 51886 41603 51886 41359 51886 41359 51887 41603 51887 41360 51887 41359 51888 41360 51888 41437 51888 41437 51889 41360 51889 41622 51889 41622 51890 41621 51890 41437 51890 41437 51891 41621 51891 41620 51891 41437 51892 41620 51892 41439 51892 41439 51893 41620 51893 41361 51893 41439 51894 41361 51894 41440 51894 41440 51895 41361 51895 41363 51895 41440 51896 41363 51896 41362 51896 41362 51897 41363 51897 41632 51897 41632 51898 41631 51898 41362 51898 41362 51899 41631 51899 41630 51899 41362 51900 41630 51900 41442 51900 41442 51901 41630 51901 41553 51901 41442 51902 41553 51902 41444 51902 41444 51903 41553 51903 41646 51903 41444 51904 41646 51904 41364 51904 41364 51905 41646 51905 41648 51905 41648 51906 41647 51906 41364 51906 41364 51907 41647 51907 41365 51907 41364 51908 41365 51909 41447 51908 41447 51910 41365 51911 41551 51912 41447 51913 41551 51913 41448 51913 41448 51914 41551 51914 41366 51914 41448 51915 41366 51915 41449 51915 41449 51916 41366 51917 41367 51918 41367 51919 41657 51919 41449 51919 41449 51920 41657 51920 41368 51920 41449 51921 41368 51921 41371 51921 41371 51922 41368 51922 41661 51922 41371 51923 41661 51923 41372 51923 41372 51924 41661 51924 41369 51924 41372 51925 41369 51925 41370 51925 41370 51926 41369 51926 41550 51926 41370 51927 41550 51927 41283 51927 41537 51928 41371 51928 41450 51928 41450 51929 41371 51929 41372 51929 41450 51930 41372 51930 41452 51930 41452 51931 41372 51931 41370 51931 41452 51932 41370 51932 41454 51932 41454 51933 41370 51933 41373 51933 41454 51934 41373 51934 41455 51934 41455 51935 41373 51935 41375 51935 41455 51936 41375 51936 41374 51936 41374 51937 41375 51937 41376 51937 41374 51938 41376 51938 41457 51938 41457 51939 41376 51939 41377 51939 41457 51940 41377 51940 41378 51940 41378 51941 41377 51941 41286 51941 41378 51942 41286 51942 41459 51942 41459 51943 41286 51943 41288 51943 41459 51944 41288 51944 41460 51944 41460 51945 41288 51945 41379 51945 41460 51946 41379 51946 41380 51946 41380 51947 41379 51947 41292 51947 41380 51948 41292 51948 41461 51948 41461 51949 41292 51949 41293 51949 41461 51950 41293 51950 41381 51950 41381 51951 41293 51951 41382 51951 41381 51952 41382 51952 41463 51952 41463 51953 41382 51953 41296 51953 41463 51954 41296 51954 41383 51954 41383 51955 41296 51955 41298 51955 41383 51956 41298 51957 41384 51958 41384 51959 41298 51959 41385 51959 41384 51960 41385 51960 41386 51960 41386 51961 41385 51961 41388 51961 41386 51962 41388 51962 41387 51962 41387 51963 41388 51963 41390 51963 41387 51964 41390 51964 41389 51964 41389 51965 41390 51966 41391 51967 41389 51968 41391 51968 41467 51968 41467 51969 41391 51969 41392 51969 41467 51970 41392 51971 41468 51972 41468 51973 41392 51973 41304 51973 41468 51974 41304 51974 41469 51974 41469 51975 41304 51975 41306 51975 41469 51976 41306 51976 41472 51976 41472 51977 41306 51977 41393 51977 41472 51978 41393 51978 41394 51978 41394 51979 41393 51979 41395 51979 41394 51980 41395 51980 41396 51980 41396 51981 41395 51981 41397 51981 41396 51982 41397 51982 41476 51982 41476 51983 41397 51983 41398 51983 41476 51984 41398 51984 41399 51984 41399 51985 41398 51985 41312 51985 41399 51986 41312 51986 41480 51986 41480 51987 41312 51987 41401 51987 41480 51988 41401 51988 41400 51988 41400 51989 41401 51989 41402 51989 41400 51990 41402 51990 41403 51990 41403 51991 41402 51991 41316 51991 41403 51992 41316 51992 41404 51992 41404 51993 41316 51993 41405 51993 41404 51994 41405 51994 41406 51994 41406 51995 41405 51995 41319 51995 41406 51996 41319 51996 41483 51996 41483 51997 41319 51997 41320 51997 41483 51998 41320 51998 41407 51998 41407 51999 41320 51999 41408 51999 41407 52000 41408 52000 41485 52000 41485 52001 41408 52001 41322 52001 41485 52002 41322 52002 41488 52002 41488 52003 41322 52003 41409 52003 41488 52004 41409 52004 41410 52004 41410 52005 41409 52005 41324 52005 41410 52006 41324 52006 41490 52006 41490 52007 41324 52007 41326 52007 41490 52008 41326 52008 41493 52008 41493 52009 41326 52009 41411 52009 41493 52010 41411 52010 41494 52010 41494 52011 41411 52011 41412 52011 41494 52012 41412 52012 41496 52012 41496 52013 41412 52014 41329 52015 41496 52016 41329 52016 41497 52016 41497 52017 41329 52017 41413 52017 41497 52018 41413 52018 41500 52018 41500 52019 41413 52019 41414 52019 41500 52020 41414 52020 41502 52020 41502 52021 41414 52021 41333 52021 41502 52022 41333 52022 41416 52022 41416 52023 41333 52023 41415 52023 41416 52024 41415 52024 41417 52024 41417 52025 41415 52025 41336 52025 41417 52026 41336 52026 41503 52026 41503 52027 41336 52027 41418 52027 41503 52028 41418 52028 41419 52028 41419 52029 41418 52029 41420 52029 41419 52030 41420 52030 41506 52030 41506 52031 41420 52031 41421 52031 41506 52032 41421 52032 41507 52032 41507 52033 41421 52033 41422 52033 41507 52034 41422 52034 41508 52034 41508 52035 41422 52035 41423 52035 41508 52036 41423 52036 41509 52036 41509 52037 41423 52037 41343 52037 41509 52038 41343 52038 41424 52038 41424 52039 41343 52039 41425 52039 41424 52040 41425 52040 41511 52040 41511 52041 41425 52041 41426 52041 41511 52042 41426 52042 41427 52042 41427 52043 41426 52043 41428 52043 41427 52044 41428 52044 41429 52044 41429 52045 41428 52045 41348 52045 41429 52046 41348 52046 41514 52046 41514 52047 41348 52047 41350 52047 41514 52048 41350 52048 41515 52048 41515 52049 41350 52049 41352 52049 41515 52050 41352 52050 41516 52050 41516 52051 41352 52051 41431 52051 41516 52052 41431 52052 41430 52052 41430 52053 41431 52053 41355 52053 41430 52054 41355 52055 41518 52056 41518 52057 41355 52057 41432 52057 41518 52058 41432 52058 41520 52058 41520 52059 41432 52059 41433 52059 41520 52060 41433 52060 41522 52060 41522 52061 41433 52061 41434 52061 41522 52062 41434 52062 41523 52062 41523 52063 41434 52063 41435 52063 41523 52064 41435 52064 41526 52064 41526 52065 41435 52065 41436 52065 41526 52066 41436 52066 41527 52066 41527 52067 41436 52067 41359 52067 41527 52068 41359 52068 41528 52068 41528 52069 41359 52069 41437 52069 41528 52070 41437 52070 41438 52070 41438 52071 41437 52071 41439 52071 41438 52072 41439 52072 41529 52072 41529 52073 41439 52073 41440 52073 41529 52074 41440 52074 41441 52074 41441 52075 41440 52075 41362 52075 41441 52076 41362 52076 41530 52076 41530 52077 41362 52077 41442 52077 41530 52078 41442 52078 41443 52078 41443 52079 41442 52079 41444 52079 41443 52080 41444 52080 41445 52080 41445 52081 41444 52081 41364 52081 41445 52082 41364 52082 41532 52082 41532 52083 41364 52083 41447 52083 41532 52084 41447 52084 41446 52084 41446 52085 41447 52085 41448 52085 41446 52086 41448 52086 41534 52086 41534 52087 41448 52087 41449 52087 41534 52088 41449 52088 41537 52088 41537 52089 41449 52090 41371 52091 41536 52092 41450 52092 41451 52092 41451 52093 41450 52093 41452 52093 41451 52094 41452 52094 41453 52094 41453 52095 41452 52095 41454 52095 41453 52096 41454 52096 41212 52096 41212 52097 41454 52097 41455 52097 41212 52098 41455 52098 41213 52098 41213 52099 41455 52099 41374 52099 41213 52100 41374 52101 41215 52102 41215 52103 41374 52103 41457 52103 41215 52104 41457 52105 41456 52106 41456 52107 41457 52107 41378 52107 41456 52108 41378 52108 41217 52108 41217 52109 41378 52109 41459 52109 41217 52110 41459 52111 41458 52110 41458 52112 41459 52112 41460 52112 41458 52113 41460 52113 41218 52113 41218 52114 41460 52114 41380 52114 41218 52115 41380 52116 41219 52117 41219 52118 41380 52118 41461 52118 41219 52119 41461 52119 41221 52119 41221 52120 41461 52120 41381 52120 41221 52121 41381 52121 41462 52121 41462 52122 41381 52122 41463 52122 41462 52123 41463 52123 41464 52123 41464 52124 41463 52124 41383 52124 41464 52125 41383 52125 41224 52125 41224 52126 41383 52126 41384 52126 41224 52127 41384 52127 41465 52127 41465 52128 41384 52128 41386 52128 41465 52129 41386 52129 41227 52129 41227 52130 41386 52130 41387 52130 41227 52131 41387 52131 41228 52131 41228 52132 41387 52132 41389 52132 41228 52133 41389 52133 41466 52133 41466 52134 41389 52134 41467 52134 41466 52135 41467 52135 41229 52135 41229 52136 41467 52136 41468 52136 41229 52137 41468 52138 41470 52139 41470 52140 41468 52140 41469 52140 41470 52141 41469 52141 41471 52141 41471 52142 41469 52142 41472 52142 41471 52143 41472 52143 41473 52143 41473 52144 41472 52144 41394 52144 41473 52145 41394 52145 41474 52145 41474 52146 41394 52146 41396 52146 41474 52147 41396 52147 41475 52147 41475 52148 41396 52148 41476 52148 41475 52149 41476 52149 41477 52149 41477 52150 41476 52150 41399 52150 41477 52151 41399 52151 41478 52151 41478 52152 41399 52153 41480 52154 41478 52155 41480 52155 41479 52155 41479 52156 41480 52156 41400 52156 41479 52157 41400 52157 41481 52157 41481 52158 41400 52158 41403 52158 41481 52159 41403 52159 41482 52159 41482 52160 41403 52160 41404 52160 41482 52161 41404 52161 41236 52161 41236 52162 41404 52163 41406 52164 41236 52165 41406 52165 41237 52165 41237 52166 41406 52166 41483 52166 41237 52167 41483 52167 41239 52167 41239 52168 41483 52168 41407 52168 41239 52169 41407 52169 41484 52169 41484 52170 41407 52170 41485 52170 41484 52171 41485 52171 41486 52171 41486 52172 41485 52172 41488 52172 41486 52173 41488 52173 41487 52173 41487 52174 41488 52174 41410 52174 41487 52175 41410 52175 41489 52175 41489 52176 41410 52177 41490 52178 41489 52179 41490 52179 41491 52179 41491 52180 41490 52180 41493 52180 41491 52181 41493 52181 41492 52181 41492 52182 41493 52182 41494 52182 41492 52183 41494 52183 41495 52183 41495 52184 41494 52184 41496 52184 41495 52185 41496 52185 41498 52185 41498 52186 41496 52186 41497 52186 41498 52187 41497 52187 41499 52187 41499 52188 41497 52188 41500 52188 41499 52189 41500 52189 41501 52189 41501 52190 41500 52190 41502 52190 41501 52191 41502 52191 41246 52191 41246 52192 41502 52192 41416 52192 41246 52193 41416 52193 41247 52193 41247 52194 41416 52194 41417 52194 41247 52195 41417 52195 41248 52195 41248 52196 41417 52196 41503 52196 41248 52197 41503 52197 41504 52197 41504 52198 41503 52198 41419 52198 41504 52199 41419 52199 41505 52199 41505 52200 41419 52201 41506 52202 41505 52203 41506 52203 41251 52203 41251 52204 41506 52205 41507 52206 41251 52207 41507 52208 41252 52209 41252 52210 41507 52210 41508 52210 41252 52211 41508 52211 41255 52211 41255 52212 41508 52212 41509 52212 41255 52213 41509 52213 41510 52213 41510 52214 41509 52214 41424 52214 41510 52215 41424 52215 41256 52215 41256 52216 41424 52217 41511 52218 41256 52219 41511 52219 41512 52219 41512 52220 41511 52220 41427 52220 41512 52221 41427 52221 41513 52221 41513 52222 41427 52222 41429 52222 41513 52223 41429 52223 41258 52223 41258 52224 41429 52225 41514 52226 41258 52227 41514 52227 41260 52227 41260 52228 41514 52228 41515 52228 41260 52229 41515 52229 41262 52229 41262 52230 41515 52230 41516 52230 41262 52231 41516 52231 41517 52231 41517 52232 41516 52232 41430 52232 41517 52233 41430 52233 41263 52233 41263 52234 41430 52234 41518 52234 41263 52235 41518 52235 41519 52235 41519 52236 41518 52236 41520 52236 41519 52237 41520 52237 41521 52237 41521 52238 41520 52238 41522 52238 41521 52239 41522 52239 41266 52239 41266 52240 41522 52240 41523 52240 41266 52241 41523 52241 41524 52241 41524 52242 41523 52242 41526 52242 41524 52243 41526 52243 41525 52243 41525 52244 41526 52244 41527 52244 41525 52245 41527 52245 41268 52245 41268 52246 41527 52246 41528 52246 41268 52247 41528 52247 41270 52247 41270 52248 41528 52248 41438 52248 41270 52249 41438 52249 41272 52249 41272 52250 41438 52250 41529 52250 41272 52251 41529 52251 41273 52251 41273 52252 41529 52252 41441 52252 41273 52253 41441 52253 41274 52253 41274 52254 41441 52254 41530 52254 41274 52255 41530 52255 41276 52255 41276 52256 41530 52256 41443 52256 41276 52257 41443 52257 41531 52257 41531 52258 41443 52258 41445 52258 41531 52259 41445 52259 41277 52259 41277 52260 41445 52260 41532 52260 41277 52261 41532 52261 41533 52261 41533 52262 41532 52262 41446 52262 41533 52263 41446 52263 41535 52263 41535 52264 41446 52264 41534 52264 41535 52265 41534 52265 41281 52265 41281 52266 41534 52267 41537 52268 41281 52269 41537 52269 41536 52269 41536 52270 41537 52270 41450 52270 41863 52271 41351 52271 41538 52271 41349 52272 41853 52272 41539 52272 41345 52273 41344 52274 41840 52275 41340 52276 41339 52276 41828 52276 41334 52277 41804 52277 41810 52277 41331 52278 41330 52279 41803 52280 41540 52281 41328 52281 41799 52281 41541 52282 41791 52282 41793 52282 41792 52283 41327 52283 41785 52283 41786 52284 41325 52284 41782 52284 41321 52285 41542 52285 41767 52285 41318 52286 41317 52286 41763 52286 41543 52287 41311 52288 41734 52289 41732 52290 41308 52291 41733 52292 41307 52293 41544 52293 41728 52293 41305 52294 41720 52294 41545 52294 41721 52295 41303 52295 41546 52295 41716 52296 41302 52296 41712 52296 41299 52297 41297 52297 41709 52297 41547 52298 41290 52298 41687 52298 41676 52299 41672 52300 41548 52301 41549 52302 41283 52303 41666 52304 41550 52305 41369 52305 41662 52305 41661 52306 41368 52306 41656 52306 41657 52307 41367 52307 41658 52307 41366 52308 41551 52308 41552 52308 41646 52309 41553 52309 41633 52309 41363 52310 41361 52310 41554 52310 41604 52311 41357 52311 41600 52311 41555 52312 41556 52313 41557 52314 41354 52315 41592 52315 41595 52315 41353 52316 41862 52316 41593 52316 41843 52317 41845 52317 41846 52317 41558 52318 41559 52318 41616 52318 41561 52319 41757 52319 41756 52319 41755 52320 41758 52320 41560 52320 41740 52321 41561 52321 41747 52321 41562 52322 41724 52322 41563 52322 41563 52323 41724 52323 41564 52323 41563 52324 41564 52324 41566 52324 41562 52325 41563 52325 41565 52325 41565 52326 41563 52326 41566 52326 41565 52327 41566 52327 41567 52327 41568 52328 41569 52328 41714 52328 41714 52329 41569 52329 41719 52329 41570 52330 41692 52330 41571 52330 41680 52331 41684 52331 41683 52331 41572 52332 41573 52333 41574 52334 41574 52335 41573 52336 41660 52337 41574 52338 41660 52338 41655 52338 41572 52339 41574 52339 41575 52339 41575 52340 41574 52340 41655 52340 41575 52341 41655 52341 41576 52341 41652 52342 41577 52342 41651 52342 41651 52343 41577 52344 41578 52345 41624 52346 41579 52346 41625 52346 41608 52347 41558 52348 41606 52349 41581 52350 41867 52351 41582 52352 41582 52353 41867 52353 41859 52353 41582 52354 41859 52354 41580 52354 41581 52355 41582 52355 41583 52355 41583 52356 41582 52356 41580 52356 41583 52357 41580 52357 41860 52357 41203 52358 41201 52358 41584 52358 41584 52359 41201 52359 41861 52359 41585 52360 41832 52360 41830 52360 41813 52361 41824 52362 41812 52363 41587 52364 41586 52365 41588 52366 41588 52367 41586 52367 41795 52367 41588 52368 41795 52368 41788 52368 41587 52369 41588 52369 41589 52369 41589 52370 41588 52370 41788 52370 41589 52371 41788 52371 41590 52371 41784 52372 41591 52372 41790 52372 41790 52373 41591 52374 41210 52375 41592 52376 41353 52376 41595 52376 41595 52377 41353 52377 41593 52377 41595 52378 41593 52378 41594 52378 41594 52379 41593 52379 41864 52379 41594 52380 41864 52380 41612 52380 41612 52381 41864 52381 41865 52381 41556 52382 41354 52382 41557 52382 41557 52383 41354 52383 41595 52383 41557 52384 41595 52384 41596 52384 41596 52385 41595 52385 41594 52385 41596 52386 41594 52386 41611 52386 41611 52387 41594 52387 41612 52387 41356 52388 41597 52388 41599 52388 41599 52389 41597 52389 41598 52389 41598 52390 41555 52390 41599 52390 41599 52391 41555 52391 41557 52391 41599 52392 41557 52392 41602 52392 41602 52393 41557 52393 41596 52393 41602 52394 41596 52394 41610 52394 41610 52395 41596 52395 41611 52395 41357 52396 41356 52396 41600 52396 41600 52397 41356 52397 41599 52397 41600 52398 41599 52398 41607 52398 41607 52399 41599 52399 41602 52399 41607 52400 41602 52400 41601 52400 41601 52401 41602 52401 41610 52401 41360 52402 41603 52402 41619 52402 41619 52403 41603 52404 41358 52405 41358 52406 41604 52406 41619 52406 41619 52407 41604 52407 41600 52407 41619 52408 41600 52408 41605 52408 41605 52409 41600 52409 41607 52409 41605 52410 41607 52410 41606 52410 41606 52411 41607 52411 41601 52411 41606 52412 41601 52412 41608 52412 41608 52413 41601 52413 41610 52413 41608 52414 41610 52414 41609 52414 41609 52415 41610 52415 41611 52415 41609 52416 41611 52416 41613 52416 41613 52417 41611 52417 41612 52417 41613 52418 41612 52418 41614 52418 41614 52419 41612 52419 41865 52419 41614 52420 41865 52420 41615 52420 41615 52421 41865 52421 41866 52421 41558 52422 41616 52422 41606 52422 41606 52423 41616 52423 41623 52423 41606 52424 41623 52424 41605 52424 41605 52425 41623 52425 41617 52425 41605 52426 41617 52426 41619 52426 41619 52427 41617 52427 41618 52427 41619 52428 41618 52428 41360 52428 41620 52429 41621 52429 41618 52429 41618 52430 41621 52431 41622 52432 41618 52433 41622 52433 41360 52433 41361 52434 41620 52435 41554 52436 41554 52437 41620 52437 41618 52437 41554 52438 41618 52438 41627 52438 41627 52439 41618 52439 41617 52439 41627 52440 41617 52440 41626 52440 41626 52441 41617 52441 41623 52441 41626 52442 41623 52442 41625 52442 41625 52443 41623 52443 41616 52443 41625 52444 41616 52444 41624 52444 41624 52445 41616 52445 41559 52445 41579 52446 41639 52446 41625 52446 41625 52447 41639 52447 41637 52447 41625 52448 41637 52448 41626 52448 41626 52449 41637 52449 41628 52449 41626 52450 41628 52450 41627 52450 41627 52451 41628 52451 41629 52451 41627 52452 41629 52452 41554 52452 41554 52453 41629 52453 41634 52453 41554 52454 41634 52454 41363 52454 41630 52455 41631 52455 41634 52455 41634 52456 41631 52456 41632 52456 41634 52457 41632 52458 41363 52459 41553 52460 41630 52460 41633 52460 41633 52461 41630 52461 41634 52461 41633 52462 41634 52462 41635 52462 41635 52463 41634 52463 41629 52463 41635 52464 41629 52464 41636 52464 41636 52465 41629 52465 41628 52465 41636 52466 41628 52466 41642 52466 41642 52467 41628 52467 41637 52467 41642 52468 41637 52468 41638 52468 41638 52469 41637 52469 41639 52469 41638 52470 41639 52471 41640 52472 41638 52473 41641 52473 41642 52473 41642 52474 41641 52474 41653 52474 41642 52475 41653 52475 41636 52475 41636 52476 41653 52476 41643 52476 41636 52477 41643 52477 41635 52477 41635 52478 41643 52478 41644 52478 41635 52479 41644 52479 41633 52479 41633 52480 41644 52480 41645 52480 41633 52481 41645 52481 41646 52481 41365 52482 41647 52482 41645 52482 41645 52483 41647 52484 41648 52485 41645 52486 41648 52486 41646 52486 41551 52487 41365 52488 41552 52489 41552 52490 41365 52490 41645 52490 41552 52491 41645 52491 41649 52491 41649 52492 41645 52492 41644 52492 41649 52493 41644 52493 41650 52493 41650 52494 41644 52494 41643 52494 41650 52495 41643 52495 41651 52495 41651 52496 41643 52496 41653 52496 41651 52497 41653 52497 41652 52497 41652 52498 41653 52498 41641 52498 41367 52499 41366 52499 41658 52499 41658 52500 41366 52500 41552 52500 41658 52501 41552 52501 41654 52501 41654 52502 41552 52502 41649 52502 41654 52503 41649 52503 41660 52503 41660 52504 41649 52504 41650 52504 41660 52505 41650 52505 41655 52505 41655 52506 41650 52506 41651 52506 41655 52507 41651 52507 41576 52507 41576 52508 41651 52508 41578 52508 41368 52509 41657 52509 41656 52509 41656 52510 41657 52510 41658 52510 41656 52511 41658 52511 41664 52511 41664 52512 41658 52512 41654 52512 41664 52513 41654 52513 41665 52513 41665 52514 41654 52514 41660 52514 41665 52515 41660 52515 41659 52515 41659 52516 41660 52516 41573 52516 41369 52517 41661 52517 41662 52517 41662 52518 41661 52518 41656 52518 41662 52519 41656 52519 41663 52519 41663 52520 41656 52520 41664 52520 41663 52521 41664 52521 41669 52521 41669 52522 41664 52522 41665 52522 41283 52523 41550 52523 41666 52523 41666 52524 41550 52524 41662 52524 41666 52525 41662 52525 41667 52525 41667 52526 41662 52526 41663 52526 41667 52527 41663 52527 41668 52527 41668 52528 41663 52528 41669 52528 41285 52529 41284 52529 41671 52529 41671 52530 41284 52530 41670 52530 41670 52531 41549 52531 41671 52531 41671 52532 41549 52532 41666 52532 41671 52533 41666 52533 41673 52533 41673 52534 41666 52534 41667 52534 41673 52535 41667 52535 41674 52535 41674 52536 41667 52536 41668 52536 41672 52537 41285 52537 41548 52537 41548 52538 41285 52538 41671 52538 41548 52539 41671 52539 41678 52539 41678 52540 41671 52540 41673 52540 41678 52541 41673 52541 41679 52541 41679 52542 41673 52542 41674 52542 41289 52543 41287 52543 41677 52543 41677 52544 41287 52545 41675 52546 41675 52547 41676 52547 41677 52547 41677 52548 41676 52548 41548 52548 41677 52549 41548 52549 41682 52549 41682 52550 41548 52550 41678 52550 41682 52551 41678 52551 41683 52551 41683 52552 41678 52552 41679 52552 41683 52553 41679 52553 41680 52553 41680 52554 41679 52554 41674 52554 41680 52555 41674 52555 41198 52555 41198 52556 41674 52556 41668 52556 41198 52557 41668 52557 41681 52557 41681 52558 41668 52558 41669 52558 41681 52559 41669 52559 41200 52559 41200 52560 41669 52560 41665 52560 41200 52561 41665 52561 41194 52561 41194 52562 41665 52562 41659 52562 41290 52563 41289 52563 41687 52563 41687 52564 41289 52564 41677 52564 41687 52565 41677 52565 41688 52565 41688 52566 41677 52566 41682 52566 41688 52567 41682 52567 41689 52567 41689 52568 41682 52568 41683 52568 41689 52569 41683 52569 41690 52569 41690 52570 41683 52570 41684 52570 41690 52571 41684 52571 41691 52571 41294 52572 41685 52572 41697 52572 41697 52573 41685 52574 41291 52575 41291 52576 41547 52576 41697 52576 41697 52577 41547 52577 41687 52577 41697 52578 41687 52578 41686 52578 41686 52579 41687 52579 41688 52579 41686 52580 41688 52580 41694 52580 41694 52581 41688 52581 41689 52581 41694 52582 41689 52582 41571 52582 41571 52583 41689 52583 41690 52583 41571 52584 41690 52584 41570 52584 41570 52585 41690 52586 41691 52587 41692 52588 41693 52588 41571 52588 41571 52589 41693 52589 41704 52589 41571 52590 41704 52590 41694 52590 41694 52591 41704 52591 41695 52591 41694 52592 41695 52592 41686 52592 41686 52593 41695 52593 41696 52593 41686 52594 41696 52594 41697 52594 41697 52595 41696 52595 41701 52595 41697 52596 41701 52596 41294 52596 41295 52597 41698 52597 41701 52597 41701 52598 41698 52598 41699 52598 41701 52599 41699 52599 41294 52599 41297 52600 41295 52601 41709 52602 41709 52603 41295 52603 41701 52603 41709 52604 41701 52604 41700 52604 41700 52605 41701 52605 41696 52605 41700 52606 41696 52606 41702 52606 41702 52607 41696 52607 41695 52607 41702 52608 41695 52608 41703 52608 41703 52609 41695 52609 41704 52609 41703 52610 41704 52610 41705 52610 41705 52611 41704 52611 41693 52611 41705 52612 41693 52612 41706 52612 41705 52613 41707 52613 41703 52613 41703 52614 41707 52614 41715 52614 41703 52615 41715 52615 41702 52615 41702 52616 41715 52616 41708 52616 41702 52617 41708 52617 41700 52617 41700 52618 41708 52618 41713 52618 41700 52619 41713 52619 41709 52619 41709 52620 41713 52620 41711 52620 41709 52621 41711 52621 41299 52621 41710 52622 41301 52622 41711 52622 41711 52623 41301 52623 41300 52623 41711 52624 41300 52624 41299 52624 41302 52625 41710 52626 41712 52627 41712 52628 41710 52628 41711 52628 41712 52629 41711 52629 41717 52629 41717 52630 41711 52630 41713 52630 41717 52631 41713 52631 41718 52631 41718 52632 41713 52632 41708 52632 41718 52633 41708 52633 41714 52633 41714 52634 41708 52634 41715 52634 41714 52635 41715 52635 41568 52635 41568 52636 41715 52636 41707 52636 41303 52637 41716 52637 41546 52637 41546 52638 41716 52638 41712 52638 41546 52639 41712 52639 41722 52639 41722 52640 41712 52640 41717 52640 41722 52641 41717 52641 41564 52641 41564 52642 41717 52642 41718 52642 41564 52643 41718 52643 41566 52643 41566 52644 41718 52644 41714 52644 41566 52645 41714 52645 41567 52645 41567 52646 41714 52646 41719 52646 41720 52647 41721 52647 41545 52647 41545 52648 41721 52648 41546 52648 41545 52649 41546 52649 41726 52649 41726 52650 41546 52650 41722 52650 41726 52651 41722 52651 41746 52651 41746 52652 41722 52652 41564 52652 41746 52653 41564 52653 41723 52653 41723 52654 41564 52654 41724 52654 41544 52655 41305 52655 41728 52655 41728 52656 41305 52656 41545 52656 41728 52657 41545 52657 41725 52657 41725 52658 41545 52658 41726 52658 41725 52659 41726 52659 41743 52659 41743 52660 41726 52660 41746 52660 41308 52661 41307 52661 41733 52661 41733 52662 41307 52662 41728 52662 41733 52663 41728 52663 41727 52663 41727 52664 41728 52664 41725 52664 41727 52665 41725 52665 41729 52665 41729 52666 41725 52666 41743 52666 41310 52667 41309 52667 41731 52667 41731 52668 41309 52668 41730 52668 41730 52669 41732 52669 41731 52669 41731 52670 41732 52670 41733 52670 41731 52671 41733 52671 41735 52671 41735 52672 41733 52672 41727 52672 41735 52673 41727 52673 41736 52673 41736 52674 41727 52674 41729 52674 41311 52675 41310 52675 41734 52675 41734 52676 41310 52676 41731 52676 41734 52677 41731 52677 41738 52677 41738 52678 41731 52678 41735 52678 41738 52679 41735 52679 41739 52679 41739 52680 41735 52680 41736 52680 41753 52681 41737 52681 41751 52681 41751 52682 41737 52682 41313 52682 41313 52683 41543 52683 41751 52683 41751 52684 41543 52684 41734 52684 41751 52685 41734 52685 41750 52685 41750 52686 41734 52686 41738 52686 41750 52687 41738 52687 41747 52687 41747 52688 41738 52688 41739 52688 41747 52689 41739 52689 41740 52689 41740 52690 41739 52690 41736 52690 41740 52691 41736 52691 41741 52691 41741 52692 41736 52692 41729 52692 41741 52693 41729 52693 41742 52693 41742 52694 41729 52694 41743 52694 41742 52695 41743 52695 41744 52695 41744 52696 41743 52696 41746 52696 41744 52697 41746 52697 41745 52697 41745 52698 41746 52698 41723 52698 41561 52699 41756 52699 41747 52699 41747 52700 41756 52700 41748 52700 41747 52701 41748 52701 41750 52701 41750 52702 41748 52702 41749 52702 41750 52703 41749 52703 41751 52703 41751 52704 41749 52704 41754 52704 41751 52705 41754 52705 41753 52705 41752 52706 41315 52706 41754 52706 41754 52707 41315 52707 41314 52707 41754 52708 41314 52708 41753 52708 41317 52709 41752 52709 41763 52709 41763 52710 41752 52710 41754 52710 41763 52711 41754 52711 41762 52711 41762 52712 41754 52712 41749 52712 41762 52713 41749 52713 41760 52713 41760 52714 41749 52714 41748 52714 41760 52715 41748 52715 41560 52715 41560 52716 41748 52716 41756 52716 41560 52717 41756 52717 41755 52717 41755 52718 41756 52718 41757 52718 41758 52719 41759 52719 41560 52719 41560 52720 41759 52720 41772 52720 41560 52721 41772 52721 41760 52721 41760 52722 41772 52722 41761 52722 41760 52723 41761 52723 41762 52723 41762 52724 41761 52724 41770 52724 41762 52725 41770 52725 41763 52725 41763 52726 41770 52726 41764 52726 41763 52727 41764 52727 41318 52727 41768 52728 41765 52728 41764 52728 41764 52729 41765 52729 41766 52729 41764 52730 41766 52730 41318 52730 41542 52731 41768 52731 41767 52731 41767 52732 41768 52732 41764 52732 41767 52733 41764 52733 41769 52733 41769 52734 41764 52734 41770 52734 41769 52735 41770 52735 41771 52735 41771 52736 41770 52736 41761 52736 41771 52737 41761 52737 41776 52737 41776 52738 41761 52738 41772 52738 41776 52739 41772 52739 41773 52739 41773 52740 41772 52740 41759 52740 41773 52741 41759 52741 41774 52741 41773 52742 41775 52742 41776 52742 41776 52743 41775 52743 41777 52743 41776 52744 41777 52744 41771 52744 41771 52745 41777 52745 41783 52745 41771 52746 41783 52746 41769 52746 41769 52747 41783 52747 41778 52747 41769 52748 41778 52748 41767 52748 41767 52749 41778 52749 41780 52749 41767 52750 41780 52750 41321 52750 41323 52751 41779 52751 41780 52751 41780 52752 41779 52752 41781 52752 41780 52753 41781 52753 41321 52753 41325 52754 41323 52754 41782 52754 41782 52755 41323 52755 41780 52755 41782 52756 41780 52756 41787 52756 41787 52757 41780 52757 41778 52757 41787 52758 41778 52758 41789 52758 41789 52759 41778 52759 41783 52759 41789 52760 41783 52760 41790 52760 41790 52761 41783 52761 41777 52761 41790 52762 41777 52762 41784 52762 41784 52763 41777 52763 41775 52763 41327 52764 41786 52764 41785 52764 41785 52765 41786 52765 41782 52765 41785 52766 41782 52766 41794 52766 41794 52767 41782 52767 41787 52767 41794 52768 41787 52768 41795 52768 41795 52769 41787 52769 41789 52769 41795 52770 41789 52770 41788 52770 41788 52771 41789 52771 41790 52771 41788 52772 41790 52772 41590 52772 41590 52773 41790 52773 41210 52773 41791 52774 41792 52774 41793 52774 41793 52775 41792 52775 41785 52775 41793 52776 41785 52776 41796 52776 41796 52777 41785 52777 41794 52777 41796 52778 41794 52778 41798 52778 41798 52779 41794 52779 41795 52779 41798 52780 41795 52780 41821 52780 41821 52781 41795 52781 41586 52781 41328 52782 41541 52783 41799 52783 41799 52784 41541 52784 41793 52784 41799 52785 41793 52785 41801 52785 41801 52786 41793 52786 41796 52786 41801 52787 41796 52787 41797 52787 41797 52788 41796 52788 41798 52788 41330 52789 41540 52789 41803 52789 41803 52790 41540 52790 41799 52790 41803 52791 41799 52791 41800 52791 41800 52792 41799 52792 41801 52792 41800 52793 41801 52793 41817 52793 41817 52794 41801 52794 41797 52794 41805 52795 41332 52795 41806 52795 41806 52796 41332 52797 41802 52798 41802 52799 41331 52799 41806 52799 41806 52800 41331 52800 41803 52800 41806 52801 41803 52801 41807 52801 41807 52802 41803 52802 41800 52802 41807 52803 41800 52803 41815 52803 41815 52804 41800 52804 41817 52804 41804 52805 41805 52805 41810 52805 41810 52806 41805 52806 41806 52806 41810 52807 41806 52807 41808 52807 41808 52808 41806 52808 41807 52808 41808 52809 41807 52809 41814 52809 41814 52810 41807 52810 41815 52810 41338 52811 41337 52811 41809 52811 41809 52812 41337 52812 41335 52812 41335 52813 41334 52813 41809 52813 41809 52814 41334 52814 41810 52814 41809 52815 41810 52815 41811 52815 41811 52816 41810 52816 41808 52816 41811 52817 41808 52817 41812 52817 41812 52818 41808 52818 41814 52818 41812 52819 41814 52819 41813 52819 41813 52820 41814 52820 41815 52820 41813 52821 41815 52821 41816 52821 41816 52822 41815 52822 41817 52822 41816 52823 41817 52823 41818 52823 41818 52824 41817 52824 41797 52824 41818 52825 41797 52825 41819 52825 41819 52826 41797 52826 41798 52826 41819 52827 41798 52827 41820 52827 41820 52828 41798 52828 41821 52828 41339 52829 41338 52829 41828 52829 41828 52830 41338 52830 41809 52830 41828 52831 41809 52831 41822 52831 41822 52832 41809 52832 41811 52832 41822 52833 41811 52833 41823 52833 41823 52834 41811 52834 41812 52834 41823 52835 41812 52835 41831 52835 41831 52836 41812 52836 41824 52836 41831 52837 41824 52837 41825 52837 41826 52838 41342 52838 41827 52838 41827 52839 41342 52839 41341 52839 41341 52840 41340 52840 41827 52840 41827 52841 41340 52841 41828 52841 41827 52842 41828 52842 41835 52842 41835 52843 41828 52843 41822 52843 41835 52844 41822 52844 41829 52844 41829 52845 41822 52845 41823 52845 41829 52846 41823 52846 41830 52846 41830 52847 41823 52847 41831 52847 41830 52848 41831 52848 41585 52848 41585 52849 41831 52849 41825 52849 41832 52850 41842 52850 41830 52850 41830 52851 41842 52851 41833 52851 41830 52852 41833 52852 41829 52852 41829 52853 41833 52853 41834 52853 41829 52854 41834 52854 41835 52854 41835 52855 41834 52855 41841 52855 41835 52856 41841 52856 41827 52856 41827 52857 41841 52857 41836 52857 41827 52858 41836 52858 41826 52858 41839 52859 41837 52859 41836 52859 41836 52860 41837 52860 41838 52860 41836 52861 41838 52862 41826 52863 41344 52864 41839 52864 41840 52864 41840 52865 41839 52865 41836 52865 41840 52866 41836 52866 41850 52866 41850 52867 41836 52867 41841 52867 41850 52868 41841 52868 41849 52868 41849 52869 41841 52869 41834 52869 41849 52870 41834 52870 41846 52870 41846 52871 41834 52871 41833 52871 41846 52872 41833 52872 41843 52872 41843 52873 41833 52873 41842 52873 41843 52874 41842 52874 41844 52874 41845 52875 41847 52875 41846 52875 41846 52876 41847 52876 41848 52876 41846 52877 41848 52877 41849 52877 41849 52878 41848 52878 41857 52878 41849 52879 41857 52879 41850 52879 41850 52880 41857 52880 41855 52880 41850 52881 41855 52881 41840 52881 41840 52882 41855 52882 41851 52882 41840 52883 41851 52883 41345 52883 41347 52884 41346 52884 41851 52884 41851 52885 41346 52885 41852 52885 41851 52886 41852 52886 41345 52886 41853 52887 41347 52887 41539 52887 41539 52888 41347 52888 41851 52888 41539 52889 41851 52889 41854 52889 41854 52890 41851 52890 41855 52890 41854 52891 41855 52891 41856 52891 41856 52892 41855 52892 41857 52892 41856 52893 41857 52893 41584 52893 41584 52894 41857 52894 41848 52894 41584 52895 41848 52895 41203 52895 41203 52896 41848 52896 41847 52896 41351 52897 41349 52897 41538 52897 41538 52898 41349 52898 41539 52898 41538 52899 41539 52899 41858 52899 41858 52900 41539 52900 41854 52900 41858 52901 41854 52901 41859 52901 41859 52902 41854 52902 41856 52902 41859 52903 41856 52903 41580 52903 41580 52904 41856 52904 41584 52904 41580 52905 41584 52905 41860 52905 41860 52906 41584 52906 41861 52906 41862 52907 41863 52907 41593 52907 41593 52908 41863 52908 41538 52908 41593 52909 41538 52909 41864 52909 41864 52910 41538 52910 41858 52910 41864 52911 41858 52911 41865 52911 41865 52912 41858 52912 41859 52912 41865 52913 41859 52913 41866 52913 41866 52914 41859 52914 41867 52914 41920 52915 41921 52915 41869 52915 41869 52916 41921 52916 41868 52916 41869 52917 41868 52917 41870 52917 41870 52918 41868 52918 41871 52918 41870 52919 41871 52919 41872 52919 41872 52920 41871 52920 41873 52920 41872 52921 41873 52921 41874 52921 41874 52922 41873 52922 41876 52922 41874 52923 41876 52923 41875 52923 41875 50 41876 50 41877 50 41875 50 41877 50 41878 50 41878 52924 41877 52924 41879 52924 41878 52924 41879 52924 41881 52924 41881 52925 41879 52925 41880 52925 41881 52925 41880 52925 41882 52925 41882 52926 41880 52926 41884 52926 41882 52927 41884 52927 41883 52927 41883 52928 41884 52928 41885 52928 41883 52929 41885 52929 41887 52929 41887 52930 41885 52930 41886 52930 41887 52931 41886 52931 41889 52931 41889 52932 41886 52932 41888 52932 41889 52933 41888 52933 41890 52933 41890 52934 41888 52934 41891 52934 41890 52935 41891 52935 41892 52935 41892 52936 41891 52936 41893 52936 41892 52936 41893 52936 41894 52936 41894 52937 41893 52937 41895 52937 41894 52938 41895 52938 41897 52938 41897 52939 41895 52939 41896 52939 41897 52940 41896 52940 41899 52940 41899 52941 41896 52941 41898 52941 41899 52942 41898 52942 41900 52942 41900 52943 41898 52943 41901 52943 41900 52944 41901 52944 41902 52944 41902 52945 41901 52945 41903 52945 41902 52946 41903 52946 41904 52946 41904 52947 41903 52947 41905 52947 41904 52948 41905 52948 41906 52948 41906 52949 41905 52949 41907 52949 41906 52950 41907 52950 41908 52950 41908 52951 41907 52951 41909 52951 41908 52952 41909 52952 41911 52952 41911 52953 41909 52953 41910 52953 41911 52954 41910 52954 41912 52954 41912 52955 41910 52955 41913 52955 41912 52956 41913 52956 41914 52956 41914 52957 41913 52957 41915 52957 41914 52958 41915 52958 41916 52958 41916 52959 41915 52959 41917 52959 41916 52960 41917 52960 41919 52960 41919 52961 41917 52961 41918 52961 41919 52962 41918 52962 41920 52962 41920 52963 41918 52963 41921 52963 42298 52964 41922 52964 41923 52964 41923 52965 41924 52965 42298 52965 42298 52966 41924 52966 41926 52966 42298 52967 41926 52967 41925 52967 41926 52968 41927 52968 42353 52968 42353 52969 42352 52969 41926 52969 41926 52970 42352 52970 42351 52970 41926 52971 42351 52971 41925 52971 41928 52972 41929 52972 41930 52972 41930 52973 41929 52973 42585 52973 41930 52974 42585 52974 41931 52974 41931 52975 42585 52975 42586 52975 41931 52976 42586 52977 42299 52978 42299 52979 42302 52979 41931 52979 41931 52980 42302 52980 41932 52980 41931 52981 41932 52981 42582 52981 41933 52982 41934 52982 42002 52982 41933 52983 42169 52983 41934 52983 41934 52984 42169 52984 42171 52984 41934 52985 42171 52985 41935 52985 42171 52986 42172 52986 41935 52986 41935 52987 42172 52987 42174 52987 41935 52988 42174 52988 41936 52988 42174 52989 42176 52989 41936 52989 41936 52990 42176 52990 42177 52990 41936 52991 42177 52991 41937 52991 42177 52992 42179 52992 41937 52992 41937 52993 42179 52993 41938 52993 41937 52994 41938 52994 41940 52994 41938 52995 41939 52995 41940 52995 41940 52996 41939 52996 42181 52996 41940 52997 42181 52997 41941 52997 42181 52998 42182 52998 41941 52998 41941 52999 42182 52999 41942 52999 41941 53000 41942 53000 41944 53000 41942 53001 41943 53001 41944 53001 41944 53002 41943 53002 42185 53002 41944 53003 42185 53003 41945 53003 42185 53004 42186 53004 41945 53004 41945 53005 42186 53005 42188 53005 41945 53006 42188 53006 41946 53006 42188 53007 42189 53007 41946 53007 41946 53008 42189 53008 41947 53008 41946 53009 41947 53009 41948 53009 41947 53010 42191 53010 41948 53010 41948 53011 42191 53011 42194 53011 41948 53012 42194 53012 41949 53012 42194 53013 42195 53013 41949 53013 41949 53014 42195 53014 42196 53014 41949 53015 42196 53015 41950 53015 42196 53016 42198 53016 41950 53016 41950 53017 42198 53017 41951 53017 41950 53018 41951 53018 41953 53018 41951 53019 41952 53019 41953 53019 41953 53020 41952 53020 42200 53020 41953 53021 42200 53021 41954 53021 42200 53022 41955 53022 41954 53022 41954 53023 41955 53023 41956 53023 41954 53024 41956 53024 41957 53024 41956 53025 42201 53025 41957 53025 41957 53026 42201 53026 42203 53026 41957 53027 42203 53027 41958 53027 42203 53028 42206 53028 41958 53028 41958 53029 42206 53029 41959 53029 41958 53030 41959 53030 41960 53030 41959 53031 42209 53031 41960 53031 41960 53032 42209 53032 41961 53032 41960 53033 41961 53033 41962 53033 41961 53034 42211 53034 41962 53034 41962 53035 42211 53035 42212 53035 41962 53036 42212 53036 41964 53036 42212 53037 41963 53037 41964 53037 41964 53038 41963 53038 41965 53038 41964 53039 41965 53039 41966 53039 41965 53040 42215 53040 41966 53040 41966 53041 42215 53041 41967 53041 41966 53042 41967 53042 41968 53042 41967 53043 42217 53043 41968 53043 41968 53044 42217 53044 41970 53044 41968 53045 41970 53045 41969 53045 41970 53046 42220 53046 41969 53046 41969 53047 42220 53047 42221 53047 41969 53048 42221 53048 41971 53048 42221 53049 42224 53049 41971 53049 41971 53050 42224 53050 41972 53050 41971 53051 41972 53051 41973 53051 41972 53052 41974 53052 41973 53052 41973 53053 41974 53053 41975 53053 41973 53054 41975 53054 41978 53054 41975 53055 41976 53055 41978 53055 41978 53056 41976 53056 41977 53056 41978 53057 41977 53057 41979 53057 41977 53058 42229 53058 41979 53058 41979 53059 42229 53059 42230 53059 41979 53060 42230 53060 41980 53060 42230 53061 41981 53061 41980 53061 41980 53062 41981 53062 42233 53062 41980 53063 42233 53063 41982 53063 42233 53064 42234 53064 41982 53064 41982 53065 42234 53065 41983 53065 41982 53066 41983 53066 41984 53066 41983 53067 42236 53067 41984 53067 41984 53068 42236 53068 42237 53068 41984 53069 42237 53069 41985 53069 42237 53070 42239 53070 41985 53070 41985 53071 42239 53071 41986 53071 41985 53072 41986 53072 41988 53072 41986 53073 41987 53073 41988 53073 41988 53074 41987 53074 41989 53074 41988 53075 41989 53075 41991 53075 41989 53076 41990 53076 41991 53076 41991 53077 41990 53077 42246 53077 41991 53078 42246 53078 41992 53078 42246 53079 42247 53079 41992 53079 41992 53080 42247 53080 42249 53080 41992 53081 42249 53081 41993 53081 42249 53082 42250 53082 41993 53082 41993 53083 42250 53083 42252 53083 41993 53084 42252 53084 41994 53084 42252 53085 41995 53085 41994 53085 41994 53086 41995 53086 41996 53086 41994 53087 41996 53087 41999 53087 41996 53088 41997 53088 41999 53088 41999 53089 41997 53089 41998 53089 41999 53090 41998 53090 42000 53090 41998 53091 42001 53091 42000 53091 42000 53092 42001 53092 42257 53092 42000 53093 42257 53093 42002 53093 42002 53094 42257 53094 42165 53094 42002 53095 42165 53095 41933 53095 42003 53096 42106 53096 42105 53096 42003 53097 42273 53098 42106 53099 42106 53100 42273 53100 42397 53100 42106 53101 42397 53101 42107 53101 42107 53102 42397 53102 42396 53102 42107 53103 42396 53103 42004 53103 42396 53104 42005 53104 42004 53104 42004 53105 42005 53105 42272 53105 42004 53106 42272 53106 42006 53106 42272 53107 42403 53108 42006 53109 42006 53110 42403 53110 42402 53110 42006 53111 42402 53111 42007 53111 42007 53112 42402 53113 42008 53114 42007 53115 42008 53115 42108 53115 42108 53116 42008 53116 42009 53116 42108 53117 42009 53117 42110 53117 42110 53118 42009 53118 42413 53118 42413 53119 42271 53120 42110 53121 42110 53122 42271 53122 42010 53122 42110 53123 42010 53123 42011 53123 42011 53124 42010 53125 42416 53124 42011 53126 42416 53126 42112 53126 42112 53127 42416 53127 42428 53127 42112 53128 42428 53128 42015 53128 42015 53129 42428 53129 42012 53129 42012 53130 42013 53130 42015 53130 42015 53131 42013 53131 42014 53131 42015 53132 42014 53132 42016 53132 42016 53133 42014 53133 42429 53133 42016 53134 42429 53134 42017 53134 42017 53135 42429 53135 42018 53135 42017 53136 42018 53136 42021 53136 42021 53137 42018 53137 42019 53137 42019 53138 42020 53138 42021 53139 42021 53140 42020 53140 42440 53140 42021 53141 42440 53141 42116 53141 42116 53142 42440 53143 42022 53144 42116 53145 42022 53145 42118 53145 42118 53146 42022 53147 42023 53148 42118 53149 42023 53149 42119 53149 42119 53150 42023 53151 42442 53152 42442 53153 42270 53153 42119 53153 42119 53154 42270 53154 42268 53154 42119 53155 42268 53155 42024 53155 42024 53156 42268 53156 42267 53156 42024 53157 42267 53157 42121 53157 42121 53158 42267 53158 42025 53158 42121 53159 42025 53159 42122 53159 42025 53160 42455 53160 42122 53160 42122 53161 42455 53161 42454 53161 42122 53162 42454 53162 42027 53162 42454 53163 42026 53163 42027 53163 42027 53164 42026 53164 42458 53164 42027 53165 42458 53165 42028 53165 42028 53166 42458 53166 42457 53166 42028 53167 42457 53167 42125 53167 42457 53168 42029 53168 42125 53168 42125 53169 42029 53169 42265 53169 42125 53170 42265 53170 42030 53170 42265 53171 42467 53171 42030 53171 42030 53172 42467 53172 42031 53172 42030 53173 42031 53173 42126 53173 42126 53174 42031 53174 42466 53174 42126 53175 42466 53175 42032 53175 42032 53176 42466 53176 42465 53176 42032 53177 42465 53177 42033 53177 42033 53178 42465 53178 42034 53178 42034 53179 42035 53179 42033 53179 42033 53180 42035 53180 42036 53180 42033 53181 42036 53181 42129 53181 42129 53182 42036 53182 42480 53182 42129 53183 42480 53183 42037 53183 42037 53184 42480 53184 42263 53184 42037 53185 42263 53185 42132 53185 42132 53186 42263 53186 42038 53186 42038 53187 42039 53187 42132 53187 42132 53188 42039 53188 42041 53188 42132 53189 42041 53189 42040 53189 42040 53190 42041 53191 42491 53192 42040 53193 42491 53193 42133 53193 42133 53194 42491 53194 42504 53194 42133 53195 42504 53195 42134 53195 42134 53196 42504 53196 42042 53196 42042 53197 42503 53197 42134 53197 42134 53198 42503 53198 42043 53198 42134 53199 42043 53199 42135 53199 42135 53200 42043 53201 42044 53202 42135 53203 42044 53203 42137 53203 42137 53204 42044 53204 42509 53204 42137 53205 42509 53205 42048 53205 42048 53206 42509 53206 42045 53206 42045 53207 42046 53208 42048 53209 42048 53210 42046 53210 42047 53210 42048 53211 42047 53211 42139 53211 42139 53212 42047 53212 42049 53212 42139 53213 42049 53213 42140 53213 42140 53214 42049 53214 42050 53214 42140 53215 42050 53215 42051 53215 42050 53216 42524 53216 42051 53216 42051 53217 42524 53217 42522 53217 42051 53218 42522 53218 42052 53218 42522 53219 42262 53220 42052 53221 42052 53222 42262 53222 42527 53222 42052 53223 42527 53223 42053 53223 42053 53224 42527 53224 42526 53224 42053 53225 42526 53225 42054 53225 42526 53226 42530 53226 42054 53226 42054 53227 42530 53227 42261 53227 42054 53228 42261 53228 42055 53228 42261 53229 42056 53230 42055 53231 42055 53232 42056 53232 42057 53232 42055 53233 42057 53233 42143 53233 42143 53234 42057 53234 42058 53234 42143 53235 42058 53235 42059 53235 42059 53236 42058 53236 42543 53236 42059 53237 42543 53237 42060 53237 42060 53238 42543 53238 42260 53238 42260 53239 42547 53239 42060 53239 42060 53240 42547 53240 42061 53240 42060 53241 42061 53241 42145 53241 42145 53242 42061 53242 42062 53242 42145 53243 42062 53243 42147 53243 42147 53244 42062 53244 42063 53244 42147 53245 42063 53245 42148 53245 42148 53246 42063 53246 42064 53246 42064 53247 42558 53248 42148 53248 42148 53249 42558 53249 42065 53249 42148 53250 42065 53250 42149 53250 42149 53251 42065 53251 42067 53251 42149 53252 42067 53252 42066 53252 42066 53253 42067 53253 42068 53253 42066 53254 42068 53254 42069 53254 42069 53255 42068 53255 42070 53255 42070 53256 42071 53257 42069 53258 42069 53259 42071 53259 42572 53259 42069 53260 42572 53260 42150 53260 42150 53261 42572 53261 42259 53261 42150 53262 42259 53262 42152 53262 42152 53263 42259 53263 42577 53263 42152 53264 42577 53264 42072 53264 42072 53265 42577 53265 42258 53265 42258 53266 42073 53266 42072 53266 42072 53267 42073 53267 42075 53267 42072 53268 42075 53268 42074 53268 42074 53269 42075 53269 42315 53269 42074 53270 42315 53270 42155 53270 42155 53271 42315 53271 42076 53271 42155 53272 42076 53272 42077 53272 42076 53273 42318 53273 42077 53273 42077 53274 42318 53274 42078 53274 42077 53275 42078 53275 42079 53275 42078 53276 42276 53277 42079 53278 42079 53279 42276 53279 42080 53279 42079 53280 42080 53280 42157 53280 42157 53281 42080 53281 42322 53281 42157 53282 42322 53282 42081 53282 42322 53283 42321 53283 42081 53283 42081 53284 42321 53284 42326 53284 42081 53285 42326 53285 42158 53285 42326 53286 42082 53286 42158 53286 42158 53287 42082 53287 42330 53287 42158 53288 42330 53288 42083 53288 42083 53289 42330 53289 42329 53289 42083 53290 42329 53290 42159 53290 42159 53291 42329 53291 42084 53291 42159 53292 42084 53292 42160 53292 42160 53293 42084 53293 42085 53293 42085 53294 42086 53294 42160 53294 42160 53295 42086 53296 42087 53297 42160 53298 42087 53298 42088 53298 42088 53299 42087 53299 42345 53299 42088 53300 42345 53300 42161 53300 42161 53301 42345 53301 42355 53301 42161 53302 42355 53302 42089 53302 42089 53303 42355 53303 42357 53303 42357 53304 42090 53304 42089 53304 42089 53305 42090 53305 42358 53305 42089 53306 42358 53306 42091 53306 42091 53307 42358 53307 42092 53307 42091 53308 42092 53308 42093 53308 42093 53309 42092 53309 42374 53309 42093 53310 42374 53310 42163 53310 42163 53311 42374 53311 42373 53311 42373 53312 42371 53312 42163 53312 42163 53313 42371 53313 42375 53313 42163 53314 42375 53314 42095 53314 42095 53315 42375 53316 42094 53317 42095 53318 42094 53318 42096 53318 42096 53319 42094 53319 42097 53319 42096 53320 42097 53320 42099 53320 42099 53321 42097 53321 42380 53321 42380 53322 42098 53322 42099 53322 42099 53323 42098 53323 42101 53323 42099 53324 42101 53324 42100 53324 42100 53325 42101 53325 42275 53325 42100 53326 42275 53326 42104 53326 42104 53327 42275 53327 42388 53328 42104 53329 42388 53329 42105 53329 42105 53330 42388 53330 42391 53330 42105 53331 42391 53331 42003 53331 42102 53332 42100 53332 42103 53332 42103 53333 42100 53333 42104 53333 42103 53334 42104 53334 42166 53334 42166 53335 42104 53335 42105 53335 42166 53336 42105 53336 42167 53336 42167 53337 42105 53337 42106 53337 42167 53338 42106 53338 42168 53338 42168 53339 42106 53339 42107 53339 42168 53340 42107 53340 42170 53340 42170 53341 42107 53341 42004 53341 42170 53342 42004 53342 42173 53342 42173 53343 42004 53343 42006 53343 42173 53344 42006 53344 42175 53344 42175 53345 42006 53345 42007 53345 42175 53346 42007 53346 42178 53346 42178 53347 42007 53347 42108 53347 42178 53348 42108 53348 42180 53348 42180 53349 42108 53349 42110 53349 42180 53350 42110 53350 42109 53350 42109 53351 42110 53351 42011 53351 42109 53352 42011 53352 42111 53352 42111 53353 42011 53353 42112 53353 42111 53354 42112 53354 42113 53354 42113 53355 42112 53355 42015 53355 42113 53356 42015 53357 42114 53358 42114 53359 42015 53360 42016 53361 42114 53362 42016 53362 42115 53362 42115 53363 42016 53363 42017 53363 42115 53364 42017 53364 42183 53364 42183 53365 42017 53365 42021 53365 42183 53366 42021 53366 42184 53366 42184 53367 42021 53367 42116 53367 42184 53368 42116 53368 42187 53368 42187 53369 42116 53369 42118 53369 42187 53370 42118 53370 42117 53370 42117 53371 42118 53371 42119 53371 42117 53372 42119 53372 42120 53372 42120 53373 42119 53373 42024 53373 42120 53374 42024 53374 42190 53374 42190 53375 42024 53375 42121 53375 42190 53376 42121 53376 42192 53376 42192 53377 42121 53377 42122 53377 42192 53378 42122 53378 42193 53378 42193 53379 42122 53379 42027 53379 42193 53380 42027 53380 42123 53380 42123 53381 42027 53381 42028 53381 42123 53382 42028 53382 42124 53382 42124 53383 42028 53383 42125 53383 42124 53384 42125 53384 42197 53384 42197 53385 42125 53385 42030 53385 42197 53386 42030 53386 42127 53386 42127 53387 42030 53387 42126 53387 42127 53388 42126 53388 42199 53388 42199 53389 42126 53389 42032 53389 42199 53390 42032 53390 42128 53390 42128 53391 42032 53391 42033 53391 42128 53392 42033 53392 42130 53392 42130 53393 42033 53393 42129 53393 42130 53394 42129 53394 42131 53394 42131 53395 42129 53395 42037 53395 42131 53396 42037 53396 42202 53396 42202 53397 42037 53397 42132 53397 42202 53398 42132 53398 42204 53398 42204 53399 42132 53399 42040 53399 42204 53400 42040 53401 42205 53402 42205 53403 42040 53403 42133 53403 42205 53404 42133 53404 42207 53404 42207 53405 42133 53405 42134 53405 42207 53406 42134 53406 42208 53406 42208 53407 42134 53407 42135 53407 42208 53408 42135 53408 42136 53408 42136 53409 42135 53409 42137 53409 42136 53410 42137 53410 42138 53410 42138 53411 42137 53411 42048 53411 42138 53412 42048 53412 42210 53412 42210 53413 42048 53413 42139 53413 42210 53414 42139 53414 42213 53414 42213 53415 42139 53416 42140 53417 42213 53418 42140 53418 42214 53418 42214 53419 42140 53419 42051 53419 42214 53420 42051 53420 42141 53420 42141 53421 42051 53421 42052 53421 42141 53422 42052 53422 42142 53422 42142 53423 42052 53423 42053 53423 42142 53424 42053 53424 42216 53424 42216 53425 42053 53425 42054 53425 42216 53426 42054 53426 42218 53426 42218 53427 42054 53427 42055 53427 42218 53428 42055 53428 42219 53428 42219 53429 42055 53429 42143 53429 42219 53430 42143 53430 42222 53430 42222 53431 42143 53431 42059 53431 42222 53432 42059 53433 42223 53434 42223 53435 42059 53435 42060 53435 42223 53436 42060 53436 42144 53436 42144 53437 42060 53438 42145 53439 42144 53440 42145 53440 42146 53440 42146 53441 42145 53442 42147 53443 42146 53444 42147 53444 42225 53444 42225 53445 42147 53445 42148 53445 42225 53446 42148 53446 42226 53446 42226 53447 42148 53447 42149 53447 42226 53448 42149 53448 42227 53448 42227 53449 42149 53449 42066 53449 42227 53450 42066 53450 42228 53450 42228 53451 42066 53451 42069 53451 42228 53452 42069 53452 42231 53452 42231 53453 42069 53454 42150 53455 42231 53456 42150 53457 42232 53458 42232 53459 42150 53459 42152 53459 42232 53460 42152 53460 42151 53460 42151 53461 42152 53461 42072 53461 42151 53462 42072 53462 42235 53462 42235 53463 42072 53463 42074 53463 42235 53464 42074 53464 42153 53464 42153 53465 42074 53465 42155 53465 42153 53466 42155 53466 42154 53466 42154 53467 42155 53467 42077 53467 42154 53468 42077 53468 42156 53468 42156 53469 42077 53469 42079 53469 42156 53470 42079 53471 42238 53472 42238 53473 42079 53473 42157 53473 42238 53474 42157 53474 42240 53474 42240 53475 42157 53475 42081 53475 42240 53476 42081 53476 42241 53476 42241 53477 42081 53477 42158 53477 42241 53478 42158 53478 42242 53478 42242 53479 42158 53479 42083 53479 42242 53480 42083 53480 42243 53480 42243 53481 42083 53481 42159 53481 42243 53482 42159 53483 42244 53484 42244 53485 42159 53485 42160 53485 42244 53486 42160 53486 42245 53486 42245 53487 42160 53487 42088 53487 42245 53488 42088 53488 42248 53488 42248 53489 42088 53489 42161 53489 42248 53490 42161 53490 42162 53490 42162 53491 42161 53491 42089 53491 42162 53492 42089 53492 42251 53492 42251 53493 42089 53493 42091 53493 42251 53494 42091 53494 42253 53494 42253 53495 42091 53495 42093 53495 42253 53496 42093 53496 42254 53496 42254 53497 42093 53497 42163 53497 42254 53498 42163 53498 42255 53498 42255 53499 42163 53499 42095 53499 42255 53500 42095 53500 42256 53500 42256 53501 42095 53501 42096 53501 42256 53502 42096 53502 42164 53502 42164 53503 42096 53503 42099 53503 42164 53504 42099 53504 42102 53504 42102 53505 42099 53505 42100 53505 42257 53506 42103 53506 42165 53506 42165 53507 42103 53507 42166 53507 42165 53508 42166 53508 41933 53508 41933 53509 42166 53509 42167 53509 41933 53510 42167 53510 42169 53510 42169 53511 42167 53511 42168 53511 42169 53512 42168 53512 42171 53512 42171 53513 42168 53513 42170 53513 42171 53514 42170 53514 42172 53514 42172 53515 42170 53515 42173 53515 42172 53516 42173 53516 42174 53516 42174 53517 42173 53518 42175 53519 42174 53520 42175 53520 42176 53520 42176 53521 42175 53522 42178 53523 42176 53524 42178 53524 42177 53524 42177 53525 42178 53525 42180 53525 42177 53526 42180 53526 42179 53526 42179 53527 42180 53527 42109 53527 42179 53528 42109 53528 41938 53528 41938 53529 42109 53529 42111 53529 41938 53530 42111 53530 41939 53530 41939 53531 42111 53531 42113 53531 41939 53532 42113 53532 42181 53532 42181 53533 42113 53534 42114 53535 42181 53536 42114 53536 42182 53536 42182 53537 42114 53537 42115 53537 42182 53538 42115 53538 41942 53538 41942 53539 42115 53539 42183 53539 41942 53540 42183 53540 41943 53540 41943 53541 42183 53541 42184 53541 41943 53542 42184 53542 42185 53542 42185 53543 42184 53543 42187 53543 42185 53544 42187 53544 42186 53544 42186 53545 42187 53545 42117 53545 42186 53546 42117 53546 42188 53546 42188 53547 42117 53547 42120 53547 42188 53548 42120 53548 42189 53548 42189 53549 42120 53549 42190 53549 42189 53550 42190 53550 41947 53550 41947 53551 42190 53551 42192 53551 41947 53552 42192 53552 42191 53552 42191 53553 42192 53553 42193 53553 42191 53554 42193 53554 42194 53554 42194 53555 42193 53555 42123 53555 42194 53556 42123 53556 42195 53556 42195 53557 42123 53557 42124 53557 42195 53558 42124 53559 42196 53560 42196 53561 42124 53561 42197 53561 42196 53562 42197 53563 42198 53564 42198 53565 42197 53566 42127 53567 42198 53568 42127 53568 41951 53568 41951 49411 42127 49411 42199 49411 41951 53569 42199 53569 41952 53569 41952 53570 42199 53570 42128 53570 41952 53571 42128 53571 42200 53571 42200 53572 42128 53573 42130 53574 42200 53575 42130 53575 41955 53575 41955 53576 42130 53576 42131 53576 41955 53577 42131 53578 41956 53579 41956 53580 42131 53580 42202 53580 41956 53581 42202 53581 42201 53581 42201 53582 42202 53582 42204 53582 42201 53583 42204 53583 42203 53583 42203 53584 42204 53584 42205 53584 42203 53585 42205 53585 42206 53585 42206 53586 42205 53586 42207 53586 42206 53587 42207 53587 41959 53587 41959 53588 42207 53588 42208 53588 41959 53589 42208 53589 42209 53589 42209 53590 42208 53590 42136 53590 42209 53591 42136 53591 41961 53591 41961 53592 42136 53592 42138 53592 41961 53593 42138 53593 42211 53593 42211 53594 42138 53594 42210 53594 42211 53595 42210 53595 42212 53595 42212 53596 42210 53596 42213 53596 42212 53597 42213 53597 41963 53597 41963 53598 42213 53598 42214 53598 41963 53599 42214 53599 41965 53599 41965 53600 42214 53601 42141 53602 41965 53603 42141 53603 42215 53603 42215 53604 42141 53604 42142 53604 42215 53605 42142 53605 41967 53605 41967 53606 42142 53606 42216 53606 41967 53607 42216 53607 42217 53607 42217 53608 42216 53608 42218 53608 42217 53609 42218 53609 41970 53609 41970 53610 42218 53610 42219 53610 41970 53611 42219 53611 42220 53611 42220 53612 42219 53612 42222 53612 42220 53613 42222 53613 42221 53613 42221 53614 42222 53614 42223 53614 42221 53615 42223 53615 42224 53615 42224 53616 42223 53616 42144 53616 42224 53617 42144 53617 41972 53617 41972 53618 42144 53618 42146 53618 41972 53619 42146 53619 41974 53619 41974 53620 42146 53620 42225 53620 41974 53621 42225 53621 41975 53621 41975 53622 42225 53622 42226 53622 41975 53623 42226 53623 41976 53623 41976 53624 42226 53624 42227 53624 41976 53625 42227 53625 41977 53625 41977 53626 42227 53627 42228 53628 41977 53629 42228 53629 42229 53629 42229 53630 42228 53630 42231 53630 42229 53631 42231 53631 42230 53631 42230 53632 42231 53632 42232 53632 42230 53633 42232 53633 41981 53633 41981 53634 42232 53634 42151 53634 41981 53635 42151 53635 42233 53635 42233 53636 42151 53636 42235 53636 42233 53637 42235 53637 42234 53637 42234 53638 42235 53638 42153 53638 42234 53639 42153 53639 41983 53640 41983 53641 42153 53641 42154 53641 41983 53642 42154 53642 42236 53642 42236 53643 42154 53643 42156 53643 42236 53644 42156 53644 42237 53644 42237 53645 42156 53645 42238 53645 42237 53646 42238 53646 42239 53646 42239 53647 42238 53647 42240 53647 42239 53648 42240 53648 41986 53648 41986 53649 42240 53649 42241 53649 41986 53650 42241 53650 41987 53650 41987 53651 42241 53651 42242 53651 41987 53652 42242 53652 41989 53652 41989 53653 42242 53653 42243 53653 41989 53654 42243 53654 41990 53654 41990 53655 42243 53655 42244 53655 41990 53656 42244 53656 42246 53656 42246 53657 42244 53657 42245 53657 42246 53658 42245 53658 42247 53658 42247 53659 42245 53659 42248 53659 42247 53660 42248 53660 42249 53660 42249 53661 42248 53661 42162 53661 42249 53662 42162 53662 42250 53662 42250 53663 42162 53663 42251 53663 42250 53664 42251 53664 42252 53664 42252 53665 42251 53665 42253 53665 42252 53666 42253 53666 41995 53666 41995 53667 42253 53668 42254 53668 41995 53669 42254 53669 41996 53669 41996 53670 42254 53670 42255 53670 41996 53671 42255 53671 41997 53671 41997 53672 42255 53672 42256 53672 41997 53673 42256 53673 41998 53673 41998 53674 42256 53674 42164 53674 41998 53675 42164 53675 42001 53675 42001 53676 42164 53676 42102 53676 42001 53677 42102 53677 42257 53677 42257 53678 42102 53678 42103 53678 42073 53679 42258 53679 42578 53679 42577 53680 42259 53680 42571 53680 42068 53681 42067 53681 42559 53681 42547 53682 42260 53682 42548 53682 42056 53683 42261 53684 42536 53685 42262 53686 42522 53686 42523 53686 42524 53687 42050 53687 42518 53687 42049 53688 42047 53688 42519 53688 42046 53689 42045 53690 42508 53691 42509 53692 42044 53692 42510 53692 42504 53693 42491 53693 42502 53693 42263 53694 42480 53694 42264 53694 42467 53695 42265 53696 42462 53697 42026 53698 42454 53699 42266 53700 42455 53701 42025 53701 42456 53701 42267 53702 42268 53702 42269 53702 42270 53703 42442 53703 42443 53703 42023 53704 42022 53704 42444 53704 42018 53705 42429 53705 42439 53705 42271 53706 42413 53706 42418 53706 42403 53707 42272 53707 42400 53707 42273 53708 42003 53709 42274 53710 42391 53711 42388 53711 42392 53711 42275 53712 42101 53712 42389 53712 42098 53713 42380 53713 42383 53713 42097 53714 42094 53714 42376 53714 42374 53715 42092 53715 42359 53715 42355 53716 42345 53716 42346 53716 42082 53717 42326 53717 42331 53717 42276 53718 42078 53719 42323 53720 42318 53721 42076 53721 42317 53721 42315 53722 42075 53722 42316 53722 42298 53723 41925 53723 42277 53723 42280 53724 42484 53724 42278 53724 42483 53725 42485 53725 42488 53725 42279 53726 42280 53726 42476 53726 42281 53727 42282 53727 42283 53727 42283 53728 42282 53728 42450 53728 42283 53729 42450 53729 42284 53729 42281 53730 42283 53730 42285 53730 42285 53731 42283 53731 42284 53731 42285 53732 42284 53732 42286 53732 42287 53733 42288 53733 42289 53733 42289 53734 42288 53734 42447 53734 42595 53735 42594 53735 42424 53735 42407 53736 42589 53736 42290 53736 42291 53737 42387 53737 42292 53737 42292 53738 42387 53739 42381 53740 42292 53741 42381 53741 42294 53741 42291 53742 42292 53742 42293 53742 42293 53743 42292 53743 42294 53743 42293 53744 42294 53744 42295 53744 42379 53745 42296 53745 42297 53745 42297 53746 42296 53746 42382 53746 42351 53747 42352 53747 42354 53747 42334 53748 42298 53749 42333 53750 42299 53751 42586 53752 42300 53753 42300 53754 42586 53754 42301 53754 42300 53755 42301 53755 42581 53755 42299 53756 42300 53757 42302 53758 42302 53759 42300 53759 42581 53759 42302 53760 42581 53760 41932 53760 42576 53761 42303 53761 42575 53761 42575 53762 42303 53762 42582 53762 42304 53763 42305 53763 42554 53763 42306 53764 42307 53764 42546 53764 42308 53765 42517 53765 42309 53765 42309 53766 42517 53766 42310 53766 42309 53767 42310 53767 42512 53767 42308 53768 42309 53769 42311 53770 42311 53771 42309 53771 42512 53771 42311 53772 42512 53772 42514 53772 42312 53773 42313 53773 42513 53773 42513 53774 42313 53774 42314 53774 42076 53775 42315 53775 42317 53775 42317 53776 42315 53776 42316 53776 42317 53777 42316 53777 42320 53777 42320 53778 42316 53778 42583 53778 42320 53779 42583 53779 42340 53779 42340 53780 42583 53780 42341 53780 42078 53781 42318 53781 42323 53781 42323 53782 42318 53782 42317 53782 42323 53783 42317 53783 42319 53783 42319 53784 42317 53784 42320 53784 42319 53785 42320 53785 42338 53785 42338 53786 42320 53786 42340 53786 42321 53787 42322 53787 42327 53787 42327 53788 42322 53788 42080 53788 42080 53789 42276 53789 42327 53789 42327 53790 42276 53790 42323 53790 42327 53791 42323 53791 42324 53791 42324 53792 42323 53792 42319 53792 42324 53793 42319 53793 42325 53793 42325 53794 42319 53794 42338 53794 42326 53795 42321 53795 42331 53795 42331 53796 42321 53796 42327 53796 42331 53797 42327 53797 42328 53797 42328 53798 42327 53798 42324 53798 42328 53799 42324 53799 42335 53799 42335 53800 42324 53800 42325 53800 42084 53801 42329 53801 42332 53801 42332 53802 42329 53802 42330 53802 42330 53803 42082 53803 42332 53803 42332 53804 42082 53804 42331 53804 42332 53805 42331 53805 42343 53805 42343 53806 42331 53806 42328 53806 42343 53807 42328 53807 42333 53807 42333 53808 42328 53808 42335 53808 42333 53809 42335 53809 42334 53809 42334 53810 42335 53810 42325 53810 42334 53811 42325 53811 42336 53811 42336 53812 42325 53812 42338 53812 42336 53813 42338 53813 42337 53813 42337 53814 42338 53814 42340 53814 42337 53815 42340 53815 42339 53815 42339 53816 42340 53816 42341 53816 42339 53817 42341 53817 42342 53817 42342 53818 42341 53818 42585 53818 42298 53819 42277 53819 42333 53819 42333 53820 42277 53820 42349 53820 42333 53821 42349 53821 42343 53821 42343 53822 42349 53822 42348 53822 42343 53823 42348 53823 42332 53823 42332 53824 42348 53824 42344 53824 42332 53825 42344 53825 42084 53825 42087 53826 42086 53826 42344 53826 42344 53827 42086 53827 42085 53827 42344 53828 42085 53828 42084 53828 42345 53829 42087 53829 42346 53829 42346 53830 42087 53830 42344 53830 42346 53831 42344 53831 42347 53831 42347 53832 42344 53832 42348 53832 42347 53833 42348 53833 42350 53833 42350 53834 42348 53834 42349 53834 42350 53835 42349 53835 42354 53835 42354 53836 42349 53836 42277 53836 42354 53837 42277 53837 42351 53837 42351 53838 42277 53839 41925 53840 42352 53841 42353 53841 42354 53841 42354 53842 42353 53842 42363 53842 42354 53843 42363 53843 42350 53843 42350 53844 42363 53844 42362 53844 42350 53845 42362 53845 42347 53845 42347 53846 42362 53846 42361 53846 42347 53847 42361 53847 42346 53847 42346 53848 42361 53848 42356 53848 42346 53849 42356 53849 42355 53849 42358 53850 42090 53850 42356 53850 42356 53851 42090 53851 42357 53851 42356 53852 42357 53852 42355 53852 42092 53853 42358 53853 42359 53853 42359 53854 42358 53854 42356 53854 42359 53855 42356 53855 42360 53855 42360 53856 42356 53856 42361 53856 42360 53857 42361 53857 42369 53857 42369 53858 42361 53858 42362 53858 42369 53859 42362 53859 42366 53859 42366 53860 42362 53860 42363 53860 42366 53861 42363 53861 42364 53861 42364 53862 42363 53862 42353 53862 42364 53863 42353 53864 41927 53865 42364 53866 42365 53866 42366 53866 42366 53867 42365 53867 42367 53867 42366 53868 42367 53868 42369 53868 42369 53869 42367 53869 42368 53869 42369 53870 42368 53870 42360 53870 42360 53871 42368 53871 42370 53871 42360 53872 42370 53872 42359 53872 42359 53873 42370 53873 42372 53873 42359 53874 42372 53874 42374 53874 42375 53875 42371 53875 42372 53875 42372 53876 42371 53876 42373 53876 42372 53877 42373 53877 42374 53877 42094 53878 42375 53878 42376 53878 42376 53879 42375 53879 42372 53879 42376 53880 42372 53880 42377 53880 42377 53881 42372 53881 42370 53881 42377 53882 42370 53882 42378 53882 42378 53883 42370 53883 42368 53883 42378 53884 42368 53884 42297 53884 42297 53885 42368 53885 42367 53885 42297 53886 42367 53886 42379 53886 42379 53887 42367 53887 42365 53887 42380 53888 42097 53888 42383 53888 42383 53889 42097 53889 42376 53889 42383 53890 42376 53890 42384 53890 42384 53891 42376 53891 42377 53891 42384 53892 42377 53892 42381 53892 42381 53893 42377 53893 42378 53893 42381 53894 42378 53894 42294 53894 42294 53895 42378 53895 42297 53895 42294 53896 42297 53896 42295 53896 42295 53897 42297 53897 42382 53897 42101 53898 42098 53898 42389 53898 42389 53899 42098 53899 42383 53899 42389 53900 42383 53900 42385 53900 42385 53901 42383 53901 42384 53901 42385 53902 42384 53902 42390 53902 42390 53903 42384 53903 42381 53903 42390 53904 42381 53904 42386 53904 42386 53905 42381 53905 42387 53905 42388 53906 42275 53906 42392 53906 42392 53907 42275 53907 42389 53907 42392 53908 42389 53908 42394 53908 42394 53909 42389 53909 42385 53909 42394 53910 42385 53910 42395 53910 42395 53911 42385 53911 42390 53911 42003 53912 42391 53912 42274 53912 42274 53913 42391 53913 42392 53913 42274 53914 42392 53914 42393 53914 42393 53915 42392 53915 42394 53915 42393 53916 42394 53916 42409 53916 42409 53917 42394 53917 42395 53917 42005 53918 42396 53918 42401 53918 42401 53919 42396 53919 42397 53919 42397 53920 42273 53920 42401 53920 42401 53921 42273 53921 42274 53921 42401 53922 42274 53922 42398 53922 42398 53923 42274 53923 42393 53923 42398 53924 42393 53924 42399 53924 42399 53925 42393 53925 42409 53925 42272 53926 42005 53926 42400 53926 42400 53927 42005 53927 42401 53927 42400 53928 42401 53928 42405 53928 42405 53929 42401 53929 42398 53929 42405 53930 42398 53930 42406 53930 42406 53931 42398 53931 42399 53931 42009 53932 42008 53932 42404 53932 42404 53933 42008 53933 42402 53933 42402 53934 42403 53934 42404 53934 42404 53935 42403 53935 42400 53935 42404 53936 42400 53936 42415 53936 42415 53937 42400 53937 42405 53937 42415 53938 42405 53938 42290 53938 42290 53939 42405 53939 42406 53939 42290 53940 42406 53940 42407 53940 42407 53941 42406 53941 42399 53941 42407 53942 42399 53942 42408 53942 42408 53943 42399 53943 42409 53943 42408 53944 42409 53944 42410 53944 42410 53945 42409 53945 42395 53945 42410 53946 42395 53946 42411 53946 42411 53947 42395 53947 42390 53947 42411 53948 42390 53948 42412 53948 42412 53949 42390 53949 42386 53949 42413 53950 42009 53950 42418 53950 42418 53951 42009 53951 42404 53951 42418 53952 42404 53952 42414 53952 42414 53953 42404 53953 42415 53953 42414 53954 42415 53954 42421 53954 42421 53955 42415 53955 42290 53955 42421 53956 42290 53956 42422 53956 42422 53957 42290 53957 42589 53957 42422 53958 42589 53958 42423 53958 42428 53959 42416 53959 42417 53959 42417 53960 42416 53960 42010 53960 42010 53961 42271 53961 42417 53961 42417 53962 42271 53962 42418 53962 42417 53963 42418 53963 42419 53963 42419 53964 42418 53964 42414 53964 42419 53965 42414 53965 42420 53965 42420 53966 42414 53966 42421 53966 42420 53967 42421 53967 42424 53967 42424 53968 42421 53968 42422 53968 42424 53969 42422 53969 42595 53969 42595 53970 42422 53971 42423 53972 42594 53973 42593 53973 42424 53973 42424 53974 42593 53974 42425 53974 42424 53975 42425 53975 42420 53975 42420 53976 42425 53976 42426 53976 42420 53977 42426 53977 42419 53977 42419 53978 42426 53978 42427 53978 42419 53979 42427 53979 42417 53979 42417 53980 42427 53980 42430 53980 42417 53981 42430 53981 42428 53981 42014 53982 42013 53982 42430 53982 42430 53983 42013 53983 42012 53983 42430 53984 42012 53984 42428 53984 42429 53985 42014 53985 42439 53985 42439 53986 42014 53986 42430 53986 42439 53987 42430 53987 42431 53987 42431 53988 42430 53988 42427 53988 42431 53989 42427 53989 42436 53989 42436 53990 42427 53990 42426 53990 42436 53991 42426 53991 42432 53991 42432 53992 42426 53992 42425 53992 42432 53993 42425 53993 42433 53993 42433 53994 42425 53994 42593 53994 42433 53995 42593 53995 42592 53995 42433 53996 42434 53996 42432 53996 42432 53997 42434 53997 42435 53997 42432 53998 42435 53998 42436 53998 42436 53999 42435 53999 42437 53999 42436 54000 42437 54000 42431 54000 42431 54001 42437 54001 42438 54001 42431 54002 42438 54002 42439 54002 42439 54003 42438 54003 42441 54003 42439 54004 42441 54004 42018 54004 42440 54005 42020 54005 42441 54005 42441 54006 42020 54006 42019 54006 42441 54007 42019 54007 42018 54007 42022 54008 42440 54009 42444 54010 42444 54011 42440 54011 42441 54011 42444 54012 42441 54012 42445 54012 42445 54013 42441 54013 42438 54013 42445 54014 42438 54014 42446 54014 42446 54015 42438 54015 42437 54015 42446 54016 42437 54016 42289 54016 42289 54017 42437 54017 42435 54017 42289 54018 42435 54018 42287 54018 42287 54019 42435 54019 42434 54019 42442 54020 42023 54020 42443 54020 42443 54021 42023 54021 42444 54021 42443 54022 42444 54022 42449 54022 42449 54023 42444 54023 42445 54023 42449 54024 42445 54024 42450 54024 42450 54025 42445 54025 42446 54025 42450 54026 42446 54026 42284 54026 42284 54027 42446 54027 42289 54027 42284 54028 42289 54028 42286 54028 42286 54029 42289 54029 42447 54029 42268 54030 42270 54030 42269 54030 42269 54031 42270 54031 42443 54031 42269 54032 42443 54032 42448 54032 42448 54033 42443 54033 42449 54033 42448 54034 42449 54034 42451 54034 42451 54035 42449 54035 42450 54035 42451 54036 42450 54036 42475 54036 42475 54037 42450 54037 42282 54037 42025 54038 42267 54038 42456 54038 42456 54039 42267 54039 42269 54039 42456 54040 42269 54040 42452 54040 42452 54041 42269 54041 42448 54041 42452 54042 42448 54042 42453 54042 42453 54043 42448 54043 42451 54043 42454 54044 42455 54044 42266 54044 42266 54045 42455 54045 42456 54045 42266 54046 42456 54046 42460 54046 42460 54047 42456 54047 42452 54047 42460 54048 42452 54048 42461 54048 42461 54049 42452 54049 42453 54049 42029 54050 42457 54050 42463 54050 42463 54051 42457 54051 42458 54051 42458 54052 42026 54052 42463 54052 42463 54053 42026 54053 42266 54053 42463 54054 42266 54054 42459 54054 42459 54055 42266 54055 42460 54055 42459 54056 42460 54056 42471 54056 42471 54057 42460 54057 42461 54057 42265 54058 42029 54058 42462 54058 42462 54059 42029 54059 42463 54059 42462 54060 42463 54060 42464 54060 42464 54061 42463 54061 42459 54061 42464 54062 42459 54062 42469 54062 42469 54063 42459 54063 42471 54063 42465 54064 42466 54064 42478 54064 42478 54065 42466 54065 42031 54065 42031 54066 42467 54066 42478 54066 42478 54067 42467 54067 42462 54067 42478 54068 42462 54068 42468 54068 42468 54069 42462 54069 42464 54069 42468 54070 42464 54070 42476 54070 42476 54071 42464 54071 42469 54071 42476 54072 42469 54072 42279 54072 42279 54073 42469 54073 42471 54073 42279 54074 42471 54074 42470 54074 42470 54075 42471 54075 42461 54075 42470 54076 42461 54076 42472 54076 42472 54077 42461 54077 42453 54077 42472 54078 42453 54078 42473 54078 42473 54079 42453 54079 42451 54079 42473 54080 42451 54080 42474 54080 42474 54081 42451 54081 42475 54081 42280 54082 42278 54082 42476 54082 42476 54083 42278 54083 42482 54083 42476 54084 42482 54084 42468 54084 42468 54085 42482 54085 42477 54085 42468 54086 42477 54086 42478 54086 42478 54087 42477 54087 42479 54087 42478 54088 42479 54088 42465 54088 42036 54089 42035 54089 42479 54089 42479 54090 42035 54090 42034 54090 42479 54091 42034 54091 42465 54091 42480 54092 42036 54092 42264 54092 42264 54093 42036 54093 42479 54093 42264 54094 42479 54094 42481 54094 42481 54095 42479 54095 42477 54095 42481 54096 42477 54096 42490 54096 42490 54097 42477 54097 42482 54097 42490 54098 42482 54098 42488 54098 42488 54099 42482 54099 42278 54099 42488 54100 42278 54100 42483 54100 42483 54101 42278 54101 42484 54101 42485 54102 42486 54102 42488 54102 42488 54103 42486 54103 42487 54103 42488 54104 42487 54104 42490 54104 42490 54105 42487 54105 42489 54105 42490 54106 42489 54106 42481 54106 42481 54107 42489 54107 42494 54107 42481 54108 42494 54108 42264 54108 42264 54109 42494 54109 42492 54109 42264 54110 42492 54110 42263 54110 42041 54111 42039 54111 42492 54111 42492 54112 42039 54112 42038 54112 42492 54113 42038 54113 42263 54113 42491 54114 42041 54114 42502 54114 42502 54115 42041 54115 42492 54115 42502 54116 42492 54116 42493 54116 42493 54117 42492 54117 42494 54117 42493 54118 42494 54118 42499 54118 42499 54119 42494 54119 42489 54119 42499 54120 42489 54120 42495 54120 42495 54121 42489 54121 42487 54121 42495 54122 42487 54122 42496 54122 42496 54123 42487 54123 42486 54123 42496 54124 42486 54124 42497 54124 42496 54125 42498 54125 42495 54125 42495 54126 42498 54126 42500 54126 42495 54127 42500 54127 42499 54127 42499 54128 42500 54128 42501 54128 42499 54129 42501 54129 42493 54129 42493 54130 42501 54130 42506 54130 42493 54131 42506 54131 42502 54131 42502 54132 42506 54132 42505 54132 42502 54133 42505 54133 42504 54133 42043 54134 42503 54134 42505 54134 42505 54135 42503 54135 42042 54135 42505 54136 42042 54136 42504 54136 42044 54137 42043 54137 42510 54137 42510 54138 42043 54138 42505 54138 42510 54139 42505 54139 42511 54139 42511 54140 42505 54140 42506 54140 42511 54141 42506 54141 42507 54141 42507 54142 42506 54142 42501 54142 42507 54143 42501 54143 42513 54143 42513 54144 42501 54144 42500 54144 42513 54145 42500 54145 42312 54145 42312 54146 42500 54146 42498 54146 42045 54147 42509 54147 42508 54147 42508 54148 42509 54148 42510 54148 42508 54149 42510 54149 42515 54149 42515 54150 42510 54150 42511 54150 42515 54151 42511 54151 42310 54151 42310 54152 42511 54152 42507 54152 42310 54153 42507 54153 42512 54153 42512 54154 42507 54154 42513 54154 42512 54155 42513 54155 42514 54155 42514 54156 42513 54156 42314 54156 42047 54157 42046 54157 42519 54157 42519 54158 42046 54158 42508 54158 42519 54159 42508 54159 42520 54159 42520 54160 42508 54160 42515 54160 42520 54161 42515 54161 42541 54161 42541 54162 42515 54162 42310 54162 42541 54163 42310 54163 42516 54163 42516 54164 42310 54164 42517 54164 42050 54165 42049 54165 42518 54165 42518 54166 42049 54166 42519 54166 42518 54167 42519 54167 42525 54167 42525 54168 42519 54168 42520 54168 42525 54169 42520 54169 42521 54169 42521 54170 42520 54170 42541 54170 42522 54171 42524 54171 42523 54171 42523 54172 42524 54172 42518 54172 42523 54173 42518 54173 42528 54173 42528 54174 42518 54174 42525 54174 42528 54175 42525 54175 42529 54175 42529 54176 42525 54176 42521 54176 42530 54177 42526 54177 42531 54177 42531 54178 42526 54179 42527 54180 42527 54181 42262 54181 42531 54181 42531 54182 42262 54182 42523 54182 42531 54183 42523 54183 42534 54183 42534 54184 42523 54184 42528 54184 42534 54185 42528 54185 42537 54185 42537 54186 42528 54186 42529 54186 42261 54187 42530 54187 42536 54187 42536 54188 42530 54188 42531 54188 42536 54189 42531 54189 42532 54189 42532 54190 42531 54190 42534 54190 42532 54191 42534 54191 42533 54191 42533 54192 42534 54192 42537 54192 42543 54193 42058 54193 42544 54193 42544 54194 42058 54194 42057 54194 42057 54195 42056 54195 42544 54195 42544 54196 42056 54196 42536 54196 42544 54197 42536 54197 42535 54197 42535 54198 42536 54198 42532 54198 42535 54199 42532 54199 42546 54199 42546 54200 42532 54200 42533 54200 42546 54201 42533 54201 42306 54201 42306 54202 42533 54202 42537 54202 42306 54203 42537 54203 42538 54203 42538 54204 42537 54204 42529 54204 42538 54205 42529 54205 42539 54205 42539 54206 42529 54206 42521 54206 42539 54207 42521 54207 42540 54207 42540 54208 42521 54208 42541 54208 42540 54209 42541 54209 42542 54209 42542 54210 42541 54210 42516 54210 42260 54211 42543 54211 42548 54211 42548 54212 42543 54212 42544 54212 42548 54213 42544 54213 42545 54213 42545 54214 42544 54214 42535 54214 42545 54215 42535 54215 42551 54215 42551 54216 42535 54216 42546 54216 42551 54217 42546 54217 42552 54217 42552 54218 42546 54218 42307 54218 42552 54219 42307 54219 42553 54219 42063 54220 42062 54220 42556 54220 42556 54221 42062 54221 42061 54221 42061 54222 42547 54222 42556 54222 42556 54223 42547 54223 42548 54223 42556 54224 42548 54224 42549 54224 42549 54225 42548 54225 42545 54225 42549 54226 42545 54226 42550 54226 42550 54227 42545 54227 42551 54227 42550 54228 42551 54228 42554 54228 42554 54229 42551 54229 42552 54229 42554 54230 42552 54230 42304 54230 42304 54231 42552 54231 42553 54231 42305 54232 42565 54232 42554 54232 42554 54233 42565 54233 42555 54233 42554 54234 42555 54234 42550 54234 42550 54235 42555 54235 42563 54235 42550 54236 42563 54236 42549 54236 42549 54237 42563 54237 42557 54237 42549 54238 42557 54238 42556 54238 42556 54239 42557 54239 42560 54239 42556 54240 42560 54240 42063 54240 42065 54241 42558 54241 42560 54241 42560 54242 42558 54242 42064 54242 42560 54243 42064 54243 42063 54243 42067 54244 42065 54244 42559 54244 42559 54245 42065 54245 42560 54245 42559 54246 42560 54246 42561 54246 42561 54247 42560 54247 42557 54247 42561 54248 42557 54248 42562 54248 42562 54249 42557 54249 42563 54249 42562 54250 42563 54250 42564 54250 42564 54251 42563 54251 42555 54251 42564 54252 42555 54252 42567 54252 42567 54253 42555 54253 42565 54253 42567 54254 42565 54254 42566 54254 42567 54255 42568 54255 42564 54255 42564 54256 42568 54256 42569 54256 42564 54257 42569 54257 42562 54257 42562 54258 42569 54258 42570 54258 42562 54259 42570 54259 42561 54259 42561 54260 42570 54260 42574 54260 42561 54261 42574 54261 42559 54261 42559 54262 42574 54262 42573 54262 42559 54263 42573 54263 42068 54263 42572 54264 42071 54264 42573 54264 42573 54265 42071 54265 42070 54265 42573 54266 42070 54266 42068 54266 42259 54267 42572 54268 42571 54269 42571 54270 42572 54270 42573 54270 42571 54271 42573 54271 42579 54271 42579 54272 42573 54272 42574 54272 42579 54273 42574 54273 42580 54273 42580 54274 42574 54274 42570 54274 42580 54275 42570 54275 42575 54275 42575 54276 42570 54276 42569 54276 42575 54277 42569 54277 42576 54277 42576 54278 42569 54278 42568 54278 42258 54279 42577 54279 42578 54279 42578 54280 42577 54280 42571 54280 42578 54281 42571 54281 42584 54281 42584 54282 42571 54282 42579 54282 42584 54283 42579 54283 42301 54283 42301 54284 42579 54284 42580 54284 42301 54285 42580 54285 42581 54285 42581 54286 42580 54286 42575 54286 42581 54287 42575 54287 41932 54287 41932 54288 42575 54288 42582 54288 42075 54289 42073 54289 42316 54289 42316 54290 42073 54290 42578 54290 42316 54291 42578 54291 42583 54291 42583 54292 42578 54292 42584 54292 42583 54293 42584 54293 42341 54293 42341 54294 42584 54294 42301 54294 42341 54295 42301 54295 42585 54295 42585 54296 42301 54296 42586 54296 42589 54297 42587 54297 42588 54297 42588 54298 42590 54298 42589 54298 42589 54299 42590 54299 42591 54299 42589 54300 42591 54300 42423 54300 42591 54301 42592 54301 42593 54301 42593 54302 42594 54302 42591 54302 42591 54303 42594 54303 42595 54303 42591 54304 42595 54305 42423 54306 42649 54307 42596 54307 42597 54307 42597 54308 42596 54308 42599 54308 42597 54308 42599 54308 42598 54308 42598 54309 42599 54309 42600 54309 42598 54310 42600 54310 42648 54310 42648 54311 42600 54311 42601 54311 42648 54312 42601 54312 42647 54312 42647 54313 42601 54313 42602 54313 42647 54314 42602 54314 42603 54314 42603 54315 42602 54315 42605 54315 42603 54316 42605 54316 42604 54316 42604 54317 42605 54317 42606 54317 42604 54318 42606 54318 42643 54318 42643 54319 42606 54319 42607 54319 42643 54319 42607 54319 42609 54319 42609 54320 42607 54320 42608 54320 42609 54320 42608 54320 42644 54320 42644 54321 42608 54321 42611 54321 42644 54321 42611 54321 42610 54321 42610 54322 42611 54322 42612 54322 42610 54322 42612 54322 42645 54322 42645 54323 42612 54323 42614 54323 42645 54323 42614 54323 42613 54323 42613 54324 42614 54324 42615 54324 42613 54324 42615 54324 42616 54324 42616 54325 42615 54325 42618 54325 42616 54326 42618 54326 42617 54326 42617 54327 42618 54327 42619 54327 42617 54328 42619 54328 42646 54328 42646 54329 42619 54329 42620 54329 42646 54330 42620 54330 42621 54330 42621 54331 42620 54331 42622 54331 42621 54332 42622 54332 42640 54332 42640 54333 42622 54333 42623 54333 42640 54334 42623 54334 42625 54334 42625 54335 42623 54335 42624 54335 42625 54336 42624 54336 42626 54336 42626 54337 42624 54337 42627 54337 42626 54337 42627 54337 42628 54337 42628 54338 42627 54338 42629 54338 42628 54339 42629 54339 42631 54339 42631 54340 42629 54340 42630 54340 42631 54341 42630 54341 42632 54341 42632 54342 42630 54342 42633 54342 42632 54343 42633 54343 42641 54343 42641 49 42633 49 42634 49 42641 49 42634 49 42635 49 42635 54344 42634 54344 42636 54344 42635 54345 42636 54345 42642 54345 42642 54346 42636 54346 42637 54346 42642 54346 42637 54346 42638 54346 42638 54347 42637 54347 42639 54347 42638 54348 42639 54348 42649 54348 42649 54307 42639 54307 42596 54307 42603 960 42604 960 42640 960 42626 960 42628 960 42647 960 42647 960 42628 960 42631 960 42647 54349 42631 54349 42632 54349 42632 960 42641 960 42647 960 42647 960 42641 960 42635 960 42647 54350 42635 54350 42642 54350 42644 54351 42610 54351 42640 54351 42640 54352 42610 54352 42645 54352 42640 54353 42645 54353 42621 54353 42613 54354 42616 54354 42617 54354 42603 960 42640 960 42647 960 42647 960 42640 960 42625 960 42647 54355 42625 54355 42626 54355 42604 960 42643 960 42640 960 42640 54356 42643 54356 42609 54356 42640 54357 42609 54357 42644 54357 42613 54358 42617 54358 42645 54358 42645 54359 42617 54359 42646 54359 42645 54360 42646 54360 42621 54360 42642 54361 42638 54361 42647 54361 42647 960 42638 960 42649 960 42647 960 42649 960 42648 960 42648 54362 42649 54362 42597 54362 42648 960 42597 960 42598 960 42670 960 42650 960 42655 960 42653 960 42655 960 42651 960 42651 960 42655 960 42652 960 42653 960 42654 960 42655 960 42655 54363 42654 54363 42661 54363 42655 54364 42661 54364 42669 54364 42650 960 42656 960 42655 960 42655 54365 42656 54365 42657 54365 42655 54366 42657 54366 42658 54366 42658 960 42659 960 42655 960 42655 54367 42659 54367 42660 54367 42655 54368 42660 54368 42652 54368 42677 960 42679 960 42661 960 42661 54369 42679 54369 42662 54369 42661 54370 42662 54370 42663 54370 42663 960 42664 960 42661 960 42661 54371 42664 54371 42665 54371 42661 54372 42665 54372 42666 54372 42666 54373 42667 54373 42661 54373 42661 54374 42667 54374 42668 54374 42661 54375 42668 54375 42669 54375 42670 960 42655 960 42673 960 42673 54376 42655 54376 42671 54376 42673 54377 42671 54377 42672 54377 42672 54378 42674 54378 42673 54378 42673 54379 42674 54379 42686 54379 42673 54380 42686 54380 42675 54380 42675 960 42686 960 42676 960 42677 960 42678 960 42679 960 42679 54381 42678 54381 42681 54381 42679 960 42681 960 42680 960 42680 960 42681 960 42682 960 42683 960 42684 960 42685 960 42685 960 42684 960 42687 960 42685 960 42687 960 42686 960 42686 54382 42687 54382 42688 54382 42686 54383 42688 54383 42676 54383 42689 54384 42690 54384 42736 54384 42791 54385 42691 54385 42790 54385 42727 54386 42692 54386 42693 54386 42760 54387 42694 54387 42763 54387 42709 54388 42695 54388 42696 54388 42823 54389 42697 54389 42867 54389 42821 54390 42699 54390 42701 54390 42776 54391 42698 54391 42775 54391 42699 54392 42700 54392 42701 54392 42701 54393 42700 54393 42702 54393 42701 54394 42702 54394 42776 54394 42697 54395 42823 54395 42864 54395 42869 54396 42708 54396 42868 54396 42868 54397 42708 54397 42703 54397 42868 54398 42703 54398 42867 54398 42867 54399 42703 54399 42704 54399 42867 54400 42704 54400 42823 54400 42874 54401 42705 54401 42873 54401 42873 54402 42705 54402 42706 54402 42873 54403 42706 54403 42869 54403 42869 54404 42706 54404 42707 54404 42869 54405 42707 54405 42708 54405 42709 54406 42696 54406 42710 54406 42710 54407 42696 54407 42802 54407 42710 54408 42802 54408 42711 54408 42711 54409 42802 54409 42804 54409 42711 54410 42804 54410 42768 54410 42712 54411 42713 54412 42810 54413 42810 54414 42713 54415 42714 54416 42810 54417 42714 54418 42759 54419 42816 54420 42881 54420 42715 54420 42715 54421 42881 54421 42882 54421 42715 54422 42882 54422 42719 54422 42716 54423 42785 54423 42717 54423 42717 54424 42785 54424 42718 54424 42717 54425 42718 54426 42719 54427 42719 54428 42718 54428 42720 54428 42719 54429 42720 54429 42715 54429 42721 54430 42754 54430 42722 54430 42722 54431 42754 54431 42723 54431 42722 54432 42723 54432 42784 54432 42784 54433 42723 54433 42724 54433 42784 54434 42724 54434 42783 54434 42691 54435 42725 54435 42790 54435 42790 54436 42725 54436 42726 54436 42790 54437 42726 54437 42727 54437 42833 54438 42835 54438 42728 54438 42728 54439 42835 54439 42729 54439 42729 54440 42835 54440 42730 54440 42729 54441 42730 54441 42826 54441 42827 54442 42731 54442 42732 54442 42732 54443 42731 54443 42733 54443 42732 54444 42733 54444 42825 54444 42825 54445 42733 54445 42824 54445 42734 54446 42782 54446 42739 54446 42739 54447 42782 54447 42735 54447 42739 54448 42735 54448 42736 54448 42690 54449 42737 54450 42736 54451 42736 54452 42737 54452 42738 54452 42736 54453 42738 54453 42739 54453 42848 54454 42849 54454 42832 54454 42832 54455 42849 54455 42740 54455 42740 54456 42849 54456 42741 54456 42740 54457 42741 54457 42742 54457 42742 54458 42741 54458 42745 54458 42742 54459 42745 54460 42743 54461 42743 54462 42745 54462 42744 54462 42744 54463 42745 54464 42853 54465 42744 54466 42853 54466 42746 54466 42769 54467 42747 54467 42770 54467 42770 54468 42747 54468 42749 54468 42770 54469 42749 54469 42748 54469 42748 54470 42749 54470 42751 54470 42748 54471 42751 54471 42750 54471 42750 54472 42751 54472 42752 54472 42753 54473 42754 54473 42755 54473 42755 54474 42754 54474 42721 54474 42755 54475 42721 54475 42756 54475 42756 54476 42721 54476 42787 54476 42756 54477 42787 54477 42693 54477 42693 54478 42787 54478 42788 54478 42693 54479 42788 54479 42727 54479 42727 54480 42788 54480 42757 54480 42727 54481 42757 54481 42790 54481 42714 54482 42758 54483 42759 54484 42759 54485 42758 54485 42760 54485 42759 54486 42760 54486 42761 54486 42761 54487 42760 54487 42763 54487 42761 54488 42763 54488 42762 54488 42762 54489 42763 54489 42764 54489 42762 54490 42764 54490 42765 54490 42765 54491 42764 54491 42766 54491 42765 54492 42766 54492 42804 54492 42804 54493 42766 54493 42767 54493 42804 54494 42767 54495 42768 54496 42769 54497 42770 54497 42771 54497 42771 54498 42770 54498 42772 54498 42771 54499 42772 54499 42773 54499 42773 54500 42772 54500 42774 54500 42773 54501 42774 54501 42775 54501 42775 54502 42774 54502 42819 54502 42775 54503 42819 54503 42776 54503 42776 54504 42819 54504 42820 54504 42776 54505 42820 54505 42701 54505 42777 54506 42731 54506 42778 54506 42778 54507 42731 54507 42827 54507 42778 54508 42827 54508 42780 54508 42780 54509 42827 54509 42779 54509 42780 54510 42779 54510 42782 54510 42782 54511 42779 54511 42781 54511 42782 54512 42781 54512 42735 54512 42783 54513 42785 54513 42784 54513 42784 54514 42785 54514 42716 54514 42784 54515 42716 54515 42722 54515 42722 54516 42716 54516 42786 54516 42722 54517 42786 54517 42721 54517 42721 54518 42786 54518 42886 54518 42721 54519 42886 54519 42787 54519 42787 54520 42886 54520 42889 54520 42787 54521 42889 54521 42788 54521 42788 54522 42889 54522 42891 54522 42788 54523 42891 54523 42757 54523 42757 54524 42891 54524 42789 54524 42757 54525 42789 54525 42790 54525 42790 54526 42789 54526 42894 54526 42790 54527 42894 54527 42791 54527 42791 54528 42894 54528 42895 54528 42791 54529 42895 54529 42792 54529 42792 54530 42895 54531 42793 54532 42792 54533 42793 54533 42794 54533 42794 54534 42793 54534 42796 54534 42794 54535 42796 54535 42795 54535 42795 54536 42796 54536 42797 54536 42795 54537 42797 54537 42799 54537 42799 54538 42797 54538 42798 54538 42799 54539 42798 54539 42800 54539 42800 54540 42798 54540 42833 54540 42800 54541 42833 54541 42801 54541 42801 54542 42833 54542 42728 54542 42695 54543 42705 54543 42696 54543 42696 54544 42705 54544 42874 54544 42696 54545 42874 54545 42802 54545 42802 54546 42874 54546 42803 54546 42802 54547 42803 54547 42804 54547 42804 54548 42803 54548 42805 54548 42804 54549 42805 54549 42765 54549 42765 54550 42805 54550 42806 54550 42765 54551 42806 54551 42762 54551 42762 54552 42806 54552 42807 54552 42762 54553 42807 54553 42761 54553 42761 54554 42807 54554 42808 54554 42761 54555 42808 54555 42759 54555 42759 54556 42808 54556 42809 54556 42759 54557 42809 54557 42810 54557 42810 54558 42809 54558 42811 54558 42810 54559 42811 54559 42712 54559 42712 54560 42811 54561 42812 54562 42712 54563 42812 54563 42813 54563 42813 54564 42812 54564 42880 54564 42813 54565 42880 54565 42814 54565 42814 54566 42880 54566 42881 54566 42814 54567 42881 54567 42815 54567 42815 54568 42881 54568 42816 54568 42752 54569 42746 54570 42750 54571 42750 54572 42746 54573 42853 54574 42750 54575 42853 54575 42748 54575 42748 54576 42853 54576 42817 54576 42748 54577 42817 54577 42770 54577 42770 54578 42817 54578 42855 54578 42770 54579 42855 54579 42772 54579 42772 54580 42855 54580 42818 54580 42772 54581 42818 54581 42774 54581 42774 54582 42818 54582 42858 54582 42774 54583 42858 54583 42819 54583 42819 54584 42858 54584 42860 54584 42819 54585 42860 54585 42820 54585 42820 54586 42860 54586 42861 54586 42820 54587 42861 54587 42701 54587 42701 54588 42861 54588 42862 54588 42701 54589 42862 54589 42821 54589 42821 54590 42862 54590 42864 54590 42821 54591 42864 54592 42822 54593 42822 54594 42864 54594 42823 54594 42824 54595 42826 54595 42825 54595 42825 54596 42826 54596 42730 54596 42825 54597 42730 54597 42732 54597 42732 54598 42730 54598 42828 54598 42732 54599 42828 54599 42827 54599 42827 54600 42828 54600 42837 54600 42827 54601 42837 54601 42779 54601 42779 54602 42837 54602 42840 54602 42779 54603 42840 54603 42781 54603 42781 54604 42840 54604 42841 54604 42781 54605 42841 54605 42735 54605 42735 54606 42841 54606 42843 54606 42735 54607 42843 54607 42736 54607 42736 54608 42843 54608 42844 54608 42736 54609 42844 54609 42689 54609 42689 54610 42844 54610 42846 54610 42689 54611 42846 54611 42829 54611 42829 54612 42846 54613 42847 54614 42829 54615 42847 54615 42830 54615 42830 54616 42847 54616 42848 54616 42830 54617 42848 54617 42831 54617 42831 54618 42848 54618 42832 54618 42798 54619 42949 54619 42833 54619 42833 54620 42949 54620 42834 54620 42833 54621 42834 54621 42835 54621 42835 54622 42834 54622 42836 54622 42835 54623 42836 54623 42730 54623 42730 54624 42836 54624 42901 54624 42730 54625 42901 54625 42828 54625 42828 54626 42901 54626 42902 54626 42828 54627 42902 54627 42837 54627 42837 54628 42902 54628 42838 54628 42837 54629 42838 54629 42840 54629 42840 54630 42838 54630 42839 54630 42840 54631 42839 54631 42841 54631 42841 54632 42839 54632 42842 54632 42841 54633 42842 54633 42843 54633 42843 54634 42842 54634 42904 54634 42843 54635 42904 54635 42844 54635 42844 54636 42904 54636 42845 54636 42844 54637 42845 54637 42846 54637 42846 54638 42845 54638 42906 54638 42846 54639 42906 54639 42847 54639 42847 54640 42906 54640 42908 54640 42847 54641 42908 54641 42848 54641 42848 54642 42908 54642 42850 54642 42848 54643 42850 54643 42849 54643 42849 54644 42850 54644 42851 54644 42849 54645 42851 54645 42741 54645 42741 54646 42851 54646 42910 54646 42741 54647 42910 54647 42745 54647 42745 54648 42910 54648 42852 54648 42745 54649 42852 54649 42853 54649 42853 54650 42852 54650 42912 54650 42853 54651 42912 54651 42817 54651 42817 54652 42912 54652 42854 54652 42817 54653 42854 54653 42855 54653 42855 54654 42854 54654 42856 54654 42855 54655 42856 54655 42818 54655 42818 54656 42856 54656 42857 54656 42818 54657 42857 54657 42858 54657 42858 54658 42857 54658 42859 54658 42858 54659 42859 54659 42860 54659 42860 54660 42859 54660 42917 54660 42860 54661 42917 54661 42861 54661 42861 54662 42917 54662 42863 54662 42861 54663 42863 54663 42862 54663 42862 54664 42863 54664 42918 54664 42862 54665 42918 54665 42864 54665 42864 54666 42918 54666 42865 54666 42864 54667 42865 54667 42697 54667 42697 54668 42865 54668 42866 54668 42697 54669 42866 54669 42867 54669 42867 54670 42866 54670 42922 54670 42867 54671 42922 54671 42868 54671 42868 54672 42922 54672 42870 54672 42868 54673 42870 54673 42869 54673 42869 54674 42870 54674 42871 54674 42869 54675 42871 54675 42873 54675 42873 54676 42871 54676 42872 54676 42873 54677 42872 54677 42874 54677 42874 54678 42872 54678 42926 54678 42874 54679 42926 54679 42803 54679 42803 54680 42926 54680 42875 54680 42803 54681 42875 54681 42805 54681 42805 54682 42875 54682 42928 54682 42805 54683 42928 54683 42806 54683 42806 54684 42928 54684 42930 54684 42806 54685 42930 54685 42807 54685 42807 54686 42930 54686 42933 54686 42807 54687 42933 54687 42808 54687 42808 54688 42933 54688 42876 54688 42808 54689 42876 54689 42809 54689 42809 54690 42876 54690 42877 54690 42809 54691 42877 54691 42811 54691 42811 54692 42877 54692 42878 54692 42811 54693 42878 54693 42812 54693 42812 54694 42878 54694 42879 54694 42812 54695 42879 54695 42880 54695 42880 54696 42879 54696 42936 54696 42880 54697 42936 54697 42881 54697 42881 54698 42936 54698 42883 54698 42881 54699 42883 54699 42882 54699 42882 54700 42883 54700 42938 54700 42882 54701 42938 54701 42719 54701 42719 54702 42938 54702 42940 54702 42719 54703 42940 54703 42717 54703 42717 54704 42940 54704 42884 54704 42717 54705 42884 54705 42716 54705 42716 54706 42884 54706 42885 54706 42716 54707 42885 54707 42786 54707 42786 54708 42885 54708 42887 54708 42786 54709 42887 54709 42886 54709 42886 54710 42887 54710 42888 54710 42886 54711 42888 54711 42889 54711 42889 54712 42888 54712 42890 54712 42889 54713 42890 54713 42891 54713 42891 54714 42890 54714 42892 54714 42891 54715 42892 54715 42789 54715 42789 54716 42892 54716 42893 54716 42789 54717 42893 54717 42894 54717 42894 54718 42893 54718 42946 54718 42894 54719 42946 54719 42895 54719 42895 54720 42946 54720 42947 54720 42895 54721 42947 54721 42793 54721 42793 54722 42947 54722 42896 54722 42793 54723 42896 54723 42796 54723 42796 54724 42896 54724 42897 54724 42796 54725 42897 54725 42797 54725 42797 54726 42897 54726 42898 54726 42797 54727 42898 54727 42798 54727 42798 54728 42898 54728 42949 54728 42949 54729 42899 54729 42834 54729 42834 54730 42899 54730 42950 54730 42834 54731 42950 54731 42836 54731 42836 54732 42950 54732 42951 54732 42836 54733 42951 54733 42901 54733 42901 54734 42951 54734 42900 54734 42901 54735 42900 54735 42902 54735 42902 54736 42900 54736 42903 54736 42902 54737 42903 54737 42838 54737 42838 54738 42903 54738 42954 54738 42838 54739 42954 54739 42839 54739 42839 54740 42954 54740 42956 54740 42839 54741 42956 54741 42842 54741 42842 54742 42956 54742 42957 54742 42842 54743 42957 54743 42904 54743 42904 54744 42957 54744 42905 54744 42904 54745 42905 54745 42845 54745 42845 54746 42905 54746 42960 54746 42845 54747 42960 54747 42906 54747 42906 54748 42960 54748 42907 54748 42906 54749 42907 54749 42908 54749 42908 54750 42907 54750 42909 54750 42908 54751 42909 54751 42850 54751 42850 54752 42909 54752 42962 54752 42850 54753 42962 54753 42851 54753 42851 54754 42962 54754 42964 54754 42851 54755 42964 54755 42910 54755 42910 54756 42964 54756 42911 54756 42910 54757 42911 54757 42852 54757 42852 54758 42911 54758 42965 54758 42852 54759 42965 54759 42912 54759 42912 54760 42965 54760 42967 54760 42912 54761 42967 54761 42854 54761 42854 54762 42967 54762 42913 54762 42854 54763 42913 54763 42856 54763 42856 54764 42913 54764 42914 54764 42856 54765 42914 54765 42857 54765 42857 54766 42914 54766 42915 54766 42857 54767 42915 54767 42859 54767 42859 54768 42915 54768 42916 54768 42859 54769 42916 54769 42917 54769 42917 54770 42916 54770 42971 54770 42917 54771 42971 54771 42863 54771 42863 54772 42971 54772 42972 54772 42863 54773 42972 54773 42918 54773 42918 54774 42972 54774 42919 54774 42918 54775 42919 54775 42865 54775 42865 54776 42919 54776 42920 54776 42865 54777 42920 54777 42866 54777 42866 54778 42920 54778 42921 54778 42866 54779 42921 54779 42922 54779 42922 54780 42921 54780 42976 54780 42922 54781 42976 54781 42870 54781 42870 54782 42976 54782 42923 54782 42870 54783 42923 54783 42871 54783 42871 54784 42923 54784 42924 54784 42871 54785 42924 54785 42872 54785 42872 54786 42924 54786 42925 54786 42872 54787 42925 54787 42926 54787 42926 54788 42925 54788 42927 54788 42926 54789 42927 54789 42875 54789 42875 54790 42927 54790 42981 54790 42875 54791 42981 54791 42928 54791 42928 54792 42981 54792 42929 54792 42928 54793 42929 54793 42930 54793 42930 54794 42929 54794 42931 54794 42930 54795 42931 54795 42933 54795 42933 54796 42931 54796 42932 54796 42933 54797 42932 54797 42876 54797 42876 54798 42932 54798 42934 54798 42876 54799 42934 54799 42877 54799 42877 54800 42934 54800 42935 54800 42877 54801 42935 54801 42878 54801 42878 54802 42935 54802 42984 54802 42878 54803 42984 54803 42879 54803 42879 54804 42984 54804 42985 54804 42879 54805 42985 54805 42936 54805 42936 54806 42985 54806 42937 54806 42936 54807 42937 54807 42883 54807 42883 54808 42937 54808 42988 54808 42883 54809 42988 54809 42938 54809 42938 54810 42988 54810 42939 54810 42938 54811 42939 54811 42940 54811 42940 54812 42939 54812 42941 54812 42940 54813 42941 54813 42884 54813 42884 54814 42941 54814 42989 54814 42884 54815 42989 54815 42885 54815 42885 54816 42989 54816 42991 54816 42885 54817 42991 54817 42887 54817 42887 54818 42991 54818 42942 54818 42887 54819 42942 54819 42888 54819 42888 54820 42942 54820 42943 54820 42888 54821 42943 54821 42890 54821 42890 54822 42943 54822 42994 54822 42890 54823 42994 54823 42892 54823 42892 54824 42994 54824 42944 54824 42892 54825 42944 54825 42893 54825 42893 54826 42944 54826 42945 54826 42893 54827 42945 54827 42946 54827 42946 54828 42945 54828 42996 54828 42946 54829 42996 54829 42947 54829 42947 54830 42996 54830 42997 54830 42947 54831 42997 54831 42896 54831 42896 54832 42997 54832 42999 54832 42896 54833 42999 54833 42897 54833 42897 54834 42999 54834 42948 54834 42897 54835 42948 54835 42898 54835 42898 54836 42948 54836 43001 54836 42898 54837 43001 54837 42949 54837 42949 54838 43001 54838 42899 54838 42899 54839 43027 54839 42950 54839 42950 54840 43027 54840 43031 54840 42950 54841 43031 54841 42951 54841 42951 54842 43031 54842 42952 54842 42951 54843 42952 54843 42900 54843 42900 54844 42952 54844 42953 54844 42900 54845 42953 54845 42903 54845 42903 54846 42953 54846 42955 54846 42903 54847 42955 54847 42954 54847 42954 54848 42955 54848 43036 54848 42954 54849 43036 54849 42956 54849 42956 54850 43036 54850 43037 54850 42956 54851 43037 54851 42957 54851 42957 54852 43037 54852 42958 54852 42957 54853 42958 54853 42905 54853 42905 54854 42958 54854 42959 54854 42905 54855 42959 54855 42960 54855 42960 54856 42959 54856 42961 54856 42960 54857 42961 54857 42907 54857 42907 54858 42961 54858 43041 54858 42907 54859 43041 54859 42909 54859 42909 54860 43041 54860 43044 54860 42909 54861 43044 54861 42962 54861 42962 54862 43044 54862 42963 54862 42962 54863 42963 54863 42964 54863 42964 54864 42963 54864 43047 54864 42964 54865 43047 54865 42911 54865 42911 54866 43047 54866 43048 54866 42911 54867 43048 54867 42965 54867 42965 54868 43048 54868 42966 54868 42965 54869 42966 54869 42967 54869 42967 54870 42966 54870 42968 54870 42967 54871 42968 54871 42913 54871 42913 54872 42968 54872 42969 54872 42913 54873 42969 54873 42914 54873 42914 54874 42969 54874 42970 54874 42914 54875 42970 54875 42915 54875 42915 54876 42970 54876 43055 54876 42915 54877 43055 54877 42916 54877 42916 54878 43055 54878 43057 54878 42916 54879 43057 54879 42971 54879 42971 54880 43057 54880 43059 54880 42971 54881 43059 54881 42972 54881 42972 54882 43059 54882 42973 54882 42972 54883 42973 54883 42919 54883 42919 54884 42973 54884 43063 54884 42919 54885 43063 54885 42920 54885 42920 54886 43063 54886 42974 54886 42920 54887 42974 54887 42921 54887 42921 54888 42974 54888 42975 54888 42921 54889 42975 54889 42976 54889 42976 54890 42975 54890 42977 54890 42976 54891 42977 54891 42923 54891 42923 54892 42977 54892 43067 54892 42923 54893 43067 54893 42924 54893 42924 54894 43067 54894 42978 54894 42924 54895 42978 54895 42925 54895 42925 54896 42978 54896 42979 54896 42925 54897 42979 54897 42927 54897 42927 54898 42979 54898 42980 54898 42927 54899 42980 54899 42981 54899 42981 54900 42980 54900 43073 54900 42981 54901 43073 54901 42929 54901 42929 54902 43073 54902 43074 54902 42929 54903 43074 54903 42931 54903 42931 54904 43074 54904 43075 54904 42931 54905 43075 54905 42932 54905 42932 54906 43075 54906 42982 54906 42932 54907 42982 54907 42934 54907 42934 54908 42982 54908 42983 54908 42934 54909 42983 54909 42935 54909 42935 54910 42983 54910 43080 54910 42935 54911 43080 54911 42984 54911 42984 54912 43080 54912 42986 54912 42984 54913 42986 54913 42985 54913 42985 54914 42986 54914 42987 54914 42985 54915 42987 54915 42937 54915 42937 54916 42987 54916 43084 54916 42937 54917 43084 54917 42988 54917 42988 54918 43084 54918 43004 54918 42988 54919 43004 54919 42939 54919 42939 54920 43004 54920 43005 54920 42939 54921 43005 54921 42941 54921 42941 54922 43005 54922 43008 54922 42941 54923 43008 54923 42989 54923 42989 54924 43008 54924 42990 54924 42989 54925 42990 54925 42991 54925 42991 54926 42990 54926 43011 54926 42991 54927 43011 54927 42942 54927 42942 54928 43011 54928 42992 54928 42942 54929 42992 54929 42943 54929 42943 54930 42992 54930 42993 54930 42943 54931 42993 54931 42994 54931 42994 54932 42993 54932 43015 54932 42994 54933 43015 54933 42944 54933 42944 54934 43015 54934 42995 54934 42944 54935 42995 54935 42945 54935 42945 54936 42995 54936 43018 54936 42945 54937 43018 54937 42996 54937 42996 54938 43018 54938 43020 54938 42996 54939 43020 54939 42997 54939 42997 54940 43020 54940 42998 54940 42997 54941 42998 54941 42999 54941 42999 54942 42998 54942 43023 54942 42999 54943 43023 54943 42948 54943 42948 54944 43023 54944 43024 54944 42948 54945 43024 54945 43001 54945 43001 54946 43024 54946 43000 54946 43001 54947 43000 54947 42899 54947 42899 54948 43000 54948 43027 54948 43002 54949 43003 54949 43004 54949 43004 54950 43003 54950 43006 54950 43004 54951 43006 54951 43005 54951 43005 54952 43006 54952 43007 54952 43005 54953 43007 54953 43008 54953 43008 54954 43007 54954 43009 54954 43008 54955 43009 54955 42990 54955 42990 54956 43009 54956 43010 54956 42990 54957 43010 54957 43011 54957 43011 54958 43010 54958 43012 54958 43011 54959 43012 54959 42992 54959 42992 54960 43012 54960 43013 54960 42992 54961 43013 54961 42993 54961 42993 54962 43013 54962 43014 54962 42993 54963 43014 54963 43015 54963 43015 54964 43014 54964 43016 54964 43015 54965 43016 54965 42995 54965 42995 54966 43016 54966 43017 54966 42995 54967 43017 54967 43018 54967 43018 54968 43017 54968 43019 54968 43018 54969 43019 54969 43020 54969 43020 54970 43019 54970 43021 54970 43020 54971 43021 54971 42998 54971 42998 54972 43021 54972 43022 54972 42998 54973 43022 54973 43023 54973 43023 54974 43022 54974 43025 54974 43023 54975 43025 54975 43024 54975 43024 54976 43025 54976 43026 54976 43024 54977 43026 54977 43000 54977 43000 54978 43026 54978 43028 54978 43000 54979 43028 54979 43027 54979 43027 54980 43028 54980 43029 54980 43027 54981 43029 54981 43031 54981 43031 54982 43029 54982 43030 54982 43031 54983 43030 54983 42952 54983 42952 54984 43030 54984 43032 54984 42952 54985 43032 54985 42953 54985 42953 54986 43032 54986 43033 54986 42953 54987 43033 54987 42955 54987 42955 54988 43033 54988 43034 54988 42955 54989 43034 54989 43036 54989 43036 54990 43034 54990 43035 54990 43036 54991 43035 54991 43037 54991 43037 54992 43035 54992 43038 54992 43037 54993 43038 54993 42958 54993 42958 54994 43038 54994 43039 54994 42958 54995 43039 54995 42959 54995 42959 54996 43039 54996 43040 54996 42959 54997 43040 54997 42961 54997 42961 54998 43040 54998 43042 54998 42961 54999 43042 54999 43041 54999 43041 55000 43042 55000 43043 55000 43041 55001 43043 55001 43044 55001 43044 55002 43043 55002 43045 55002 43044 55003 43045 55003 42963 55003 42963 55004 43045 55004 43046 55004 42963 55005 43046 55005 43047 55005 43047 55006 43046 55006 43049 55006 43047 55007 43049 55007 43048 55007 43048 55008 43049 55008 43050 55008 43048 55009 43050 55009 42966 55009 42966 55010 43050 55010 43051 55010 42966 55011 43051 55011 42968 55011 42968 55012 43051 55012 43052 55012 42968 55013 43052 55013 42969 55013 42969 55014 43052 55014 43053 55014 42969 55015 43053 55015 42970 55015 42970 55016 43053 55016 43054 55016 42970 55017 43054 55017 43055 55017 43055 55018 43054 55018 43056 55018 43055 55019 43056 55019 43057 55019 43057 55020 43056 55020 43058 55020 43057 55021 43058 55021 43059 55021 43059 55022 43058 55022 43060 55022 43059 55023 43060 55023 42973 55023 42973 55024 43060 55024 43061 55024 42973 55025 43061 55025 43063 55025 43063 55026 43061 55026 43062 55026 43063 55027 43062 55027 42974 55027 42974 55028 43062 55028 43064 55028 42974 55029 43064 55029 42975 55029 42975 55030 43064 55030 43065 55030 42975 55031 43065 55031 42977 55031 42977 55032 43065 55032 43066 55032 42977 55033 43066 55033 43067 55033 43067 55034 43066 55034 43068 55034 43067 55035 43068 55035 42978 55035 42978 55036 43068 55036 43069 55036 42978 55037 43069 55037 42979 55037 42979 55038 43069 55038 43070 55038 42979 55039 43070 55039 42980 55039 42980 55040 43070 55040 43071 55040 42980 55041 43071 55041 43073 55041 43073 55042 43071 55042 43072 55042 43073 55043 43072 55043 43074 55043 43074 55044 43072 55044 43076 55044 43074 55045 43076 55045 43075 55045 43075 55046 43076 55046 43077 55046 43075 55047 43077 55047 42982 55047 42982 55048 43077 55048 43078 55048 42982 55049 43078 55049 42983 55049 42983 55050 43078 55050 43079 55050 42983 55051 43079 55051 43080 55051 43080 55052 43079 55052 43081 55052 43080 55053 43081 55053 42986 55053 42986 55054 43081 55054 43082 55054 42986 55055 43082 55055 42987 55055 42987 55056 43082 55056 43083 55056 42987 55057 43083 55057 43084 55057 43084 55058 43083 55058 43002 55058 43084 55059 43002 55059 43004 55059 43085 55060 43160 55060 43087 55060 43087 55061 43160 55061 43086 55061 43087 55062 43086 55062 43088 55062 43088 55063 43086 55063 43089 55063 43088 55064 43089 55064 43091 55064 43091 55065 43089 55065 43090 55065 43091 55066 43090 55066 43092 55066 43092 55067 43090 55067 43093 55067 43092 55068 43093 55068 43094 55068 43094 55069 43093 55069 43096 55069 43094 55069 43096 55069 43095 55069 43095 55070 43096 55070 43098 55070 43095 55070 43098 55070 43097 55070 43097 55071 43098 55071 43099 55071 43097 55072 43099 55072 43100 55072 43100 55073 43099 55073 43101 55073 43100 55073 43101 55073 43102 55073 43102 55074 43101 55074 43104 55074 43102 55075 43104 55075 43103 55075 43103 6 43104 6 43105 6 43103 6 43105 6 43106 6 43106 55076 43105 55076 43107 55076 43106 55077 43107 55077 43108 55077 43108 55078 43107 55078 43109 55078 43108 55078 43109 55078 43110 55078 43110 55079 43109 55079 43111 55079 43110 55080 43111 55080 43112 55080 43112 55081 43111 55081 43113 55081 43112 55081 43113 55081 43114 55081 43114 55082 43113 55082 43115 55082 43114 55082 43115 55082 43116 55082 43116 55083 43115 55083 43118 55083 43116 55084 43118 55084 43117 55084 43117 55085 43118 55085 43119 55085 43117 55086 43119 55086 43120 55086 43120 55087 43119 55087 43122 55087 43120 55088 43122 55088 43121 55088 43121 55089 43122 55089 43123 55089 43121 55090 43123 55090 43124 55090 43124 55091 43123 55091 43125 55091 43124 55092 43125 55092 43127 55092 43127 55093 43125 55093 43126 55093 43127 55094 43126 55094 43128 55094 43128 55095 43126 55095 43129 55095 43128 55096 43129 55096 43130 55096 43130 55097 43129 55097 43131 55097 43130 55098 43131 55098 43132 55098 43132 55099 43131 55099 43134 55099 43132 55099 43134 55099 43133 55099 43133 55100 43134 55100 43135 55100 43133 55101 43135 55101 43136 55101 43136 55102 43135 55102 43138 55102 43136 55103 43138 55103 43137 55103 43137 55104 43138 55104 43139 55104 43137 55105 43139 55105 43140 55105 43140 55106 43139 55106 43141 55106 43140 55107 43141 55107 43142 55107 43142 21 43141 21 43143 21 43142 21 43143 21 43144 21 43144 55108 43143 55108 43146 55108 43144 55109 43146 55109 43145 55109 43145 55110 43146 55110 43147 55110 43145 55111 43147 55111 43148 55111 43148 55112 43147 55112 43150 55112 43148 55113 43150 55113 43149 55113 43149 55114 43150 55114 43151 55114 43149 55115 43151 55115 43152 55115 43152 55116 43151 55116 43154 55116 43152 55116 43154 55116 43153 55116 43153 55117 43154 55117 43155 55117 43153 55118 43155 55118 43156 55118 43156 55119 43155 55119 43158 55119 43156 55120 43158 55120 43157 55120 43157 55121 43158 55121 43159 55121 43157 55122 43159 55122 43085 55122 43085 55123 43159 55123 43160 55123 43161 55124 43162 55124 43163 55124 43163 55125 43162 55125 43165 55125 43163 55126 43165 55126 43164 55126 43164 55127 43165 55127 43167 55127 43164 55128 43167 55128 43166 55128 43166 55129 43167 55129 43168 55129 43166 55130 43168 55130 43211 55130 43211 55131 43168 55131 43169 55131 43211 55132 43169 55132 43212 55132 43212 49 43169 49 43170 49 43212 49 43170 49 43207 49 43207 55133 43170 55133 43172 55133 43207 55133 43172 55133 43171 55133 43171 55134 43172 55134 43173 55134 43171 55134 43173 55134 43206 55134 43206 55135 43173 55135 43174 55135 43206 55136 43174 55136 43210 55136 43210 55137 43174 55137 43175 55137 43210 55138 43175 55138 43204 55138 43204 55139 43175 55139 43176 55139 43204 55140 43176 55140 43205 55140 43205 55141 43176 55141 43177 55141 43205 55142 43177 55142 43178 55142 43178 55143 43177 55143 43179 55143 43178 55144 43179 55144 43208 55144 43208 55145 43179 55145 43180 55145 43208 55145 43180 55145 43209 55145 43209 55146 43180 55146 43181 55146 43209 55147 43181 55147 43183 55147 43183 55148 43181 55148 43182 55148 43183 55149 43182 55149 43184 55149 43184 55150 43182 55150 43185 55150 43184 55151 43185 55151 43213 55151 43213 55152 43185 55152 43187 55152 43213 54320 43187 54320 43186 54320 43186 55153 43187 55153 43188 55153 43186 55154 43188 55154 43189 55154 43189 55155 43188 55155 43191 55155 43189 55156 43191 55156 43190 55156 43190 55157 43191 55157 43192 55157 43190 54323 43192 54323 43193 54323 43193 55158 43192 55158 43194 55158 43193 55159 43194 55159 43214 55159 43214 55160 43194 55160 43195 55160 43214 55161 43195 55161 43196 55161 43196 55162 43195 55162 43198 55162 43196 55163 43198 55163 43197 55163 43197 55164 43198 55164 43199 55164 43197 55165 43199 55165 43201 55165 43201 55166 43199 55166 43200 55166 43201 55167 43200 55167 43202 55167 43202 55168 43200 55168 43203 55168 43202 55169 43203 55169 43161 55169 43161 55170 43203 55170 43162 55170 43197 960 43201 960 43186 960 43204 55171 43205 55171 43201 55171 43201 960 43205 960 43178 960 43161 960 43163 960 43210 960 43210 960 43163 960 43164 960 43210 960 43164 960 43166 960 43210 960 43207 960 43206 960 43206 55172 43207 55172 43171 55172 43178 960 43208 960 43201 960 43201 960 43208 960 43209 960 43201 55173 43209 55173 43183 55173 43204 960 43201 960 43210 960 43210 55174 43201 55174 43202 55174 43210 55175 43202 55175 43161 55175 43166 960 43211 960 43210 960 43210 55176 43211 55176 43212 55176 43210 960 43212 960 43207 960 43183 960 43184 960 43201 960 43201 960 43184 960 43213 960 43201 55177 43213 55177 43186 55177 43193 960 43186 960 43190 960 43190 960 43186 960 43189 960 43193 960 43214 960 43186 960 43186 960 43214 960 43196 960 43186 55178 43196 55178 43197 55178 43215 55179 43217 55179 43216 55179 43216 55180 43217 55180 43218 55180 43216 55181 43218 55181 43223 55181 43219 55182 43220 55182 43221 55182 43221 55183 43220 55183 43585 55183 43221 55184 43585 55185 43701 55186 43701 55187 43703 55187 43221 55187 43221 55188 43703 55188 43222 55188 43221 55189 43222 55189 43218 55189 43218 55190 43222 55190 43704 55190 43218 55191 43704 55191 43223 55191 43224 55192 43225 55192 43226 55192 43226 55193 43225 55193 43231 55193 43226 55194 43231 55194 43630 55194 43227 55195 43228 55195 43230 55195 43230 55196 43228 55196 43636 55196 43230 55197 43636 55197 43593 55197 43593 55198 43229 55198 43230 55198 43230 55199 43229 55199 43628 55199 43230 55200 43628 55200 43231 55200 43231 55201 43628 55201 43629 55201 43231 55202 43629 55202 43630 55202 43307 55203 43232 55203 43233 55203 43307 55204 43234 55204 43232 55204 43232 55205 43234 55206 43492 55207 43232 55208 43492 55208 43235 55208 43492 55209 43495 55209 43235 55209 43235 55210 43495 55210 43236 55210 43235 55211 43236 55211 43238 55211 43236 55212 43237 55212 43238 55212 43238 51661 43237 51661 43239 51661 43238 55213 43239 55213 43240 55213 43239 55214 43241 55214 43240 55214 43240 55215 43241 55215 43498 55215 43240 55216 43498 55216 43242 55216 43498 55217 43243 55217 43242 55217 43242 55218 43243 55218 43500 55218 43242 55219 43500 55219 43244 55219 43500 55220 43245 55220 43244 55220 43244 51670 43245 51670 43246 51670 43244 51671 43246 51671 43247 51671 43246 51672 43503 51672 43247 51672 43247 55221 43503 55221 43248 55221 43247 55222 43248 55222 43250 55222 43248 55223 43249 55223 43250 55223 43250 55224 43249 55224 43251 55224 43250 55225 43251 55225 43252 55225 43251 51677 43504 51677 43252 51677 43252 51678 43504 51678 43507 51678 43252 55226 43507 55226 43253 55226 43507 55227 43254 55227 43253 55227 43253 55228 43254 55228 43255 55228 43253 55229 43255 55229 43256 55229 43255 55230 43508 55230 43256 55230 43256 55231 43508 55231 43509 55231 43256 55232 43509 55232 43257 55232 43509 55233 43258 55233 43257 55233 43257 35538 43258 35538 43259 35538 43257 55234 43259 55234 43261 55234 43259 51689 43510 51689 43261 51689 43261 35541 43510 35541 43260 35541 43261 55235 43260 55235 43262 55235 43260 55236 43263 55236 43262 55236 43262 35544 43263 35544 43511 35544 43262 55237 43511 55237 43265 55237 43511 55238 43264 55238 43265 55238 43265 55239 43264 55239 43512 55239 43265 55240 43512 55240 43266 55240 43512 55241 43515 55241 43266 55241 43266 55242 43515 55242 43267 55242 43266 55243 43267 55243 43268 55243 43267 51699 43269 51699 43268 51699 43268 51700 43269 51700 43270 51700 43268 55244 43270 55244 43272 55244 43270 35555 43271 35555 43272 35555 43272 35556 43271 35556 43517 35556 43272 55245 43517 55245 43273 55245 43517 51704 43520 51704 43273 51704 43273 55246 43520 55246 43521 55246 43273 55247 43521 55247 43274 55247 43521 55248 43522 55248 43274 55248 43274 55249 43522 55249 43275 55249 43274 55250 43275 55250 43278 55250 43275 35564 43276 35564 43278 35564 43278 55251 43276 55251 43277 55251 43278 55252 43277 55252 43280 55252 43277 55253 43525 55253 43280 55253 43280 51608 43525 51608 43279 51608 43280 55254 43279 55254 43281 55254 43279 55255 43528 55255 43281 55255 43281 55256 43528 55256 43529 55256 43281 55257 43529 55257 43282 55257 43529 55258 43283 55258 43282 55258 43282 55259 43283 55259 43530 55259 43282 55260 43530 55260 43284 55260 43530 55261 43531 55261 43284 55261 43284 51616 43531 51616 43533 51616 43284 51617 43533 51617 43285 51617 43533 51618 43286 51618 43285 51618 43285 55262 43286 55262 43287 55262 43285 55263 43287 55263 43288 55263 43287 55264 43534 55264 43288 55264 43288 55265 43534 55265 43535 55265 43288 55266 43535 55266 43290 55266 43535 51624 43289 51624 43290 51624 43290 51625 43289 51625 43538 51625 43290 55267 43538 55267 43291 55267 43538 55268 43539 55268 43291 55268 43291 55269 43539 55269 43540 55269 43291 55270 43540 55270 43293 55270 43540 55271 43542 55271 43293 55271 43293 55272 43542 55272 43292 55272 43293 55273 43292 55273 43294 55273 43292 55274 43543 55274 43294 55274 43294 55275 43543 55275 43295 55275 43294 55276 43295 55276 43296 55276 43295 51635 43544 51635 43296 51635 43296 35598 43544 35598 43545 35598 43296 55277 43545 55277 43297 55277 43545 55278 43547 55278 43297 55278 43297 55279 43547 55279 43298 55279 43297 55280 43298 55280 43300 55280 43298 55281 43299 55281 43300 55281 43300 55282 43299 55282 43549 55282 43300 55283 43549 55283 43302 55283 43549 55284 43552 55284 43302 55284 43302 35607 43552 35607 43301 35607 43302 55285 43301 55285 43304 55285 43301 51646 43303 51646 43304 51646 43304 51647 43303 51647 43553 51647 43304 55286 43553 55286 43305 55286 43553 35612 43554 35612 43305 35612 43305 55287 43554 55287 43490 55287 43305 55288 43490 55288 43233 55288 43233 51651 43490 51651 43306 51651 43233 55289 43306 55289 43307 55289 43308 55290 43309 55290 43310 55290 43308 55291 43569 55292 43309 55293 43309 55294 43569 55294 43688 55294 43309 55295 43688 55295 43409 55295 43409 55296 43688 55296 43687 55296 43409 55297 43687 55297 43311 55297 43687 55298 43691 55298 43311 55298 43311 55299 43691 55299 43312 55299 43311 55300 43312 55300 43313 55300 43312 55301 43696 55301 43313 55301 43313 55302 43696 55302 43695 55302 43313 55303 43695 55303 43314 55303 43314 55304 43695 55304 43694 55304 43314 55305 43694 55305 43412 55305 43412 55306 43694 55306 43693 55306 43412 55307 43693 55307 43413 55307 43413 55308 43693 55308 43315 55308 43315 55309 43712 55309 43413 55309 43413 55310 43712 55310 43316 55310 43413 55311 43316 55311 43415 55311 43415 55312 43316 55312 43317 55312 43415 55313 43317 55313 43318 55313 43318 55314 43317 55314 43319 55314 43318 55315 43319 55315 43416 55315 43416 55316 43319 55316 43320 55316 43320 55317 43321 55317 43416 55317 43416 55318 43321 55318 43719 55318 43416 55319 43719 55319 43418 55319 43418 55320 43719 55321 43322 55322 43418 55323 43322 55323 43323 55323 43323 55324 43322 55324 43734 55324 43323 55325 43734 55325 43324 55325 43324 55326 43734 55326 43733 55326 43733 55327 43325 55327 43324 55327 43324 55328 43325 55328 43326 55328 43324 55329 43326 55329 43421 55329 43421 55330 43326 55330 43735 55330 43421 55331 43735 55331 43423 55331 43423 55332 43735 55332 43327 55332 43423 55333 43327 55333 43426 55333 43426 55334 43327 55334 43567 55334 43567 55335 43744 55335 43426 55335 43426 55336 43744 55336 43566 55336 43426 55337 43566 55337 43427 55337 43427 55338 43566 55338 43328 55338 43427 55339 43328 55339 43329 55339 43329 51867 43328 51867 43330 51867 43329 55340 43330 55340 43332 55340 43330 55341 43331 55341 43332 55341 43332 55342 43331 55342 43751 55342 43332 55343 43751 55344 43429 55345 43751 55346 43755 55347 43429 55348 43429 55349 43755 55349 43333 55349 43429 55350 43333 55350 43432 55350 43432 55351 43333 55351 43754 55351 43432 55352 43754 55352 43334 55352 43754 55353 43753 55353 43334 55353 43334 55354 43753 55354 43335 55354 43334 55355 43335 55355 43336 55355 43335 55356 43763 55357 43336 55358 43336 55359 43763 55359 43762 55359 43336 55360 43762 55360 43434 55360 43434 55361 43762 55361 43337 55361 43434 55362 43337 55362 43438 55362 43438 55363 43337 55363 43774 55363 43438 55364 43774 55364 43339 55364 43339 55365 43774 55365 43338 55365 43338 55366 43780 55366 43339 55366 43339 55367 43780 55367 43340 55367 43339 55368 43340 55368 43440 55368 43440 55369 43340 55369 43341 55369 43440 55370 43341 55370 43442 55370 43442 55371 43341 55371 43779 55371 43442 55372 43779 55372 43342 55372 43342 55373 43779 55373 43343 55373 43343 55374 43790 55375 43342 55376 43342 55377 43790 55377 43344 55377 43342 55378 43344 55378 43444 55378 43444 55379 43344 55379 43791 55379 43444 55380 43791 55380 43346 55380 43346 55381 43791 55381 43345 55381 43346 55382 43345 55382 43347 55382 43347 55383 43345 55383 43804 55383 43804 55384 43348 55384 43347 55384 43347 55385 43348 55385 43349 55385 43347 55386 43349 55386 43448 55386 43448 55387 43349 55387 43564 55387 43448 55388 43564 55388 43449 55388 43449 55389 43564 55389 43563 55389 43449 55390 43563 55390 43350 55390 43350 55391 43563 55391 43562 55391 43562 55392 43561 55392 43350 55392 43350 55393 43561 55393 43351 55393 43350 55394 43351 55394 43451 55394 43451 55395 43351 55395 43352 55395 43451 55396 43352 55396 43353 55396 43353 55397 43352 55397 43354 55397 43353 55398 43354 55398 43355 55398 43354 55399 43819 55399 43355 55399 43355 55400 43819 55400 43356 55400 43355 55401 43356 55401 43452 55401 43356 55402 43357 55402 43452 55402 43452 55403 43357 55403 43358 55403 43452 55404 43358 55404 43454 55404 43454 55405 43358 55405 43359 55405 43454 55406 43359 55406 43361 55406 43359 55407 43360 55407 43361 55407 43361 55408 43360 55408 43362 55408 43361 55409 43362 55409 43364 55409 43362 55410 43832 55410 43364 55410 43364 55411 43832 55411 43363 55411 43364 55412 43363 55412 43365 55412 43365 55413 43363 55413 43830 55413 43365 55414 43830 55414 43457 55414 43457 55415 43830 55415 43366 55415 43457 55416 43366 55416 43458 55416 43458 55417 43366 55417 43841 55417 43841 55418 43559 55418 43458 55418 43458 55419 43559 55419 43848 55419 43458 55420 43848 55420 43367 55420 43367 55421 43848 55421 43847 55421 43367 55422 43847 55422 43368 55422 43368 55423 43847 55423 43845 55423 43368 55424 43845 55424 43369 55424 43369 55425 43845 55425 43857 55425 43857 55426 43855 55426 43369 55426 43369 55427 43855 55427 43858 55427 43369 55428 43858 55428 43462 55428 43462 55429 43858 55430 43370 55431 43462 55432 43370 55432 43465 55432 43465 55433 43370 55433 43371 55433 43465 55434 43371 55434 43372 55434 43372 55435 43371 55435 43373 55435 43373 55436 43873 55436 43372 55436 43372 55437 43873 55437 43872 55437 43372 55438 43872 55438 43467 55438 43467 55439 43872 55439 43558 55439 43467 55440 43558 55440 43374 55440 43374 55441 43558 55441 43877 55441 43374 55442 43877 55442 43469 55442 43469 55443 43877 55443 43375 55443 43375 55444 43376 55444 43469 55445 43469 55446 43376 55446 43884 55446 43469 55447 43884 55447 43471 55447 43471 55448 43884 55448 43378 55448 43471 55449 43378 55449 43377 55449 43377 51756 43378 51756 43574 51756 43377 55450 43574 55450 43381 55450 43574 55451 43379 55451 43381 55451 43381 55452 43379 55452 43380 55452 43381 55453 43380 55453 43382 55453 43380 55454 43383 55455 43382 55456 43382 55457 43383 55457 43384 55457 43382 55458 43384 55458 43385 55458 43385 55459 43384 55459 43386 55459 43385 55460 43386 55460 43476 55460 43386 55461 43621 55461 43476 55461 43476 55462 43621 55462 43573 55462 43476 55463 43573 55463 43387 55463 43573 55464 43572 55464 43387 55464 43387 55465 43572 55465 43626 55465 43387 55466 43626 55466 43478 55466 43478 55467 43626 55467 43388 55467 43478 55468 43388 55468 43389 55468 43389 55469 43388 55469 43625 55469 43389 55470 43625 55470 43391 55470 43391 55471 43625 55471 43390 55471 43390 55472 43639 55472 43391 55472 43391 55473 43639 55473 43392 55473 43391 55474 43392 55474 43481 55474 43481 55475 43392 55475 43393 55475 43481 55476 43393 55476 43394 55476 43394 55477 43393 55477 43650 55477 43394 55478 43650 55478 43483 55478 43483 55479 43650 55479 43652 55479 43652 55480 43651 55480 43483 55480 43483 55481 43651 55481 43395 55481 43483 55482 43395 55482 43396 55482 43396 55483 43395 55483 43571 55483 43396 55484 43571 55484 43485 55484 43485 55485 43571 55485 43397 55485 43485 55486 43397 55486 43486 55486 43486 55487 43397 55487 43398 55487 43398 55488 43399 55488 43486 55488 43486 55489 43399 55489 43665 55489 43486 55490 43665 55491 43488 55490 43488 55492 43665 55493 43570 55494 43488 55495 43570 55495 43400 55495 43400 55496 43570 55496 43401 55496 43400 55497 43401 55497 43403 55497 43403 55498 43401 55499 43402 55500 43402 55501 43675 55501 43403 55501 43403 55502 43675 55502 43674 55502 43403 55503 43674 55503 43407 55503 43407 55504 43674 55504 43681 55504 43407 55505 43681 55505 43404 55505 43404 55506 43681 55506 43405 55506 43404 55507 43405 55507 43310 55507 43310 55508 43405 55508 43406 55508 43310 55509 43406 55509 43308 55509 43556 55510 43407 55510 43557 55510 43557 55511 43407 55511 43404 55511 43557 55512 43404 55512 43408 55512 43408 55513 43404 55513 43310 55513 43408 55514 43310 55514 43491 55514 43491 55515 43310 55515 43309 55515 43491 55516 43309 55516 43493 55516 43493 55517 43309 55517 43409 55517 43493 55518 43409 55518 43494 55518 43494 55519 43409 55519 43311 55519 43494 55520 43311 55520 43496 55520 43496 55521 43311 55521 43313 55521 43496 55522 43313 55522 43497 55522 43497 55523 43313 55523 43314 55523 43497 55524 43314 55524 43410 55524 43410 55525 43314 55525 43412 55525 43410 55526 43412 55526 43411 55526 43411 55527 43412 55527 43413 55527 43411 55528 43413 55528 43499 55528 43499 55529 43413 55529 43415 55529 43499 55530 43415 55530 43414 55530 43414 55531 43415 55531 43318 55531 43414 55532 43318 55532 43501 55532 43501 55533 43318 55533 43416 55533 43501 55534 43416 55534 43417 55534 43417 55535 43416 55535 43418 55535 43417 55536 43418 55536 43502 55536 43502 55537 43418 55537 43323 55537 43502 55538 43323 55539 43419 55540 43419 55541 43323 55541 43324 55541 43419 55542 43324 55542 43420 55542 43420 55543 43324 55543 43421 55543 43420 55544 43421 55544 43422 55544 43422 55545 43421 55545 43423 55545 43422 55546 43423 55546 43424 55546 43424 55547 43423 55548 43426 55549 43424 55550 43426 55550 43425 55550 43425 55551 43426 55551 43427 55551 43425 55552 43427 55553 43505 55554 43505 55555 43427 55555 43329 55555 43505 55556 43329 55556 43506 55556 43506 55557 43329 55557 43332 55557 43506 55558 43332 55558 43428 55558 43428 55559 43332 55559 43429 55559 43428 55560 43429 55560 43430 55560 43430 55561 43429 55561 43432 55561 43430 55562 43432 55562 43431 55562 43431 55563 43432 55563 43334 55563 43431 55564 43334 55564 43433 55564 43433 55565 43334 55565 43336 55565 43433 55566 43336 55566 43435 55566 43435 55567 43336 55567 43434 55567 43435 55568 43434 55568 43436 55568 43436 55569 43434 55569 43438 55569 43436 55570 43438 55570 43437 55570 43437 55571 43438 55571 43339 55571 43437 55572 43339 55572 43439 55572 43439 55573 43339 55573 43440 55573 43439 55574 43440 55574 43441 55574 43441 55575 43440 55575 43442 55575 43441 55576 43442 55576 43443 55576 43443 55577 43442 55577 43342 55577 43443 55578 43342 55578 43445 55578 43445 55579 43342 55579 43444 55579 43445 55580 43444 55580 43513 55580 43513 55581 43444 55581 43346 55581 43513 55582 43346 55582 43514 55582 43514 52081 43346 52081 43347 52081 43514 55583 43347 55583 43446 55583 43446 55584 43347 55584 43448 55584 43446 55585 43448 55585 43447 55585 43447 55586 43448 55586 43449 55586 43447 55587 43449 55587 43450 55587 43450 55588 43449 55588 43350 55588 43450 55589 43350 55589 43516 55589 43516 55590 43350 55590 43451 55590 43516 55591 43451 55591 43518 55591 43518 55592 43451 55592 43353 55592 43518 55593 43353 55593 43519 55593 43519 55594 43353 55595 43355 55596 43519 55597 43355 55597 43453 55597 43453 55598 43355 55598 43452 55598 43453 55599 43452 55599 43523 55599 43523 55600 43452 55600 43454 55600 43523 55601 43454 55601 43524 55601 43524 55602 43454 55602 43361 55602 43524 55603 43361 55603 43455 55603 43455 55604 43361 55604 43364 55604 43455 55605 43364 55605 43456 55605 43456 55606 43364 55606 43365 55606 43456 55607 43365 55607 43526 55607 43526 55608 43365 55608 43457 55608 43526 55609 43457 55609 43527 55609 43527 55610 43457 55610 43458 55610 43527 55611 43458 55611 43459 55611 43459 55612 43458 55612 43367 55612 43459 55613 43367 55613 43460 55613 43460 55614 43367 55614 43368 55614 43460 55615 43368 55615 43461 55615 43461 55616 43368 55616 43369 55616 43461 55617 43369 55617 43532 55617 43532 55618 43369 55618 43462 55618 43532 55619 43462 55619 43463 55619 43463 55620 43462 55620 43465 55620 43463 55621 43465 55621 43464 55621 43464 55622 43465 55622 43372 55622 43464 55623 43372 55623 43466 55623 43466 55624 43372 55624 43467 55624 43466 55625 43467 55625 43468 55625 43468 55626 43467 55626 43374 55626 43468 55627 43374 55627 43536 55627 43536 55628 43374 55628 43469 55628 43536 55629 43469 55629 43470 55629 43470 55630 43469 55630 43471 55630 43470 55631 43471 55631 43537 55631 43537 55632 43471 55632 43377 55632 43537 55633 43377 55633 43472 55633 43472 55634 43377 55634 43381 55634 43472 55635 43381 55636 43541 55637 43541 55638 43381 55638 43382 55638 43541 55639 43382 55639 43473 55639 43473 55640 43382 55640 43385 55640 43473 55641 43385 55641 43474 55641 43474 55642 43385 55642 43476 55642 43474 55643 43476 55643 43475 55643 43475 55644 43476 55644 43387 55644 43475 55645 43387 55645 43477 55645 43477 55646 43387 55646 43478 55646 43477 55647 43478 55647 43479 55647 43479 55648 43478 55648 43389 55648 43479 55649 43389 55649 43546 55649 43546 55650 43389 55650 43391 55650 43546 55651 43391 55651 43480 55651 43480 55652 43391 55652 43481 55652 43480 55653 43481 55653 43548 55653 43548 55654 43481 55654 43394 55654 43548 55655 43394 55655 43482 55655 43482 55656 43394 55656 43483 55656 43482 55657 43483 55657 43484 55657 43484 55658 43483 55658 43396 55658 43484 55659 43396 55659 43550 55659 43550 55660 43396 55660 43485 55660 43550 55661 43485 55661 43551 55661 43551 52001 43485 52001 43486 52001 43551 55662 43486 55662 43487 55662 43487 55663 43486 55663 43488 55663 43487 55664 43488 55664 43489 55664 43489 55665 43488 55665 43400 55665 43489 55666 43400 55666 43555 55666 43555 55667 43400 55667 43403 55667 43555 55668 43403 55668 43556 55668 43556 55669 43403 55670 43407 55671 43490 55672 43557 55672 43306 55672 43306 55673 43557 55673 43408 55673 43306 55674 43408 55674 43307 55674 43307 55675 43408 55675 43491 55675 43307 55676 43491 55676 43234 55676 43234 55677 43491 55677 43493 55677 43234 55678 43493 55678 43492 55678 43492 55679 43493 55679 43494 55679 43492 55680 43494 55681 43495 55682 43495 55683 43494 55683 43496 55683 43495 55684 43496 55685 43236 55686 43236 55687 43496 55687 43497 55687 43236 55688 43497 55688 43237 55688 43237 55689 43497 55689 43410 55689 43237 55690 43410 55691 43239 55690 43239 55692 43410 55692 43411 55692 43239 55693 43411 55693 43241 55693 43241 55694 43411 55694 43499 55694 43241 55695 43499 55696 43498 55697 43498 55698 43499 55698 43414 55698 43498 55699 43414 55699 43243 55699 43243 55700 43414 55700 43501 55700 43243 55701 43501 55701 43500 55701 43500 55702 43501 55702 43417 55702 43500 55703 43417 55703 43245 55703 43245 55704 43417 55704 43502 55704 43245 55705 43502 55705 43246 55705 43246 55706 43502 55706 43419 55706 43246 55707 43419 55707 43503 55707 43503 55708 43419 55708 43420 55708 43503 55709 43420 55709 43248 55709 43248 55710 43420 55710 43422 55710 43248 55711 43422 55711 43249 55711 43249 55712 43422 55712 43424 55712 43249 55713 43424 55713 43251 55713 43251 55714 43424 55714 43425 55714 43251 55715 43425 55715 43504 55715 43504 55716 43425 55716 43505 55716 43504 55717 43505 55718 43507 55719 43507 55720 43505 55720 43506 55720 43507 55721 43506 55721 43254 55721 43254 55722 43506 55722 43428 55722 43254 55723 43428 55723 43255 55723 43255 55724 43428 55724 43430 55724 43255 55725 43430 55725 43508 55725 43508 55726 43430 55726 43431 55726 43508 55727 43431 55727 43509 55727 43509 55728 43431 55728 43433 55728 43509 55729 43433 55729 43258 55729 43258 55730 43433 55730 43435 55730 43258 55731 43435 55731 43259 55731 43259 55732 43435 55733 43436 55734 43259 55735 43436 55735 43510 55735 43510 55736 43436 55736 43437 55736 43510 55737 43437 55737 43260 55737 43260 55738 43437 55738 43439 55738 43260 55739 43439 55739 43263 55739 43263 55740 43439 55740 43441 55740 43263 55741 43441 55741 43511 55741 43511 55742 43441 55743 43443 55744 43511 55745 43443 55745 43264 55745 43264 55746 43443 55746 43445 55746 43264 55747 43445 55747 43512 55747 43512 55748 43445 55748 43513 55748 43512 55749 43513 55749 43515 55749 43515 55750 43513 55750 43514 55750 43515 55751 43514 55751 43267 55751 43267 55752 43514 55752 43446 55752 43267 55753 43446 55753 43269 55753 43269 55754 43446 55754 43447 55754 43269 55755 43447 55755 43270 55755 43270 55756 43447 55757 43450 55758 43270 55759 43450 55759 43271 55759 43271 55760 43450 55760 43516 55760 43271 55761 43516 55761 43517 55761 43517 55762 43516 55762 43518 55762 43517 55763 43518 55763 43520 55763 43520 55764 43518 55764 43519 55764 43520 55765 43519 55765 43521 55765 43521 55766 43519 55766 43453 55766 43521 55767 43453 55767 43522 55767 43522 55768 43453 55768 43523 55768 43522 55769 43523 55769 43275 55769 43275 55770 43523 55770 43524 55770 43275 55771 43524 55771 43276 55771 43276 55772 43524 55772 43455 55772 43276 55773 43455 55773 43277 55773 43277 55774 43455 55774 43456 55774 43277 55775 43456 55775 43525 55775 43525 55776 43456 55776 43526 55776 43525 55777 43526 55777 43279 55777 43279 55778 43526 55778 43527 55778 43279 55779 43527 55779 43528 55779 43528 55780 43527 55781 43459 55782 43528 55783 43459 55783 43529 55783 43529 55784 43459 55785 43460 55786 43529 55787 43460 55788 43283 55789 43283 55790 43460 55790 43461 55790 43283 55791 43461 55791 43530 55791 43530 55792 43461 55792 43532 55792 43530 55793 43532 55793 43531 55793 43531 55794 43532 55794 43463 55794 43531 55795 43463 55795 43533 55795 43533 55796 43463 55797 43464 55798 43533 55799 43464 55799 43286 55799 43286 55800 43464 55800 43466 55800 43286 55801 43466 55801 43287 55801 43287 55802 43466 55802 43468 55802 43287 55803 43468 55803 43534 55803 43534 55804 43468 55805 43536 55806 43534 55807 43536 55807 43535 55807 43535 55808 43536 55808 43470 55808 43535 55809 43470 55809 43289 55809 43289 55810 43470 55810 43537 55810 43289 55811 43537 55811 43538 55811 43538 55812 43537 55812 43472 55812 43538 55813 43472 55813 43539 55813 43539 55814 43472 55814 43541 55814 43539 55815 43541 55815 43540 55815 43540 55816 43541 55816 43473 55816 43540 55817 43473 55817 43542 55817 43542 55818 43473 55818 43474 55818 43542 55819 43474 55819 43292 55819 43292 55820 43474 55820 43475 55820 43292 55821 43475 55821 43543 55821 43543 55822 43475 55822 43477 55822 43543 55823 43477 55823 43295 55823 43295 55824 43477 55824 43479 55824 43295 55825 43479 55825 43544 55825 43544 55826 43479 55826 43546 55826 43544 55827 43546 55827 43545 55827 43545 55828 43546 55828 43480 55828 43545 55829 43480 55829 43547 55829 43547 55830 43480 55830 43548 55830 43547 55831 43548 55831 43298 55831 43298 55832 43548 55832 43482 55832 43298 55833 43482 55833 43299 55833 43299 55834 43482 55834 43484 55834 43299 55835 43484 55835 43549 55835 43549 55836 43484 55836 43550 55836 43549 55837 43550 55837 43552 55837 43552 55838 43550 55838 43551 55838 43552 55839 43551 55839 43301 55839 43301 55840 43551 55840 43487 55840 43301 55841 43487 55841 43303 55841 43303 55842 43487 55842 43489 55842 43303 55843 43489 55843 43553 55843 43553 55844 43489 55844 43555 55844 43553 55845 43555 55845 43554 55845 43554 55846 43555 55847 43556 55848 43554 55849 43556 55849 43490 55849 43490 55850 43556 55850 43557 55850 43376 55851 43375 55851 43876 55851 43877 55852 43558 55852 43879 55852 43371 55853 43370 55854 43859 55855 43559 55856 43841 55856 43560 55856 43832 55857 43362 55857 43834 55857 43357 55858 43356 55859 43821 55860 43819 55861 43354 55861 43820 55861 43352 55862 43351 55862 43812 55862 43561 55863 43562 55863 43813 55863 43563 55864 43564 55864 43565 55864 43345 55865 43791 55865 43792 55865 43780 55866 43338 55866 43781 55866 43763 55867 43335 55868 43759 55869 43755 55870 43751 55871 43756 55872 43331 55873 43330 55873 43752 55873 43328 55874 43566 55874 43748 55874 43744 55875 43567 55875 43739 55875 43327 55876 43735 55876 43568 55876 43734 55877 43322 55877 43720 55877 43712 55878 43315 55878 43705 55878 43696 55879 43312 55880 43698 55881 43569 55882 43308 55883 43683 55884 43406 55885 43405 55885 43682 55885 43681 55886 43674 55886 43676 55886 43675 55887 43402 55887 43678 55887 43401 55888 43570 55888 43666 55888 43397 55889 43571 55889 43653 55889 43639 55890 43390 55890 43640 55890 43572 55891 43573 55891 43622 55891 43383 55892 43380 55893 43614 55894 43379 55895 43574 55895 43615 55895 43378 55896 43884 55896 43612 55896 43784 55897 43575 55897 43783 55897 43767 55898 43576 55898 43766 55898 43577 55899 43746 55899 43578 55899 43578 55900 43746 55900 43745 55900 43578 55901 43745 55901 43743 55901 43577 55902 43578 55902 43579 55902 43579 55903 43578 55903 43743 55903 43579 55904 43743 55904 43580 55904 43738 55905 43581 55905 43737 55905 43737 55906 43581 55906 43582 55906 43714 55907 43583 55907 43584 55907 43701 55908 43585 55908 43708 55908 43586 55909 43587 55910 43589 55911 43589 55912 43587 55913 43670 55914 43589 55915 43670 55915 43671 55915 43586 55916 43589 55916 43588 55916 43588 55917 43589 55917 43671 55917 43588 55918 43671 55918 43672 55918 43590 55919 43591 55919 43592 55919 43592 55920 43591 55921 43673 55922 43644 55923 43645 55923 43646 55923 43593 55924 43636 55925 43634 55926 43595 55927 43594 55928 43596 55929 43596 55930 43594 55930 43882 55930 43596 55931 43882 55931 43597 55931 43595 55932 43596 55932 43598 55932 43598 55933 43596 55933 43597 55933 43598 55934 43597 55934 43599 55934 43600 55935 43601 55935 43602 55935 43602 55936 43601 55936 43883 55936 43853 55937 43854 55937 43852 55937 43836 55938 43603 55939 43604 55940 43607 55941 43605 55942 43606 55943 43606 55944 43605 55944 43817 55944 43606 55945 43817 55945 43810 55945 43607 55946 43606 55946 43608 55946 43608 55947 43606 55947 43810 55947 43608 55948 43810 55948 43609 55948 43610 55949 43611 55949 43808 55949 43808 55950 43611 55951 43811 55952 43574 55953 43378 55953 43615 55953 43615 55954 43378 55954 43612 55954 43615 55955 43612 55955 43617 55955 43617 55956 43612 55956 43885 55956 43617 55957 43885 55957 43613 55957 43613 55958 43885 55958 43886 55958 43380 55959 43379 55959 43614 55959 43614 55960 43379 55960 43615 55960 43614 55961 43615 55961 43620 55961 43620 55962 43615 55962 43617 55962 43620 55963 43617 55963 43616 55963 43616 55964 43617 55964 43613 55964 43621 55965 43386 55965 43618 55965 43618 55966 43386 55966 43384 55966 43384 55967 43383 55967 43618 55967 43618 55968 43383 55968 43614 55968 43618 55969 43614 55969 43623 55969 43623 55970 43614 55970 43620 55970 43623 55971 43620 55971 43619 55971 43619 55972 43620 55972 43616 55972 43573 55973 43621 55973 43622 55973 43622 55974 43621 55974 43618 55974 43622 55975 43618 55975 43627 55975 43627 55976 43618 55976 43623 55976 43627 55977 43623 55977 43624 55977 43624 55978 43623 55978 43619 55978 43625 55979 43388 55979 43631 55979 43631 55980 43388 55981 43626 55982 43626 55983 43572 55983 43631 55983 43631 55984 43572 55984 43622 55984 43631 55985 43622 55985 43633 55985 43633 55986 43622 55986 43627 55986 43633 55987 43627 55987 43634 55987 43634 55988 43627 55988 43624 55988 43634 55989 43624 55989 43593 55989 43593 55990 43624 55990 43619 55990 43593 55991 43619 55991 43229 55991 43229 55992 43619 55992 43616 55992 43229 55993 43616 55993 43628 55993 43628 55994 43616 55994 43613 55994 43628 55995 43613 55995 43629 55995 43629 55996 43613 55996 43886 55996 43629 55997 43886 55997 43630 55997 43630 55998 43886 55998 43226 55998 43390 55999 43625 55999 43640 55999 43640 56000 43625 56000 43631 56000 43640 56001 43631 56001 43632 56001 43632 56002 43631 56002 43633 56002 43632 56003 43633 56003 43643 56003 43643 56004 43633 56004 43634 56004 43643 56005 43634 56005 43635 56005 43635 56006 43634 56006 43636 56006 43635 56007 43636 56007 43637 56007 43650 56008 43393 56008 43638 56008 43638 56009 43393 56009 43392 56009 43392 56010 43639 56010 43638 56010 43638 56011 43639 56011 43640 56011 43638 56012 43640 56012 43641 56012 43641 56013 43640 56013 43632 56013 43641 56014 43632 56014 43642 56014 43642 56015 43632 56015 43643 56015 43642 56016 43643 56016 43646 56016 43646 56017 43643 56017 43635 56017 43646 56018 43635 56018 43644 56018 43644 56019 43635 56019 43637 56019 43645 56020 43647 56020 43646 56020 43646 56021 43647 56021 43648 56021 43646 56022 43648 56022 43642 56022 43642 56023 43648 56023 43657 56023 43642 56024 43657 56024 43641 56024 43641 56025 43657 56025 43649 56025 43641 56026 43649 56026 43638 56026 43638 56027 43649 56027 43654 56027 43638 52727 43654 52727 43650 52727 43395 56028 43651 56028 43654 56028 43654 56029 43651 56029 43652 56029 43654 56030 43652 56031 43650 56032 43571 56033 43395 56033 43653 56033 43653 56034 43395 56034 43654 56034 43653 56035 43654 56035 43655 56035 43655 56036 43654 56036 43649 56036 43655 56037 43649 56037 43656 56037 43656 56038 43649 56038 43657 56038 43656 56039 43657 56039 43660 56039 43660 56040 43657 56040 43648 56040 43660 56041 43648 56041 43658 56041 43658 56042 43648 56042 43647 56042 43658 56043 43647 56044 43659 56045 43658 56046 43661 56046 43660 56046 43660 56047 43661 56047 43662 56047 43660 56048 43662 56048 43656 56048 43656 56049 43662 56049 43663 56049 43656 56050 43663 56050 43655 56050 43655 56051 43663 56051 43664 56051 43655 56052 43664 56052 43653 56052 43653 56053 43664 56053 43667 56053 43653 56054 43667 56054 43397 56054 43665 56055 43399 56055 43667 56055 43667 56056 43399 56057 43398 56058 43667 56059 43398 56059 43397 56059 43570 56060 43665 56061 43666 56062 43666 56063 43665 56063 43667 56063 43666 56064 43667 56064 43668 56064 43668 56065 43667 56065 43664 56065 43668 56066 43664 56066 43669 56066 43669 56067 43664 56067 43663 56067 43669 56068 43663 56068 43592 56068 43592 56069 43663 56069 43662 56069 43592 56070 43662 56070 43590 56070 43590 56071 43662 56071 43661 56071 43402 56072 43401 56072 43678 56072 43678 56073 43401 56073 43666 56073 43678 56074 43666 56074 43679 56074 43679 56075 43666 56075 43668 56075 43679 56076 43668 56076 43670 56076 43670 56077 43668 56077 43669 56077 43670 56078 43669 56078 43671 56078 43671 56079 43669 56079 43592 56079 43671 56080 43592 56080 43672 56080 43672 56081 43592 56081 43673 56081 43674 56082 43675 56082 43676 56082 43676 56083 43675 56083 43678 56083 43676 56084 43678 56084 43677 56084 43677 56085 43678 56085 43679 56085 43677 56086 43679 56086 43680 56086 43680 56087 43679 56087 43670 56087 43680 56088 43670 56088 43216 56088 43216 56089 43670 56089 43587 56089 43405 56090 43681 56090 43682 56090 43682 56091 43681 56091 43676 56091 43682 56092 43676 56092 43685 56092 43685 56093 43676 56093 43677 56093 43685 56094 43677 56094 43686 56094 43686 56095 43677 56095 43680 56095 43308 56096 43406 56096 43683 56096 43683 56097 43406 56097 43682 56097 43683 56098 43682 56098 43684 56098 43684 56099 43682 56099 43685 56099 43684 56100 43685 56100 43690 56100 43690 56101 43685 56101 43686 56101 43691 56102 43687 56102 43689 56102 43689 56103 43687 56103 43688 56103 43688 56104 43569 56104 43689 56104 43689 56105 43569 56105 43683 56105 43689 56106 43683 56106 43692 56106 43692 56107 43683 56107 43684 56107 43692 56108 43684 56108 43702 56108 43702 56109 43684 56109 43690 56109 43312 56110 43691 56110 43698 56110 43698 56111 43691 56111 43689 56111 43698 56112 43689 56112 43699 56112 43699 56113 43689 56113 43692 56113 43699 56114 43692 56114 43700 56114 43700 56115 43692 56115 43702 56115 43693 56116 43694 56116 43697 56116 43697 56117 43694 56118 43695 56119 43695 56120 43696 56120 43697 56120 43697 56121 43696 56121 43698 56121 43697 56122 43698 56122 43707 56122 43707 56123 43698 56123 43699 56123 43707 56124 43699 56124 43708 56124 43708 56125 43699 56125 43700 56125 43708 56126 43700 56126 43701 56126 43701 56127 43700 56127 43702 56127 43701 56128 43702 56128 43703 56128 43703 56129 43702 56129 43690 56129 43703 56130 43690 56130 43222 56130 43222 56131 43690 56131 43686 56131 43222 56132 43686 56132 43704 56132 43704 56133 43686 56133 43680 56133 43704 56134 43680 56134 43223 56134 43223 56135 43680 56135 43216 56135 43315 56136 43693 56136 43705 56136 43705 56137 43693 56137 43697 56137 43705 56138 43697 56138 43713 56138 43713 56139 43697 56139 43707 56139 43713 56140 43707 56140 43706 56140 43706 56141 43707 56141 43708 56141 43706 56142 43708 56142 43709 56142 43709 56143 43708 56143 43585 56143 43709 56144 43585 56144 43710 56144 43319 56145 43317 56145 43711 56145 43711 56146 43317 56147 43316 56148 43316 56149 43712 56149 43711 56149 43711 56150 43712 56150 43705 56150 43711 56151 43705 56151 43717 56151 43717 56152 43705 56152 43713 56152 43717 56153 43713 56153 43716 56153 43716 56154 43713 56154 43706 56154 43716 56155 43706 56155 43584 56155 43584 56156 43706 56156 43709 56156 43584 56157 43709 56157 43714 56157 43714 56158 43709 56159 43710 56160 43583 56161 43723 56161 43584 56161 43584 56162 43723 56162 43715 56162 43584 56163 43715 56163 43716 56163 43716 56164 43715 56164 43722 56164 43716 56165 43722 56165 43717 56165 43717 56166 43722 56166 43721 56166 43717 56167 43721 56167 43711 56167 43711 56168 43721 56168 43718 56168 43711 56169 43718 56169 43319 56169 43719 56170 43321 56170 43718 56170 43718 56171 43321 56171 43320 56171 43718 56172 43320 56172 43319 56172 43322 56173 43719 56174 43720 56175 43720 56176 43719 56176 43718 56176 43720 56177 43718 56177 43730 56177 43730 56178 43718 56178 43721 56178 43730 56179 43721 56179 43729 56179 43729 56180 43721 56180 43722 56180 43729 56181 43722 56181 43728 56181 43728 56182 43722 56182 43715 56182 43728 56183 43715 56183 43725 56183 43725 56184 43715 56184 43723 56184 43725 56185 43723 56185 43724 56185 43725 56186 43726 56186 43728 56186 43728 56187 43726 56187 43727 56187 43728 56188 43727 56188 43729 56188 43729 56189 43727 56189 43736 56189 43729 56190 43736 56190 43730 56190 43730 56191 43736 56191 43731 56191 43730 56192 43731 56192 43720 56192 43720 56193 43731 56193 43732 56193 43720 56194 43732 56194 43734 56194 43326 56195 43325 56195 43732 56195 43732 56196 43325 56196 43733 56196 43732 56197 43733 56197 43734 56197 43735 56198 43326 56199 43568 56200 43568 56201 43326 56201 43732 56201 43568 56202 43732 56202 43741 56202 43741 56203 43732 56203 43731 56203 43741 56204 43731 56204 43742 56204 43742 56205 43731 56205 43736 56205 43742 56206 43736 56206 43737 56206 43737 56207 43736 56207 43727 56207 43737 56208 43727 56208 43738 56208 43738 56209 43727 56209 43726 56209 43567 56210 43327 56210 43739 56210 43739 56211 43327 56211 43568 56211 43739 56212 43568 56212 43740 56212 43740 56213 43568 56213 43741 56213 43740 56214 43741 56214 43745 56214 43745 56215 43741 56215 43742 56215 43745 56216 43742 56216 43743 56216 43743 56217 43742 56217 43737 56217 43743 56218 43737 56218 43580 56218 43580 56219 43737 56219 43582 56219 43566 56220 43744 56220 43748 56220 43748 56221 43744 56221 43739 56221 43748 56222 43739 56222 43749 56222 43749 56223 43739 56223 43740 56223 43749 56224 43740 56224 43750 56224 43750 56225 43740 56225 43745 56225 43750 56226 43745 56226 43889 56226 43889 56227 43745 56227 43746 56227 43330 56228 43328 56228 43752 56228 43752 56229 43328 56229 43748 56229 43752 56230 43748 56230 43747 56230 43747 56231 43748 56231 43749 56231 43747 56232 43749 56232 43772 56232 43772 56233 43749 56233 43750 56233 43751 56234 43331 56234 43756 56234 43756 56235 43331 56235 43752 56235 43756 56236 43752 56236 43758 56236 43758 56237 43752 56237 43747 56237 43758 56238 43747 56238 43770 56238 43770 56239 43747 56239 43772 56239 43753 56240 43754 56240 43760 56240 43760 56241 43754 56241 43333 56241 43333 56242 43755 56242 43760 56242 43760 56243 43755 56243 43756 56243 43760 56244 43756 56244 43757 56244 43757 56245 43756 56245 43758 56245 43757 56246 43758 56246 43761 56246 43761 56247 43758 56247 43770 56247 43335 56248 43753 56248 43759 56248 43759 56249 43753 56249 43760 56249 43759 56250 43760 56250 43765 56250 43765 56251 43760 56251 43757 56251 43765 56252 43757 56252 43768 56252 43768 56253 43757 56253 43761 56253 43774 56254 43337 56254 43775 56254 43775 56255 43337 56255 43762 56255 43762 56256 43763 56256 43775 56256 43775 56257 43763 56257 43759 56257 43775 56258 43759 56258 43764 56258 43764 56259 43759 56259 43765 56259 43764 56260 43765 56260 43766 56260 43766 56261 43765 56261 43768 56261 43766 56262 43768 56262 43767 56262 43767 56263 43768 56263 43761 56263 43767 56264 43761 56264 43769 56264 43769 56265 43761 56265 43770 56265 43769 56266 43770 56266 43893 56266 43893 56267 43770 56267 43772 56267 43893 56268 43772 56268 43771 56268 43771 56269 43772 56269 43750 56269 43771 56270 43750 56270 43773 56270 43773 56271 43750 56271 43889 56271 43338 56272 43774 56272 43781 56272 43781 56273 43774 56273 43775 56273 43781 56274 43775 56274 43782 56274 43782 56275 43775 56275 43764 56275 43782 56276 43764 56276 43776 56276 43776 56277 43764 56277 43766 56277 43776 56278 43766 56278 43777 56278 43777 56279 43766 56279 43576 56279 43777 56280 43576 56280 43778 56280 43779 56281 43341 56281 43789 56281 43789 56282 43341 56282 43340 56282 43340 56283 43780 56283 43789 56283 43789 56284 43780 56284 43781 56284 43789 56285 43781 56285 43787 56285 43787 56286 43781 56286 43782 56286 43787 56287 43782 56287 43786 56287 43786 56288 43782 56288 43776 56288 43786 56289 43776 56289 43783 56289 43783 56290 43776 56290 43777 56290 43783 56291 43777 56291 43784 56291 43784 56292 43777 56292 43778 56292 43575 56293 43798 56293 43783 56293 43783 56294 43798 56294 43785 56294 43783 56295 43785 56295 43786 56295 43786 56296 43785 56296 43795 56296 43786 56297 43795 56297 43787 56297 43787 56298 43795 56298 43793 56298 43787 56299 43793 56299 43789 56299 43789 56300 43793 56300 43788 56300 43789 52454 43788 52454 43779 52454 43344 56301 43790 56301 43788 56301 43788 56302 43790 56302 43343 56302 43788 56303 43343 56303 43779 56303 43791 56304 43344 56304 43792 56304 43792 56305 43344 56305 43788 56305 43792 56306 43788 56306 43803 56306 43803 56307 43788 56307 43793 56307 43803 56308 43793 56308 43794 56308 43794 56309 43793 56309 43795 56309 43794 56310 43795 56310 43796 56310 43796 56311 43795 56311 43785 56311 43796 56312 43785 56312 43797 56312 43797 56313 43785 56313 43798 56313 43797 56314 43798 56314 43799 56314 43797 56315 43800 56315 43796 56315 43796 56316 43800 56316 43801 56316 43796 56317 43801 56317 43794 56317 43794 56318 43801 56318 43802 56318 43794 56319 43802 56319 43803 56319 43803 56320 43802 56320 43806 56320 43803 56321 43806 56321 43792 56321 43792 56322 43806 56322 43805 56322 43792 56323 43805 56323 43345 56323 43349 56324 43348 56324 43805 56324 43805 56325 43348 56325 43804 56325 43805 56326 43804 56326 43345 56326 43564 56327 43349 56327 43565 56327 43565 56328 43349 56328 43805 56328 43565 56329 43805 56329 43809 56329 43809 56330 43805 56330 43806 56330 43809 56331 43806 56331 43807 56331 43807 56332 43806 56332 43802 56332 43807 56333 43802 56333 43808 56333 43808 56334 43802 56334 43801 56334 43808 56335 43801 56335 43610 56335 43610 56336 43801 56336 43800 56336 43562 56337 43563 56337 43813 56337 43813 56338 43563 56338 43565 56338 43813 56339 43565 56339 43815 56339 43815 56340 43565 56340 43809 56340 43815 56341 43809 56341 43817 56341 43817 56342 43809 56342 43807 56342 43817 56343 43807 56343 43810 56343 43810 56344 43807 56344 43808 56344 43810 56345 43808 56345 43609 56345 43609 56346 43808 56346 43811 56346 43351 56347 43561 56347 43812 56347 43812 56348 43561 56348 43813 56348 43812 56349 43813 56349 43814 56349 43814 56350 43813 56350 43815 56350 43814 56351 43815 56351 43816 56351 43816 56352 43815 56352 43817 56352 43816 56353 43817 56353 43818 56353 43818 56354 43817 56354 43605 56354 43354 56355 43352 56356 43820 56356 43820 56357 43352 56357 43812 56357 43820 56358 43812 56358 43824 56358 43824 56359 43812 56359 43814 56359 43824 56360 43814 56360 43825 56360 43825 56361 43814 56361 43816 56361 43356 56362 43819 56362 43821 56362 43821 56363 43819 56363 43820 56363 43821 56364 43820 56364 43822 56364 43822 56365 43820 56365 43824 56365 43822 56366 43824 56366 43823 56366 43823 56367 43824 56367 43825 56367 43360 56368 43359 56368 43826 56368 43826 56369 43359 56370 43358 56371 43358 56372 43357 56372 43826 56372 43826 56373 43357 56373 43821 56373 43826 56374 43821 56374 43827 56374 43827 56375 43821 56375 43822 56375 43827 56376 43822 56376 43829 56376 43829 56377 43822 56377 43823 56377 43362 56378 43360 56378 43834 56378 43834 56379 43360 56379 43826 56379 43834 56380 43826 56380 43835 56380 43835 56381 43826 56381 43827 56381 43835 56382 43827 56382 43828 56382 43828 56383 43827 56383 43829 56383 43366 56384 43830 56384 43831 56384 43831 56385 43830 56385 43363 56385 43363 56386 43832 56386 43831 56386 43831 56387 43832 56387 43834 56387 43831 56388 43834 56388 43833 56388 43833 56389 43834 56389 43835 56389 43833 56390 43835 56390 43604 56390 43604 56391 43835 56391 43828 56391 43604 56392 43828 56392 43836 56392 43836 56393 43828 56393 43829 56393 43836 56394 43829 56394 43837 56394 43837 56395 43829 56395 43823 56395 43837 56396 43823 56396 43838 56396 43838 56397 43823 56397 43825 56397 43838 56398 43825 56398 43839 56398 43839 56399 43825 56399 43816 56399 43839 56400 43816 56400 43840 56400 43840 56401 43816 56401 43818 56401 43841 56402 43366 56402 43560 56402 43560 56403 43366 56403 43831 56403 43560 56404 43831 56404 43851 56404 43851 56405 43831 56405 43833 56405 43851 56406 43833 56406 43842 56406 43842 56407 43833 56407 43604 56407 43842 56408 43604 56408 43843 56408 43843 56409 43604 56409 43603 56409 43843 56410 43603 56410 43844 56410 43845 56411 43847 56411 43846 56411 43846 56412 43847 56412 43848 56412 43848 56413 43559 56413 43846 56413 43846 56414 43559 56414 43560 56414 43846 56415 43560 56415 43849 56415 43849 56416 43560 56416 43851 56416 43849 56417 43851 56417 43850 56417 43850 56418 43851 56418 43842 56418 43850 56419 43842 56419 43852 56419 43852 56420 43842 56420 43843 56420 43852 56421 43843 56421 43853 56421 43853 56422 43843 56422 43844 56422 43854 56423 43866 56423 43852 56423 43852 56424 43866 56424 43864 56424 43852 56425 43864 56425 43850 56425 43850 56426 43864 56426 43863 56426 43850 56427 43863 56427 43849 56427 43849 56428 43863 56428 43861 56428 43849 56429 43861 56429 43846 56429 43846 56430 43861 56430 43856 56430 43846 56431 43856 56431 43845 56431 43858 56432 43855 56432 43856 56432 43856 56433 43855 56433 43857 56433 43856 56434 43857 56435 43845 56436 43370 56437 43858 56437 43859 56437 43859 56438 43858 56438 43856 56438 43859 56439 43856 56439 43860 56439 43860 56440 43856 56440 43861 56440 43860 56441 43861 56441 43862 56441 43862 56442 43861 56442 43863 56442 43862 56443 43863 56443 43869 56443 43869 56444 43863 56444 43864 56444 43869 56445 43864 56445 43865 56445 43865 56446 43864 56446 43866 56446 43865 56447 43866 56447 43867 56447 43865 56448 43868 56448 43869 56448 43869 56449 43868 56449 43875 56449 43869 56450 43875 56450 43862 56450 43862 56451 43875 56451 43870 56451 43862 56452 43870 56452 43860 56452 43860 56453 43870 56453 43871 56453 43860 56454 43871 56454 43859 56454 43859 56455 43871 56455 43874 56455 43859 56456 43874 56456 43371 56456 43872 56457 43873 56457 43874 56457 43874 56458 43873 56458 43373 56458 43874 56459 43373 56459 43371 56459 43558 56460 43872 56460 43879 56460 43879 56461 43872 56461 43874 56461 43879 56462 43874 56462 43880 56462 43880 56463 43874 56463 43871 56463 43880 56464 43871 56464 43881 56464 43881 56465 43871 56465 43870 56465 43881 56466 43870 56466 43602 56466 43602 56467 43870 56467 43875 56467 43602 56468 43875 56468 43600 56468 43600 56469 43875 56469 43868 56469 43375 56470 43877 56470 43876 56470 43876 56471 43877 56471 43879 56471 43876 56472 43879 56472 43878 56472 43878 56473 43879 56473 43880 56473 43878 56474 43880 56474 43882 56474 43882 56475 43880 56475 43881 56475 43882 56476 43881 56476 43597 56476 43597 56477 43881 56477 43602 56477 43597 56478 43602 56478 43599 56478 43599 56479 43602 56479 43883 56479 43884 56480 43376 56480 43612 56480 43612 56481 43376 56481 43876 56481 43612 56482 43876 56482 43885 56482 43885 56483 43876 56483 43878 56483 43885 56484 43878 56484 43886 56484 43886 56485 43878 56485 43882 56485 43886 56486 43882 56486 43226 56486 43226 56487 43882 56487 43594 56487 43887 56488 43888 56488 43889 56488 43889 56489 43888 56489 43894 56489 43889 56490 43894 56490 43773 56490 43890 56491 43891 56491 43892 56491 43892 56492 43891 56492 43576 56492 43892 56493 43576 56493 43767 56493 43767 56494 43769 56495 43892 56496 43892 56497 43769 56497 43893 56497 43892 56498 43893 56498 43894 56498 43894 56499 43893 56499 43771 56499 43894 56500 43771 56500 43773 56500 43910 960 43912 960 43895 960 43895 56501 43912 56501 43896 56501 43913 960 43897 960 43912 960 43897 960 43898 960 43912 960 43912 56502 43898 56502 43899 56502 43912 960 43899 960 43896 960 43933 960 43900 960 43924 960 43895 960 43901 960 43903 960 43903 960 43901 960 43902 960 43903 960 43902 960 43904 960 43903 56503 43905 56503 43895 56503 43895 960 43905 960 43906 960 43895 56504 43906 56504 43907 56504 43907 960 43908 960 43895 960 43895 56505 43908 56505 43909 56505 43895 56506 43909 56506 43910 56506 43914 960 43924 960 43912 960 43912 56507 43924 56507 43911 56507 43912 56508 43911 56508 43913 56508 43914 56509 43915 56509 43924 56509 43924 56510 43915 56510 43916 56510 43924 56511 43916 56511 43922 56511 43904 960 43902 960 43928 960 43928 56512 43902 56512 43917 56512 43928 56513 43917 56513 43918 56513 43918 56514 43919 56514 43928 56514 43928 56515 43919 56515 43920 56515 43928 56516 43920 56516 43921 56516 43922 56517 43923 56517 43924 56517 43924 960 43923 960 43925 960 43924 56518 43925 56518 43930 56518 43921 56519 43926 56519 43928 56519 43928 56520 43926 56520 43927 56520 43928 56521 43927 56521 43929 56521 43930 56522 43931 56522 43924 56522 43924 56523 43931 56523 43932 56523 43924 56524 43932 56524 43933 56524 44314 56525 44312 56526 43934 56527 43934 56528 44312 56528 43936 56528 43934 56529 43936 56530 43935 56531 43936 56532 44455 56532 43935 56532 43935 56533 44455 56533 44454 56533 43935 56534 44454 56535 43937 56536 43937 56537 44454 56538 44452 56539 43937 56540 44452 56541 44453 56542 43938 56543 43939 56543 43940 56543 43940 56544 43939 56544 43941 56544 43940 56545 43941 56545 43946 56545 43942 56546 43943 56546 43945 56546 43945 56547 43943 56547 43944 56547 43945 56548 43944 56548 44560 56548 44560 56549 44561 56549 43945 56549 43945 56550 44561 56550 44562 56550 43945 56551 44562 56551 43941 56551 43941 56552 44562 56552 44563 56552 43941 56553 44563 56553 43946 56553 43949 56554 43947 56554 43948 56554 43948 56555 44205 56555 43949 56555 43949 56556 44205 56556 44207 56556 43949 56557 44207 56557 43950 56557 44207 56558 43951 56558 43950 56558 43950 56559 43951 56559 44209 56559 43950 56560 44209 56560 43952 56560 44209 56561 44211 56561 43952 56561 43952 53047 44211 53047 44213 53047 43952 56562 44213 56562 43953 56562 44213 56563 44214 56563 43953 56563 43953 56564 44214 56564 43954 56564 43953 56565 43954 56565 43955 56565 43954 56566 44216 56566 43955 56566 43955 56567 44216 56567 43956 56567 43955 56568 43956 56568 43957 56568 43956 56569 44218 56569 43957 56569 43957 53056 44218 53056 44219 53056 43957 56570 44219 56570 43958 56570 44219 53058 44221 53058 43958 53058 43958 56571 44221 56571 44223 56571 43958 56572 44223 56572 43960 56572 44223 56573 43959 56573 43960 56573 43960 56574 43959 56574 43961 56574 43960 56575 43961 56575 43962 56575 43961 56576 44227 56576 43962 56576 43962 56577 44227 56577 44229 56577 43962 56578 44229 56578 43963 56578 44229 56579 44230 56579 43963 56579 43963 56580 44230 56580 43964 56580 43963 56581 43964 56581 43965 56581 43964 56582 44235 56582 43965 56582 43965 56583 44235 56583 44236 56583 43965 56584 44236 56584 43966 56584 44236 56585 43967 56585 43966 56585 43966 53074 43967 53074 43968 53074 43966 56586 43968 56586 43969 56586 43968 56587 44237 56587 43969 56587 43969 56588 44237 56588 43970 56588 43969 56589 43970 56589 43971 56589 43970 56590 44238 56590 43971 56590 43971 56591 44238 56591 44239 56591 43971 56592 44239 56592 43973 56592 44239 56593 43972 56593 43973 56593 43973 56594 43972 56594 44240 56594 43973 56595 44240 56595 43974 56595 44240 56596 43975 56596 43974 56596 43974 56597 43975 56597 44243 56597 43974 56598 44243 56598 43977 56598 44243 56599 43976 56599 43977 56599 43977 56600 43976 56600 44246 56600 43977 56601 44246 56601 43979 56601 44246 56602 43978 56602 43979 56602 43979 56603 43978 56603 43981 56603 43979 56604 43981 56604 43980 56604 43981 56605 43982 56605 43980 56605 43980 56606 43982 56606 43983 56606 43980 56607 43983 56607 43984 56607 43983 56608 44248 56608 43984 56608 43984 56609 44248 56609 43985 56609 43984 56610 43985 56610 43987 56610 43985 56611 43986 56611 43987 56611 43987 56612 43986 56612 43988 56612 43987 56613 43988 56613 43990 56613 43988 56614 43989 56614 43990 56614 43990 52990 43989 52990 44253 52990 43990 56615 44253 56615 43991 56615 44253 56616 43992 56616 43991 56616 43991 56617 43992 56617 43993 56617 43991 56618 43993 56618 43994 56618 43993 56619 43995 56619 43994 56619 43994 56620 43995 56620 43996 56620 43994 56621 43996 56621 43997 56621 43996 56622 43998 56622 43997 56622 43997 52999 43998 52999 44000 52999 43997 56623 44000 56623 43999 56623 44000 53001 44001 53001 43999 53001 43999 56624 44001 56624 44258 56624 43999 56625 44258 56625 44002 56625 44258 56626 44259 56626 44002 56626 44002 56627 44259 56627 44003 56627 44002 56628 44003 56628 44004 56628 44003 56629 44005 56629 44004 56629 44004 56630 44005 56630 44261 56630 44004 56631 44261 56631 44006 56631 44261 56632 44262 56632 44006 56632 44006 56633 44262 56633 44264 56633 44006 56634 44264 56634 44007 56634 44264 56635 44265 56635 44007 56635 44007 56636 44265 56636 44008 56636 44007 56637 44008 56637 44009 56637 44008 56638 44010 56638 44009 56638 44009 53017 44010 53017 44012 53017 44009 56639 44012 56639 44011 56639 44012 56640 44013 56640 44011 56640 44011 56641 44013 56641 44269 56641 44011 56642 44269 56642 44014 56642 44269 56643 44270 56643 44014 56643 44014 56644 44270 56644 44016 56644 44014 56645 44016 56645 44015 56645 44016 56646 44273 56646 44015 56646 44015 56647 44273 56647 44017 56647 44015 56648 44017 56648 44020 56648 44017 56649 44018 56649 44020 56649 44020 56650 44018 56650 44019 56650 44020 56651 44019 56651 44021 56651 44019 56652 44022 56652 44021 56652 44021 56653 44022 56653 44277 56653 44021 56654 44277 56654 44024 56654 44277 56655 44023 56655 44024 56655 44024 56656 44023 56656 44202 56656 44024 56657 44202 56657 43947 56657 43947 56658 44202 56658 44203 56658 43947 56659 44203 56659 43948 56659 44295 56660 44026 56660 44131 56660 44295 56661 44025 56662 44026 56663 44026 56664 44025 56664 44028 56664 44026 56665 44028 56665 44027 56665 44027 56666 44028 56666 44412 56666 44027 56667 44412 56667 44139 56667 44412 56668 44029 56668 44139 56668 44139 56669 44029 56669 44294 56669 44139 56670 44294 56670 44030 56670 44294 56671 44419 56672 44030 56673 44030 56674 44419 56674 44031 56674 44030 56675 44031 56675 44140 56675 44140 56676 44031 56677 44033 56678 44140 56679 44033 56679 44032 56679 44032 56680 44033 56680 44430 56680 44032 56681 44430 56681 44142 56681 44142 56682 44430 56682 44434 56682 44434 56683 44433 56684 44142 56685 44142 56686 44433 56686 44431 56686 44142 56687 44431 56687 44034 56687 44034 56688 44431 56689 44293 56688 44034 56690 44293 56690 44143 56690 44143 56691 44293 56691 44445 56691 44143 56692 44445 56692 44145 56692 44145 56693 44445 56693 44035 56693 44035 56694 44446 56694 44145 56694 44145 56695 44446 56695 44036 56695 44145 56696 44036 56696 44037 56696 44037 56697 44036 56697 44447 56697 44037 56698 44447 56698 44038 56698 44038 56699 44447 56699 44463 56699 44038 56700 44463 56700 44148 56700 44148 56701 44463 56701 44462 56701 44462 56702 44039 56702 44148 56703 44148 56704 44039 56704 44460 56704 44148 56705 44460 56705 44149 56705 44149 56706 44460 56707 44292 56708 44149 56709 44292 56709 44150 56709 44150 56710 44292 56711 44041 56712 44150 56713 44041 56713 44040 56713 44040 56714 44041 56715 44467 56716 44467 56717 44472 56717 44040 56717 44040 56718 44472 56718 44290 56718 44040 56719 44290 56719 44042 56719 44042 56720 44290 56720 44477 56720 44042 56721 44477 56721 44043 56721 44043 56722 44477 56722 44044 56722 44043 56723 44044 56723 44045 56723 44044 56724 44479 56724 44045 56724 44045 56725 44479 56725 44289 56725 44045 56726 44289 56726 44151 56726 44289 56727 44484 56727 44151 56727 44151 56728 44484 56728 44046 56728 44151 56729 44046 56729 44047 56729 44047 56730 44046 56730 44483 56730 44047 56731 44483 56731 44049 56731 44483 56732 44048 56732 44049 56732 44049 56733 44048 56733 44050 56733 44049 56734 44050 56734 44153 56734 44050 56735 44051 56735 44153 56735 44153 56736 44051 56736 44052 56736 44153 56737 44052 56737 44053 56737 44053 56738 44052 56738 44054 56738 44053 56739 44054 56739 44156 56739 44156 56740 44054 56740 44505 56740 44156 56741 44505 56741 44159 56741 44159 56742 44505 56742 44055 56742 44055 56743 44056 56743 44159 56743 44159 56744 44056 56744 44507 56744 44159 56745 44507 56745 44161 56745 44161 56746 44507 56746 44506 56746 44161 56747 44506 56747 44057 56747 44057 56748 44506 56748 44288 56748 44057 56749 44288 56749 44059 56749 44059 56750 44288 56750 44058 56750 44058 56751 44060 56751 44059 56751 44059 56752 44060 56752 44061 56752 44059 56753 44061 56753 44062 56753 44062 56754 44061 56755 44516 56756 44062 56757 44516 56757 44164 56757 44164 56758 44516 56758 44530 56758 44164 56759 44530 56759 44165 56759 44165 56760 44530 56760 44063 56760 44063 56761 44064 56761 44165 56761 44165 56762 44064 56762 44533 56762 44165 56763 44533 56763 44166 56763 44166 56764 44533 56765 44531 56766 44166 56767 44531 56767 44167 56767 44167 56768 44531 56768 44065 56768 44167 56769 44065 56769 44169 56769 44169 56770 44065 56770 44287 56770 44287 56771 44286 56772 44169 56773 44169 56774 44286 56774 44066 56774 44169 56775 44066 56775 44067 56775 44067 56776 44066 56776 44068 56776 44067 56777 44068 56777 44172 56777 44172 56778 44068 56778 44284 56778 44172 56779 44284 56779 44070 56779 44284 56780 44069 56780 44070 56780 44070 56781 44069 56781 44071 56781 44070 56782 44071 56782 44173 56782 44071 56783 44283 56784 44173 56785 44173 56786 44283 56786 44073 56786 44173 56787 44073 56787 44072 56787 44072 56788 44073 56788 44074 56788 44072 56789 44074 56789 44075 56789 44074 56790 44076 56790 44075 56790 44075 56791 44076 56791 44077 56791 44075 56792 44077 56792 44175 56792 44077 56793 44078 56794 44175 56795 44175 56796 44078 56796 44557 56796 44175 56797 44557 56797 44176 56797 44176 56798 44557 56798 44079 56798 44176 56799 44079 56799 44177 56799 44177 56800 44079 56800 44080 56800 44177 56801 44080 56801 44082 56801 44082 56802 44080 56802 44571 56802 44571 56803 44081 56803 44082 56803 44082 56804 44081 56804 44083 56804 44082 56805 44083 56805 44084 56805 44084 56806 44083 56806 44282 56806 44084 56807 44282 56807 44181 56807 44181 56808 44282 56808 44085 56808 44181 56809 44085 56809 44086 56809 44086 56810 44085 56810 44087 56810 44087 56811 44088 56812 44086 56812 44086 56813 44088 56813 44089 56813 44086 56814 44089 56814 44090 56814 44090 56815 44089 56815 44091 56815 44090 56816 44091 56816 44092 56816 44092 56817 44091 56817 44093 56817 44092 56818 44093 56818 44096 56818 44096 56819 44093 56819 44094 56819 44094 56820 44095 56821 44096 56822 44096 56823 44095 56823 44097 56823 44096 56824 44097 56824 44098 56824 44098 56825 44097 56825 44588 56825 44098 56826 44588 56826 44185 56826 44185 56827 44588 56827 44594 56827 44185 56828 44594 56828 44099 56828 44099 56829 44594 56829 44100 56829 44100 56830 44600 56830 44099 56830 44099 56831 44600 56831 44102 56831 44099 56832 44102 56832 44101 56832 44101 56833 44102 56833 44104 56833 44101 56834 44104 56834 44103 56834 44103 56835 44104 56835 44299 56835 44103 56836 44299 56836 44189 56836 44299 56837 44105 56837 44189 56837 44189 56838 44105 56838 44341 56838 44189 56839 44341 56839 44191 56839 44341 56840 44106 56841 44191 56842 44191 56843 44106 56843 44107 56843 44191 56844 44107 56844 44193 56844 44193 56845 44107 56845 44108 56845 44193 56846 44108 56846 44110 56846 44108 56847 44345 56847 44110 56847 44110 56848 44345 56848 44109 56848 44110 56849 44109 56849 44194 56849 44109 56850 44351 56850 44194 56850 44194 56851 44351 56851 44350 56851 44194 56852 44350 56852 44111 56852 44111 56853 44350 56853 44112 56853 44111 56854 44112 56854 44113 56854 44113 56855 44112 56855 44348 56855 44113 56856 44348 56856 44115 56856 44115 56857 44348 56857 44114 56857 44114 56858 44368 56858 44115 56858 44115 56859 44368 56860 44117 56861 44115 56862 44117 56862 44116 56862 44116 56863 44117 56863 44118 56863 44116 56864 44118 56864 44197 56864 44197 56865 44118 56865 44119 56865 44197 56866 44119 56866 44198 56866 44198 56867 44119 56867 44377 56867 44377 56868 44120 56868 44198 56868 44198 56869 44120 56869 44376 56869 44198 56870 44376 56870 44121 56870 44121 56871 44376 56871 44298 56871 44121 56872 44298 56872 44199 56872 44199 56873 44298 56873 44391 56873 44199 56874 44391 56874 44122 56874 44122 56875 44391 56875 44390 56875 44390 56876 44123 56876 44122 56876 44122 56877 44123 56877 44125 56877 44122 56878 44125 56878 44124 56878 44124 56879 44125 56880 44126 56881 44124 56882 44126 56882 44201 56882 44201 56883 44126 56883 44396 56883 44201 56884 44396 56884 44127 56884 44127 56885 44396 56885 44128 56885 44128 56886 44404 56886 44127 56886 44127 56887 44404 56887 44129 56887 44127 56888 44129 56888 44134 56888 44134 56889 44129 56889 44130 56889 44134 56890 44130 56890 44135 56890 44135 56891 44130 56891 44296 56892 44135 56893 44296 56893 44131 56893 44131 56894 44296 56894 44132 56894 44131 56895 44132 56895 44295 56895 44133 56896 44134 56896 44204 56896 44204 56897 44134 56897 44135 56897 44204 56898 44135 56898 44136 56898 44136 56899 44135 56899 44131 56899 44136 56900 44131 56900 44137 56900 44137 56901 44131 56901 44026 56901 44137 56902 44026 56902 44206 56902 44206 56903 44026 56903 44027 56903 44206 56904 44027 56904 44138 56904 44138 56905 44027 56905 44139 56905 44138 56906 44139 56906 44208 56906 44208 56907 44139 56907 44030 56907 44208 56908 44030 56908 44210 56908 44210 56909 44030 56909 44140 56909 44210 56910 44140 56910 44212 56910 44212 56911 44140 56911 44032 56911 44212 56912 44032 56912 44141 56912 44141 56913 44032 56913 44142 56913 44141 56914 44142 56914 44215 56914 44215 56915 44142 56915 44034 56915 44215 56916 44034 56916 44144 56916 44144 56917 44034 56917 44143 56917 44144 56918 44143 56918 44217 56918 44217 56919 44143 56919 44145 56919 44217 56920 44145 56921 44146 56922 44146 56923 44145 56924 44037 56925 44146 56926 44037 56926 44147 56926 44147 56927 44037 56927 44038 56927 44147 56928 44038 56928 44220 56928 44220 56929 44038 56929 44148 56929 44220 56930 44148 56930 44222 56930 44222 56931 44148 56931 44149 56931 44222 56932 44149 56932 44224 56932 44224 56933 44149 56933 44150 56933 44224 56934 44150 56934 44225 56934 44225 56935 44150 56935 44040 56935 44225 56936 44040 56936 44226 56936 44226 56937 44040 56937 44042 56937 44226 56938 44042 56938 44228 56938 44228 56939 44042 56939 44043 56939 44228 56940 44043 56940 44231 56940 44231 56941 44043 56941 44045 56941 44231 56942 44045 56942 44232 56942 44232 56943 44045 56943 44151 56943 44232 56944 44151 56944 44233 56944 44233 56945 44151 56945 44047 56945 44233 56946 44047 56946 44234 56946 44234 56947 44047 56947 44049 56947 44234 56948 44049 56948 44152 56948 44152 56949 44049 56949 44153 56949 44152 56950 44153 56950 44154 56950 44154 56951 44153 56951 44053 56951 44154 56952 44053 56952 44155 56952 44155 56953 44053 56953 44156 56953 44155 56954 44156 56954 44157 56954 44157 56955 44156 56955 44159 56955 44157 56956 44159 56956 44158 56956 44158 56957 44159 56957 44161 56957 44158 56958 44161 56958 44160 56958 44160 56959 44161 56959 44057 56959 44160 56960 44057 56960 44162 56960 44162 56961 44057 56961 44059 56961 44162 56962 44059 56962 44163 56962 44163 56963 44059 56963 44062 56963 44163 56964 44062 56965 44241 56966 44241 56967 44062 56967 44164 56967 44241 56968 44164 56968 44242 56968 44242 56969 44164 56969 44165 56969 44242 56970 44165 56970 44244 56970 44244 56971 44165 56971 44166 56971 44244 56972 44166 56972 44245 56972 44245 56973 44166 56973 44167 56973 44245 56974 44167 56974 44168 56974 44168 56975 44167 56975 44169 56975 44168 56976 44169 56976 44170 56976 44170 56977 44169 56977 44067 56977 44170 56978 44067 56978 44171 56978 44171 56979 44067 56980 44172 56981 44171 56982 44172 56982 44247 56982 44247 56983 44172 56983 44070 56983 44247 56984 44070 56984 44174 56984 44174 56985 44070 56985 44173 56985 44174 56986 44173 56986 44249 56986 44249 56987 44173 56987 44072 56987 44249 56988 44072 56988 44250 56988 44250 56989 44072 56989 44075 56989 44250 56990 44075 56990 44251 56990 44251 56991 44075 56991 44175 56991 44251 56992 44175 56992 44252 56992 44252 56993 44175 56993 44176 56993 44252 56994 44176 56994 44254 56994 44254 56995 44176 56995 44177 56995 44254 56996 44177 56997 44178 56998 44178 56999 44177 56999 44082 56999 44178 57000 44082 57000 44179 57000 44179 57001 44082 57002 44084 57003 44179 57004 44084 57004 44255 57004 44255 57005 44084 57006 44181 57007 44255 57008 44181 57008 44180 57008 44180 57009 44181 57009 44086 57009 44180 57010 44086 57010 44256 57010 44256 57011 44086 57011 44090 57011 44256 57012 44090 57012 44182 57012 44182 57013 44090 57013 44092 57013 44182 57014 44092 57014 44183 57014 44183 57015 44092 57015 44096 57015 44183 57016 44096 57016 44257 57016 44257 57017 44096 57018 44098 57019 44257 57020 44098 57021 44184 57022 44184 57023 44098 57023 44185 57023 44184 57024 44185 57024 44186 57024 44186 57025 44185 57025 44099 57025 44186 57026 44099 57026 44260 57026 44260 57027 44099 57027 44101 57027 44260 57028 44101 57028 44187 57028 44187 57029 44101 57029 44103 57029 44187 57030 44103 57030 44188 57030 44188 57031 44103 57031 44189 57031 44188 57032 44189 57032 44190 57032 44190 57033 44189 57033 44191 57033 44190 57034 44191 57035 44263 57036 44263 57037 44191 57037 44193 57037 44263 57038 44193 57038 44192 57038 44192 57039 44193 57039 44110 57039 44192 57040 44110 57040 44266 57040 44266 57041 44110 57041 44194 57041 44266 57042 44194 57042 44267 57042 44267 57043 44194 57043 44111 57043 44267 57044 44111 57044 44195 57044 44195 57045 44111 57045 44113 57045 44195 57046 44113 57047 44268 57048 44268 57049 44113 57049 44115 57049 44268 57050 44115 57050 44271 57050 44271 57051 44115 57051 44116 57051 44271 57052 44116 57052 44196 57052 44196 57053 44116 57053 44197 57053 44196 57054 44197 57054 44272 57054 44272 57055 44197 57055 44198 57055 44272 57056 44198 57056 44274 57056 44274 57057 44198 57057 44121 57057 44274 57058 44121 57058 44275 57058 44275 57059 44121 57059 44199 57059 44275 57060 44199 57060 44200 57060 44200 57061 44199 57061 44122 57061 44200 57062 44122 57062 44276 57062 44276 57063 44122 57063 44124 57063 44276 57064 44124 57064 44278 57064 44278 57065 44124 57065 44201 57065 44278 57066 44201 57066 44279 57066 44279 57067 44201 57067 44127 57067 44279 57068 44127 57068 44133 57068 44133 57069 44127 57069 44134 57069 44202 57070 44204 57070 44203 57070 44203 57071 44204 57071 44136 57071 44203 57072 44136 57072 43948 57072 43948 57073 44136 57073 44137 57073 43948 57074 44137 57074 44205 57074 44205 57075 44137 57075 44206 57075 44205 57076 44206 57076 44207 57076 44207 57077 44206 57077 44138 57077 44207 57078 44138 57078 43951 57078 43951 57079 44138 57079 44208 57079 43951 57080 44208 57080 44209 57080 44209 57081 44208 57082 44210 57083 44209 57084 44210 57084 44211 57084 44211 57085 44210 57086 44212 57087 44211 57088 44212 57088 44213 57088 44213 57089 44212 57089 44141 57089 44213 57090 44141 57090 44214 57090 44214 57091 44141 57091 44215 57091 44214 57092 44215 57092 43954 57092 43954 57093 44215 57093 44144 57093 43954 57094 44144 57094 44216 57094 44216 57095 44144 57095 44217 57095 44216 57096 44217 57096 43956 57096 43956 57097 44217 57098 44146 57099 43956 57100 44146 57100 44218 57100 44218 57101 44146 57101 44147 57101 44218 57102 44147 57102 44219 57102 44219 57103 44147 57103 44220 57103 44219 57104 44220 57104 44221 57104 44221 57105 44220 57105 44222 57105 44221 57106 44222 57106 44223 57106 44223 57107 44222 57107 44224 57107 44223 57108 44224 57108 43959 57108 43959 57109 44224 57109 44225 57109 43959 57110 44225 57110 43961 57110 43961 57111 44225 57111 44226 57111 43961 57112 44226 57112 44227 57112 44227 57113 44226 57113 44228 57113 44227 57114 44228 57114 44229 57114 44229 57115 44228 57115 44231 57115 44229 57116 44231 57116 44230 57116 44230 57117 44231 57117 44232 57117 44230 57118 44232 57118 43964 57118 43964 57119 44232 57119 44233 57119 43964 57120 44233 57120 44235 57120 44235 57121 44233 57121 44234 57121 44235 57122 44234 57123 44236 57124 44236 57125 44234 57125 44152 57125 44236 57126 44152 57127 43967 57128 43967 57129 44152 57130 44154 57131 43967 57132 44154 57132 43968 57132 43968 57133 44154 57133 44155 57133 43968 57134 44155 57134 44237 57134 44237 57135 44155 57135 44157 57135 44237 57136 44157 57136 43970 57136 43970 57137 44157 57138 44158 57139 43970 57140 44158 57140 44238 57140 44238 57141 44158 57141 44160 57141 44238 57142 44160 57143 44239 57144 44239 57145 44160 57145 44162 57145 44239 57146 44162 57146 43972 57146 43972 57147 44162 57147 44163 57147 43972 57148 44163 57148 44240 57148 44240 57149 44163 57149 44241 57149 44240 57150 44241 57150 43975 57150 43975 57151 44241 57151 44242 57151 43975 57152 44242 57152 44243 57152 44243 57153 44242 57153 44244 57153 44243 57154 44244 57154 43976 57154 43976 57155 44244 57155 44245 57155 43976 57156 44245 57156 44246 57156 44246 57157 44245 57157 44168 57157 44246 57158 44168 57158 43978 57158 43978 57159 44168 57159 44170 57159 43978 57160 44170 57160 43981 57160 43981 57161 44170 57161 44171 57161 43981 57162 44171 57162 43982 57162 43982 57163 44171 57163 44247 57163 43982 57164 44247 57164 43983 57164 43983 57165 44247 57166 44174 57167 43983 57168 44174 57168 44248 57168 44248 57169 44174 57169 44249 57169 44248 57170 44249 57170 43985 57170 43985 57171 44249 57171 44250 57171 43985 57172 44250 57172 43986 57172 43986 57173 44250 57173 44251 57173 43986 57174 44251 57174 43988 57174 43988 57175 44251 57175 44252 57175 43988 57176 44252 57176 43989 57176 43989 57177 44252 57177 44254 57177 43989 57178 44254 57178 44253 57178 44253 57179 44254 57179 44178 57179 44253 57180 44178 57180 43992 57180 43992 57181 44178 57181 44179 57181 43992 57182 44179 57182 43993 57182 43993 57183 44179 57183 44255 57183 43993 57184 44255 57184 43995 57184 43995 57185 44255 57185 44180 57185 43995 57186 44180 57186 43996 57186 43996 57187 44180 57187 44256 57187 43996 57188 44256 57188 43998 57188 43998 57189 44256 57189 44182 57189 43998 57190 44182 57190 44000 57190 44000 57191 44182 57192 44183 57193 44000 57194 44183 57194 44001 57194 44001 57195 44183 57195 44257 57195 44001 57196 44257 57196 44258 57196 44258 57197 44257 57197 44184 57197 44258 57198 44184 57198 44259 57198 44259 57199 44184 57199 44186 57199 44259 57200 44186 57200 44003 57200 44003 57201 44186 57201 44260 57201 44003 57202 44260 57202 44005 57202 44005 57203 44260 57203 44187 57203 44005 57204 44187 57204 44261 57205 44261 57206 44187 57206 44188 57206 44261 57207 44188 57207 44262 57207 44262 57208 44188 57208 44190 57208 44262 57209 44190 57209 44264 57209 44264 57210 44190 57210 44263 57210 44264 57211 44263 57211 44265 57211 44265 57212 44263 57212 44192 57212 44265 57213 44192 57213 44008 57213 44008 57214 44192 57214 44266 57214 44008 57215 44266 57215 44010 57215 44010 57216 44266 57216 44267 57216 44010 57217 44267 57217 44012 57217 44012 57218 44267 57218 44195 57218 44012 57219 44195 57219 44013 57219 44013 57220 44195 57220 44268 57220 44013 57221 44268 57221 44269 57221 44269 57222 44268 57222 44271 57222 44269 57223 44271 57223 44270 57223 44270 57224 44271 57224 44196 57224 44270 57225 44196 57225 44016 57225 44016 57226 44196 57226 44272 57226 44016 57227 44272 57227 44273 57227 44273 57228 44272 57228 44274 57228 44273 57229 44274 57229 44017 57229 44017 57230 44274 57230 44275 57230 44017 57231 44275 57231 44018 57231 44018 57232 44275 57233 44200 57233 44018 57234 44200 57234 44019 57234 44019 57235 44200 57235 44276 57235 44019 57236 44276 57236 44022 57236 44022 57237 44276 57237 44278 57237 44022 57238 44278 57238 44277 57238 44277 57239 44278 57239 44279 57239 44277 57240 44279 57240 44023 57240 44023 57241 44279 57241 44133 57241 44023 57242 44133 57242 44202 57242 44202 57243 44133 57243 44204 57243 44600 57244 44100 57244 44595 57244 44594 57245 44588 57245 44280 57245 44093 57246 44091 57246 44281 57246 44085 57247 44282 57247 44577 57247 44078 57248 44077 57249 44558 57250 44283 57251 44071 57251 44553 57251 44069 57252 44284 57252 44546 57252 44068 57253 44066 57253 44285 57253 44286 57254 44287 57255 44543 57256 44065 57257 44531 57257 44532 57257 44530 57258 44516 57258 44517 57258 44288 57259 44506 57259 44515 57259 44051 57260 44050 57261 44489 57262 44484 57263 44289 57264 44480 57265 44479 57266 44044 57266 44481 57266 44477 57267 44290 57267 44291 57267 44472 57268 44467 57268 44473 57268 44041 57269 44292 57269 44464 57269 44463 57270 44447 57270 44448 57270 44445 57271 44293 57271 44444 57271 44419 57272 44294 57272 44415 57272 44025 57273 44295 57274 44409 57275 44132 57276 44296 57276 44406 57276 44130 57277 44129 57277 44297 57277 44404 57278 44128 57278 44397 57278 44396 57279 44126 57279 44398 57279 44391 57280 44298 57280 44378 57280 44119 57281 44118 57281 44375 57281 44351 57282 44109 57282 44353 57282 44106 57283 44341 57284 44343 57285 44105 57286 44299 57286 44339 57286 44104 57287 44102 57287 44300 57287 44452 57288 44454 57288 44456 57288 43944 57289 44301 57289 44564 57289 44322 57290 44302 57290 44303 57290 44427 57291 44304 57292 44438 57293 44500 57294 44305 57294 44306 57294 44510 57295 44511 57295 44509 57295 44492 57296 44500 57296 44501 57296 44307 57297 44308 57297 44309 57297 44309 57298 44308 57298 44476 57298 44309 57299 44476 57299 44471 57299 44307 57300 44309 57300 44310 57300 44310 57301 44309 57301 44471 57301 44310 57302 44471 57302 44311 57302 43936 57303 44312 57303 44313 57303 44313 57304 44312 57304 44314 57304 44437 57305 44439 57305 44436 57305 44421 57306 44427 57306 44315 57306 44316 57307 44608 57307 44318 57307 44318 57308 44608 57309 44317 57310 44318 57311 44317 57311 44401 57311 44316 57312 44318 57312 44319 57312 44319 57313 44318 57313 44401 57313 44319 57314 44401 57314 44609 57314 44394 57315 44320 57315 44402 57315 44402 57316 44320 57316 44403 57316 44370 57317 44321 57317 44371 57317 44357 57318 44322 57319 44354 57320 44323 57321 44324 57322 44327 57323 44327 57324 44324 57324 44325 57324 44327 57325 44325 57325 44328 57325 44323 57326 44327 57327 44326 57328 44326 57329 44327 57329 44328 57329 44326 57330 44328 57330 44329 57330 44330 57331 44331 57331 44591 57331 44591 57332 44331 57332 44599 57332 44574 57333 44332 57333 44573 57333 44560 57334 43944 57334 44565 57334 44333 57335 44545 57335 44335 57335 44335 57336 44545 57336 44538 57336 44335 57337 44538 57337 44541 57337 44333 57338 44335 57339 44334 57340 44334 57341 44335 57341 44541 57341 44334 57342 44541 57342 44336 57342 44536 57343 44337 57343 44542 57343 44542 57344 44337 57344 44338 57344 44299 57345 44104 57345 44339 57345 44339 57346 44104 57346 44300 57346 44339 57347 44300 57347 44340 57347 44340 57348 44300 57348 44601 57348 44340 57349 44601 57349 44361 57349 44361 57350 44601 57350 44602 57350 44341 57351 44105 57351 44343 57351 44343 57352 44105 57352 44339 57352 44343 57353 44339 57353 44344 57353 44344 57354 44339 57354 44340 57354 44344 57355 44340 57355 44342 57355 44342 57356 44340 57356 44361 57356 44345 57357 44108 57357 44346 57357 44346 57358 44108 57358 44107 57358 44107 57359 44106 57359 44346 57359 44346 57360 44106 57360 44343 57360 44346 57361 44343 57361 44347 57361 44347 57362 44343 57362 44344 57362 44347 57363 44344 57363 44359 57363 44359 57364 44344 57364 44342 57364 44109 57365 44345 57365 44353 57365 44353 57366 44345 57366 44346 57366 44353 57367 44346 57367 44355 57367 44355 57368 44346 57368 44347 57368 44355 57369 44347 57369 44356 57369 44356 57370 44347 57370 44359 57370 44348 57371 44112 57371 44349 57371 44349 57372 44112 57372 44350 57372 44350 57373 44351 57373 44349 57373 44349 57374 44351 57374 44353 57374 44349 57375 44353 57375 44352 57375 44352 57376 44353 57376 44355 57376 44352 57377 44355 57377 44354 57377 44354 57378 44355 57378 44356 57378 44354 57379 44356 57379 44357 57379 44357 57380 44356 57380 44359 57380 44357 57381 44359 57381 44358 57381 44358 57382 44359 57382 44342 57382 44358 57383 44342 57383 44360 57383 44360 57384 44342 57384 44361 57384 44360 57385 44361 57385 44362 57385 44362 57386 44361 57386 44602 57386 44362 57387 44602 57387 44363 57387 44363 57388 44602 57388 44364 57388 44322 57389 44303 57389 44354 57389 44354 57390 44303 57390 44365 57390 44354 57391 44365 57391 44352 57391 44352 57392 44365 57392 44366 57392 44352 57393 44366 57393 44349 57393 44349 57394 44366 57394 44367 57394 44349 57395 44367 57395 44348 57395 44117 57396 44368 57396 44367 57396 44367 57397 44368 57397 44114 57397 44367 57398 44114 57398 44348 57398 44118 57399 44117 57399 44375 57399 44375 57400 44117 57400 44367 57400 44375 57401 44367 57401 44374 57401 44374 57402 44367 57402 44366 57402 44374 57403 44366 57403 44369 57403 44369 57404 44366 57404 44365 57404 44369 57405 44365 57405 44371 57405 44371 57406 44365 57406 44303 57406 44371 57407 44303 57407 44370 57407 44370 57408 44303 57409 44302 57410 44321 57411 44372 57411 44371 57411 44371 57412 44372 57412 44383 57412 44371 57413 44383 57413 44369 57413 44369 57414 44383 57414 44373 57414 44369 57415 44373 57415 44374 57415 44374 57416 44373 57416 44381 57416 44374 57417 44381 57417 44375 57417 44375 57418 44381 57418 44379 57418 44375 57419 44379 57419 44119 57419 44376 57420 44120 57420 44379 57420 44379 57421 44120 57421 44377 57421 44379 57422 44377 57422 44119 57422 44298 57423 44376 57423 44378 57423 44378 57424 44376 57424 44379 57424 44378 57425 44379 57425 44380 57425 44380 57426 44379 57426 44381 57426 44380 57427 44381 57427 44387 57427 44387 57428 44381 57428 44373 57428 44387 57429 44373 57429 44382 57429 44382 57430 44373 57430 44383 57430 44382 57431 44383 57431 44384 57431 44384 57432 44383 57432 44372 57432 44384 57433 44372 57434 44385 57435 44384 57436 44395 57436 44382 57436 44382 57437 44395 57437 44386 57437 44382 57438 44386 57438 44387 57438 44387 57439 44386 57439 44393 57439 44387 57440 44393 57440 44380 57440 44380 57441 44393 57441 44388 57441 44380 57442 44388 57442 44378 57442 44378 57443 44388 57443 44389 57443 44378 57444 44389 57444 44391 57444 44125 57445 44123 57445 44389 57445 44389 57446 44123 57446 44390 57446 44389 57447 44390 57447 44391 57447 44126 57448 44125 57448 44398 57448 44398 57449 44125 57449 44389 57449 44398 57450 44389 57450 44392 57450 44392 57451 44389 57451 44388 57451 44392 57452 44388 57452 44400 57452 44400 57453 44388 57453 44393 57453 44400 57454 44393 57454 44402 57454 44402 57455 44393 57455 44386 57455 44402 57456 44386 57456 44394 57456 44394 57457 44386 57457 44395 57457 44128 57458 44396 57458 44397 57458 44397 57459 44396 57459 44398 57459 44397 57460 44398 57460 44399 57460 44399 57461 44398 57461 44392 57461 44399 57462 44392 57462 44317 57462 44317 57463 44392 57463 44400 57463 44317 57464 44400 57464 44401 57464 44401 57465 44400 57465 44402 57465 44401 57466 44402 57466 44609 57466 44609 57467 44402 57467 44403 57467 44129 57468 44404 57468 44297 57468 44297 57469 44404 57469 44397 57469 44297 57470 44397 57470 44407 57470 44407 57471 44397 57471 44399 57471 44407 57472 44399 57472 44405 57472 44405 57473 44399 57473 44317 57473 44405 57474 44317 57474 44607 57474 44607 57475 44317 57475 44608 57475 44296 57476 44130 57476 44406 57476 44406 57477 44130 57477 44297 57477 44406 57478 44297 57478 44411 57478 44411 57479 44297 57479 44407 57479 44411 57480 44407 57480 44408 57480 44408 57481 44407 57481 44405 57481 44295 57482 44132 57482 44409 57482 44409 57483 44132 57483 44406 57483 44409 57484 44406 57484 44410 57484 44410 57485 44406 57485 44411 57485 44410 57486 44411 57486 44413 57486 44413 57487 44411 57487 44408 57487 44029 57488 44412 57488 44414 57488 44414 57489 44412 57489 44028 57489 44028 57490 44025 57490 44414 57490 44414 57491 44025 57491 44409 57491 44414 57492 44409 57492 44416 57492 44416 57493 44409 57493 44410 57493 44416 57494 44410 57494 44422 57494 44422 57495 44410 57495 44413 57495 44294 57496 44029 57496 44415 57496 44415 57497 44029 57497 44414 57497 44415 57498 44414 57498 44417 57498 44417 57499 44414 57499 44416 57499 44417 57500 44416 57500 44418 57500 44418 57501 44416 57501 44422 57501 44430 57502 44033 57502 44429 57502 44429 57503 44033 57503 44031 57503 44031 57504 44419 57504 44429 57504 44429 57505 44419 57505 44415 57505 44429 57506 44415 57506 44420 57506 44420 57507 44415 57507 44417 57507 44420 57508 44417 57508 44315 57508 44315 57509 44417 57509 44418 57509 44315 57510 44418 57510 44421 57510 44421 57511 44418 57511 44422 57511 44421 57512 44422 57512 44423 57512 44423 57513 44422 57513 44413 57513 44423 57514 44413 57514 44424 57514 44424 57515 44413 57515 44408 57515 44424 57516 44408 57516 44425 57516 44425 57517 44408 57517 44405 57517 44425 57518 44405 57518 44426 57518 44426 57519 44405 57519 44607 57519 44427 57520 44438 57520 44315 57520 44315 57521 44438 57521 44435 57521 44315 57522 44435 57522 44420 57522 44420 57523 44435 57523 44428 57523 44420 57524 44428 57524 44429 57524 44429 57525 44428 57525 44432 57525 44429 57526 44432 57526 44430 57526 44431 57527 44433 57527 44432 57527 44432 57528 44433 57528 44434 57528 44432 57529 44434 57529 44430 57529 44293 57530 44431 57531 44444 57532 44444 57533 44431 57533 44432 57533 44444 57534 44432 57534 44442 57534 44442 57535 44432 57535 44428 57535 44442 57536 44428 57536 44441 57536 44441 57537 44428 57537 44435 57537 44441 57538 44435 57538 44436 57538 44436 57539 44435 57539 44438 57539 44436 57540 44438 57540 44437 57540 44437 57541 44438 57542 44304 57543 44439 57544 44440 57544 44436 57544 44436 57545 44440 57545 44451 57545 44436 57546 44451 57546 44441 57546 44441 57547 44451 57547 44443 57547 44441 57548 44443 57548 44442 57548 44442 57549 44443 57549 44450 57549 44442 57550 44450 57550 44444 57550 44444 57551 44450 57551 44449 57551 44444 57552 44449 57552 44445 57552 44036 57553 44446 57553 44449 57553 44449 57554 44446 57554 44035 57554 44449 57555 44035 57555 44445 57555 44447 57556 44036 57556 44448 57556 44448 57557 44036 57557 44449 57557 44448 57558 44449 57558 44459 57558 44459 57559 44449 57559 44450 57559 44459 57560 44450 57560 44457 57560 44457 57561 44450 57561 44443 57561 44457 57562 44443 57562 44456 57562 44456 57563 44443 57563 44451 57563 44456 57564 44451 57564 44452 57564 44452 57565 44451 57565 44440 57565 44452 54254 44440 54254 44453 54254 44454 57566 44455 57566 44456 57566 44456 57567 44455 57567 44466 57567 44456 57568 44466 57568 44457 57568 44457 57569 44466 57569 44458 57569 44457 57570 44458 57570 44459 57570 44459 57571 44458 57571 44465 57571 44459 57572 44465 57572 44448 57572 44448 57573 44465 57573 44461 57573 44448 57574 44461 57574 44463 57574 44460 57575 44039 57575 44461 57575 44461 57576 44039 57576 44462 57576 44461 57577 44462 57577 44463 57577 44292 57578 44460 57579 44464 57580 44464 57581 44460 57581 44461 57581 44464 57582 44461 57582 44469 57582 44469 57583 44461 57583 44465 57583 44469 57584 44465 57584 44470 57584 44470 57585 44465 57585 44458 57585 44470 57586 44458 57586 44313 57586 44313 57587 44458 57587 44466 57587 44313 57588 44466 57588 43936 57588 43936 57589 44466 57589 44455 57589 44467 57590 44041 57590 44473 57590 44473 57591 44041 57591 44464 57591 44473 57592 44464 57592 44468 57592 44468 57593 44464 57593 44469 57593 44468 57594 44469 57594 44476 57594 44476 57595 44469 57595 44470 57595 44476 57596 44470 57596 44471 57596 44471 57597 44470 57597 44313 57597 44471 57598 44313 57598 44311 57598 44311 57599 44313 57599 44314 57599 44290 57600 44472 57600 44291 57600 44291 57601 44472 57601 44473 57601 44291 57602 44473 57602 44478 57602 44478 57603 44473 57603 44468 57603 44478 57604 44468 57604 44474 57604 44474 57605 44468 57605 44476 57605 44474 57606 44476 57606 44475 57606 44475 57607 44476 57607 44308 57607 44044 57608 44477 57608 44481 57608 44481 57609 44477 57609 44291 57609 44481 57610 44291 57610 44482 57610 44482 57611 44291 57611 44478 57611 44482 57612 44478 57612 44497 57612 44497 57613 44478 57613 44474 57613 44289 57614 44479 57614 44480 57614 44480 57615 44479 57615 44481 57615 44480 57616 44481 57616 44485 57616 44485 57617 44481 57617 44482 57617 44485 57618 44482 57618 44495 57618 44495 57619 44482 57619 44497 57619 44048 57620 44483 57620 44486 57620 44486 57621 44483 57621 44046 57621 44046 57622 44484 57622 44486 57622 44486 57623 44484 57623 44480 57623 44486 57624 44480 57624 44488 57624 44488 57625 44480 57625 44485 57625 44488 57626 44485 57626 44494 57626 44494 57627 44485 57627 44495 57627 44050 57628 44048 57628 44489 57628 44489 57629 44048 57629 44486 57629 44489 57630 44486 57630 44490 57630 44490 57631 44486 57631 44488 57631 44490 57632 44488 57632 44487 57632 44487 57633 44488 57633 44494 57633 44505 57634 44054 57634 44503 57634 44503 57635 44054 57635 44052 57635 44052 57636 44051 57636 44503 57636 44503 57637 44051 57637 44489 57637 44503 57638 44489 57638 44491 57638 44491 57639 44489 57639 44490 57639 44491 57640 44490 57640 44501 57640 44501 57641 44490 57641 44487 57641 44501 57642 44487 57642 44492 57642 44492 57643 44487 57643 44494 57643 44492 57644 44494 57644 44493 57644 44493 57645 44494 57645 44495 57645 44493 57646 44495 57646 44496 57646 44496 57647 44495 57647 44497 57647 44496 57648 44497 57648 44498 57648 44498 57649 44497 57649 44474 57649 44498 57650 44474 57650 44499 57650 44499 57651 44474 57651 44475 57651 44500 57652 44306 57652 44501 57652 44501 57653 44306 57653 44508 57653 44501 57654 44508 57654 44491 57654 44491 57655 44508 57655 44502 57655 44491 57656 44502 57656 44503 57656 44503 57657 44502 57657 44504 57657 44503 57658 44504 57658 44505 57658 44507 57659 44056 57659 44504 57659 44504 57660 44056 57660 44055 57660 44504 57661 44055 57661 44505 57661 44506 57662 44507 57662 44515 57662 44515 57663 44507 57663 44504 57663 44515 57664 44504 57664 44514 57664 44514 57665 44504 57665 44502 57665 44514 57666 44502 57666 44513 57666 44513 57667 44502 57667 44508 57667 44513 57668 44508 57668 44509 57668 44509 57669 44508 57669 44306 57669 44509 57670 44306 57670 44510 57670 44510 57671 44306 57671 44305 57671 44511 57672 44512 57672 44509 57672 44509 57673 44512 57673 44521 57673 44509 57674 44521 57674 44513 57674 44513 57675 44521 57675 44520 57675 44513 57676 44520 57676 44514 57676 44514 57677 44520 57677 44519 57677 44514 57678 44519 57678 44515 57678 44515 57679 44519 57679 44518 57679 44515 57680 44518 57680 44288 57680 44061 57681 44060 57681 44518 57681 44518 57682 44060 57682 44058 57682 44518 57683 44058 57683 44288 57683 44516 57684 44061 57684 44517 57684 44517 57685 44061 57685 44518 57685 44517 57686 44518 57686 44528 57686 44528 57687 44518 57687 44519 57687 44528 57688 44519 57688 44527 57688 44527 57689 44519 57689 44520 57689 44527 57690 44520 57690 44525 57690 44525 57691 44520 57691 44521 57691 44525 57692 44521 57692 44522 57692 44522 57693 44521 57693 44512 57693 44522 57694 44512 57694 44523 57694 44522 57695 44524 57695 44525 57695 44525 57696 44524 57696 44526 57696 44525 57697 44526 57697 44527 57697 44527 57698 44526 57698 44535 57698 44527 57699 44535 57699 44528 57699 44528 57700 44535 57700 44529 57700 44528 57701 44529 57701 44517 57701 44517 57702 44529 57702 44534 57702 44517 57703 44534 57703 44530 57703 44533 57704 44064 57704 44534 57704 44534 57705 44064 57705 44063 57705 44534 57706 44063 57706 44530 57706 44531 57707 44533 57707 44532 57707 44532 57708 44533 57708 44534 57708 44532 57709 44534 57709 44539 57709 44539 57710 44534 57710 44529 57710 44539 57711 44529 57711 44540 57711 44540 57712 44529 57712 44535 57712 44540 57713 44535 57713 44542 57713 44542 57714 44535 57714 44526 57714 44542 57715 44526 57715 44536 57715 44536 57716 44526 57716 44524 57716 44287 57717 44065 57717 44543 57717 44543 57718 44065 57718 44532 57718 44543 57719 44532 57719 44537 57719 44537 57720 44532 57720 44539 57720 44537 57721 44539 57721 44538 57721 44538 57722 44539 57722 44540 57722 44538 57723 44540 57723 44541 57723 44541 57724 44540 57724 44542 57724 44541 57725 44542 57725 44336 57725 44336 57726 44542 57726 44338 57726 44066 57727 44286 57727 44285 57727 44285 57728 44286 57728 44543 57728 44285 57729 44543 57729 44547 57729 44547 57730 44543 57730 44537 57730 44547 57731 44537 57731 44544 57731 44544 57732 44537 57732 44538 57732 44544 57733 44538 57733 43940 57733 43940 57734 44538 57734 44545 57734 44284 57735 44068 57735 44546 57735 44546 57736 44068 57736 44285 57736 44546 57737 44285 57737 44548 57737 44548 57738 44285 57738 44547 57738 44548 57739 44547 57739 44549 57739 44549 57740 44547 57740 44544 57740 44071 57741 44069 57741 44553 57741 44553 57742 44069 57742 44546 57742 44553 57743 44546 57743 44550 57743 44550 57744 44546 57744 44548 57744 44550 57745 44548 57745 44551 57745 44551 57746 44548 57746 44549 57746 44076 57747 44074 57747 44552 57747 44552 57748 44074 57749 44073 57750 44073 57751 44283 57751 44552 57751 44552 57752 44283 57752 44553 57752 44552 57753 44553 57753 44554 57753 44554 57754 44553 57754 44550 57754 44554 57755 44550 57755 44559 57755 44559 57756 44550 57756 44551 57756 44077 57757 44076 57757 44558 57757 44558 57758 44076 57758 44552 57758 44558 57759 44552 57759 44555 57759 44555 57760 44552 57760 44554 57760 44555 57761 44554 57761 44556 57761 44556 57762 44554 57762 44559 57762 44080 57763 44079 57763 44569 57763 44569 57764 44079 57764 44557 57764 44557 57765 44078 57765 44569 57765 44569 57766 44078 57766 44558 57766 44569 57767 44558 57767 44566 57767 44566 57768 44558 57768 44555 57768 44566 57769 44555 57769 44565 57769 44565 57770 44555 57770 44556 57770 44565 57771 44556 57771 44560 57771 44560 57772 44556 57772 44559 57772 44560 57773 44559 57773 44561 57773 44561 57774 44559 57774 44551 57774 44561 57775 44551 57775 44562 57775 44562 57776 44551 57776 44549 57776 44562 57777 44549 57777 44563 57777 44563 57778 44549 57778 44544 57778 44563 57779 44544 57779 43946 57779 43946 57780 44544 57780 43940 57780 43944 57781 44564 57781 44565 57781 44565 57782 44564 57782 44567 57782 44565 57783 44567 57783 44566 57783 44566 57784 44567 57784 44568 57784 44566 57785 44568 57785 44569 57785 44569 57786 44568 57786 44570 57786 44569 57787 44570 57787 44080 57787 44083 57788 44081 57788 44570 57788 44570 57789 44081 57789 44571 57789 44570 57790 44571 57790 44080 57790 44282 57791 44083 57791 44577 57791 44577 57792 44083 57792 44570 57792 44577 57793 44570 57793 44572 57793 44572 57794 44570 57794 44568 57794 44572 57795 44568 57795 44575 57795 44575 57796 44568 57796 44567 57796 44575 57797 44567 57797 44573 57797 44573 57798 44567 57798 44564 57798 44573 57799 44564 57799 44574 57799 44574 57800 44564 57800 44301 57800 44332 57801 44583 57801 44573 57801 44573 57802 44583 57802 44581 57802 44573 57803 44581 57803 44575 57803 44575 57804 44581 57804 44580 57804 44575 57805 44580 57805 44572 57805 44572 57806 44580 57806 44576 57806 44572 57807 44576 57807 44577 57807 44577 57808 44576 57808 44578 57808 44577 57809 44578 57809 44085 57809 44089 57810 44088 57810 44578 57810 44578 57811 44088 57811 44087 57811 44578 57812 44087 57812 44085 57812 44091 57813 44089 57813 44281 57813 44281 57814 44089 57814 44578 57814 44281 57815 44578 57815 44579 57815 44579 57816 44578 57816 44576 57816 44579 57817 44576 57817 44587 57817 44587 57818 44576 57818 44580 57818 44587 57819 44580 57819 44585 57819 44585 57820 44580 57820 44581 57820 44585 57821 44581 57821 44582 57821 44582 57822 44581 57822 44583 57822 44582 53995 44583 53995 44584 53995 44582 57823 44593 57823 44585 57823 44585 57824 44593 57824 44586 57824 44585 57825 44586 57825 44587 57825 44587 57826 44586 57826 44592 57826 44587 57827 44592 57827 44579 57827 44579 57828 44592 57828 44590 57828 44579 57829 44590 57829 44281 57829 44281 57830 44590 57830 44589 57830 44281 57831 44589 57831 44093 57831 44097 57832 44095 57832 44589 57832 44589 57833 44095 57833 44094 57833 44589 57834 44094 57834 44093 57834 44588 57835 44097 57836 44280 57837 44280 57838 44097 57838 44589 57838 44280 57839 44589 57839 44596 57839 44596 57840 44589 57840 44590 57840 44596 57841 44590 57841 44598 57841 44598 57842 44590 57842 44592 57842 44598 57843 44592 57843 44591 57843 44591 57844 44592 57844 44586 57844 44591 57845 44586 57845 44330 57845 44330 57846 44586 57846 44593 57846 44100 57847 44594 57847 44595 57847 44595 57848 44594 57848 44280 57848 44595 57849 44280 57849 44597 57849 44597 57850 44280 57850 44596 57850 44597 57851 44596 57851 44325 57851 44325 57852 44596 57852 44598 57852 44325 57853 44598 57853 44328 57853 44328 57854 44598 57854 44591 57854 44328 57855 44591 57855 44329 57855 44329 57856 44591 57856 44599 57856 44102 57857 44600 57857 44300 57857 44300 57858 44600 57858 44595 57858 44300 57859 44595 57859 44601 57859 44601 57860 44595 57860 44597 57860 44601 57861 44597 57861 44602 57861 44602 57862 44597 57862 44325 57862 44602 57863 44325 57863 44364 57863 44364 57864 44325 57864 44324 57864 44603 57865 44605 57865 44604 57865 44604 57866 44605 57866 44607 57866 44604 57867 44607 57867 44606 57867 44606 57868 44607 57868 44608 57868 44606 57869 44608 57869 44316 57869 44316 57870 44319 57870 44606 57870 44606 57871 44319 57871 44609 57871 44606 57872 44609 57872 44403 57872 44610 57873 44657 57873 44611 57873 44611 57874 44657 57874 44655 57874 44611 57875 44612 57875 44610 57875 44610 57876 44612 57876 44613 57876 44610 57877 44613 57877 44614 57877 44614 57878 44613 57878 44615 57878 44614 57879 44615 57879 44616 57879 44616 57880 44615 57880 44617 57880 44616 57881 44617 57881 44618 57881 44618 57882 44617 57882 44620 57882 44618 57883 44620 57883 44619 57883 44619 57884 44620 57884 44622 57884 44619 57885 44622 57885 44621 57885 44621 57886 44622 57886 44624 57886 44621 57887 44624 57887 44623 57887 44623 57888 44624 57888 44625 57888 44623 57888 44625 57888 44626 57888 44626 57889 44625 57889 44627 57889 44626 57890 44627 57890 44629 57890 44629 57891 44627 57891 44628 57891 44629 57892 44628 57892 44630 57892 44630 57893 44628 57893 44631 57893 44630 57893 44631 57893 44632 57893 44632 57894 44631 57894 44634 57894 44632 57895 44634 57895 44633 57895 44633 57896 44634 57896 44636 57896 44633 57897 44636 57897 44635 57897 44635 57898 44636 57898 44637 57898 44635 57899 44637 57899 44638 57899 44638 57900 44637 57900 44639 57900 44638 57901 44639 57901 44641 57901 44641 57902 44639 57902 44640 57902 44641 57903 44640 57903 44642 57903 44642 57904 44640 57904 44643 57904 44642 57905 44643 57905 44644 57905 44644 57906 44643 57906 44646 57906 44644 57907 44646 57907 44645 57907 44645 57908 44646 57908 44647 57908 44645 57909 44647 57909 44648 57909 44648 57910 44647 57910 44650 57910 44648 57911 44650 57911 44649 57911 44649 57912 44650 57912 44651 57912 44649 57913 44651 57913 44653 57913 44653 57914 44651 57914 44652 57914 44653 57915 44652 57915 44654 57915 44654 57916 44652 57916 44655 57916 44654 57917 44655 57917 44656 57917 44656 57918 44655 57918 44657 57918 44658 57919 44705 57919 44659 57919 44659 57920 44705 57920 44703 57920 44659 57919 44660 57919 44658 57919 44658 57921 44660 57921 44661 57921 44658 57922 44661 57922 44662 57922 44662 57923 44661 57923 44663 57923 44662 57924 44663 57924 44664 57924 44664 57880 44663 57880 44666 57880 44664 57881 44666 57881 44665 57881 44665 57925 44666 57925 44667 57925 44665 57883 44667 57883 44668 57883 44668 57926 44667 57926 44670 57926 44668 57927 44670 57927 44669 57927 44669 57928 44670 57928 44671 57928 44669 57929 44671 57929 44673 57929 44673 57930 44671 57930 44672 57930 44673 57931 44672 57931 44674 57931 44674 57932 44672 57932 44676 57932 44674 57933 44676 57933 44675 57933 44675 57934 44676 57934 44677 57934 44675 57892 44677 57892 44678 57892 44678 57893 44677 57893 44680 57893 44678 57935 44680 57935 44679 57935 44679 57936 44680 57936 44681 57936 44679 57937 44681 57937 44682 57937 44682 57938 44681 57938 44684 57938 44682 57939 44684 57939 44683 57939 44683 57899 44684 57899 44685 57899 44683 57899 44685 57899 44687 57899 44687 57900 44685 57900 44686 57900 44687 57940 44686 57940 44688 57940 44688 57941 44686 57941 44689 57941 44688 57942 44689 57942 44690 57942 44690 57943 44689 57943 44692 57943 44690 57944 44692 57944 44691 57944 44691 57945 44692 57945 44693 57945 44691 57946 44693 57946 44695 57946 44695 57947 44693 57947 44694 57947 44695 57948 44694 57948 44696 57948 44696 57910 44694 57910 44697 57910 44696 57949 44697 57949 44698 57949 44698 57912 44697 57912 44700 57912 44698 57913 44700 57913 44699 57913 44699 57950 44700 57950 44701 57950 44699 57951 44701 57951 44702 57951 44702 57952 44701 57952 44703 57952 44702 57953 44703 57953 44704 57953 44704 57920 44703 57920 44705 57920 44706 57873 44708 57873 44707 57873 44707 57874 44708 57874 44752 57874 44707 57875 44709 57875 44706 57875 44706 57921 44709 57921 44710 57921 44706 57922 44710 57922 44711 57922 44711 57923 44710 57923 44712 57923 44711 57924 44712 57924 44713 57924 44713 57880 44712 57880 44714 57880 44713 57881 44714 57881 44716 57881 44716 57925 44714 57925 44715 57925 44716 57883 44715 57883 44718 57883 44718 57926 44715 57926 44717 57926 44718 57927 44717 57927 44719 57927 44719 57954 44717 57954 44721 57954 44719 57955 44721 57955 44720 57955 44720 57956 44721 57956 44722 57956 44720 57957 44722 57957 44724 57957 44724 57889 44722 57889 44723 57889 44724 57958 44723 57958 44726 57958 44726 57934 44723 57934 44725 57934 44726 57892 44725 57892 44728 57892 44728 57893 44725 57893 44727 57893 44728 57935 44727 57935 44729 57935 44729 57936 44727 57936 44730 57936 44729 57937 44730 57937 44731 57937 44731 57938 44730 57938 44732 57938 44731 57939 44732 57939 44733 57939 44733 57899 44732 57899 44734 57899 44733 57899 44734 57899 44735 57899 44735 57900 44734 57900 44737 57900 44735 57940 44737 57940 44736 57940 44736 57959 44737 57959 44738 57959 44736 57903 44738 57903 44739 57903 44739 57960 44738 57960 44741 57960 44739 57960 44741 57960 44740 57960 44740 57961 44741 57961 44742 57961 44740 57962 44742 57962 44743 57962 44743 57947 44742 57947 44744 57947 44743 57948 44744 57948 44745 57948 44745 57910 44744 57910 44746 57910 44745 57949 44746 57949 44747 57949 44747 57912 44746 57912 44748 57912 44747 57913 44748 57913 44749 57913 44749 57950 44748 57950 44750 57950 44749 57951 44750 57951 44751 57951 44751 57952 44750 57952 44752 57952 44751 57953 44752 57953 44753 57953 44753 57918 44752 57918 44708 57918 44783 57963 44767 57963 44754 57963 44755 57964 44756 57964 44760 57964 44777 57965 44758 57965 44757 57965 44757 590 44758 590 44803 590 44757 590 44803 590 44756 590 44756 57966 44803 57966 44759 57966 44756 57967 44759 57967 44760 57967 44768 590 44770 590 44761 590 44761 57968 44770 57968 44810 57968 44761 57969 44810 57969 44776 57969 44762 57970 44786 57970 44754 57970 44754 57971 44786 57971 44763 57971 44754 57972 44763 57972 44783 57972 44760 590 44764 590 44755 590 44755 57973 44764 57973 44797 57973 44755 57974 44797 57974 44765 57974 44765 57975 44797 57975 44766 57975 44765 590 44766 590 44779 590 44783 590 44782 590 44767 590 44767 57976 44782 57976 44814 57976 44767 590 44814 590 44768 590 44768 57977 44814 57977 44769 57977 44768 57978 44769 57978 44770 57978 44771 57979 44772 57979 44773 57979 44773 590 44772 590 44774 590 44773 590 44774 590 44762 590 44762 57980 44774 57980 44775 57980 44762 57981 44775 57981 44786 57981 44810 57982 44808 57982 44776 57982 44776 590 44808 590 44805 590 44776 590 44805 590 44777 590 44777 590 44805 590 44778 590 44777 590 44778 590 44758 590 44766 590 44794 590 44779 590 44779 590 44794 590 44792 590 44779 590 44792 590 44771 590 44771 590 44792 590 44780 590 44771 590 44780 590 44772 590 44784 57919 44781 57919 44782 57919 44782 57920 44781 57920 44814 57920 44782 57919 44783 57919 44784 57919 44784 57876 44783 57876 44763 57876 44784 57877 44763 57877 44785 57877 44785 57878 44763 57878 44786 57878 44785 57879 44786 57879 44787 57879 44787 57880 44786 57880 44775 57880 44787 57881 44775 57881 44788 57881 44788 57882 44775 57882 44774 57882 44788 57883 44774 57883 44789 57883 44789 57884 44774 57884 44772 57884 44789 57885 44772 57885 44790 57885 44790 57983 44772 57983 44780 57983 44790 57984 44780 57984 44791 57984 44791 57985 44780 57985 44792 57985 44791 57986 44792 57986 44793 57986 44793 57932 44792 57932 44794 57932 44793 57987 44794 57987 44795 57987 44795 57891 44794 57891 44766 57891 44795 57892 44766 57892 44796 57892 44796 57893 44766 57893 44797 57893 44796 57893 44797 57893 44798 57893 44798 57894 44797 57894 44764 57894 44798 57895 44764 57895 44799 57895 44799 57896 44764 57896 44760 57896 44799 57897 44760 57897 44800 57897 44800 57898 44760 57898 44759 57898 44800 57899 44759 57899 44801 57899 44801 57900 44759 57900 44803 57900 44801 57901 44803 57901 44802 57901 44802 57988 44803 57988 44758 57988 44802 57942 44758 57942 44804 57942 44804 57989 44758 57989 44778 57989 44804 57990 44778 57990 44806 57990 44806 57991 44778 57991 44805 57991 44806 57992 44805 57992 44807 57992 44807 57908 44805 57908 44808 57908 44807 57909 44808 57909 44809 57909 44809 57910 44808 57910 44810 57910 44809 57911 44810 57911 44811 57911 44811 57912 44810 57912 44770 57912 44811 57913 44770 57913 44812 57913 44812 57914 44770 57914 44769 57914 44812 57915 44769 57915 44813 57915 44813 57916 44769 57916 44814 57916 44813 57917 44814 57917 44815 57917 44815 57920 44814 57920 44781 57920 44816 57993 44818 57993 44817 57993 44817 57994 44818 57994 44865 57994 44817 57995 44819 57995 44816 57995 44816 57996 44819 57996 44820 57996 44816 57996 44820 57996 44821 57996 44821 57997 44820 57997 44872 57997 44821 57998 44872 57998 44822 57998 44822 57999 44872 57999 44823 57999 44822 58000 44823 58000 44824 58000 44824 58001 44823 58001 44825 58001 44824 58002 44825 58002 44826 58002 44826 58003 44825 58003 44896 58003 44826 58004 44896 58004 44827 58004 44827 58005 44896 58005 44828 58005 44827 58006 44828 58006 44829 58006 44829 58007 44828 58007 44830 58007 44829 58007 44830 58007 44831 58007 44831 58008 44830 58008 44893 58008 44831 58009 44893 58009 44832 58009 44832 58010 44893 58010 44875 58010 44832 58011 44875 58011 44833 58011 44833 58012 44875 58012 44835 58012 44833 58013 44835 58013 44834 58013 44834 58014 44835 58014 44836 58014 44834 58015 44836 58015 44837 58015 44837 58016 44836 58016 44838 58016 44837 58017 44838 58017 44839 58017 44839 58018 44838 58018 44840 58018 44839 58019 44840 58019 44841 58019 44841 58020 44840 58020 44842 58020 44841 58021 44842 58021 44843 58021 44843 58022 44842 58022 44870 58022 44843 58023 44870 58023 44844 58023 44844 58024 44870 58024 44846 58024 44844 58024 44846 58024 44845 58024 44845 58025 44846 58025 44847 58025 44845 58026 44847 58026 44848 58026 44848 58027 44847 58027 44901 58027 44848 58028 44901 58028 44849 58028 44849 58029 44901 58029 44850 58029 44849 58029 44850 58029 44851 58029 44851 58030 44850 58030 44898 58030 44851 58031 44898 58031 44852 58031 44852 58032 44898 58032 44897 58032 44852 58033 44897 58033 44853 58033 44853 58034 44897 58034 44854 58034 44853 58035 44854 58035 44855 58035 44855 58036 44854 58036 44883 58036 44855 58037 44883 58037 44856 58037 44856 58038 44883 58038 44858 58038 44856 58039 44858 58039 44857 58039 44857 58040 44858 58040 44888 58040 44857 58041 44888 58041 44859 58041 44859 58042 44888 58042 44887 58042 44859 58043 44887 58043 44860 58043 44860 58044 44887 58044 44861 58044 44860 58045 44861 58045 44862 58045 44862 58046 44861 58046 44864 58046 44862 58047 44864 58047 44863 58047 44863 58048 44864 58048 44891 58048 44863 58049 44891 58049 44866 58049 44866 58050 44891 58050 44865 58050 44866 58051 44865 58051 44867 58051 44867 58052 44865 58052 44818 58052 44900 590 44847 590 44868 590 44868 58053 44847 58053 44846 58053 44868 590 44846 590 44869 590 44869 58054 44846 58054 44870 58054 44869 590 44870 590 44878 590 44819 58055 44889 58055 44873 58055 44895 590 44823 590 44871 590 44871 590 44823 590 44872 590 44871 590 44872 590 44873 590 44873 58056 44872 58056 44820 58056 44873 58057 44820 58057 44819 58057 44880 590 44835 590 44874 590 44874 58058 44835 58058 44875 58058 44874 58059 44875 58059 44876 58059 44876 58060 44875 58060 44893 58060 44876 58061 44893 58061 44877 58061 44870 58062 44842 58062 44878 58062 44878 58063 44842 58063 44840 58063 44878 590 44840 590 44879 590 44879 58064 44840 58064 44838 58064 44879 590 44838 590 44880 590 44880 58065 44838 58065 44836 58065 44880 58066 44836 58066 44835 58066 44881 58067 44858 58067 44882 58067 44882 590 44858 590 44883 590 44882 58068 44883 58068 44884 58068 44884 590 44883 590 44854 590 44884 58069 44854 58069 44885 58069 44892 590 44861 590 44886 590 44886 58070 44861 58070 44887 58070 44886 58071 44887 58071 44881 58071 44881 590 44887 590 44888 590 44881 590 44888 590 44858 590 44819 590 44817 590 44889 590 44889 58072 44817 58072 44865 58072 44889 590 44865 590 44890 590 44890 58073 44865 58073 44891 58073 44890 590 44891 590 44892 590 44892 58074 44891 58074 44864 58074 44892 590 44864 590 44861 590 44893 590 44830 590 44877 590 44877 590 44830 590 44828 590 44877 58075 44828 58075 44894 58075 44894 590 44828 590 44896 590 44894 590 44896 590 44895 590 44895 58076 44896 58076 44825 58076 44895 58077 44825 58077 44823 58077 44854 590 44897 590 44885 590 44885 58078 44897 58078 44898 58078 44885 590 44898 590 44899 590 44899 58079 44898 58079 44850 58079 44899 58080 44850 58080 44900 58080 44900 590 44850 590 44901 590 44900 58081 44901 58081 44847 58081 44902 58082 44903 58082 44904 58082 44904 57994 44903 57994 44946 57994 44904 58083 44905 58083 44902 58083 44902 58084 44905 58084 44906 58084 44902 58085 44906 58085 44907 58085 44907 58086 44906 58086 44957 58086 44907 57998 44957 57998 44908 57998 44908 58087 44957 58087 44955 58087 44908 58000 44955 58000 44909 58000 44909 58088 44955 58088 44910 58088 44909 58089 44910 58089 44911 58089 44911 58003 44910 58003 44912 58003 44911 58090 44912 58090 44913 58090 44913 58091 44912 58091 44979 58091 44913 58006 44979 58006 44914 58006 44914 58092 44979 58092 44977 58092 44914 58093 44977 58093 44915 58093 44915 58008 44977 58008 44976 58008 44915 58094 44976 58094 44916 58094 44916 58095 44976 58095 44960 58095 44916 58011 44960 58011 44917 58011 44917 58096 44960 58096 44919 58096 44917 58013 44919 58013 44918 58013 44918 58014 44919 58014 44920 58014 44918 58097 44920 58097 44922 58097 44922 58017 44920 58017 44921 58017 44922 58016 44921 58016 44923 58016 44923 58018 44921 58018 44963 58018 44923 58019 44963 58019 44924 58019 44924 58020 44963 58020 44925 58020 44924 58098 44925 58098 44926 58098 44926 58022 44925 58022 44953 58022 44926 58023 44953 58023 44927 58023 44927 58099 44953 58099 44950 58099 44927 58024 44950 58024 44928 58024 44928 58025 44950 58025 44949 58025 44928 58026 44949 58026 44929 58026 44929 58100 44949 58100 44987 58100 44929 58101 44987 58101 44930 58101 44930 58102 44987 58102 44986 58102 44930 58103 44986 58103 44931 58103 44931 58030 44986 58030 44985 58030 44931 58031 44985 58031 44932 58031 44932 58104 44985 58104 44982 58104 44932 58033 44982 58033 44934 58033 44934 58105 44982 58105 44933 58105 44934 58106 44933 58106 44935 58106 44935 58107 44933 58107 44966 58107 44935 58037 44966 58037 44936 58037 44936 58038 44966 58038 44970 58038 44936 58038 44970 58038 44937 58038 44937 58108 44970 58108 44938 58108 44937 58041 44938 58041 44939 58041 44939 58042 44938 58042 44940 58042 44939 58043 44940 58043 44941 58043 44941 58109 44940 58109 44975 58109 44941 58110 44975 58110 44942 58110 44942 58046 44975 58046 44944 58046 44942 58047 44944 58047 44943 58047 44943 58048 44944 58048 44974 58048 44943 58111 44974 58111 44945 58111 44945 58051 44974 58051 44946 58051 44945 58050 44946 58050 44947 58050 44947 58112 44946 58112 44903 58112 44948 590 44949 590 44951 590 44951 58113 44949 58113 44950 58113 44951 590 44950 590 44952 590 44952 58114 44950 58114 44953 58114 44952 590 44953 590 44962 590 44905 58055 44971 58055 44954 58055 44981 590 44955 590 44956 590 44956 590 44955 590 44957 590 44956 590 44957 590 44954 590 44954 58056 44957 58056 44906 58056 44954 58057 44906 58057 44905 58057 44958 590 44919 590 44959 590 44959 58058 44919 58058 44960 58058 44959 58115 44960 58115 44961 58115 44961 58060 44960 58060 44976 58060 44961 58061 44976 58061 44978 58061 44953 58062 44925 58062 44962 58062 44962 58063 44925 58063 44963 58063 44962 590 44963 590 44964 590 44964 58116 44963 58116 44921 58116 44964 590 44921 590 44958 590 44958 58065 44921 58065 44920 58065 44958 58066 44920 58066 44919 58066 44969 58067 44970 58067 44965 58067 44965 590 44970 590 44966 590 44965 58068 44966 58068 44967 58068 44967 590 44966 590 44933 590 44967 58117 44933 58117 44983 58117 44973 590 44975 590 44968 590 44968 58070 44975 58070 44940 58070 44968 58071 44940 58071 44969 58071 44969 590 44940 590 44938 590 44969 590 44938 590 44970 590 44905 590 44904 590 44971 590 44971 58072 44904 58072 44946 58072 44971 590 44946 590 44972 590 44972 58073 44946 58073 44974 58073 44972 590 44974 590 44973 590 44973 58074 44974 58074 44944 58074 44973 590 44944 590 44975 590 44976 590 44977 590 44978 590 44978 590 44977 590 44979 590 44978 58075 44979 58075 44980 58075 44980 590 44979 590 44912 590 44980 590 44912 590 44981 590 44981 58076 44912 58076 44910 58076 44981 58077 44910 58077 44955 58077 44933 590 44982 590 44983 590 44983 58078 44982 58078 44985 58078 44983 590 44985 590 44984 590 44984 58118 44985 58118 44986 58118 44984 58080 44986 58080 44948 58080 44948 590 44986 590 44987 590 44948 58119 44987 58119 44949 58119 44988 58120 45306 58120 44989 58120 44988 58121 44989 58121 44990 58121 44990 58122 44989 58122 44991 58122 44990 58123 44991 58123 44992 58123 44992 58124 44991 58124 45012 58124 44992 58125 45012 58125 44993 58125 44993 58126 45012 58126 44994 58126 44993 58127 44994 58127 45556 58127 45359 58128 45554 58128 45562 58128 45358 58129 45360 58129 45021 58129 45021 58130 45360 58130 44995 58130 45021 58131 44995 58131 45562 58131 45562 58132 44995 58132 44996 58132 45562 58133 44996 58133 45359 58133 45021 58134 44997 58134 45358 58134 45358 58135 44997 58135 45011 58135 45358 58136 45011 58136 44998 58136 44998 58137 45011 58137 45329 58137 44998 58138 45329 58138 45357 58138 44989 58139 45306 58139 45000 58139 45012 58140 44991 58140 45013 58140 44994 58141 45012 58141 45016 58141 44991 58142 44989 58142 45007 58142 45007 58143 44989 58143 45000 58143 45007 58144 45000 58144 44999 58144 44999 58145 45000 58145 45001 58145 45001 58146 45002 58146 44999 58146 44999 58147 45002 58147 45308 58147 44999 58148 45308 58148 45010 58148 45308 58149 45003 58149 45010 58149 45010 58150 45003 58150 45006 58150 45010 58151 45006 58151 45004 58151 45329 58152 45011 58152 45314 58152 45314 58153 45011 58153 45004 58153 45314 58154 45004 58154 45005 58154 45005 58155 45004 58155 45006 58155 44991 58156 45007 58156 45013 58156 45013 58157 45007 58157 44999 58157 45013 58158 44999 58158 45008 58158 45008 58159 44999 58159 45010 58159 45008 58160 45010 58160 45009 58160 45009 58161 45010 58161 45004 58161 45009 58162 45004 58162 45015 58162 45015 58163 45004 58163 45011 58163 45015 58164 45011 58164 44997 58164 45012 58165 45013 58165 45016 58165 45016 58166 45013 58166 45008 58166 45016 58167 45008 58167 45017 58167 45017 58168 45008 58168 45009 58168 45017 58169 45009 58169 45020 58169 45020 58170 45009 58170 45015 58170 45020 58171 45015 58171 45014 58171 45014 58172 45015 58172 44997 58172 45014 58173 44997 58173 45021 58173 44994 58174 45016 58174 45563 58174 45563 58175 45016 58175 45017 58175 45563 58176 45017 58176 45018 58176 45018 58177 45017 58177 45020 58177 45018 58178 45020 58178 45019 58178 45019 58179 45020 58179 45014 58179 45019 58180 45014 58180 45564 58180 45564 58181 45014 58181 45021 58181 45564 58182 45021 58182 45562 58182 45206 58183 45022 58183 45023 58183 45206 58184 45023 58184 45204 58184 45204 58185 45023 58185 45024 58185 45204 58186 45024 58186 45025 58186 45025 58187 45024 58187 45026 58187 45025 58188 45026 58188 45213 58188 45213 58189 45026 58189 45028 58189 45213 58190 45028 58190 45027 58190 45027 58191 45028 58191 45029 58191 45027 58192 45029 58192 45208 58192 45206 58193 45216 58193 45022 58193 45022 58194 45216 58194 45030 58194 45077 58195 45051 58195 45318 58195 45318 58196 45051 58196 45033 58196 45318 58197 45033 58197 45031 58197 45031 58198 45033 58198 45032 58198 45032 58199 45033 58199 45034 58199 45034 58200 45033 58200 45035 58200 45034 58201 45035 58201 45310 58201 45310 58202 45035 58202 45038 58202 45310 58203 45038 58203 45036 58203 45036 58204 45038 58205 45037 58206 45037 58207 45038 58207 45056 58207 45037 58208 45056 58208 45039 58208 45039 58209 45056 58209 45057 58209 45039 58210 45057 58210 45341 58210 45040 58211 45341 58211 45064 58211 45064 58212 45341 58212 45057 58212 45065 58213 45058 58213 45326 58213 45326 58214 45058 58214 45041 58214 45043 58215 45042 58215 45044 58215 45043 58216 45044 58216 45045 58216 45045 58217 45044 58217 45047 58217 45045 58218 45047 58218 45046 58218 45132 58219 45133 58219 45059 58219 45132 58220 45059 58220 45085 58220 45046 58221 45047 58221 45048 58221 45048 58222 45047 58222 45084 58222 45048 58223 45084 58223 45062 58223 45053 58224 45078 58224 45049 58224 45049 58225 45078 58225 45050 58225 45049 58226 45050 58226 45080 58226 45051 58227 45097 58227 45033 58227 45033 58228 45097 58228 45052 58228 45033 58229 45052 58229 45035 58229 45035 58230 45052 58230 45038 58230 45038 58231 45052 58231 45078 58231 45038 58232 45078 58232 45056 58232 45056 58233 45078 58233 45053 58233 45056 58234 45053 58234 45054 58234 45054 58235 45055 58235 45056 58235 45056 58236 45055 58236 45058 58236 45056 58237 45058 58237 45057 58237 45057 58238 45058 58238 45064 58238 45059 58239 45060 58239 45085 58239 45085 58240 45060 58240 45061 58240 45085 58241 45061 58241 45062 58241 45062 58242 45061 58242 45063 58242 45062 58243 45063 58243 45048 58243 45048 58244 45063 58244 45064 58244 45048 58245 45064 58245 45065 58245 45065 58246 45064 58246 45058 58246 45108 58247 45107 58247 45076 58247 45125 58248 45565 58248 45126 58248 45126 9190 45565 9190 45066 9190 45126 58249 45066 58249 45113 58249 45113 58250 45066 58250 45067 58250 45113 58251 45067 58251 45115 58251 45230 58252 45068 58252 45102 58252 45076 58253 45107 58253 45073 58253 45073 58254 45107 58254 45110 58254 45073 58255 45110 58255 45070 58255 45069 58256 45104 58256 45076 58256 45076 58257 45104 58257 45103 58257 45076 58258 45103 58258 45108 58258 45070 58259 45071 58259 45073 58259 45073 58260 45071 58260 45072 58260 45073 58261 45072 58261 45067 58261 45067 58262 45072 58262 45111 58262 45067 58263 45111 58263 45115 58263 45102 9647 45101 9647 45230 9647 45230 58264 45101 58264 45074 58264 45230 58265 45074 58265 45075 58265 45075 58266 45074 58266 45099 58266 45075 58267 45099 58267 45076 58267 45076 58268 45099 58268 45105 58268 45076 58269 45105 58269 45069 58269 45051 58270 45077 58270 45093 58270 45078 58271 45079 58271 45050 58271 45116 58272 45317 58272 45118 58272 45118 58273 45317 58273 45080 58273 45050 58274 45079 58274 45080 58274 45080 58275 45079 58275 45081 58275 45080 58276 45081 58276 45118 58276 45044 58277 45042 58277 45130 58277 45130 58278 45148 58278 45044 58278 45044 58279 45148 58279 45150 58279 45044 58280 45150 58280 45047 58280 45047 58281 45150 58281 45082 58281 45047 58282 45082 58282 45084 58282 45084 58283 45082 58283 45083 58283 45084 58284 45083 58284 45062 58284 45062 58285 45083 58285 45161 58285 45062 58286 45161 58286 45085 58286 45085 58287 45161 58287 45147 58287 45085 58288 45147 58288 45132 58288 45086 58289 45342 58289 45133 58289 45087 58290 45088 58290 45142 58290 45142 58291 45088 58292 45089 58293 45142 58294 45089 58294 45090 58294 45138 58295 45091 58295 45092 58295 45092 58296 45091 58296 45094 58296 45092 58297 45094 58297 45093 58297 45093 58298 45094 58298 45095 58298 45093 58299 45095 58299 45051 58299 45051 58300 45095 58300 45096 58300 45051 58301 45096 58301 45097 58301 45097 58302 45096 58302 45098 58302 45097 58303 45098 58303 45052 58303 45100 58304 45141 58304 45099 58304 45099 58305 45074 58305 45100 58305 45100 58306 45074 58306 45101 58306 45100 58307 45101 58307 45142 58307 45142 58308 45101 58308 45102 58308 45142 58309 45102 58309 45087 58309 45140 58310 45109 58310 45103 58310 45103 58311 45104 58311 45140 58311 45140 58312 45104 58312 45069 58312 45140 58313 45069 58313 45141 58313 45141 58314 45069 58314 45105 58314 45141 58315 45105 58315 45099 58315 45106 58316 45110 58316 45153 58316 45153 58317 45110 58317 45107 58317 45153 58318 45107 58318 45109 58318 45109 58319 45107 58319 45108 58319 45109 58320 45108 58320 45103 58320 45112 58321 45071 58321 45106 58321 45106 58322 45071 58322 45070 58322 45106 58323 45070 58323 45110 58323 45114 58324 45111 58324 45112 58324 45112 58325 45111 58325 45072 58325 45112 58326 45072 58326 45071 58326 45139 58327 45113 58327 45114 58327 45114 58328 45113 58328 45115 58328 45114 58329 45115 58329 45111 58329 45120 58330 45127 58330 45117 58330 45116 58331 45118 58331 45117 58331 45117 58332 45118 58332 45119 58332 45117 58333 45119 58333 45120 58333 45127 58334 45121 58334 45122 58334 45122 58335 45121 58335 45123 58335 45123 58336 45124 58336 45122 58336 45122 58337 45124 58337 45125 58337 45122 58338 45125 58338 45139 58338 45139 58339 45125 58339 45126 58339 45139 58340 45126 58340 45113 58340 45127 58341 45122 58341 45117 58341 45117 58342 45122 58342 45166 58342 45117 58343 45166 58343 45128 58343 45128 58344 45166 58344 45129 58344 45128 58345 45129 58345 45331 58345 45331 58346 45129 58346 45164 58346 45331 58347 45164 58347 45332 58347 45332 58348 45164 58348 45167 58348 45332 58349 45167 58349 45323 58349 45323 58350 45167 58350 45130 58350 45323 58351 45130 58351 45339 58351 45339 58352 45130 58352 45042 58352 45339 58353 45042 58353 45131 58353 45132 58354 45147 58354 45133 58354 45133 58355 45147 58355 45155 58355 45133 58356 45155 58356 45086 58356 45086 58357 45155 58357 45157 58357 45086 58358 45157 58358 45134 58358 45134 58359 45157 58359 45158 58359 45134 58360 45158 58360 45135 58360 45135 58361 45158 58361 45145 58361 45135 58362 45145 58362 45319 58362 45319 58363 45145 58363 45137 58363 45319 58364 45137 58364 45136 58364 45136 58365 45137 58365 45142 58365 45136 58366 45142 58366 45092 58366 45092 58367 45142 58367 45090 58367 45092 58368 45090 58368 45138 58368 45122 58369 45139 58369 45152 58369 45152 58370 45139 58370 45114 58370 45152 58371 45114 58371 45112 58371 45140 58372 45141 58372 45171 58372 45171 58373 45141 58373 45100 58373 45082 58374 45150 58374 45483 58374 45100 58375 45142 58375 45171 58375 45171 58376 45142 58376 45137 58376 45171 58377 45137 58377 45143 58377 45143 58378 45137 58378 45145 58378 45143 58379 45145 58379 45144 58379 45144 58380 45145 58380 45158 58380 45144 58381 45158 58381 45475 58381 45161 58382 45146 58382 45147 58382 45147 58383 45146 58383 45154 58383 45147 58384 45154 58384 45155 58384 45130 58385 45169 58385 45148 58385 45148 58386 45169 58386 45149 58386 45148 58387 45149 58387 45150 58387 45150 58388 45149 58388 45151 58388 45150 58389 45151 58389 45483 58389 45112 58390 45106 58390 45152 58390 45152 58391 45106 58391 45153 58391 45152 58392 45153 58392 45171 58392 45171 58393 45153 58393 45109 58393 45171 58394 45109 58394 45140 58394 45154 58395 45156 58395 45155 58395 45155 58396 45156 58396 45479 58396 45155 58397 45479 58397 45157 58397 45157 58398 45479 58398 45477 58398 45157 58399 45477 58399 45158 58399 45158 58400 45477 58400 45159 58400 45158 58401 45159 58401 45475 58401 45483 58402 45160 58402 45082 58402 45082 58403 45160 58403 45481 58403 45082 58404 45481 58404 45083 58404 45083 58405 45481 58405 45162 58405 45083 58406 45162 58406 45161 58406 45161 58407 45162 58407 45163 58407 45161 58408 45163 58408 45146 58408 45397 58409 45164 58409 45165 58409 45165 58410 45164 58410 45129 58410 45165 58411 45129 58411 45152 58411 45152 58412 45129 58412 45166 58412 45152 58413 45166 58413 45122 58413 45397 58414 45489 58414 45164 58414 45164 58415 45489 58415 45487 58415 45164 58416 45487 58416 45167 58416 45167 58417 45487 58417 45168 58417 45167 58418 45168 58418 45130 58418 45130 58419 45168 58419 45486 58419 45130 58420 45486 58420 45169 58420 45170 58421 45187 58421 45179 58421 45172 58422 45171 58422 45385 58422 45385 58423 45171 58423 45143 58423 45172 58424 45173 58424 45171 58424 45171 58425 45173 58425 45174 58425 45171 58426 45174 58426 45175 58426 45175 58427 45174 58427 45176 58427 45175 58428 45176 58428 45182 58428 45182 58429 45176 58429 45387 58429 45182 58430 45387 58430 45177 58430 45187 58431 45178 58431 45179 58431 45179 58432 45178 58432 45181 58432 45179 58433 45181 58433 45180 58433 45180 58434 45181 58434 45182 58434 45180 58435 45182 58435 45388 58435 45388 58436 45182 58436 45177 58436 45170 58437 45179 58437 45185 58437 45185 58438 45179 58438 45183 58438 45185 58439 45183 58440 45184 58441 45428 58442 45273 58442 45429 58442 45429 58443 45273 58443 45185 58443 45429 58444 45185 58444 45186 58444 45186 58445 45185 58445 45184 58445 45188 58446 45178 58446 45187 58446 45187 58447 45170 58447 45188 58447 45188 58448 45170 58448 45185 58448 45188 58449 45185 58449 45273 58449 45273 58450 45189 58450 45188 58450 45188 58451 45189 58451 45190 58451 45188 58452 45190 58452 45191 58452 45194 58453 45201 58453 45192 58453 45192 58454 45201 58454 45193 58454 45194 58455 45192 58455 45195 58455 45195 58456 45192 58456 45188 58456 45195 58457 45188 58457 45191 58457 45201 58458 45202 58458 45193 58458 45193 58459 45202 58459 45197 58459 45193 58460 45197 58460 45196 58460 45196 58461 45197 58461 45199 58461 45196 58462 45199 58462 45198 58462 45198 58463 45199 58463 45209 58463 45198 58464 45209 58464 45200 58464 45237 58465 45221 58465 45203 58465 45201 58466 45237 58466 45202 58466 45202 58467 45237 58467 45203 58467 45202 590 45203 590 45197 590 45197 58468 45203 58468 45210 58468 45204 58469 45205 58469 45206 58469 45206 590 45205 590 45207 590 45206 590 45207 590 45216 590 45214 590 45208 590 45212 590 45212 58470 45208 58470 45209 58470 45210 590 45211 590 45197 590 45197 590 45211 590 45212 590 45197 590 45212 590 45199 590 45199 58471 45212 58471 45209 58471 45204 590 45025 590 45205 590 45205 58472 45025 58472 45213 58472 45205 590 45213 590 45214 590 45214 58473 45213 58473 45027 58473 45214 58474 45027 58474 45208 58474 45207 590 45215 590 45216 590 45216 590 45215 590 45217 590 45216 590 45217 590 45218 590 45218 590 45217 590 45219 590 45218 590 45219 590 45237 590 45237 58475 45219 58475 45220 58475 45237 58476 45220 58476 45221 58476 45246 58477 45222 58477 45223 58477 45223 58478 45222 58478 45218 58478 45223 58479 45218 58479 45243 58479 45243 58480 45218 58480 45237 58480 45224 58481 45225 58481 45234 58481 45234 58482 45225 58482 45236 58482 45236 58483 45225 58483 45226 58483 45236 58484 45226 58484 45246 58484 45246 58485 45226 58485 45227 58485 45246 58486 45227 58486 45222 58486 45230 58487 45075 58488 45228 58489 45228 58490 45229 58490 45230 58490 45230 58491 45229 58491 45232 58491 45230 58492 45232 58492 45231 58492 45231 58493 45232 58493 45233 58493 45231 58494 45233 58494 45234 58494 45234 58495 45233 58495 45235 58495 45234 58496 45235 58496 45224 58496 45234 58497 45236 58497 45252 58497 45246 58498 45223 58498 45247 58498 45243 58499 45237 58499 45244 58499 45244 58500 45237 58500 45238 58500 45244 58501 45238 58501 45239 58502 45239 58503 45238 58503 45240 58503 45239 58504 45240 58504 45241 58504 45241 58505 45240 58505 45242 58505 45241 58506 45242 58506 45269 58507 45269 58508 45242 58508 45270 58508 45223 58509 45243 58509 45247 58509 45247 58510 45243 58510 45244 58510 45247 58511 45244 58511 45245 58511 45245 58512 45244 58512 45239 58512 45245 58513 45239 58513 45250 58513 45250 58514 45239 58514 45241 58514 45250 58515 45241 58515 45268 58515 45268 58516 45241 58516 45269 58516 45236 58517 45246 58517 45252 58517 45252 58518 45246 58518 45247 58518 45252 58519 45247 58519 45248 58519 45248 58520 45247 58520 45245 58520 45248 58521 45245 58521 45249 58521 45249 58522 45245 58522 45250 58522 45249 58523 45250 58523 45251 58523 45251 58524 45250 58524 45268 58524 45231 58525 45234 58525 45255 58525 45255 58526 45234 58526 45252 58526 45255 58527 45252 58527 45258 58527 45258 58528 45252 58528 45248 58528 45258 58529 45248 58529 45253 58529 45253 58530 45248 58530 45249 58530 45253 58531 45249 58531 45272 58531 45272 58532 45249 58532 45251 58532 45230 58533 45231 58533 45254 58533 45254 58534 45231 58534 45255 58534 45254 58535 45255 58535 45256 58535 45256 58536 45255 58536 45258 58536 45256 58537 45258 58537 45257 58537 45257 58538 45258 58538 45253 58538 45257 58539 45253 58539 45259 58539 45259 58540 45253 58540 45272 58540 45290 58541 45261 58541 45280 58541 45280 58542 45261 58542 45320 58542 45280 58543 45320 58543 45321 58543 45295 58544 45363 58544 45290 58544 45290 58545 45363 58545 45260 58545 45290 58546 45260 58546 45261 58546 45262 58547 45263 58547 45264 58547 45264 58548 45263 58548 45265 58548 45264 58549 45265 58549 45295 58549 45295 58550 45265 58550 45362 58550 45295 58551 45362 58551 45363 58551 45262 58552 45266 58552 45428 58552 45428 58553 45266 58553 45267 58553 45428 58554 45267 58554 45274 58554 45268 58555 45269 58555 45273 58555 45273 58556 45269 58556 45270 58556 45273 58557 45270 58557 45189 58557 45264 58558 45277 58558 45262 58558 45262 58559 45277 58559 45271 58559 45262 58560 45271 58560 45266 58560 45428 58561 45272 58561 45273 58561 45273 58562 45272 58562 45251 58562 45273 58563 45251 58563 45268 58563 45274 58564 45275 58564 45428 58564 45428 58565 45275 58565 45259 58565 45428 58566 45259 58566 45272 58566 45304 58567 45276 58567 45302 58567 45302 58568 45276 58568 45277 58568 45302 58569 45277 58569 45301 58569 45301 58570 45277 58570 45264 58570 45280 58571 45321 58571 45278 58571 45295 58572 45290 58572 45291 58572 45264 58573 45295 58573 45296 58573 45290 58574 45280 58574 45279 58574 45279 58575 45280 58575 45278 58575 45279 58576 45278 58576 45282 58576 45282 58577 45278 58577 45309 58577 45309 58578 45281 58578 45282 58578 45282 58579 45281 58579 45283 58579 45282 58580 45283 58580 45285 58580 45283 58581 45284 58581 45285 58581 45285 58582 45284 58582 45286 58582 45285 58583 45286 58583 45289 58583 45287 58584 45293 58584 45288 58584 45288 58585 45293 58585 45289 58585 45288 58586 45289 58586 45307 58586 45307 58587 45289 58587 45286 58587 45290 58588 45279 58588 45291 58588 45291 58589 45279 58589 45282 58589 45291 58590 45282 58590 45292 58590 45292 58591 45282 58591 45285 58591 45292 58592 45285 58592 45298 58592 45298 58593 45285 58593 45289 58593 45298 58594 45289 58594 45299 58594 45299 58595 45289 58595 45293 58595 45299 58596 45293 58596 45294 58596 45295 58597 45291 58597 45296 58597 45296 58598 45291 58598 45292 58598 45296 58599 45292 58599 45297 58599 45297 58600 45292 58600 45298 58600 45297 58601 45298 58601 45303 58601 45303 58602 45298 58602 45299 58602 45303 58603 45299 58603 45305 58603 45305 58604 45299 58604 45294 58604 45305 58605 45294 58605 45300 58605 45264 58606 45296 58606 45301 58606 45301 58607 45296 58607 45297 58607 45301 58608 45297 58608 45302 58608 45302 58609 45297 58609 45303 58609 45302 58610 45303 58610 45304 58610 45304 58611 45303 58611 45305 58611 45304 58612 45305 58612 45276 58612 45276 58613 45305 58613 45300 58613 45276 58614 45300 58614 45277 58614 45306 58615 45287 58615 45000 58615 45000 58616 45287 58616 45288 58616 45000 58617 45288 58617 45001 58617 45001 58618 45288 58618 45002 58618 45002 58619 45288 58619 45307 58619 45002 58620 45307 58620 45308 58620 45307 58621 45286 58621 45308 58621 45308 58622 45286 58622 45284 58622 45308 58623 45284 58623 45003 58623 45003 58624 45284 58624 45283 58624 45003 58625 45283 58625 45006 58625 45006 58626 45283 58626 45281 58626 45006 58627 45281 58627 45005 58627 45005 58628 45281 58628 45309 58628 45005 58629 45309 58629 45314 58630 45321 58631 45318 58631 45278 58631 45278 58632 45318 58632 45031 58632 45278 58633 45031 58633 45309 58633 45309 58634 45031 58634 45032 58634 45036 58635 45311 58635 45310 58635 45310 58636 45311 58636 45315 58636 45310 58637 45315 58637 45034 58638 45316 58639 45329 58639 45312 58639 45312 58640 45329 58640 45314 58640 45312 58641 45314 58641 45313 58641 45313 58642 45314 58642 45309 58642 45313 58643 45309 58643 45315 58643 45315 58644 45309 58644 45032 58644 45315 58645 45032 58645 45034 58645 45340 58646 45311 58646 45036 58646 45329 58647 45316 58647 45317 58647 45318 58648 45321 58648 45077 58648 45077 58649 45321 58649 45093 58649 45135 58650 45319 58650 45320 58650 45320 58651 45319 58651 45136 58651 45320 58652 45136 58652 45321 58652 45321 58653 45136 58653 45092 58653 45321 58654 45092 58654 45093 58654 45322 58655 45327 58655 45364 58655 45332 58656 45323 58656 45334 58656 45334 58657 45323 58657 45338 58657 45324 58658 45325 58658 45335 58658 45335 58659 45325 58659 45326 58659 45364 58660 45327 58660 45379 58660 45379 58661 45327 58661 45328 58661 45379 58662 45328 58662 45380 58662 45317 58663 45116 58663 45329 58663 45329 58664 45116 58664 45117 58664 45329 58665 45117 58665 45357 58665 45357 58666 45117 58666 45128 58666 45357 58667 45128 58667 45330 58667 45330 58668 45128 58668 45331 58668 45330 58669 45331 58669 45373 58669 45373 58670 45331 58670 45332 58670 45373 58671 45332 58671 45333 58671 45333 58672 45332 58672 45334 58672 45335 58673 45322 58673 45324 58673 45324 58674 45322 58674 45364 58674 45324 58675 45364 58675 45336 58675 45336 58676 45364 58676 45355 58676 45336 58677 45355 58677 45337 58677 45337 58678 45355 58678 45377 58678 45337 58679 45377 58679 45131 58679 45131 58680 45377 58680 45338 58680 45131 58681 45338 58681 45339 58681 45339 58682 45338 58682 45323 58682 45036 58683 45037 58683 45340 58683 45340 58684 45037 58684 45039 58684 45340 58685 45039 58685 45041 58685 45041 58686 45039 58686 45341 58686 45041 58687 45341 58687 45326 58687 45326 58688 45341 58688 45040 58688 45326 58689 45040 58689 45335 58689 45328 58690 45342 58690 45380 58690 45380 58691 45342 58691 45086 58691 45380 58692 45086 58692 45343 58692 45343 58693 45086 58693 45134 58693 45343 58694 45134 58694 45344 58694 45344 58695 45134 58695 45382 58695 45135 58696 45320 58696 45134 58696 45134 58697 45320 58697 45361 58697 45134 58698 45361 58698 45382 58698 45367 58699 45346 58699 45345 58699 45345 58700 45346 58700 45369 58700 45354 58701 45371 58701 45346 58701 45346 58702 45371 58702 45347 58702 45346 58703 45347 58703 45369 58703 45366 58704 45349 58704 45348 58704 45348 58705 45349 58705 45371 58705 45348 58706 45371 58707 45350 58708 45350 58709 45371 58709 45354 58709 45366 58710 45348 58710 45364 58710 45364 58711 45348 58711 45351 58711 45364 58712 45351 58712 45355 58712 45378 58713 45352 58713 45379 58713 45414 58714 45353 58714 45346 58714 45346 58715 45353 58715 45412 58715 45346 58716 45412 58716 45354 58716 45354 58717 45412 58717 45356 58717 45354 58718 45356 58718 45350 58718 45377 58719 45355 58719 45411 58719 45411 58720 45355 58720 45351 58720 45411 58721 45351 58721 45356 58721 45356 58722 45351 58722 45348 58722 45356 58723 45348 58723 45350 58723 45357 58724 45330 58724 44998 58724 44998 58725 45330 58725 45358 58725 45359 58726 45373 58726 45554 58726 45554 58727 45373 58727 45399 58727 45554 58728 45399 58728 45502 58728 45359 58729 44996 58729 45373 58729 45373 58730 44996 58730 44995 58730 45373 58731 44995 58731 45330 58731 45330 58732 44995 58732 45360 58732 45330 58733 45360 58733 45358 58733 45361 58734 45363 58734 45382 58734 45382 58735 45363 58735 45362 58735 45382 58736 45362 58736 45265 58736 45428 58737 45430 58737 45262 58737 45262 58738 45430 58738 45382 58738 45262 58739 45382 58739 45263 58739 45263 58740 45382 58740 45265 58740 45320 58741 45261 58741 45361 58741 45361 58742 45261 58742 45260 58742 45361 58743 45260 58743 45363 58743 45379 58744 45352 58744 45364 58744 45364 58745 45352 58745 45365 58745 45364 58746 45365 58746 45366 58746 45366 58747 45365 58747 45372 58747 45366 58748 45372 58748 45349 58748 45346 58749 45367 58749 45414 58749 45414 58750 45367 58750 45368 58750 45414 58751 45368 58751 45416 58751 45416 58752 45368 58752 45345 58752 45416 58753 45345 58753 45417 58753 45417 58754 45345 58754 45369 58754 45417 58755 45369 58755 45418 58755 45418 58756 45369 58756 45370 58756 45370 58757 45369 58757 45347 58757 45370 58758 45347 58758 45372 58758 45372 58759 45347 58759 45371 58759 45372 58760 45371 58760 45349 58760 45402 58761 45401 58761 45373 58761 45373 58762 45401 58762 45400 58762 45373 58763 45400 58763 45399 58763 45402 58764 45373 58764 45404 58764 45404 58765 45373 58765 45333 58765 45404 58766 45333 58766 45374 58766 45374 58767 45333 58767 45334 58767 45374 58768 45334 58768 45375 58768 45375 58769 45334 58769 45406 58769 45406 58770 45334 58770 45338 58770 45406 58771 45338 58771 45407 58771 45411 58772 45410 58772 45377 58772 45377 58773 45410 58773 45376 58773 45377 58774 45376 58774 45338 58774 45338 58775 45376 58775 45409 58775 45338 58776 45409 58776 45407 58776 45378 58777 45379 58777 45421 58777 45421 58778 45379 58778 45380 58778 45421 58779 45380 58779 45422 58779 45422 58780 45380 58780 45424 58780 45424 58781 45380 58781 45343 58781 45424 58782 45343 58782 45425 58782 45425 58783 45343 58783 45381 58783 45381 58784 45343 58784 45344 58784 45381 58785 45344 58785 45384 58785 45430 58786 45433 58786 45382 58786 45382 58787 45433 58787 45434 58787 45382 58788 45434 58788 45344 58788 45344 58789 45434 58789 45383 58789 45344 58790 45383 58791 45384 58791 45496 58792 45501 58793 45390 58794 45389 58795 45502 58795 45399 58795 45173 58796 45172 58796 45144 58796 45144 58797 45172 58797 45385 58797 45144 58798 45385 58799 45143 58800 45177 58801 45387 58801 45386 58801 45386 58802 45387 58802 45176 58802 45386 58803 45176 58803 45174 58803 45179 58804 45180 58804 45435 58804 45435 58805 45180 58805 45388 58805 45429 58806 45186 58806 45431 58806 45431 58807 45186 58807 45184 58807 45431 58808 45184 58809 45183 58810 45389 58811 45399 58811 45398 58811 45496 58812 45390 58812 45495 58812 45498 58813 45395 58813 45391 58813 45391 58814 45395 58814 45392 58814 45391 58815 45392 58816 45393 58817 45500 58818 45394 58819 45395 58820 45395 58821 45394 58821 45396 58821 45395 58822 45396 58822 45392 58822 45397 58823 45165 58823 45492 58823 45501 58824 45398 58824 45390 58824 45390 58825 45398 58825 45399 58825 45390 58826 45399 58826 45449 58826 45399 58827 45400 58827 45449 58827 45449 58828 45400 58828 45401 58828 45449 58829 45401 58829 45403 58829 45401 58830 45402 58830 45403 58830 45403 58831 45402 58831 45404 58831 45403 58832 45404 58832 45447 58832 45404 58833 45374 58833 45447 58833 45447 58834 45374 58834 45375 58834 45447 58835 45375 58835 45405 58835 45375 58836 45406 58836 45405 58836 45405 58837 45406 58837 45407 58837 45405 58838 45407 58838 45408 58838 45408 58839 45407 58839 45409 58839 45408 58840 45409 58840 45445 58840 45409 58841 45376 58841 45445 58841 45445 58842 45376 58842 45410 58842 45445 58843 45410 58843 45444 58843 45410 58844 45411 58844 45444 58844 45444 58845 45411 58845 45356 58845 45444 58846 45356 58846 45443 58846 45443 58847 45356 58847 45412 58847 45443 58848 45412 58848 45413 58848 45412 58849 45353 58849 45413 58849 45413 58850 45353 58850 45414 58850 45413 58851 45414 58851 45415 58851 45415 58852 45414 58852 45416 58852 45415 58853 45416 58853 45441 58853 45416 58854 45417 58854 45441 58854 45441 58855 45417 58855 45418 58855 45441 58856 45418 58856 45419 58856 45418 58857 45370 58857 45419 58857 45419 58858 45370 58858 45372 58858 45419 58859 45372 58859 45440 58859 45440 58860 45372 58860 45365 58860 45440 58861 45365 58861 45438 58861 45365 58862 45352 58862 45438 58862 45438 58863 45352 58863 45378 58863 45438 58864 45378 58864 45420 58864 45378 58865 45421 58865 45420 58865 45420 58866 45421 58866 45422 58866 45420 58867 45422 58867 45423 58867 45423 58868 45422 58868 45424 58868 45423 58869 45424 58869 45426 58869 45426 58870 45424 58870 45425 58870 45425 58871 45381 58871 45426 58871 45426 58872 45381 58872 45384 58872 45426 58873 45384 58873 45427 58873 45427 58874 45384 58874 45383 58874 45427 58875 45383 58875 45432 58875 45428 58876 45429 58876 45430 58876 45430 58877 45429 58877 45431 58877 45430 58878 45431 58878 45433 58878 45433 58879 45431 58879 45432 58879 45433 58880 45432 58880 45434 58880 45434 58881 45432 58881 45383 58881 45183 58882 45179 58882 45431 58882 45431 58883 45179 58883 45435 58883 45431 58884 45435 58884 45432 58884 45432 58885 45435 58885 45450 58885 45432 58886 45450 58886 45427 58886 45427 58887 45450 58887 45451 58887 45427 58888 45451 58888 45426 58888 45426 58889 45451 58889 45453 58889 45426 58890 45453 58890 45423 58890 45423 58891 45453 58891 45436 58891 45423 58892 45436 58892 45420 58892 45420 58893 45436 58893 45437 58893 45420 58894 45437 58894 45438 58894 45438 58895 45437 58895 45439 58895 45438 58896 45439 58896 45440 58896 45440 58897 45439 58897 45455 58897 45440 58898 45455 58898 45419 58898 45419 58899 45455 58899 45457 58899 45419 58900 45457 58900 45441 58900 45441 58901 45457 58901 45459 58901 45441 58902 45459 58902 45415 58902 45415 58903 45459 58903 45442 58903 45415 58904 45442 58904 45413 58904 45413 58905 45442 58905 45461 58905 45413 58906 45461 58906 45443 58906 45443 58907 45461 58907 45464 58907 45443 58908 45464 58908 45444 58908 45444 58909 45464 58909 45446 58909 45444 58910 45446 58910 45445 58910 45445 58911 45446 58911 45465 58911 45445 58912 45465 58912 45408 58912 45408 58913 45465 58913 45467 58913 45408 58914 45467 58914 45405 58914 45405 58915 45467 58915 45469 58915 45405 58916 45469 58916 45447 58916 45447 58917 45469 58917 45470 58917 45447 58918 45470 58918 45403 58918 45403 58919 45470 58919 45448 58919 45403 58920 45448 58920 45449 58920 45449 58921 45448 58921 45473 58921 45449 58922 45473 58922 45390 58922 45390 58923 45473 58923 45395 58923 45390 58924 45395 58924 45495 58924 45495 58925 45395 58925 45498 58925 45388 58926 45177 58926 45435 58926 45435 58927 45177 58927 45386 58927 45435 58928 45386 58928 45450 58928 45450 58929 45386 58929 45474 58929 45450 58930 45474 58930 45451 58930 45451 58931 45474 58931 45452 58931 45451 58932 45452 58932 45453 58932 45453 58933 45452 58933 45476 58933 45453 58934 45476 58934 45436 58934 45436 58935 45476 58935 45478 58935 45436 58936 45478 58936 45437 58936 45437 58937 45478 58937 45454 58937 45437 58938 45454 58938 45439 58938 45439 58939 45454 58939 45456 58939 45439 58940 45456 58940 45455 58940 45455 58941 45456 58941 45480 58941 45455 58942 45480 58942 45457 58942 45457 58943 45480 58943 45458 58943 45457 58944 45458 58944 45459 58944 45459 58945 45458 58945 45460 58945 45459 58946 45460 58946 45442 58946 45442 58947 45460 58947 45462 58947 45442 58948 45462 58948 45461 58948 45461 58949 45462 58949 45482 58949 45461 58950 45482 58950 45464 58950 45464 58951 45482 58951 45463 58951 45464 58952 45463 58952 45446 58952 45446 58953 45463 58953 45484 58953 45446 58954 45484 58954 45465 58954 45465 58955 45484 58955 45466 58955 45465 58956 45466 58956 45467 58956 45467 58957 45466 58957 45468 58957 45467 58958 45468 58958 45469 58958 45469 58959 45468 58959 45485 58959 45469 58960 45485 58960 45470 58960 45470 58961 45485 58961 45471 58961 45470 58962 45471 58962 45448 58962 45448 58963 45471 58963 45472 58963 45448 58964 45472 58964 45473 58964 45473 58965 45472 58965 45488 58965 45473 58966 45488 58966 45395 58966 45395 58967 45488 58967 45490 58967 45395 58968 45490 58968 45500 58968 45500 58969 45490 58969 45491 58969 45174 58970 45173 58970 45386 58970 45386 58971 45173 58971 45144 58971 45386 58972 45144 58972 45474 58972 45474 58973 45144 58973 45475 58973 45474 58974 45475 58974 45452 58974 45452 58975 45475 58975 45159 58975 45452 58976 45159 58976 45476 58976 45476 58977 45159 58977 45477 58977 45476 58978 45477 58978 45478 58978 45478 58979 45477 58979 45479 58979 45478 58980 45479 58980 45454 58980 45454 58981 45479 58981 45156 58981 45454 58982 45156 58982 45456 58982 45456 58983 45156 58983 45154 58983 45456 58984 45154 58984 45480 58984 45480 58985 45154 58985 45146 58985 45480 58986 45146 58986 45458 58986 45458 58987 45146 58987 45163 58987 45458 58988 45163 58988 45460 58988 45460 58989 45163 58989 45162 58989 45460 58990 45162 58990 45462 58990 45462 58991 45162 58991 45481 58991 45462 58992 45481 58992 45482 58992 45482 58993 45481 58993 45160 58993 45482 58994 45160 58994 45463 58994 45463 58995 45160 58995 45483 58995 45463 58996 45483 58996 45484 58996 45484 58997 45483 58997 45151 58997 45484 58998 45151 58998 45466 58998 45466 58999 45151 58999 45149 58999 45466 59000 45149 59000 45468 59000 45468 59001 45149 59001 45169 59001 45468 59002 45169 59002 45485 59002 45485 59003 45169 59003 45486 59003 45485 59004 45486 59004 45471 59004 45471 59005 45486 59005 45168 59005 45471 59006 45168 59006 45472 59006 45472 59007 45168 59007 45487 59007 45472 59008 45487 59008 45488 59008 45488 59009 45487 59009 45489 59009 45488 59010 45489 59010 45490 59010 45490 59011 45489 59011 45397 59011 45490 59012 45397 59012 45491 59012 45491 59013 45397 59013 45492 59013 45497 59014 45493 59014 45494 59014 45498 59015 45391 59016 45393 59017 45495 59018 45497 59018 45496 59018 45496 59019 45497 59020 45501 59021 45495 59022 45498 59022 45497 59022 45497 59023 45498 59023 45393 59023 45497 59024 45393 59024 45499 59024 45499 59025 45393 59025 45392 59025 45392 59026 45396 59026 45499 59026 45499 59027 45396 59027 45394 59027 45499 59028 45394 59028 45152 59028 45152 59029 45394 59030 45500 59031 45500 59032 45491 59032 45152 59032 45152 59033 45491 59033 45492 59033 45152 59034 45492 59034 45165 59034 45497 59035 45494 59035 45501 59035 45501 59036 45494 59036 45551 59036 45501 59037 45551 59037 45398 59037 45552 59038 45502 59038 45551 59038 45551 59039 45502 59039 45389 59039 45551 59040 45389 59040 45398 59040 45511 59041 45503 59041 45512 59041 45512 59042 45503 59042 45528 59042 45505 59043 45513 59043 45504 59043 45505 59044 45504 59044 45507 59044 45507 58462 45504 58462 45506 58462 45507 58462 45506 58462 45538 58462 45538 59045 45506 59045 45508 59045 45538 58459 45508 58459 45509 58459 45509 59046 45508 59046 45510 59046 45509 59047 45510 59047 45531 59047 45531 59048 45510 59048 45511 59048 45531 59049 45511 59049 45512 59049 45505 59050 45540 59050 45513 59050 45513 59051 45540 59051 45514 59051 45519 59052 45518 59052 45515 59052 45516 59053 45517 59053 45518 59053 45518 59054 45517 59054 45550 59054 45518 59055 45550 59055 45515 59055 45515 59056 45520 59056 45519 59056 45519 59057 45520 59057 45548 59057 45519 59058 45548 59058 45521 59058 45521 59059 45548 59059 45547 59059 45521 59060 45547 59060 45522 59060 45528 590 45523 590 45524 590 45524 590 45523 590 45525 590 45525 59061 45523 59061 45521 59061 45525 590 45521 590 45526 590 45524 590 45527 590 45528 590 45528 59062 45527 59062 45529 59062 45528 590 45529 590 45512 590 45512 590 45529 590 45530 590 45512 59063 45530 59063 45531 59063 45531 590 45530 590 45537 590 45531 590 45537 590 45509 590 45544 590 45532 590 45534 590 45534 59064 45532 59064 45533 59064 45534 590 45533 590 45522 590 45522 59065 45533 59065 45535 59065 45522 590 45535 590 45521 590 45521 59066 45535 59066 45536 59066 45521 59067 45536 59067 45526 59067 45509 590 45537 590 45538 590 45538 59068 45537 59068 45541 59068 45538 59069 45541 59069 45507 59069 45544 590 45539 590 45532 590 45532 59070 45539 59070 45540 59070 45532 590 45540 590 45541 590 45541 59071 45540 59071 45505 59071 45541 59072 45505 59072 45507 59072 45520 59073 45549 59073 45548 59073 45548 59074 45549 59074 45546 59074 45514 59075 45540 59075 45539 59075 45514 59076 45539 59076 45542 59076 45542 59077 45539 59077 45544 59077 45542 59078 45544 59078 45543 59078 45543 59079 45544 59079 45534 59079 45543 59080 45534 59080 45545 59080 45545 59081 45534 59081 45522 59081 45545 59082 45522 59082 45546 59082 45546 59083 45522 59083 45547 59083 45546 59084 45547 59084 45548 59084 45494 59085 45493 59085 45549 59085 45520 59086 45515 59086 45549 59086 45549 59087 45515 59087 45550 59087 45551 59088 45494 59088 45552 59088 45552 59089 45494 59089 45549 59089 45552 59090 45549 59090 45517 59090 45517 59091 45549 59091 45550 59091 45553 59092 45554 59092 45502 59092 45552 59093 45517 59093 45516 59093 45553 59094 45555 59094 45554 59094 45554 59095 45555 59095 45556 59095 45554 59096 45556 59096 45562 59096 45557 59097 45572 59097 45502 59097 45502 59098 45572 59098 45558 59098 45502 59099 45558 59099 45553 59099 45563 59100 45018 59100 45019 59100 45516 59101 45559 59101 45552 59101 45552 59102 45559 59102 45560 59102 45552 59103 45560 59103 45502 59103 45502 59104 45560 59104 45561 59104 45502 59105 45561 59105 45557 59105 45556 59106 44994 59106 45562 59106 45562 59107 44994 59108 45563 59109 45562 59110 45563 59110 45564 59110 45564 59111 45563 59111 45019 59111 45066 59112 45565 59112 45566 59112 45066 59113 45566 59113 45567 59113 45567 59114 45566 59114 45568 59114 45567 59115 45568 59115 45570 59115 45570 59116 45568 59116 45569 59116 45570 59117 45569 59117 45571 59117 45571 59118 45569 59118 45572 59118 45571 59119 45572 59119 45557 59119 45573 590 45574 590 45578 590 45576 590 45575 590 45577 590 45577 59120 45575 59120 45607 59120 45577 590 45607 590 45583 590 45605 590 45580 590 45607 590 45576 590 45577 590 45578 590 45578 59121 45577 59121 45579 59121 45578 59122 45579 59122 45573 59122 45580 590 45581 590 45607 590 45607 59123 45581 59123 45582 59123 45607 59124 45582 59124 45583 59124 45574 590 45584 590 45578 590 45578 59125 45584 59125 45585 59125 45578 59126 45585 59126 45593 59126 45593 59127 45586 59127 45591 59127 45587 590 45588 590 45606 590 45600 590 45589 590 45593 590 45593 59128 45589 59128 45590 59128 45593 59129 45590 59129 45586 59129 45591 590 45592 590 45593 590 45593 59130 45592 59130 45594 59130 45593 59131 45594 59131 45578 59131 45588 590 45595 590 45606 590 45606 59132 45595 59132 45596 59132 45606 59133 45596 59133 45597 59133 45598 590 45604 590 45599 590 45599 590 45604 590 45602 590 45600 590 45601 590 45589 590 45589 590 45601 590 45602 590 45589 590 45602 590 45603 590 45603 590 45602 590 45604 590 45605 59134 45607 59134 45606 59134 45606 59135 45607 59135 45608 59135 45606 59136 45608 59136 45587 59136 45597 59137 45609 59137 45606 59137 45606 59138 45609 59138 45610 59138 45606 59139 45610 59139 45611 59139 45661 59140 45612 59140 45662 59140 45662 59141 45612 59141 45613 59141 45662 59142 45613 59142 45615 59142 45615 59143 45613 59143 45614 59143 45615 59144 45614 59144 45616 59144 45616 59145 45614 59145 45617 59145 45616 59146 45617 59146 45619 59146 45619 59147 45617 59147 45618 59147 45619 59147 45618 59147 45620 59147 45620 59148 45618 59148 45621 59148 45620 59149 45621 59149 45622 59149 45622 59150 45621 59150 45624 59150 45622 59150 45624 59150 45623 59150 45623 59151 45624 59151 45625 59151 45623 59152 45625 59152 45626 59152 45626 59153 45625 59153 45627 59153 45626 59154 45627 59154 45628 59154 45628 59155 45627 59155 45630 59155 45628 59156 45630 59156 45629 59156 45629 59157 45630 59157 45631 59157 45629 59158 45631 59158 45632 59158 45632 59159 45631 59159 45633 59159 45632 59160 45633 59160 45634 59160 45634 59161 45633 59161 45636 59161 45634 59162 45636 59162 45635 59162 45635 59163 45636 59163 45637 59163 45635 59164 45637 59164 45638 59164 45638 59165 45637 59165 45640 59165 45638 59166 45640 59166 45639 59166 45639 59167 45640 59167 45641 59167 45639 59167 45641 59167 45642 59167 45642 59168 45641 59168 45643 59168 45642 59169 45643 59169 45644 59169 45644 59170 45643 59170 45645 59170 45644 59171 45645 59171 45646 59171 45646 59172 45645 59172 45647 59172 45646 59173 45647 59173 45648 59173 45648 59174 45647 59174 45649 59174 45648 59175 45649 59175 45650 59175 45650 59176 45649 59176 45652 59176 45650 59177 45652 59177 45651 59177 45651 59178 45652 59178 45654 59178 45651 59179 45654 59179 45653 59179 45653 59180 45654 59180 45655 59180 45653 59181 45655 59181 45656 59181 45656 59182 45655 59182 45657 59182 45656 59183 45657 59183 45659 59183 45659 59184 45657 59184 45658 59184 45659 59185 45658 59185 45660 59185 45660 59186 45658 59186 45661 59186 45660 59187 45661 59187 45662 59187 45663 590 45664 590 45676 590 45685 590 45665 590 45684 590 45663 590 45676 590 45690 590 45666 590 45676 590 45692 590 45692 59188 45676 59188 45667 59188 45692 59189 45667 59189 45668 59189 45666 590 45669 590 45676 590 45676 59190 45669 59190 45670 59190 45676 59191 45670 59191 45671 59191 45671 590 45672 590 45676 590 45676 59192 45672 59192 45673 59192 45676 59193 45673 59193 45674 59193 45664 590 45675 590 45676 590 45676 59194 45675 59194 45677 59194 45676 590 45677 590 45678 590 45678 590 45679 590 45676 590 45676 59195 45679 59195 45680 59195 45676 590 45680 590 45681 590 45699 590 45682 590 45684 590 45684 590 45682 590 45683 590 45684 59196 45683 59196 45685 59196 45665 590 45686 590 45684 590 45684 59197 45686 59197 45687 59197 45684 59198 45687 59198 45694 59198 45674 590 45688 590 45676 590 45676 59199 45688 59199 45689 59199 45676 59200 45689 59200 45690 59200 45668 590 45691 590 45692 590 45692 59201 45691 59201 45684 59201 45692 590 45684 590 45693 590 45693 590 45684 590 45694 590 45684 590 45695 590 45699 590 45699 59202 45695 59202 45696 59202 45699 59203 45696 59203 45697 59203 45697 590 45698 590 45699 590 45699 590 45698 590 45700 590 45699 590 45700 590 45701 590 45735 59204 45720 59204 45702 59204 45702 590 45720 590 45726 590 45740 59205 45731 59205 45738 59205 45712 59206 45706 59206 45703 59206 45716 590 45704 590 45715 590 45719 590 45720 590 45712 590 45712 590 45720 590 45705 590 45712 590 45705 590 45706 590 45707 59207 45738 59207 45708 59207 45708 59208 45738 59208 45702 59208 45738 590 45709 590 45702 590 45702 59209 45709 59209 45710 59209 45702 59210 45710 59210 45711 59210 45703 590 45713 590 45712 590 45712 59211 45713 59211 45716 59211 45712 59212 45716 59212 45714 59212 45715 590 45717 590 45716 590 45716 590 45717 590 45718 590 45716 590 45718 590 45714 590 45719 590 45721 590 45720 590 45720 59213 45721 59213 45722 59213 45720 59214 45722 59214 45723 59214 45723 59215 45724 59215 45720 59215 45720 59216 45724 59216 45725 59216 45720 59217 45725 59217 45726 59217 45707 59218 45727 59218 45738 59218 45738 59219 45727 59219 45728 59219 45738 59220 45728 59220 45736 59220 45729 590 45730 590 45731 590 45731 590 45730 590 45732 590 45731 59221 45732 59221 45738 59221 45711 590 45733 590 45702 590 45702 59222 45733 59222 45734 59222 45702 59223 45734 59223 45735 59223 45736 590 45737 590 45738 590 45738 59224 45737 59224 45739 59224 45738 59225 45739 59225 45740 59225 45741 590 45742 590 45769 590 45769 59226 45742 59226 45743 59226 45769 59227 45743 59227 45767 59227 45765 59228 45759 59228 45744 59228 45745 590 45746 590 45769 590 45769 590 45746 590 45747 590 45769 59229 45747 59229 45748 59229 45748 590 45749 590 45769 590 45769 59230 45749 59230 45750 59230 45769 590 45750 590 45741 590 45758 590 45752 590 45751 590 45751 590 45752 590 45753 590 45754 590 45756 590 45755 590 45755 59231 45756 59231 45752 59231 45755 59232 45752 59232 45757 59232 45757 59233 45752 59233 45758 59233 45759 590 45760 590 45744 590 45744 590 45760 590 45761 590 45744 59234 45761 59234 45771 59234 45762 59235 45763 59235 45769 59235 45769 59236 45763 59236 45764 59236 45769 59237 45764 59237 45777 59237 45765 590 45744 590 45755 590 45755 590 45744 590 45766 590 45755 590 45766 590 45754 590 45767 59238 45768 59238 45769 59238 45769 59239 45768 59239 45744 59239 45769 590 45744 590 45770 590 45770 590 45744 590 45771 590 45772 590 45773 590 45774 590 45774 590 45773 590 45775 590 45774 590 45775 590 45769 590 45769 590 45775 590 45776 590 45769 59240 45776 59240 45762 59240 45777 590 45778 590 45769 590 45769 59241 45778 59241 45779 59241 45769 59242 45779 59242 45745 59242 45839 59243 45840 59243 45780 59243 45780 59244 45840 59244 45782 59244 45780 59245 45782 59245 45781 59245 45781 59246 45782 59246 45783 59246 45781 59247 45783 59247 45784 59247 45784 59248 45783 59248 45785 59248 45784 59249 45785 59249 45786 59249 45786 59250 45785 59250 45788 59250 45786 59251 45788 59251 45787 59251 45787 59252 45788 59252 45841 59252 45787 59253 45841 59253 45789 59253 45789 59254 45841 59254 45790 59254 45789 59255 45790 59255 45791 59255 45791 59256 45790 59256 45844 59256 45791 59257 45844 59257 45792 59257 45792 59258 45844 59258 45843 59258 45792 59259 45843 59259 45793 59259 45793 59260 45843 59260 45842 59260 45793 59261 45842 59261 45795 59261 45795 59262 45842 59262 45794 59262 45795 59263 45794 59263 45796 59263 45796 59264 45794 59264 45853 59264 45796 59265 45853 59265 45797 59265 45797 59266 45853 59266 45798 59266 45797 59267 45798 59267 45799 59267 45799 59268 45798 59268 45854 59268 45799 59269 45854 59269 45800 59269 45800 59270 45854 59270 45801 59270 45800 59271 45801 59271 45802 59271 45802 59272 45801 59272 45857 59272 45802 59273 45857 59273 45803 59273 45803 59274 45857 59274 45804 59274 45803 59275 45804 59275 45805 59275 45805 59276 45804 59276 45806 59276 45805 59277 45806 59277 45807 59277 45807 59278 45806 59278 45809 59278 45807 59279 45809 59279 45808 59279 45808 59280 45809 59280 45810 59280 45808 59281 45810 59281 45811 59281 45811 59282 45810 59282 45813 59282 45811 59283 45813 59283 45812 59283 45812 59284 45813 59284 45815 59284 45812 59285 45815 59285 45814 59285 45814 59286 45815 59286 45848 59286 45814 59287 45848 59287 45816 59287 45816 59288 45848 59288 45849 59288 45816 59289 45849 59289 45817 59289 45817 59290 45849 59290 45818 59290 45817 59291 45818 59291 45819 59291 45819 59292 45818 59292 45820 59292 45819 59293 45820 59293 45821 59293 45821 59294 45820 59294 45822 59294 45821 59295 45822 59295 45823 59295 45823 59296 45822 59296 45845 59296 45823 59297 45845 59297 45824 59297 45824 59298 45845 59298 45825 59298 45824 59299 45825 59299 45826 59299 45826 59300 45825 59300 45847 59300 45826 59301 45847 59301 45827 59301 45827 59302 45847 59302 45846 59302 45827 59303 45846 59303 45828 59303 45828 59304 45846 59304 45829 59304 45828 59305 45829 59305 45830 59305 45830 59306 45829 59306 45851 59306 45830 59307 45851 59307 45832 59307 45832 59308 45851 59308 45831 59308 45832 59309 45831 59309 45833 59309 45833 59310 45831 59310 45856 59310 45833 59311 45856 59311 45834 59311 45834 59312 45856 59312 45835 59312 45834 59313 45835 59313 45836 59313 45836 59314 45835 59314 45855 59314 45836 59315 45855 59315 45837 59315 45837 59316 45855 59316 45850 59316 45837 59317 45850 59317 45838 59317 45838 59318 45850 59318 45852 59318 45838 59319 45852 59319 45839 59319 45839 59320 45852 59320 45840 59320 45790 590 45841 590 45845 590 45845 59321 45841 59321 45788 59321 45848 59322 45815 59322 45798 59322 45822 59323 45820 59323 45843 59323 45843 59324 45820 59324 45818 59324 45843 590 45818 590 45842 590 45842 590 45818 590 45794 590 45822 590 45843 590 45845 590 45845 59325 45843 59325 45844 59325 45845 590 45844 590 45790 590 45788 59326 45785 59326 45845 59326 45845 59327 45785 59327 45783 59327 45845 590 45783 590 45782 590 45852 59328 45846 59328 45847 59328 45848 590 45798 590 45849 590 45852 590 45850 590 45846 590 45846 59329 45850 59329 45855 59329 45846 590 45855 590 45829 590 45856 59330 45831 59330 45851 59330 45782 590 45840 590 45845 590 45845 59331 45840 59331 45852 59331 45845 590 45852 590 45825 590 45825 590 45852 590 45847 590 45849 590 45798 590 45818 590 45818 590 45798 590 45853 590 45818 590 45853 590 45794 590 45815 59332 45813 59332 45798 59332 45798 59333 45813 59333 45810 59333 45798 59334 45810 59334 45854 59334 45854 59335 45810 59335 45801 59335 45829 59336 45855 59336 45851 59336 45851 59337 45855 59337 45835 59337 45851 59338 45835 59338 45856 59338 45810 59339 45809 59339 45801 59339 45801 590 45809 590 45806 590 45801 590 45806 590 45857 590 45857 590 45806 590 45804 590 45879 590 45858 590 45866 590 45866 590 45858 590 45859 590 45860 59340 45861 59340 45871 59340 45859 590 45862 590 45866 590 45866 590 45862 590 45863 590 45866 590 45863 590 45868 590 45864 59341 45865 59341 45871 59341 45871 59342 45865 59342 45866 59342 45871 590 45866 590 45867 590 45867 59343 45866 59343 45868 59343 45866 59344 45875 59344 45876 59344 45869 590 45894 590 45896 590 45861 590 45870 590 45871 590 45871 59345 45870 59345 45872 59345 45871 590 45872 590 45864 590 45873 59346 45889 59346 45866 59346 45866 59347 45889 59347 45874 59347 45866 590 45874 590 45875 590 45876 590 45877 590 45866 590 45866 59348 45877 59348 45878 59348 45866 59349 45878 59349 45879 59349 45869 590 45896 590 45871 590 45871 59350 45896 59350 45880 59350 45871 59351 45880 59351 45860 59351 45885 59352 45881 59352 45883 59352 45883 590 45881 590 45882 590 45883 59353 45882 59353 45884 59353 45885 59354 45883 59354 45888 59354 45888 59355 45883 59355 45886 59355 45888 59356 45886 59356 45891 59356 45873 590 45887 590 45889 590 45889 59357 45887 59357 45888 59357 45889 590 45888 590 45890 590 45890 590 45888 590 45891 590 45892 590 45893 590 45894 590 45894 59358 45893 59358 45895 59358 45894 59359 45895 59359 45896 59359 45971 59360 45897 59360 45898 59360 45898 59361 45897 59361 45899 59361 45898 59362 45899 59362 45900 59362 45900 59363 45899 59363 45902 59363 45900 59364 45902 59364 45901 59364 45901 59365 45902 59365 45903 59365 45901 59366 45903 59366 45904 59366 45904 59367 45903 59367 45905 59367 45904 59368 45905 59368 45907 59368 45907 59369 45905 59369 45906 59369 45907 59370 45906 59370 45908 59370 45908 59371 45906 59371 45910 59371 45908 59372 45910 59372 45909 59372 45909 59373 45910 59373 45911 59373 45909 59374 45911 59374 45912 59374 45912 59375 45911 59375 45913 59375 45912 59376 45913 59376 45914 59376 45914 59377 45913 59377 45916 59377 45914 59378 45916 59378 45915 59378 45915 59379 45916 59379 45917 59379 45915 59380 45917 59380 45918 59380 45918 59381 45917 59381 45919 59381 45918 59382 45919 59382 45920 59382 45920 59383 45919 59383 45921 59383 45920 59384 45921 59384 45922 59384 45922 59385 45921 59385 45923 59385 45922 59386 45923 59386 45925 59386 45925 59387 45923 59387 45924 59387 45925 59388 45924 59388 45926 59388 45926 59389 45924 59389 45927 59389 45926 59390 45927 59390 45928 59390 45928 59391 45927 59391 45930 59391 45928 59392 45930 59392 45929 59392 45929 59393 45930 59393 45932 59393 45929 59393 45932 59393 45931 59393 45931 59394 45932 59394 45934 59394 45931 59395 45934 59395 45933 59395 45933 59396 45934 59396 45936 59396 45933 59397 45936 59397 45935 59397 45935 59398 45936 59398 45937 59398 45935 59398 45937 59398 45938 59398 45938 59399 45937 59399 45940 59399 45938 59399 45940 59399 45939 59399 45939 59400 45940 59400 45942 59400 45939 59401 45942 59401 45941 59401 45941 59402 45942 59402 45944 59402 45941 59403 45944 59403 45943 59403 45943 59404 45944 59404 45946 59404 45943 59405 45946 59405 45945 59405 45945 59406 45946 59406 45947 59406 45945 59407 45947 59407 45948 59407 45948 59408 45947 59408 45950 59408 45948 59409 45950 59409 45949 59409 45949 59410 45950 59410 45952 59410 45949 59411 45952 59411 45951 59411 45951 59412 45952 59412 45954 59412 45951 59413 45954 59413 45953 59413 45953 59414 45954 59414 45955 59414 45953 59415 45955 59415 45956 59415 45956 59416 45955 59416 45957 59416 45956 59417 45957 59417 45959 59417 45959 59418 45957 59418 45958 59418 45959 59419 45958 59419 45960 59419 45960 59420 45958 59420 45961 59420 45960 59421 45961 59421 45962 59421 45962 59422 45961 59422 45963 59422 45962 59423 45963 59423 45965 59423 45965 59424 45963 59424 45964 59424 45965 59425 45964 59425 45966 59425 45966 59426 45964 59426 45967 59426 45966 59427 45967 59427 45968 59427 45968 59428 45967 59428 45969 59428 45968 59429 45969 59429 45970 59429 45970 59430 45969 59430 45972 59430 45970 59431 45972 59431 45971 59431 45971 59360 45972 59360 45897 59360 45973 59432 45974 59432 46021 59432 46021 59433 45974 59433 45975 59433 46021 59434 45975 59434 46020 59434 46020 59435 45975 59435 45976 59435 46020 59436 45976 59436 45977 59436 45977 59437 45976 59437 45978 59437 45977 59437 45978 59437 45980 59437 45980 59438 45978 59438 45979 59438 45980 59439 45979 59439 46017 59439 46017 59440 45979 59440 45982 59440 46017 59441 45982 59441 45981 59441 45981 59442 45982 59442 45983 59442 45981 59443 45983 59443 46014 59443 46014 59444 45983 59444 45985 59444 46014 59445 45985 59445 45984 59445 45984 59446 45985 59446 45986 59446 45984 59447 45986 59447 45987 59447 45987 59448 45986 59448 45988 59448 45987 59449 45988 59449 46013 59449 46013 59450 45988 59450 45989 59450 46013 59451 45989 59451 45991 59451 45991 59452 45989 59452 45990 59452 45991 59453 45990 59453 45992 59453 45992 59454 45990 59454 45994 59454 45992 59455 45994 59455 45993 59455 45993 59456 45994 59456 45995 59456 45993 59457 45995 59457 45997 59457 45997 59458 45995 59458 45996 59458 45997 59459 45996 59459 45998 59459 45998 59460 45996 59460 46000 59460 45998 59461 46000 59461 45999 59461 45999 59462 46000 59462 46001 59462 45999 59462 46001 59462 46027 59462 46027 59463 46001 59463 46002 59463 46027 59464 46002 59464 46004 59464 46004 59465 46002 59465 46003 59465 46004 59466 46003 59466 46005 59466 46005 59467 46003 59467 46006 59467 46005 59468 46006 59468 46025 59468 46025 59469 46006 59469 46007 59469 46025 59470 46007 59470 46008 59470 46008 59471 46007 59471 46009 59471 46008 59472 46009 59472 46023 59472 46023 59473 46009 59473 46010 59473 46023 59474 46010 59474 46011 59474 46011 59475 46010 59475 45973 59475 46011 59476 45973 59476 46021 59476 45991 59477 46012 59477 46013 59477 46013 59478 46012 59478 46041 59478 46013 59479 46041 59479 45987 59479 45987 59480 46041 59480 46032 59480 45987 59481 46032 59481 45984 59481 45984 59482 46032 59482 46031 59482 45984 59483 46031 59483 46014 59483 46014 59484 46031 59484 46015 59484 46014 59485 46015 59485 45981 59485 45981 59486 46015 59486 46016 59486 45981 59487 46016 59487 46017 59487 46017 59488 46016 59488 46018 59488 46017 59489 46018 59489 45980 59489 45980 59490 46018 59490 46019 59490 45980 59491 46019 59491 45977 59491 45977 59492 46019 59492 46038 59492 45977 59493 46038 59493 46020 59493 46020 59494 46038 59494 46037 59494 46020 59495 46037 59495 46021 59495 46021 59496 46037 59496 46036 59496 46021 59497 46036 59497 46011 59497 46011 59498 46036 59498 46022 59498 46011 59499 46022 59499 46023 59499 46023 59500 46022 59500 46035 59500 46023 59501 46035 59501 46008 59501 46008 59502 46035 59502 46024 59502 46008 59503 46024 59503 46025 59503 46025 59504 46024 59504 46034 59504 46025 59505 46034 59505 46005 59505 46005 59506 46034 59506 46030 59506 46005 59507 46030 59507 46004 59507 46004 59508 46030 59508 46026 59508 46004 59509 46026 59509 46027 59509 46027 59510 46026 59510 46028 59510 46027 59511 46028 59511 45999 59511 45999 59512 46028 59512 46033 59512 45999 59513 46033 59513 45998 59513 45998 59514 46033 59514 46042 59514 45998 59515 46042 59515 45997 59515 45997 59516 46042 59516 46029 59516 45997 59517 46029 59517 45993 59517 45993 59518 46029 59518 46040 59518 45993 59519 46040 59519 45992 59519 45992 59520 46040 59520 46039 59520 45992 59521 46039 59521 45991 59521 45991 59522 46039 59522 46012 59522 46026 590 46018 590 46028 590 46028 590 46018 590 46033 590 46026 590 46030 590 46018 590 46018 59523 46030 59523 46034 59523 46018 590 46034 590 46019 590 46018 590 46016 590 46033 590 46033 59524 46016 59524 46015 59524 46033 59525 46015 59525 46031 59525 46031 590 46032 590 46033 590 46033 59526 46032 59526 46041 59526 46033 59527 46041 59527 46042 59527 46024 590 46035 590 46034 590 46034 590 46035 590 46022 590 46034 590 46022 590 46036 590 46036 590 46037 590 46034 590 46034 59528 46037 59528 46038 59528 46034 590 46038 590 46019 590 46041 590 46012 590 46039 590 46039 590 46040 590 46041 590 46041 59529 46040 59529 46029 59529 46041 59530 46029 59530 46042 59530 46096 59531 46043 59531 46044 59531 46044 59532 46043 59532 46045 59532 46044 59533 46045 59533 46046 59533 46046 59534 46045 59534 46047 59534 46046 59535 46047 59535 50384 59535 46048 59536 50404 59536 46049 59536 46049 59537 50404 59537 46050 59537 46049 59538 46050 59538 46051 59538 46051 59539 46050 59539 46052 59539 46051 59540 46052 59540 46053 59540 46053 59541 46052 59541 46054 59541 46053 59542 46054 59542 46055 59542 46055 59543 46054 59543 46056 59543 46055 59544 46056 59544 46057 59544 46057 59545 46056 59545 46058 59545 46057 59546 46058 59546 46059 59546 46059 59547 46058 59547 46060 59547 46059 59548 46060 59548 46062 59548 46062 59549 46060 59549 46061 59549 46062 59550 46061 59550 46063 59550 46063 59551 46061 59551 46065 59551 46063 59552 46065 59552 46064 59552 46064 59553 46065 59553 46066 59553 46064 59554 46066 59554 46067 59554 46067 59555 46066 59555 46068 59555 46067 59556 46068 59556 46069 59556 46069 59557 46068 59557 46070 59557 46069 59558 46070 59558 46071 59558 46071 59559 46070 59559 46073 59559 46071 59560 46073 59560 46072 59560 46072 59561 46073 59561 46074 59561 46072 59562 46074 59562 46075 59562 46075 59563 46074 59563 46077 59563 46075 59564 46077 59564 46076 59564 46076 59565 46077 59565 46078 59565 46076 59566 46078 59566 46079 59566 46079 59567 46078 59567 46080 59567 46079 59568 46080 59568 46081 59568 46081 59569 46080 59569 46082 59569 46081 59570 46082 59570 46083 59570 46083 59571 46082 59571 46084 59571 46083 59572 46084 59572 46085 59572 46085 59573 46084 59573 46086 59573 46085 59574 46086 59574 46087 59574 46087 59575 46086 59575 46089 59575 46087 59576 46089 59576 46088 59576 46088 59577 46089 59577 46090 59577 46088 59578 46090 59578 46091 59578 46091 59579 46090 59579 46092 59579 46091 59580 46092 59580 46093 59580 46093 59581 46092 59581 46095 59581 46093 59582 46095 59582 46094 59582 46094 59583 46095 59583 46097 59583 46094 59583 46097 59583 46096 59583 46096 59584 46097 59584 46043 59584 46098 59585 46100 59585 46124 59585 46111 590 46099 590 46124 590 46100 590 46101 590 46124 590 46124 59586 46101 59586 46102 59586 46124 59587 46102 59587 46128 59587 46103 59588 46129 59588 46135 59588 46113 590 46114 590 46104 590 46105 590 46106 590 46108 590 46108 59589 46106 59589 46107 59589 46108 59590 46107 59590 46109 59590 46135 590 46129 590 46110 590 46111 590 46124 590 46104 590 46104 590 46124 590 46112 590 46104 59591 46112 59591 46113 59591 46114 590 46115 590 46104 590 46104 59592 46115 59592 46108 59592 46104 590 46108 590 46116 590 46116 590 46108 590 46109 590 46099 590 46117 590 46124 590 46124 59593 46117 59593 46118 59593 46124 59594 46118 59594 46119 59594 46126 59595 46120 59595 46134 59595 46121 590 46122 590 46128 590 46128 59596 46122 59596 46131 59596 46119 590 46123 590 46124 590 46124 59597 46123 59597 46125 59597 46124 59598 46125 59598 46098 59598 46126 590 46134 590 46127 590 46110 590 46129 590 46128 590 46128 590 46129 590 46130 590 46128 59599 46130 59599 46121 59599 46131 59600 46132 59600 46128 59600 46128 59601 46132 59601 46133 59601 46128 59602 46133 59602 46124 59602 46127 590 46134 590 46135 590 46135 59603 46134 59603 46136 59603 46135 59604 46136 59604 46103 59604 46211 59605 46212 59605 46137 59605 46137 59606 46212 59606 46138 59606 46137 59607 46138 59607 46140 59607 46140 59608 46138 59608 46139 59608 46140 59609 46139 59609 46142 59609 46142 59610 46139 59610 46141 59610 46142 59611 46141 59611 46143 59611 46143 59612 46141 59612 46144 59612 46143 59613 46144 59613 46146 59613 46146 59614 46144 59614 46145 59614 46146 59615 46145 59615 46147 59615 46147 59616 46145 59616 46148 59616 46147 59617 46148 59617 46149 59617 46149 59618 46148 59618 46150 59618 46149 59619 46150 59619 46151 59619 46151 59620 46150 59620 46152 59620 46151 59621 46152 59621 46153 59621 46153 59622 46152 59622 46154 59622 46153 59623 46154 59623 46155 59623 46155 59624 46154 59624 46157 59624 46155 59624 46157 59624 46156 59624 46156 59625 46157 59625 46158 59625 46156 59626 46158 59626 46159 59626 46159 59627 46158 59627 46161 59627 46159 59628 46161 59628 46160 59628 46160 59629 46161 59629 46163 59629 46160 59630 46163 59630 46162 59630 46162 59631 46163 59631 46164 59631 46162 59632 46164 59632 46165 59632 46165 59633 46164 59633 46167 59633 46165 59633 46167 59633 46166 59633 46166 59634 46167 59634 46168 59634 46166 59635 46168 59635 46169 59635 46169 59636 46168 59636 46171 59636 46169 59637 46171 59637 46170 59637 46170 59638 46171 59638 46172 59638 46170 59639 46172 59639 46173 59639 46173 59640 46172 59640 46174 59640 46173 59641 46174 59641 46175 59641 46175 59642 46174 59642 46177 59642 46175 59643 46177 59643 46176 59643 46176 59644 46177 59644 46178 59644 46176 59645 46178 59645 46179 59645 46179 59646 46178 59646 46180 59646 46179 59647 46180 59647 46181 59647 46181 59648 46180 59648 46183 59648 46181 59649 46183 59649 46182 59649 46182 59650 46183 59650 46185 59650 46182 59651 46185 59651 46184 59651 46184 59652 46185 59652 46186 59652 46184 59653 46186 59653 46187 59653 46187 59654 46186 59654 46188 59654 46187 59655 46188 59655 46189 59655 46189 59656 46188 59656 46190 59656 46189 59657 46190 59657 46191 59657 46191 59658 46190 59658 46192 59658 46191 59659 46192 59659 46193 59659 46193 59660 46192 59660 46194 59660 46193 59661 46194 59661 46195 59661 46195 59662 46194 59662 46196 59662 46195 59663 46196 59663 46197 59663 46197 59664 46196 59664 46199 59664 46197 59664 46199 59664 46198 59664 46198 59665 46199 59665 46201 59665 46198 59666 46201 59666 46200 59666 46200 59667 46201 59667 46202 59667 46200 59668 46202 59668 46203 59668 46203 59669 46202 59669 46204 59669 46203 59670 46204 59670 46205 59670 46205 59671 46204 59671 46206 59671 46205 59672 46206 59672 46207 59672 46207 59673 46206 59673 46208 59673 46207 59674 46208 59674 46209 59674 46209 59675 46208 59675 46210 59675 46209 59676 46210 59676 46211 59676 46211 59605 46210 59605 46212 59605 46213 59677 46214 59677 46216 59677 46216 59678 46214 59678 46215 59678 46216 59679 46215 59679 46259 59679 46259 59680 46215 59680 46217 59680 46259 59681 46217 59681 46219 59681 46219 59682 46217 59682 46218 59682 46219 59683 46218 59683 46257 59683 46257 59684 46218 59684 46220 59684 46257 59684 46220 59684 46255 59684 46255 59685 46220 59685 46221 59685 46255 59686 46221 59686 46254 59686 46254 59687 46221 59687 46222 59687 46254 59688 46222 59688 46252 59688 46252 59689 46222 59689 46223 59689 46252 59690 46223 59690 46224 59690 46224 59691 46223 59691 46225 59691 46224 59692 46225 59692 46227 59692 46227 59693 46225 59693 46226 59693 46227 59694 46226 59694 46249 59694 46249 59695 46226 59695 46228 59695 46249 59696 46228 59696 46229 59696 46229 59697 46228 59697 46230 59697 46229 59698 46230 59698 46274 59698 46274 59699 46230 59699 46232 59699 46274 59700 46232 59700 46231 59700 46231 59701 46232 59701 46234 59701 46231 59702 46234 59702 46233 59702 46233 59703 46234 59703 46235 59703 46233 59704 46235 59704 46236 59704 46236 59705 46235 59705 46237 59705 46236 59706 46237 59706 46238 59706 46238 59707 46237 59707 46239 59707 46238 59708 46239 59708 46269 59708 46269 59709 46239 59709 46240 59709 46269 59710 46240 59710 46242 59710 46242 59711 46240 59711 46241 59711 46242 59711 46241 59711 46243 59711 46243 59712 46241 59712 46244 59712 46243 59713 46244 59713 46266 59713 46266 59714 46244 59714 46245 59714 46266 59715 46245 59715 46246 59715 46246 59716 46245 59716 46247 59716 46246 59717 46247 59717 46262 59717 46262 59718 46247 59718 46248 59718 46262 59719 46248 59719 46261 59719 46261 59720 46248 59720 46213 59720 46261 59721 46213 59721 46216 59721 46229 59722 46250 59722 46249 59722 46249 59723 46250 59723 46251 59723 46249 59724 46251 59724 46227 59724 46227 59725 46251 59725 46275 59725 46227 59726 46275 59726 46224 59726 46224 59727 46275 59727 46278 59727 46224 59728 46278 59728 46252 59728 46252 59729 46278 59729 46253 59729 46252 59730 46253 59730 46254 59730 46254 59731 46253 59731 46256 59731 46254 59732 46256 59732 46255 59732 46255 59733 46256 59733 46258 59733 46255 59734 46258 59734 46257 59734 46257 59735 46258 59735 46282 59735 46257 59736 46282 59736 46219 59736 46219 59737 46282 59737 46281 59737 46219 59738 46281 59738 46259 59738 46259 59739 46281 59739 46260 59739 46259 59740 46260 59740 46216 59740 46216 59741 46260 59741 46277 59741 46216 59742 46277 59742 46261 59742 46261 59743 46277 59743 46263 59743 46261 59744 46263 59744 46262 59744 46262 59745 46263 59745 46276 59745 46262 59746 46276 59746 46246 59746 46246 59747 46276 59747 46264 59747 46246 59748 46264 59748 46266 59748 46266 59749 46264 59749 46265 59749 46266 59750 46265 59750 46243 59750 46243 59751 46265 59751 46267 59751 46243 59752 46267 59752 46242 59752 46242 59753 46267 59753 46268 59753 46242 59754 46268 59754 46269 59754 46269 59755 46268 59755 46270 59755 46269 59756 46270 59756 46238 59756 46238 59757 46270 59757 46271 59757 46238 59758 46271 59758 46236 59758 46236 59759 46271 59759 46272 59759 46236 59760 46272 59760 46233 59760 46233 59761 46272 59761 46273 59761 46233 59762 46273 59762 46231 59762 46231 59763 46273 59763 46280 59763 46231 59764 46280 59764 46274 59764 46274 59765 46280 59765 46279 59765 46274 59766 46279 59766 46229 59766 46229 59767 46279 59767 46250 59767 46276 590 46275 590 46264 590 46264 590 46275 590 46265 590 46275 59768 46271 59768 46270 59768 46270 590 46268 590 46275 590 46275 59769 46268 59769 46267 59769 46275 59770 46267 59770 46265 59770 46276 590 46263 590 46275 590 46275 59771 46263 59771 46277 59771 46275 590 46277 590 46260 590 46258 590 46256 590 46275 590 46275 590 46256 590 46253 590 46275 590 46253 590 46278 590 46251 590 46250 590 46275 590 46275 590 46250 590 46279 590 46275 59772 46279 59772 46280 59772 46260 590 46281 590 46275 590 46275 590 46281 590 46282 590 46275 59773 46282 59773 46258 59773 46280 590 46273 590 46275 590 46275 59774 46273 59774 46272 59774 46275 59775 46272 59775 46271 59775 46357 59776 46283 59776 46284 59776 46284 59777 46283 59777 46286 59777 46284 59778 46286 59778 46285 59778 46285 59779 46286 59779 46287 59779 46285 59780 46287 59780 46288 59780 46288 59781 46287 59781 46290 59781 46288 59782 46290 59782 46289 59782 46289 59783 46290 59783 46291 59783 46289 59784 46291 59784 46292 59784 46292 59785 46291 59785 46293 59785 46292 59786 46293 59786 46295 59786 46295 59787 46293 59787 46294 59787 46295 59787 46294 59787 46296 59787 46296 59788 46294 59788 46297 59788 46296 59788 46297 59788 46298 59788 46298 59789 46297 59789 46299 59789 46298 59790 46299 59790 46300 59790 46300 59791 46299 59791 46301 59791 46300 59792 46301 59792 46303 59792 46303 59793 46301 59793 46302 59793 46303 59794 46302 59794 46304 59794 46304 59795 46302 59795 46306 59795 46304 59796 46306 59796 46305 59796 46305 59797 46306 59797 46307 59797 46305 59798 46307 59798 46308 59798 46308 59799 46307 59799 46309 59799 46308 59800 46309 59800 46310 59800 46310 59801 46309 59801 46311 59801 46310 59802 46311 59802 46312 59802 46312 59803 46311 59803 46313 59803 46312 59804 46313 59804 46315 59804 46315 59805 46313 59805 46314 59805 46315 59806 46314 59806 46316 59806 46316 59807 46314 59807 46317 59807 46316 59808 46317 59808 46318 59808 46318 59809 46317 59809 46319 59809 46318 59810 46319 59810 46320 59810 46320 59811 46319 59811 46321 59811 46320 59812 46321 59812 46322 59812 46322 59813 46321 59813 46324 59813 46322 59814 46324 59814 46323 59814 46323 59815 46324 59815 46326 59815 46323 59816 46326 59816 46325 59816 46325 59817 46326 59817 46327 59817 46325 59817 46327 59817 46328 59817 46328 59818 46327 59818 46329 59818 46328 59819 46329 59819 46330 59819 46330 59820 46329 59820 46331 59820 46330 59821 46331 59821 46332 59821 46332 59822 46331 59822 46333 59822 46332 59823 46333 59823 46334 59823 46334 59824 46333 59824 46336 59824 46334 59824 46336 59824 46335 59824 46335 59825 46336 59825 46338 59825 46335 59826 46338 59826 46337 59826 46337 59827 46338 59827 46340 59827 46337 59828 46340 59828 46339 59828 46339 59829 46340 59829 46341 59829 46339 59830 46341 59830 46342 59830 46342 59831 46341 59831 46343 59831 46342 59831 46343 59831 46344 59831 46344 59832 46343 59832 46346 59832 46344 59833 46346 59833 46345 59833 46345 59834 46346 59834 46347 59834 46345 59835 46347 59835 46348 59835 46348 59836 46347 59836 46349 59836 46348 59837 46349 59837 46350 59837 46350 59838 46349 59838 46351 59838 46350 59839 46351 59839 46352 59839 46352 59840 46351 59840 46354 59840 46352 59840 46354 59840 46353 59840 46353 59841 46354 59841 46356 59841 46353 59842 46356 59842 46355 59842 46355 59843 46356 59843 46358 59843 46355 59843 46358 59843 46357 59843 46357 59844 46358 59844 46283 59844 46359 59845 46371 59845 46360 59845 46360 590 46371 590 46361 590 46362 590 46363 590 46371 590 46364 590 46365 590 46395 590 46395 59846 46365 59846 46366 59846 46395 59847 46366 59847 46380 59847 46363 59848 46367 59848 46371 59848 46371 59849 46367 59849 46368 59849 46371 59850 46368 59850 46369 59850 46369 590 46370 590 46371 590 46371 59851 46370 59851 46372 59851 46371 59852 46372 59852 46373 59852 46373 590 46374 590 46371 590 46371 59853 46374 59853 46375 59853 46371 59854 46375 59854 46376 59854 46386 590 46377 590 46371 590 46371 59855 46377 59855 46378 59855 46371 59856 46378 59856 46379 59856 46380 59857 46381 59857 46395 59857 46395 59858 46381 59858 46382 59858 46395 590 46382 590 46393 590 46364 59859 46395 59859 46371 59859 46371 590 46395 590 46383 590 46371 59860 46383 59860 46362 59860 46376 590 46384 590 46371 590 46371 59861 46384 59861 46385 59861 46371 59862 46385 59862 46386 59862 46360 59863 46387 59863 46359 59863 46359 59864 46387 59864 46388 59864 46359 59865 46388 59865 46389 59865 46389 590 46388 590 46390 590 46379 590 46391 590 46371 590 46371 59866 46391 59866 46392 59866 46371 59867 46392 59867 46361 59867 46393 590 46394 590 46395 590 46395 59868 46394 59868 46396 59868 46395 59869 46396 59869 46397 59869 46398 590 46405 590 46415 590 46399 590 46400 590 46418 590 46401 590 46403 590 46405 590 46401 590 46405 590 46402 590 46403 590 46404 590 46405 590 46405 59870 46404 59870 46406 59870 46405 59871 46406 59871 46415 59871 46415 590 46407 590 46413 590 46399 590 46418 590 46405 590 46405 59872 46418 59872 46408 59872 46405 59873 46408 59873 46402 59873 46415 590 46409 590 46407 590 46407 590 46409 590 46410 590 46407 59874 46410 59874 46411 59874 46411 59875 46410 59875 46412 59875 46413 590 46414 590 46415 590 46415 59876 46414 59876 46416 59876 46415 59877 46416 59877 46417 59877 46400 590 46419 590 46418 590 46418 59878 46419 59878 46420 59878 46418 59879 46420 59879 46425 59879 46425 59880 46420 59880 46421 59880 46425 59881 46421 59881 46424 59881 46417 590 46422 590 46415 590 46415 59882 46422 59882 46423 59882 46415 59883 46423 59883 46398 59883 46424 590 46426 590 46425 590 46425 59884 46426 59884 46427 59884 46425 59885 46427 59885 46428 59885 46428 590 46429 590 46425 590 46425 59886 46429 59886 46430 59886 46425 59887 46430 59887 46431 59887 46431 59888 46432 59888 46425 59888 46425 590 46432 590 46433 590 46425 590 46433 590 46435 590 46435 590 46433 590 46434 590 46435 590 46434 590 46436 590 46511 59889 46512 59889 46437 59889 46437 59890 46512 59890 46438 59890 46437 59891 46438 59891 46439 59891 46439 59892 46438 59892 46440 59892 46439 59893 46440 59893 46441 59893 46441 59894 46440 59894 46443 59894 46441 59895 46443 59895 46442 59895 46442 59896 46443 59896 46444 59896 46442 59897 46444 59897 46445 59897 46445 59898 46444 59898 46447 59898 46445 59899 46447 59899 46446 59899 46446 59900 46447 59900 46448 59900 46446 59900 46448 59900 46449 59900 46449 59901 46448 59901 46450 59901 46449 59901 46450 59901 46451 59901 46451 59902 46450 59902 46453 59902 46451 59903 46453 59903 46452 59903 46452 59904 46453 59904 46455 59904 46452 59905 46455 59905 46454 59905 46454 59906 46455 59906 46456 59906 46454 59907 46456 59907 46458 59907 46458 59908 46456 59908 46457 59908 46458 59909 46457 59909 46460 59909 46460 59910 46457 59910 46459 59910 46460 59911 46459 59911 46461 59911 46461 59912 46459 59912 46462 59912 46461 59913 46462 59913 46463 59913 46463 59914 46462 59914 46464 59914 46463 59915 46464 59915 46465 59915 46465 59916 46464 59916 46466 59916 46465 59917 46466 59917 46468 59917 46468 59918 46466 59918 46467 59918 46468 59919 46467 59919 46469 59919 46469 59920 46467 59920 46470 59920 46469 59921 46470 59921 46471 59921 46471 59922 46470 59922 46473 59922 46471 59923 46473 59923 46472 59923 46472 59924 46473 59924 46474 59924 46472 59925 46474 59925 46475 59925 46475 59926 46474 59926 46476 59926 46475 59927 46476 59927 46478 59927 46478 59928 46476 59928 46477 59928 46478 59929 46477 59929 46479 59929 46479 59930 46477 59930 46480 59930 46479 59930 46480 59930 46481 59930 46481 59931 46480 59931 46482 59931 46481 59932 46482 59932 46483 59932 46483 59933 46482 59933 46485 59933 46483 59934 46485 59934 46484 59934 46484 59935 46485 59935 46486 59935 46484 59936 46486 59936 46487 59936 46487 59937 46486 59937 46489 59937 46487 59937 46489 59937 46488 59937 46488 59938 46489 59938 46491 59938 46488 59939 46491 59939 46490 59939 46490 59940 46491 59940 46493 59940 46490 59941 46493 59941 46492 59941 46492 59942 46493 59942 46494 59942 46492 59943 46494 59943 46496 59943 46496 59944 46494 59944 46495 59944 46496 59944 46495 59944 46497 59944 46497 59945 46495 59945 46499 59945 46497 59946 46499 59946 46498 59946 46498 59947 46499 59947 46500 59947 46498 59948 46500 59948 46501 59948 46501 59949 46500 59949 46502 59949 46501 59950 46502 59950 46503 59950 46503 59951 46502 59951 46505 59951 46503 59952 46505 59952 46504 59952 46504 59953 46505 59953 46506 59953 46504 59953 46506 59953 46507 59953 46507 59954 46506 59954 46508 59954 46507 59955 46508 59955 46509 59955 46509 59956 46508 59956 46510 59956 46509 59956 46510 59956 46511 59956 46511 59957 46510 59957 46512 59957 46513 590 46519 590 46517 590 46542 590 46514 590 46549 590 46515 59958 46516 59958 46535 59958 46513 590 46517 590 46514 590 46514 59959 46517 59959 46518 59959 46514 59960 46518 59960 46549 59960 46515 590 46535 590 46537 590 46519 590 46520 590 46517 590 46517 59961 46520 59961 46535 59961 46517 590 46535 590 46521 590 46521 59962 46535 59962 46516 59962 46524 59963 46525 59963 46533 59963 46522 59964 46523 59964 46549 59964 46524 59965 46526 59965 46525 59965 46525 59966 46526 59966 46528 59966 46525 59967 46528 59967 46527 59967 46527 590 46528 590 46529 590 46534 59968 46530 59968 46531 59968 46531 59969 46530 59969 46524 59969 46531 59970 46524 59970 46532 59970 46532 590 46524 590 46533 590 46534 590 46531 590 46535 590 46535 59971 46531 59971 46536 59971 46535 59972 46536 59972 46537 59972 46548 590 46538 590 46549 590 46549 59973 46538 59973 46539 59973 46523 590 46540 590 46549 590 46549 59974 46540 59974 46541 59974 46549 59975 46541 59975 46542 59975 46543 590 46544 590 46545 590 46545 590 46544 590 46546 590 46545 590 46546 590 46549 590 46549 59976 46546 59976 46547 59976 46549 59977 46547 59977 46548 59977 46539 590 46550 590 46549 590 46549 59978 46550 59978 46551 59978 46549 59979 46551 59979 46522 59979 46552 59980 46627 59980 46553 59980 46553 59981 46627 59981 46554 59981 46553 59982 46554 59982 46555 59982 46555 59983 46554 59983 46557 59983 46555 59984 46557 59984 46556 59984 46556 59985 46557 59985 46558 59985 46556 59985 46558 59985 46559 59985 46559 59986 46558 59986 46560 59986 46559 59987 46560 59987 46561 59987 46561 59988 46560 59988 46562 59988 46561 59989 46562 59989 46563 59989 46563 59990 46562 59990 46565 59990 46563 59991 46565 59991 46564 59991 46564 59992 46565 59992 46566 59992 46564 59993 46566 59993 46567 59993 46567 59994 46566 59994 46568 59994 46567 59995 46568 59995 46569 59995 46569 59996 46568 59996 46570 59996 46569 59997 46570 59997 46571 59997 46571 59998 46570 59998 46572 59998 46571 59999 46572 59999 46573 59999 46573 60000 46572 60000 46574 60000 46573 60001 46574 60001 46575 60001 46575 60002 46574 60002 46577 60002 46575 60003 46577 60003 46576 60003 46576 60004 46577 60004 46578 60004 46576 60005 46578 60005 46579 60005 46579 60006 46578 60006 46580 60006 46579 60007 46580 60007 46581 60007 46581 60008 46580 60008 46583 60008 46581 60009 46583 60009 46582 60009 46582 60010 46583 60010 46584 60010 46582 60011 46584 60011 46585 60011 46585 60012 46584 60012 46587 60012 46585 60013 46587 60013 46586 60013 46586 60014 46587 60014 46589 60014 46586 60015 46589 60015 46588 60015 46588 60016 46589 60016 46590 60016 46588 60017 46590 60017 46591 60017 46591 60018 46590 60018 46592 60018 46591 60019 46592 60019 46593 60019 46593 60020 46592 60020 46594 60020 46593 60021 46594 60021 46595 60021 46595 60022 46594 60022 46596 60022 46595 60023 46596 60023 46597 60023 46597 60024 46596 60024 46599 60024 46597 60025 46599 60025 46598 60025 46598 60026 46599 60026 46601 60026 46598 60027 46601 60027 46600 60027 46600 60028 46601 60028 46602 60028 46600 60028 46602 60028 46603 60028 46603 60029 46602 60029 46604 60029 46603 60030 46604 60030 46605 60030 46605 60031 46604 60031 46606 60031 46605 60032 46606 60032 46607 60032 46607 60033 46606 60033 46608 60033 46607 60034 46608 60034 46609 60034 46609 60035 46608 60035 46610 60035 46609 60036 46610 60036 46611 60036 46611 60037 46610 60037 46613 60037 46611 60038 46613 60038 46612 60038 46612 60039 46613 60039 46614 60039 46612 60040 46614 60040 46616 60040 46616 60041 46614 60041 46615 60041 46616 60042 46615 60042 46617 60042 46617 60043 46615 60043 46618 60043 46617 60043 46618 60043 46620 60043 46620 60044 46618 60044 46619 60044 46620 60045 46619 60045 46621 60045 46621 60046 46619 60046 46622 60046 46621 60047 46622 60047 46624 60047 46624 60048 46622 60048 46623 60048 46624 60048 46623 60048 46625 60048 46625 60049 46623 60049 46626 60049 46625 60050 46626 60050 46552 60050 46552 60051 46626 60051 46627 60051 46628 60052 46629 60052 46630 60052 46630 60053 46629 60053 46649 60053 46630 60054 46649 60054 46631 60054 46631 60055 46649 60055 46632 60055 46632 60056 46649 60056 46661 60056 46632 60057 46661 60057 46633 60057 46633 60058 46661 60058 46634 60058 46634 60059 46661 60059 46645 60059 46634 60060 46645 60060 46635 60060 46629 60061 46767 60061 46636 60061 46770 590 46659 590 46649 590 46655 60062 46786 60062 46785 60062 46637 590 46638 590 46641 590 46641 60063 46638 60063 46920 60063 46649 60064 46639 60064 46640 60064 46920 590 46765 590 46641 590 46641 590 46765 590 46764 590 46641 590 46764 590 46642 590 46643 590 46645 590 46644 590 46644 60065 46645 60065 46652 60065 46661 590 46804 590 46646 590 46639 590 46649 590 46647 590 46647 60066 46649 60066 46629 60066 46647 590 46629 590 46781 590 46640 590 46648 590 46649 590 46649 60067 46648 60067 46810 60067 46649 60068 46810 60068 46770 60068 46900 60069 46894 60069 46629 60069 46629 590 46894 590 46888 590 46629 60070 46888 60070 46767 60070 46785 60071 46650 60071 46655 60071 46655 60072 46650 60072 46940 60072 46655 590 46940 590 46641 590 46641 60073 46940 60073 46762 60073 46641 60074 46762 60074 46637 60074 46761 590 46760 590 46655 590 46757 60075 46651 60075 46645 60075 46645 60076 46651 60076 46758 60076 46645 590 46758 590 46652 590 46636 60077 46768 60077 46629 60077 46629 590 46768 590 46653 590 46629 60078 46653 60078 46781 60078 46642 590 46654 590 46641 590 46641 60079 46654 60079 46773 60079 46641 590 46773 590 46629 590 46629 60080 46773 60080 46775 60080 46629 590 46775 590 46900 590 46643 590 46982 590 46645 590 46645 60081 46982 60081 46983 60081 46645 60082 46983 60082 46655 60082 46655 60083 46983 60083 46656 60083 46655 60084 46656 60084 46761 60084 46760 590 46949 590 46655 590 46655 60085 46949 60085 46657 60085 46655 60086 46657 60086 46786 60086 46646 590 46658 590 46661 590 46661 590 46658 590 46779 590 46661 590 46779 590 47018 590 46659 590 46660 590 46649 590 46649 590 46660 590 46839 590 46649 60087 46839 60087 46661 60087 46661 60088 46839 60088 46662 60088 46661 60089 46662 60089 46804 60089 47018 590 47006 590 46661 590 46661 60090 47006 60090 46663 60090 46661 60091 46663 60091 46645 60091 46645 60092 46663 60092 46754 60092 46645 590 46754 590 46757 590 46751 60093 46664 60093 46743 60093 46665 60094 46666 60094 46845 60094 46845 60095 46666 60095 46664 60095 46845 60096 46664 60096 46846 60096 46846 60097 46664 60097 46751 60097 46665 60098 46847 60098 46666 60098 46666 60099 46847 60099 46857 60099 46666 60100 46857 60100 46668 60100 46860 60101 46669 60101 46862 60101 46862 60102 46669 60102 46668 60102 46862 60103 46668 60103 46667 60103 46667 60104 46668 60104 46857 60104 46860 60105 46858 60105 46669 60105 46669 60106 46858 60106 46807 60106 46669 60107 46807 60107 46671 60107 46670 60108 46672 60108 46869 60108 46869 60109 46672 60109 46671 60109 46869 60110 46671 60110 46806 60110 46806 60111 46671 60111 46807 60111 46670 60112 46673 60112 46672 60112 46672 60113 46673 60113 46674 60113 46672 60114 46674 60114 46675 60114 46674 60115 46871 60115 46675 60115 46675 60116 46871 60116 46870 60116 46675 60117 46870 60117 46676 60117 46677 60118 46678 60118 46679 60118 46679 60119 46678 60119 46676 60119 46679 60120 46676 60120 46749 60120 46749 60121 46676 60121 46870 60121 46677 60122 46680 60122 46678 60122 46678 60123 46680 60123 46683 60123 46678 60124 46683 60124 46682 60124 46893 60125 46685 60125 46899 60125 46899 60126 46685 60126 46682 60126 46899 60127 46682 60127 46681 60127 46681 60128 46682 60128 46683 60128 46893 60129 46684 60129 46685 60129 46685 60130 46684 60130 46690 60130 46685 60131 46690 60131 46686 60131 46905 60132 46687 60132 46688 60132 46688 60133 46687 60133 46686 60133 46688 60134 46686 60134 46689 60134 46689 60135 46686 60135 46690 60135 46905 60136 46904 60136 46687 60136 46687 60137 46904 60137 46691 60137 46687 60138 46691 60138 46692 60138 46691 60139 46693 60140 46692 60141 46692 60142 46693 60142 46694 60142 46692 60143 46694 60143 46697 60143 46695 60144 46696 60144 46919 60144 46919 60145 46696 60145 46697 60145 46919 60146 46697 60146 46747 60146 46747 60147 46697 60147 46694 60147 46695 60148 46698 60148 46696 60148 46696 60149 46698 60149 46699 60149 46696 60150 46699 60150 46700 60150 46929 60151 46702 60151 46701 60151 46701 60152 46702 60152 46700 60152 46701 60153 46700 60153 46703 60153 46703 60154 46700 60154 46699 60154 46929 60155 46704 60155 46702 60155 46702 60156 46704 60156 46934 60156 46702 60157 46934 60157 46707 60157 46935 60158 46710 60158 46705 60158 46705 60159 46710 60159 46707 60159 46705 60160 46707 60160 46706 60160 46706 60161 46707 60161 46934 60161 46935 60162 46708 60162 46710 60162 46710 60163 46708 60163 46709 60163 46710 60164 46709 60164 46711 60164 46709 60165 46823 60165 46711 60165 46711 60166 46823 60166 46937 60166 46711 60167 46937 60167 46712 60167 46948 60168 46714 60168 46942 60168 46942 60169 46714 60169 46712 60169 46942 60170 46712 60170 46947 60170 46947 60171 46712 60171 46937 60171 46948 60172 46713 60172 46714 60172 46714 60173 46713 60173 46959 60173 46714 60174 46959 60174 46715 60174 46967 60175 46716 60175 46717 60175 46717 60176 46716 60176 46715 60176 46717 60177 46715 60177 46963 60177 46963 60178 46715 60178 46959 60178 46967 60179 46718 60179 46716 60179 46716 60180 46718 60180 46973 60180 46716 60181 46973 60181 46720 60181 46721 60182 46719 60182 46977 60182 46977 60183 46719 60183 46720 60183 46977 60184 46720 60184 46978 60184 46978 60185 46720 60185 46973 60185 46721 60186 46975 60186 46719 60186 46719 60187 46975 60187 46974 60187 46719 60188 46974 60188 46722 60188 46974 60189 46723 60189 46722 60189 46722 60190 46723 60190 46724 60190 46722 60191 46724 60191 46726 60191 46724 60192 46725 60192 46726 60192 46726 60193 46725 60193 46727 60193 46726 60194 46727 60194 46728 60194 46728 60195 46727 60195 46996 60195 46728 60196 46996 60196 46731 60196 46731 60197 46996 60197 46991 60197 46731 60198 46991 60198 46729 60198 47005 60199 46730 60199 47001 60199 47001 60200 46730 60200 46731 60200 47001 60201 46731 60201 46745 60201 46745 60202 46731 60202 46729 60202 47005 60203 46732 60203 46730 60203 46730 60204 46732 60204 46733 60204 46730 60205 46733 60205 46735 60205 46737 60206 46739 60206 46734 60206 46734 60207 46739 60207 46735 60207 46734 60208 46735 60208 46736 60208 46736 60209 46735 60209 46733 60209 46737 60210 46738 60210 46739 60210 46739 60211 46738 60211 46837 60211 46739 60212 46837 60212 46740 60212 46837 60213 47012 60213 46740 60213 46740 60214 47012 60214 47026 60214 46740 60215 47026 60215 46742 60215 47026 60216 46741 60216 46742 60216 46742 60217 46741 60217 47019 60217 46742 60218 47019 60218 46743 60218 46743 60219 47019 60219 46744 60219 46743 60220 46744 60220 46751 60220 46745 60221 46729 60221 46998 60221 46963 60222 46959 60222 46746 60222 46703 60223 46699 60223 46923 60223 46747 60224 46694 60224 46748 60224 46681 60225 46683 60225 46887 60225 46749 60226 46870 60226 46750 60226 46846 60227 46751 60227 46844 60227 46752 60228 46789 60228 47016 60228 46981 60229 46778 60229 46787 60229 46777 60230 46776 60230 46782 60230 46774 60231 46753 60231 46909 60231 46772 60232 46780 60232 46874 60232 46662 60233 46839 60233 47028 60233 46804 60234 46662 60234 47027 60234 46663 60235 47006 60235 47008 60235 46754 60236 46663 60236 46755 60236 46757 60237 46754 60237 46756 60237 46651 60238 46757 60238 46992 60238 46758 60239 46651 60239 46984 60239 46656 60240 46983 60240 46964 60240 46761 60241 46656 60241 46759 60241 46760 60242 46761 60242 46960 60242 46949 60243 46760 60243 46951 60243 46657 60244 46949 60244 46950 60244 46637 60245 46762 60245 46930 60245 46638 60246 46637 60246 46926 60246 46920 60247 46638 60247 46763 60247 46765 60248 46920 60248 46914 60248 46764 60249 46765 60249 46915 60249 46894 60250 46900 60250 46895 60250 46888 60251 46894 60251 46766 60251 46767 60252 46888 60252 46884 60252 46636 60253 46767 60253 46885 60253 46768 60254 46636 60254 46769 60254 46659 60255 46770 60255 46854 60255 46660 60256 46659 60256 46849 60256 46839 60257 46660 60257 46771 60257 46781 60258 46780 60258 46647 60258 46647 60259 46780 60259 46772 60259 46647 60260 46772 60260 46639 60260 46654 60261 46753 60261 46773 60261 46773 60262 46753 60262 46774 60262 46773 60263 46774 60263 46775 60263 46785 60264 46776 60264 46650 60264 46650 60265 46776 60265 46777 60265 46650 60266 46777 60266 46940 60266 46644 60267 46778 60267 46643 60267 46643 60268 46778 60268 46981 60268 46643 60269 46981 60269 46982 60269 46658 60270 46789 60270 46779 60270 46779 60271 46789 60271 46752 60271 46779 60272 46752 60272 47018 60272 46872 60273 46874 60273 46791 60273 46791 60274 46874 60274 46780 60274 46791 60275 46780 60275 46792 60275 46792 60276 46780 60276 46781 60276 46792 60277 46781 60277 46653 60277 46907 60278 46909 60278 46795 60278 46795 60279 46909 60279 46753 60279 46795 60280 46753 60280 46796 60280 46796 60281 46753 60281 46654 60281 46796 60282 46654 60282 46642 60282 46938 60283 46782 60283 46783 60283 46783 60284 46782 60284 46776 60284 46783 60285 46776 60285 46784 60285 46784 60286 46776 60286 46785 60286 46784 60287 46785 60287 46786 60287 46980 60288 46787 60288 46801 60288 46801 60289 46787 60289 46778 60289 46801 60290 46778 60290 46788 60290 46788 60291 46778 60291 46644 60291 46788 60292 46644 60292 46652 60292 47013 60293 47016 60293 46802 60293 46802 60294 47016 60294 46789 60294 46802 60295 46789 60295 46803 60295 46803 60296 46789 60296 46658 60296 46803 60297 46658 60297 46646 60297 46809 60298 46805 60298 46855 60298 46750 60299 46872 60299 46790 60299 46790 60300 46872 60300 46791 60300 46790 60301 46791 60301 46878 60301 46878 60302 46791 60302 46792 60302 46878 60303 46792 60303 46793 60303 46793 60304 46792 60304 46653 60304 46793 60305 46653 60305 46768 60305 46818 60306 46902 60306 46901 60306 46748 60307 46907 60307 46794 60307 46794 60308 46907 60308 46795 60308 46794 60309 46795 60309 46911 60309 46911 60310 46795 60310 46796 60310 46911 60311 46796 60311 46797 60311 46797 60312 46796 60312 46642 60312 46797 60313 46642 60313 46764 60313 46827 60314 46822 60314 46828 60314 46946 60315 46938 60315 46945 60315 46945 60316 46938 60316 46783 60316 46945 60317 46783 60317 46798 60317 46798 60318 46783 60318 46784 60318 46798 60319 46784 60319 46943 60319 46943 60320 46784 60320 46786 60320 46943 60321 46786 60321 46657 60321 46799 60322 46800 60322 46969 60322 46979 60323 46980 60323 46989 60323 46989 60324 46980 60324 46801 60324 46989 60325 46801 60325 46986 60325 46986 60326 46801 60326 46788 60326 46986 60327 46788 60327 46985 60327 46985 60328 46788 60328 46652 60328 46985 60329 46652 60329 46758 60329 46835 60330 46834 60330 47009 60330 47025 60331 47013 60331 47024 60331 47024 60332 47013 60332 46802 60332 47024 60333 46802 60333 47021 60333 47021 60334 46802 60334 46803 60334 47021 60335 46803 60335 47020 60335 47020 60336 46803 60336 46646 60336 47020 60337 46646 60337 46804 60337 46856 60338 46805 60338 46861 60338 46861 60339 46805 60339 46809 60339 46861 60340 46809 60340 46859 60340 46806 60341 46807 60341 46808 60341 46808 60342 46807 60342 46859 60342 46808 60343 46859 60343 46866 60343 46866 60344 46859 60344 46809 60344 46866 60345 46809 60345 46865 60345 46865 60346 46809 60346 46855 60346 46865 60347 46855 60347 46863 60347 46810 60348 46648 60348 46864 60348 46864 60349 46648 60349 46812 60349 46864 60350 46812 60350 46811 60350 46811 60351 46812 60351 46815 60351 46811 60352 46815 60352 46867 60352 46867 60353 46815 60353 46813 60353 46867 60354 46813 60354 46868 60354 46868 60355 46813 60355 46814 60355 46648 60356 46640 60356 46812 60356 46812 60357 46640 60357 46876 60357 46812 60358 46876 60358 46815 60358 46815 60359 46876 60359 46875 60359 46815 60360 46875 60360 46813 60360 46813 60361 46875 60361 46873 60361 46813 60362 46873 60362 46814 60362 46814 60363 46873 60363 46816 60363 46814 60364 46816 60364 46674 60364 46674 60365 46816 60365 46871 60365 46906 60366 46902 60366 46817 60366 46817 60367 46902 60367 46818 60367 46817 60368 46818 60368 46903 60368 46693 60369 46691 60369 46908 60369 46908 60370 46691 60370 46903 60370 46908 60371 46903 60371 46819 60371 46819 60372 46903 60372 46818 60372 46819 60373 46818 60373 46820 60373 46820 60374 46818 60374 46901 60374 46820 60375 46901 60375 46910 60375 46821 60376 46822 60376 46936 60376 46936 60377 46822 60377 46827 60377 46936 60378 46827 60378 46825 60378 46823 60379 46709 60379 46824 60379 46824 60380 46709 60380 46825 60380 46824 60381 46825 60381 46939 60381 46939 60382 46825 60382 46827 60382 46939 60383 46827 60383 46826 60383 46826 60384 46827 60384 46828 60384 46826 60385 46828 60385 46941 60385 46971 60386 46800 60386 46976 60386 46976 60387 46800 60387 46799 60387 46976 60388 46799 60388 46829 60388 46723 60389 46974 60389 46830 60389 46830 60390 46974 60390 46829 60390 46830 60391 46829 60391 46831 60391 46831 60392 46829 60392 46799 60392 46831 60393 46799 60393 46832 60393 46832 60394 46799 60394 46969 60394 46832 60395 46969 60395 46968 60395 46833 60396 46834 60396 46836 60396 46836 60397 46834 60397 46835 60397 46836 60398 46835 60398 46838 60398 47012 60399 46837 60399 47014 60399 47014 60400 46837 60400 46838 60400 47014 60401 46838 60401 47015 60401 47015 60402 46838 60402 46835 60402 47015 60403 46835 60403 47017 60403 47017 60404 46835 60404 47009 60404 47017 60405 47009 60405 47007 60405 46839 60406 46771 60406 47028 60406 47028 60407 46771 60407 46840 60407 47028 60408 46840 60408 46841 60408 46841 60409 46840 60409 46842 60409 46841 60410 46842 60410 47029 60410 47029 60411 46842 60411 46844 60411 47029 60412 46844 60412 47030 60412 47030 60413 46844 60413 46751 60413 47030 60414 46751 60414 46744 60414 46660 60415 46849 60415 46771 60415 46771 60416 46849 60416 46850 60416 46771 60417 46850 60417 46840 60417 46840 60418 46850 60418 46852 60418 46840 60419 46852 60419 46842 60419 46842 60420 46852 60420 46843 60420 46842 60421 46843 60421 46844 60421 46844 60422 46843 60422 46845 60422 46844 60423 46845 60423 46846 60423 46853 60424 46847 60424 46665 60424 46659 60425 46854 60425 46849 60425 46849 60426 46854 60426 46848 60426 46849 60427 46848 60427 46850 60427 46850 60428 46848 60428 46851 60428 46850 60429 46851 60429 46852 60429 46852 60430 46851 60430 46853 60430 46852 60431 46853 60431 46843 60431 46843 60432 46853 60432 46665 60432 46843 60433 46665 60433 46845 60433 46770 60434 46863 60434 46854 60434 46854 60435 46863 60435 46855 60435 46854 60436 46855 60436 46848 60436 46848 60437 46855 60437 46805 60437 46848 60438 46805 60438 46851 60438 46851 60439 46805 60439 46856 60439 46851 60440 46856 60440 46853 60440 46853 60441 46856 60441 46857 60441 46853 60442 46857 60442 46847 60442 46807 60443 46858 60443 46859 60443 46859 60444 46858 60444 46860 60444 46859 60445 46860 60445 46861 60445 46861 60446 46860 60446 46862 60446 46861 60447 46862 60447 46856 60447 46856 60448 46862 60448 46667 60448 46856 60449 46667 60449 46857 60449 46770 60450 46810 60450 46863 60450 46863 60451 46810 60451 46864 60451 46863 60452 46864 60452 46865 60452 46865 60453 46864 60453 46811 60453 46865 60454 46811 60454 46866 60454 46866 60455 46811 60455 46867 60455 46866 60456 46867 60456 46808 60456 46808 60457 46867 60457 46868 60457 46808 60458 46868 60458 46806 60458 46674 60459 46673 60459 46814 60459 46814 60460 46673 60460 46670 60460 46814 60461 46670 60461 46868 60461 46868 60462 46670 60462 46869 60462 46868 60463 46869 60463 46806 60463 46870 60464 46871 60464 46750 60464 46750 60465 46871 60465 46816 60465 46750 60466 46816 60466 46872 60466 46872 60467 46816 60467 46873 60467 46872 60468 46873 60468 46874 60468 46874 60469 46873 60469 46875 60469 46874 60470 46875 60470 46772 60470 46772 60471 46875 60471 46876 60471 46772 60472 46876 60472 46639 60472 46639 60473 46876 60473 46640 60473 46768 60474 46769 60474 46793 60474 46793 60475 46769 60475 46877 60475 46793 60476 46877 60476 46878 60476 46878 60477 46877 60477 46879 60477 46878 60478 46879 60478 46790 60478 46790 60479 46879 60479 46883 60479 46790 60480 46883 60480 46750 60480 46750 60481 46883 60481 46679 60481 46750 60482 46679 60482 46749 60482 46882 60483 46680 60483 46677 60483 46636 60484 46885 60484 46769 60484 46769 60485 46885 60485 46880 60485 46769 60486 46880 60486 46877 60486 46877 60487 46880 60487 46881 60487 46877 60488 46881 60488 46879 60488 46879 60489 46881 60489 46882 60489 46879 60490 46882 60490 46883 60490 46883 60491 46882 60491 46677 60491 46883 60492 46677 60492 46679 60492 46767 60493 46884 60493 46885 60493 46885 60494 46884 60494 46886 60494 46885 60495 46886 60495 46880 60495 46880 60496 46886 60496 46891 60496 46880 60497 46891 60497 46881 60497 46881 60498 46891 60498 46887 60498 46881 60499 46887 60499 46882 60499 46882 60500 46887 60500 46683 60500 46882 60501 46683 60501 46680 60501 46888 60502 46766 60502 46884 60502 46884 60503 46766 60503 46889 60503 46884 60504 46889 60504 46886 60504 46886 60505 46889 60505 46897 60505 46886 60506 46897 60506 46891 60506 46891 60507 46897 60507 46890 60507 46891 60508 46890 60508 46887 60508 46887 60509 46890 60509 46899 60509 46887 60510 46899 60510 46681 60510 46892 60511 46684 60511 46893 60511 46894 60512 46895 60512 46766 60512 46766 60513 46895 60513 46896 60513 46766 60514 46896 60514 46889 60514 46889 60515 46896 60515 46898 60515 46889 60516 46898 60516 46897 60516 46897 60517 46898 60517 46892 60517 46897 60518 46892 60518 46890 60518 46890 60519 46892 60519 46893 60519 46890 60520 46893 60520 46899 60520 46900 60521 46910 60521 46895 60521 46895 60522 46910 60522 46901 60522 46895 60523 46901 60523 46896 60523 46896 60524 46901 60524 46902 60524 46896 60525 46902 60525 46898 60525 46898 60526 46902 60526 46906 60526 46898 60527 46906 60527 46892 60527 46892 60528 46906 60528 46690 60528 46892 60529 46690 60529 46684 60529 46691 60530 46904 60530 46903 60530 46903 60531 46904 60531 46905 60531 46903 60532 46905 60532 46817 60532 46817 60533 46905 60533 46688 60533 46817 60534 46688 60534 46906 60534 46906 60535 46688 60535 46689 60535 46906 60536 46689 60536 46690 60536 46694 60537 46693 60537 46748 60537 46748 60538 46693 60538 46908 60538 46748 60539 46908 60539 46907 60539 46907 60540 46908 60540 46819 60540 46907 60541 46819 60541 46909 60541 46909 60542 46819 60542 46820 60542 46909 60543 46820 60543 46774 60543 46774 60544 46820 60544 46910 60544 46774 60545 46910 60545 46775 60545 46775 60546 46910 60546 46900 60546 46764 60547 46915 60547 46797 60547 46797 60548 46915 60548 46916 60548 46797 60549 46916 60549 46911 60549 46911 60550 46916 60550 46912 60550 46911 60551 46912 60551 46794 60551 46794 60552 46912 60552 46918 60552 46794 60553 46918 60553 46748 60553 46748 60554 46918 60554 46919 60554 46748 60555 46919 60555 46747 60555 46913 60556 46698 60556 46695 60556 46765 60557 46914 60557 46915 60557 46915 60558 46914 60558 46917 60558 46915 60559 46917 60559 46916 60559 46916 60560 46917 60560 46922 60560 46916 60561 46922 60561 46912 60561 46912 60562 46922 60562 46913 60562 46912 60563 46913 60563 46918 60563 46918 60564 46913 60564 46695 60564 46918 60565 46695 60565 46919 60565 46920 60566 46763 60566 46914 60566 46914 60567 46763 60567 46924 60567 46914 60568 46924 60568 46917 60568 46917 60569 46924 60569 46921 60569 46917 60570 46921 60570 46922 60570 46922 60571 46921 60571 46923 60571 46922 60572 46923 60572 46913 60572 46913 60573 46923 60573 46699 60573 46913 60574 46699 60574 46698 60574 46638 60575 46926 60575 46763 60575 46763 60576 46926 60576 46927 60576 46763 60577 46927 60577 46924 60577 46924 60578 46927 60578 46925 60578 46924 60579 46925 60579 46921 60579 46921 60580 46925 60580 46928 60580 46921 60581 46928 60581 46923 60581 46923 60582 46928 60582 46701 60582 46923 60583 46701 60583 46703 60583 46933 60584 46704 60584 46929 60584 46637 60585 46930 60585 46926 60585 46926 60586 46930 60586 46931 60586 46926 60587 46931 60587 46927 60587 46927 60588 46931 60588 46932 60588 46927 60589 46932 60589 46925 60589 46925 60590 46932 60590 46933 60590 46925 60591 46933 60591 46928 60591 46928 60592 46933 60592 46929 60592 46928 60593 46929 60593 46701 60593 46762 60594 46941 60594 46930 60594 46930 60595 46941 60595 46828 60595 46930 60596 46828 60596 46931 60596 46931 60597 46828 60597 46822 60597 46931 60598 46822 60598 46932 60598 46932 60599 46822 60599 46821 60599 46932 60600 46821 60600 46933 60600 46933 60601 46821 60601 46934 60601 46933 60602 46934 60602 46704 60602 46709 60603 46708 60603 46825 60603 46825 60604 46708 60604 46935 60604 46825 60605 46935 60605 46936 60605 46936 60606 46935 60606 46705 60606 46936 60607 46705 60607 46821 60607 46821 60608 46705 60608 46706 60608 46821 60609 46706 60609 46934 60609 46937 60610 46823 60610 46946 60610 46946 60611 46823 60611 46824 60611 46946 60612 46824 60612 46938 60612 46938 60613 46824 60613 46939 60613 46938 60614 46939 60614 46782 60614 46782 60615 46939 60615 46826 60615 46782 60616 46826 60616 46777 60616 46777 60617 46826 60617 46941 60617 46777 60618 46941 60618 46940 60618 46940 60619 46941 60619 46762 60619 46953 60620 46942 60620 46947 60620 46657 60621 46950 60621 46943 60621 46943 60622 46950 60622 46952 60622 46943 60623 46952 60623 46798 60623 46798 60624 46952 60624 46944 60624 46798 60625 46944 60625 46945 60625 46945 60626 46944 60626 46953 60626 46945 60627 46953 60627 46946 60627 46946 60628 46953 60628 46947 60628 46946 60629 46947 60629 46937 60629 46958 60630 46713 60630 46948 60630 46949 60631 46951 60631 46950 60631 46950 60632 46951 60632 46955 60632 46950 60633 46955 60633 46952 60633 46952 60634 46955 60634 46957 60634 46952 60635 46957 60635 46944 60635 46944 60636 46957 60636 46958 60636 46944 60637 46958 60637 46953 60637 46953 60638 46958 60638 46948 60638 46953 60639 46948 60639 46942 60639 46760 60640 46960 60640 46951 60640 46951 60641 46960 60641 46954 60641 46951 60642 46954 60642 46955 60642 46955 60643 46954 60643 46956 60643 46955 60644 46956 60644 46957 60644 46957 60645 46956 60645 46746 60645 46957 60646 46746 60646 46958 60646 46958 60647 46746 60647 46959 60647 46958 60648 46959 60648 46713 60648 46761 60649 46759 60649 46960 60649 46960 60650 46759 60650 46961 60650 46960 60651 46961 60651 46954 60651 46954 60652 46961 60652 46962 60652 46954 60653 46962 60653 46956 60653 46956 60654 46962 60654 46966 60654 46956 60655 46966 60655 46746 60655 46746 60656 46966 60656 46717 60656 46746 60657 46717 60657 46963 60657 46972 60658 46718 60658 46967 60658 46656 60659 46964 60659 46759 60659 46759 60660 46964 60660 46970 60660 46759 60661 46970 60661 46961 60661 46961 60662 46970 60662 46965 60662 46961 60663 46965 60663 46962 60663 46962 60664 46965 60664 46972 60664 46962 60665 46972 60665 46966 60665 46966 60666 46972 60666 46967 60666 46966 60667 46967 60667 46717 60667 46983 60668 46968 60668 46964 60668 46964 60669 46968 60669 46969 60669 46964 60670 46969 60670 46970 60670 46970 60671 46969 60671 46800 60671 46970 60672 46800 60672 46965 60672 46965 60673 46800 60673 46971 60673 46965 60674 46971 60674 46972 60674 46972 60675 46971 60675 46973 60675 46972 60676 46973 60676 46718 60676 46974 60677 46975 60677 46829 60677 46829 60678 46975 60678 46721 60678 46829 60679 46721 60679 46976 60679 46976 60680 46721 60680 46977 60680 46976 60681 46977 60681 46971 60681 46971 60682 46977 60682 46978 60682 46971 60683 46978 60683 46973 60683 46724 60684 46723 60684 46979 60684 46979 60685 46723 60685 46830 60685 46979 60686 46830 60686 46980 60686 46980 60687 46830 60687 46831 60687 46980 60688 46831 60688 46787 60688 46787 60689 46831 60689 46832 60689 46787 60690 46832 60690 46981 60690 46981 60691 46832 60691 46968 60691 46981 60692 46968 60692 46982 60692 46982 60693 46968 60693 46983 60693 46990 60694 46727 60694 46725 60694 46758 60695 46984 60695 46985 60695 46985 60696 46984 60696 46987 60696 46985 60697 46987 60697 46986 60697 46986 60698 46987 60698 46988 60698 46986 60699 46988 60699 46989 60699 46989 60700 46988 60700 46990 60700 46989 60701 46990 60701 46979 60701 46979 60702 46990 60702 46725 60702 46979 60703 46725 60703 46724 60703 46995 60704 46991 60704 46996 60704 46651 60705 46992 60705 46984 60705 46984 60706 46992 60706 46993 60706 46984 60707 46993 60707 46987 60707 46987 60708 46993 60708 46994 60708 46987 60709 46994 60709 46988 60709 46988 60710 46994 60710 46995 60710 46988 60711 46995 60711 46990 60711 46990 60712 46995 60712 46996 60712 46990 60713 46996 60713 46727 60713 46757 60714 46756 60714 46992 60714 46992 60715 46756 60715 46999 60715 46992 60716 46999 60716 46993 60716 46993 60717 46999 60717 46997 60717 46993 60718 46997 60718 46994 60718 46994 60719 46997 60719 46998 60719 46994 60720 46998 60720 46995 60720 46995 60721 46998 60721 46729 60721 46995 60722 46729 60722 46991 60722 46754 60723 46755 60723 46756 60723 46756 60724 46755 60724 47002 60724 46756 60725 47002 60725 46999 60725 46999 60726 47002 60726 47000 60726 46999 60727 47000 60727 46997 60727 46997 60728 47000 60728 47004 60728 46997 60729 47004 60729 46998 60729 46998 60730 47004 60730 47001 60730 46998 60731 47001 60731 46745 60731 47003 60732 46732 60732 47005 60732 46663 60733 47008 60733 46755 60733 46755 60734 47008 60734 47010 60734 46755 60735 47010 60735 47002 60735 47002 60736 47010 60736 47011 60736 47002 60737 47011 60737 47000 60737 47000 60738 47011 60738 47003 60738 47000 60739 47003 60739 47004 60739 47004 60740 47003 60740 47005 60740 47004 60741 47005 60741 47001 60741 47006 60742 47007 60742 47008 60742 47008 60743 47007 60743 47009 60743 47008 60744 47009 60744 47010 60744 47010 60745 47009 60745 46834 60745 47010 60746 46834 60746 47011 60746 47011 60747 46834 60747 46833 60747 47011 60748 46833 60748 47003 60748 47003 60749 46833 60749 46733 60749 47003 60750 46733 60750 46732 60750 46837 60751 46738 60751 46838 60751 46838 60752 46738 60752 46737 60752 46838 60753 46737 60753 46836 60753 46836 60754 46737 60754 46734 60754 46836 60755 46734 60755 46833 60755 46833 60756 46734 60756 46736 60756 46833 60757 46736 60757 46733 60757 47026 60758 47012 60758 47025 60758 47025 60759 47012 60759 47014 60759 47025 60760 47014 60760 47013 60760 47013 60761 47014 60761 47015 60761 47013 60762 47015 60762 47016 60762 47016 60763 47015 60763 47017 60763 47016 60764 47017 60764 46752 60764 46752 60765 47017 60765 47007 60765 46752 60766 47007 60766 47018 60766 47018 60767 47007 60767 47006 60767 47031 60768 47019 60768 46741 60768 46804 60769 47027 60769 47020 60769 47020 60770 47027 60770 47022 60770 47020 60771 47022 60771 47021 60771 47021 60772 47022 60772 47023 60772 47021 60773 47023 60773 47024 60773 47024 60774 47023 60774 47031 60774 47024 60775 47031 60775 47025 60775 47025 60776 47031 60776 46741 60776 47025 60777 46741 60777 47026 60777 46662 60778 47028 60778 47027 60778 47027 60779 47028 60779 46841 60779 47027 60780 46841 60780 47022 60780 47022 60781 46841 60781 47029 60781 47022 60782 47029 60782 47023 60782 47023 60783 47029 60783 47030 60783 47023 60784 47030 60784 47031 60784 47031 60785 47030 60785 46744 60785 47031 60786 46744 60786 47019 60786 47041 60787 47032 60787 47034 60787 47034 590 47032 590 47033 590 47034 590 47033 590 47035 590 47038 590 47034 590 47036 590 47036 590 47034 590 47037 590 47038 60788 47039 60788 47034 60788 47034 60789 47039 60789 47040 60789 47034 60790 47040 60790 47041 60790 47035 590 47042 590 47034 590 47034 60791 47042 60791 47043 60791 47034 60792 47043 60792 47044 60792 47045 60793 47078 60793 47046 60793 47046 60794 47078 60794 47084 60794 47046 60795 47084 60795 47047 60795 47047 60796 47084 60796 47048 60796 47048 60797 47084 60797 47059 60797 47048 60798 47059 60798 47049 60798 47050 60799 47068 60799 47051 60799 47051 60800 47068 60800 47065 60800 47051 60801 47065 60801 47052 60801 47052 60802 47065 60802 47053 60802 47053 60803 47065 60803 47071 60803 47053 60802 47071 60802 47054 60802 47186 60804 47443 60804 47071 60804 47055 60805 47347 60805 47059 60805 47072 590 47208 590 47071 590 47071 60806 47208 60806 47185 60806 47071 60807 47185 60807 47186 60807 47066 590 47056 590 47065 590 47065 60808 47056 60808 47057 60808 47059 60809 47058 60809 47196 60809 47347 60810 47060 60810 47059 60810 47059 60811 47060 60811 47173 60811 47059 60812 47173 60812 47058 60812 47057 590 47281 590 47065 590 47065 590 47281 590 47061 590 47065 60813 47061 60813 47175 60813 47069 590 47062 590 47068 590 47068 60814 47062 60814 47063 60814 47063 590 47191 590 47068 590 47068 590 47191 590 47064 590 47068 60815 47064 60815 47065 60815 47065 590 47064 590 47177 590 47065 590 47177 590 47066 590 47082 60816 47067 60816 47068 60816 47068 60817 47067 60817 47174 60817 47068 590 47174 590 47069 590 47220 590 47204 590 47078 590 47078 590 47204 590 47070 590 47080 60818 47412 60818 47078 60818 47078 60819 47412 60819 47221 60819 47078 60820 47221 60820 47220 60820 47175 590 47176 590 47065 590 47065 60821 47176 60821 47167 60821 47065 60822 47167 60822 47071 60822 47071 60823 47167 60823 47168 60823 47071 60824 47168 60824 47072 60824 47075 590 47216 590 47084 590 47084 60825 47216 60825 47182 60825 47073 60826 47074 60826 47084 60826 47084 590 47074 590 47376 590 47084 32368 47376 32368 47075 32368 47443 590 47076 590 47071 590 47071 60827 47076 60827 47077 60827 47071 590 47077 590 47078 590 47078 60828 47077 60828 47079 60828 47078 60829 47079 60829 47080 60829 47196 590 47081 590 47059 590 47059 60830 47081 60830 47180 60830 47059 590 47180 590 47068 590 47068 590 47180 590 47181 590 47068 590 47181 590 47082 590 47070 590 47401 590 47078 590 47078 60831 47401 60831 47083 60831 47078 60832 47083 60832 47084 60832 47084 590 47083 590 47169 590 47084 60833 47169 60833 47073 60833 47182 590 47183 590 47084 590 47084 60834 47183 60834 47371 60834 47084 590 47371 590 47059 590 47059 60835 47371 60835 47358 60835 47059 60836 47358 60836 47055 60836 47087 60837 47086 60837 47085 60837 47268 60838 47089 60838 47270 60838 47270 60839 47089 60839 47086 60839 47270 60840 47086 60840 47262 60840 47262 60841 47086 60841 47087 60841 47268 60842 47274 60842 47089 60842 47089 60843 47274 60843 47088 60843 47089 60844 47088 60844 47090 60844 47278 60845 47092 60845 47279 60845 47279 60846 47092 60846 47090 60846 47279 60847 47090 60847 47091 60847 47091 60848 47090 60848 47088 60848 47278 60849 47275 60849 47092 60849 47092 60850 47275 60850 47093 60850 47092 60851 47093 60851 47094 60851 47288 60852 47095 60852 47289 60852 47289 60853 47095 60853 47094 60853 47289 60854 47094 60854 47225 60854 47225 60855 47094 60855 47093 60855 47288 60856 47287 60856 47095 60856 47095 60857 47287 60857 47234 60857 47095 60858 47234 60858 47097 60858 47234 60859 47096 60859 47097 60859 47097 60860 47096 60860 47163 60860 47097 60861 47163 60861 47101 60861 47098 60862 47099 60862 47100 60862 47100 60863 47099 60863 47101 60863 47100 60864 47101 60864 47300 60864 47300 60865 47101 60865 47163 60865 47098 60866 47102 60866 47099 60866 47099 60867 47102 60867 47307 60867 47099 60868 47307 60868 47105 60868 47314 60869 47103 60869 47104 60869 47104 60870 47103 60870 47105 60870 47104 60871 47105 60871 47312 60871 47312 60872 47105 60872 47307 60872 47314 60873 47313 60873 47103 60873 47103 60874 47313 60874 47326 60874 47103 60875 47326 60875 47106 60875 47324 60876 47107 60876 47325 60876 47325 60877 47107 60877 47106 60877 47325 60878 47106 60878 47108 60878 47108 60879 47106 60879 47326 60879 47324 60880 47323 60880 47107 60880 47107 60881 47323 60881 47110 60881 47107 60882 47110 60882 47109 60882 47110 60883 47111 60883 47109 60883 47109 60884 47111 60884 47112 60884 47109 60885 47112 60885 47113 60885 47340 60886 47114 60886 47341 60886 47341 60887 47114 60887 47113 60887 47341 60888 47113 60888 47161 60888 47161 60889 47113 60889 47112 60889 47340 60890 47346 60890 47114 60890 47114 60891 47346 60891 47160 60891 47114 60892 47160 60892 47117 60892 47353 60893 47116 60893 47115 60893 47115 60894 47116 60894 47117 60894 47115 60895 47117 60895 47118 60895 47118 60896 47117 60896 47160 60896 47353 60897 47119 60897 47116 60897 47116 60898 47119 60898 47361 60898 47116 60899 47361 60899 47120 60899 47363 60900 47122 60900 47365 60900 47365 60901 47122 60901 47120 60901 47365 60902 47120 60902 47366 60902 47366 60903 47120 60903 47361 60903 47363 60904 47121 60904 47122 60904 47122 60905 47121 60905 47362 60905 47122 60906 47362 60906 47123 60906 47362 60907 47240 60907 47123 60907 47123 60908 47240 60908 47125 60908 47123 60909 47125 60909 47124 60909 47381 60910 47127 60910 47373 60910 47373 60911 47127 60911 47124 60911 47373 60912 47124 60912 47375 60912 47375 60913 47124 60913 47125 60913 47381 60914 47126 60914 47127 60914 47127 60915 47126 60915 47128 60915 47127 60916 47128 60916 47131 60916 47133 60917 47129 60917 47130 60917 47130 60918 47129 60918 47131 60918 47130 60919 47131 60919 47132 60919 47132 60920 47131 60920 47128 60920 47133 60921 47134 60921 47129 60921 47129 60922 47134 60922 47396 60922 47129 60923 47396 60923 47137 60923 47135 60924 47138 60924 47398 60924 47398 60925 47138 60925 47137 60925 47398 60926 47137 60926 47136 60926 47136 60927 47137 60927 47396 60927 47135 60928 47397 60928 47138 60928 47138 60929 47397 60929 47247 60929 47138 60930 47247 60930 47139 60930 47247 60931 47399 60931 47139 60931 47139 60932 47399 60932 47410 60932 47139 60933 47410 60933 47140 60933 47410 60934 47403 60934 47140 60934 47140 60935 47403 60935 47402 60935 47140 60936 47402 60936 47141 60936 47141 60937 47402 60937 47411 60937 47141 60938 47411 60938 47143 60938 47143 60939 47411 60939 47142 60939 47143 60940 47142 60940 47145 60940 47429 60941 47147 60941 47423 60941 47423 60942 47147 60942 47143 60942 47423 60943 47143 60943 47144 60943 47144 60944 47143 60944 47145 60944 47429 60945 47146 60945 47147 60945 47147 60946 47146 60946 47148 60946 47147 60947 47148 60947 47150 60947 47434 60948 47152 60948 47149 60948 47149 60949 47152 60949 47150 60949 47149 60950 47150 60950 47436 60950 47436 60951 47150 60951 47148 60951 47434 60952 47151 60952 47152 60952 47152 60953 47151 60953 47254 60953 47152 60954 47254 60954 47154 60954 47254 60955 47153 60955 47154 60955 47154 60956 47153 60956 47437 60956 47154 60957 47437 60957 47155 60957 47437 60958 47156 60958 47155 60958 47155 60959 47156 60959 47157 60959 47155 60960 47157 60960 47085 60960 47085 60961 47157 60961 47158 60961 47085 60962 47158 60962 47087 60962 47144 60963 47145 60963 47159 60963 47132 60964 47128 60964 47388 60964 47118 60965 47160 60965 47345 60965 47161 60966 47112 60966 47327 60966 47312 60967 47307 60967 47162 60967 47300 60968 47163 60968 47290 60968 47262 60969 47087 60969 47261 60969 47164 60970 47187 60970 47441 60970 47184 60971 47202 60971 47201 60971 47165 60972 47199 60972 47369 60972 47330 60973 47166 60973 47193 60973 47179 60974 47178 60974 47188 60974 47168 60975 47167 60975 47447 60975 47072 60976 47168 60976 47449 60976 47077 60977 47076 60977 47430 60977 47079 60978 47077 60978 47424 60978 47080 60979 47079 60979 47419 60979 47412 60980 47080 60980 47413 60980 47221 60981 47412 60981 47404 60981 47169 60982 47083 60982 47170 60982 47073 60983 47169 60983 47171 60983 47074 60984 47073 60984 47387 60984 47376 60985 47074 60985 47377 60985 47075 60986 47376 60986 47378 60986 47055 60987 47358 60987 47172 60987 47347 60988 47055 60988 47354 60988 47060 60989 47347 60989 47348 60989 47173 60990 47060 60990 47342 60990 47058 60991 47173 60991 47337 60991 47067 60992 47082 60992 47320 60992 47174 60993 47067 60993 47309 60993 47069 60994 47174 60994 47308 60994 47062 60995 47069 60995 47301 60995 47063 60996 47062 60996 47302 60996 47175 60997 47061 60997 47263 60997 47176 60998 47175 60998 47259 60998 47167 60999 47176 60999 47258 60999 47064 61000 47178 61000 47177 61000 47177 61001 47178 61001 47179 61001 47177 61002 47179 61002 47066 61002 47081 61003 47166 61003 47180 61003 47180 61004 47166 61004 47330 61004 47180 61005 47330 61005 47181 61005 47182 61006 47199 61006 47183 61006 47183 61007 47199 61007 47165 61007 47183 61008 47165 61008 47371 61008 47204 61009 47202 61009 47070 61009 47070 61010 47202 61010 47184 61010 47070 61011 47184 61011 47401 61011 47185 61012 47187 61012 47186 61012 47186 61013 47187 61013 47164 61013 47186 61014 47164 61014 47443 61014 47291 61015 47188 61015 47189 61015 47189 61016 47188 61016 47178 61016 47189 61017 47178 61017 47190 61017 47190 61018 47178 61018 47064 61018 47190 61019 47064 61019 47191 61019 47192 61020 47193 61020 47194 61020 47194 61021 47193 61021 47166 61021 47194 61022 47166 61022 47195 61022 47195 61023 47166 61023 47081 61023 47195 61024 47081 61024 47196 61024 47213 61025 47369 61025 47197 61025 47197 61026 47369 61026 47199 61026 47197 61027 47199 61027 47198 61027 47198 61028 47199 61028 47182 61028 47198 61029 47182 61029 47216 61029 47200 61030 47201 61030 47218 61030 47218 61031 47201 61031 47202 61031 47218 61032 47202 61032 47203 61032 47203 61033 47202 61033 47204 61033 47203 61034 47204 61034 47220 61034 47205 61035 47441 61035 47206 61035 47206 61036 47441 61036 47187 61036 47206 61037 47187 61037 47207 61037 47207 61038 47187 61038 47185 61038 47207 61039 47185 61039 47208 61039 47227 61040 47272 61040 47209 61040 47290 61041 47291 61041 47298 61041 47298 61042 47291 61042 47189 61042 47298 61043 47189 61043 47297 61043 47297 61044 47189 61044 47190 61044 47297 61045 47190 61045 47210 61045 47210 61046 47190 61046 47191 61046 47210 61047 47191 61047 47063 61047 47236 61048 47321 61048 47211 61048 47327 61049 47192 61049 47335 61049 47335 61050 47192 61050 47194 61050 47335 61051 47194 61051 47334 61051 47334 61052 47194 61052 47195 61052 47334 61053 47195 61053 47332 61053 47332 61054 47195 61054 47196 61054 47332 61055 47196 61055 47058 61055 47243 61056 47360 61056 47212 61056 47367 61057 47213 61057 47214 61057 47214 61058 47213 61058 47197 61058 47214 61059 47197 61059 47215 61059 47215 61060 47197 61060 47198 61060 47215 61061 47198 61061 47374 61061 47374 61062 47198 61062 47216 61062 47374 61063 47216 61063 47075 61063 47251 61064 47217 61064 47252 61064 47408 61065 47200 61065 47407 61065 47407 61066 47200 61066 47218 61066 47407 61067 47218 61067 47406 61067 47406 61068 47218 61068 47203 61068 47406 61069 47203 61069 47219 61069 47219 61070 47203 61070 47220 61070 47219 61071 47220 61071 47221 61071 47255 61072 47432 61072 47431 61072 47222 61073 47205 61073 47223 61073 47223 61074 47205 61074 47206 61074 47223 61075 47206 61075 47445 61075 47445 61076 47206 61076 47207 61076 47445 61077 47207 61077 47224 61077 47224 61078 47207 61078 47208 61078 47224 61079 47208 61079 47072 61079 47280 61080 47272 61080 47277 61080 47277 61081 47272 61081 47227 61081 47277 61082 47227 61082 47276 61082 47225 61083 47093 61083 47285 61083 47285 61084 47093 61084 47276 61084 47285 61085 47276 61085 47226 61085 47226 61086 47276 61086 47227 61086 47226 61087 47227 61087 47228 61087 47228 61088 47227 61088 47209 61088 47228 61089 47209 61089 47271 61089 47281 61090 47057 61090 47282 61090 47282 61091 47057 61091 47229 61091 47282 61092 47229 61092 47283 61092 47283 61093 47229 61093 47230 61093 47283 61094 47230 61094 47284 61094 47284 61095 47230 61095 47231 61095 47284 61096 47231 61096 47286 61096 47286 61097 47231 61097 47232 61097 47057 61098 47056 61098 47229 61098 47229 61099 47056 61099 47294 61099 47229 61100 47294 61100 47230 61100 47230 61101 47294 61101 47293 61101 47230 61102 47293 61102 47231 61102 47231 61103 47293 61103 47292 61103 47231 61104 47292 61104 47232 61104 47232 61105 47292 61105 47233 61105 47232 61106 47233 61106 47234 61106 47234 61107 47233 61108 47096 61109 47322 61110 47321 61110 47235 61110 47235 61111 47321 61111 47236 61111 47235 61112 47236 61112 47237 61112 47111 61113 47110 61113 47328 61113 47328 61114 47110 61114 47237 61114 47328 61115 47237 61115 47329 61115 47329 61116 47237 61116 47236 61116 47329 61117 47236 61117 47238 61117 47238 61118 47236 61118 47211 61118 47238 61119 47211 61119 47331 61119 47239 61120 47360 61120 47364 61120 47364 61121 47360 61121 47243 61121 47364 61122 47243 61122 47242 61122 47240 61123 47362 61123 47241 61123 47241 61124 47362 61124 47242 61124 47241 61125 47242 61125 47368 61125 47368 61126 47242 61126 47243 61126 47368 61127 47243 61127 47244 61127 47244 61128 47243 61128 47212 61128 47244 61129 47212 61129 47370 61129 47245 61130 47217 61130 47246 61130 47246 61131 47217 61131 47251 61131 47246 61132 47251 61132 47249 61132 47399 61133 47247 61133 47248 61133 47248 61134 47247 61134 47249 61134 47248 61135 47249 61135 47250 61135 47250 61136 47249 61136 47251 61136 47250 61137 47251 61137 47400 61137 47400 61138 47251 61138 47252 61138 47400 61139 47252 61139 47394 61139 47435 61140 47432 61140 47253 61140 47253 61141 47432 61141 47255 61141 47253 61142 47255 61142 47433 61142 47153 61143 47254 61143 47438 61143 47438 61144 47254 61144 47433 61144 47438 61145 47433 61145 47439 61145 47439 61146 47433 61146 47255 61146 47439 61147 47255 61147 47440 61147 47440 61148 47255 61148 47431 61148 47440 61149 47431 61149 47442 61149 47167 61150 47258 61150 47447 61150 47447 61151 47258 61151 47260 61151 47447 61152 47260 61152 47448 61152 47448 61153 47260 61153 47256 61153 47448 61154 47256 61154 47451 61154 47451 61155 47256 61155 47261 61155 47451 61156 47261 61156 47257 61156 47257 61157 47261 61157 47087 61157 47257 61158 47087 61158 47158 61158 47176 61159 47259 61159 47258 61159 47258 61160 47259 61160 47264 61160 47258 61161 47264 61161 47260 61161 47260 61162 47264 61162 47267 61162 47260 61163 47267 61163 47256 61163 47256 61164 47267 61164 47269 61164 47256 61165 47269 61165 47261 61165 47261 61166 47269 61166 47270 61166 47261 61167 47270 61167 47262 61167 47273 61168 47274 61168 47268 61168 47175 61169 47263 61169 47259 61169 47259 61170 47263 61170 47265 61170 47259 61171 47265 61171 47264 61171 47264 61172 47265 61172 47266 61172 47264 61173 47266 61173 47267 61173 47267 61174 47266 61174 47273 61174 47267 61175 47273 61175 47269 61175 47269 61176 47273 61176 47268 61176 47269 61177 47268 61177 47270 61177 47061 61178 47271 61178 47263 61178 47263 61179 47271 61179 47209 61179 47263 61180 47209 61180 47265 61180 47265 61181 47209 61181 47272 61181 47265 61182 47272 61182 47266 61182 47266 61183 47272 61183 47280 61183 47266 61184 47280 61184 47273 61184 47273 61185 47280 61185 47088 61185 47273 61186 47088 61186 47274 61186 47093 61187 47275 61187 47276 61187 47276 61188 47275 61188 47278 61188 47276 61189 47278 61189 47277 61189 47277 61190 47278 61190 47279 61190 47277 61191 47279 61191 47280 61191 47280 61192 47279 61192 47091 61192 47280 61193 47091 61193 47088 61193 47061 61194 47281 61194 47271 61194 47271 61195 47281 61195 47282 61195 47271 61196 47282 61196 47228 61196 47228 61197 47282 61197 47283 61197 47228 61198 47283 61198 47226 61198 47226 61199 47283 61199 47284 61199 47226 61200 47284 61200 47285 61200 47285 61201 47284 61201 47286 61201 47285 61202 47286 61202 47225 61202 47234 61203 47287 61203 47232 61203 47232 61204 47287 61204 47288 61204 47232 61205 47288 61205 47286 61205 47286 61206 47288 61206 47289 61206 47286 61207 47289 61207 47225 61207 47163 61208 47096 61208 47290 61208 47290 61209 47096 61209 47233 61209 47290 61210 47233 61210 47291 61210 47291 61211 47233 61211 47292 61211 47291 61212 47292 61212 47188 61212 47188 61213 47292 61213 47293 61213 47188 61214 47293 61214 47179 61214 47179 61215 47293 61215 47294 61215 47179 61216 47294 61216 47066 61216 47066 61217 47294 61217 47056 61217 47063 61218 47302 61218 47210 61218 47210 61219 47302 61219 47295 61219 47210 61220 47295 61220 47297 61220 47297 61221 47295 61221 47296 61221 47297 61222 47296 61222 47298 61222 47298 61223 47296 61223 47299 61223 47298 61224 47299 61224 47290 61224 47290 61225 47299 61225 47100 61225 47290 61226 47100 61226 47300 61226 47305 61227 47102 61227 47098 61227 47062 61228 47301 61228 47302 61228 47302 61229 47301 61229 47303 61229 47302 61230 47303 61230 47295 61230 47295 61231 47303 61231 47304 61231 47295 61232 47304 61232 47296 61232 47296 61233 47304 61233 47305 61233 47296 61234 47305 61234 47299 61234 47299 61235 47305 61235 47098 61235 47299 61236 47098 61236 47100 61236 47069 61237 47308 61237 47301 61237 47301 61238 47308 61238 47306 61238 47301 61239 47306 61239 47303 61239 47303 61240 47306 61240 47310 61240 47303 61241 47310 61241 47304 61241 47304 61242 47310 61242 47162 61242 47304 61243 47162 61243 47305 61243 47305 61244 47162 61244 47307 61244 47305 61245 47307 61245 47102 61245 47174 61246 47309 61246 47308 61246 47308 61247 47309 61247 47315 61247 47308 61248 47315 61248 47306 61248 47306 61249 47315 61249 47317 61249 47306 61250 47317 61250 47310 61250 47310 61251 47317 61251 47311 61251 47310 61252 47311 61252 47162 61252 47162 61253 47311 61253 47104 61253 47162 61254 47104 61254 47312 61254 47319 61255 47313 61255 47314 61255 47067 61256 47320 61256 47309 61256 47309 61257 47320 61257 47316 61257 47309 61258 47316 61258 47315 61258 47315 61259 47316 61259 47318 61259 47315 61260 47318 61260 47317 61260 47317 61261 47318 61261 47319 61261 47317 61262 47319 61262 47311 61262 47311 61263 47319 61263 47314 61263 47311 61264 47314 61264 47104 61264 47082 61265 47331 61265 47320 61265 47320 61266 47331 61266 47211 61266 47320 61267 47211 61267 47316 61267 47316 61268 47211 61268 47321 61268 47316 61269 47321 61269 47318 61269 47318 61270 47321 61270 47322 61270 47318 61271 47322 61271 47319 61271 47319 61272 47322 61272 47326 61272 47319 61273 47326 61273 47313 61273 47110 61274 47323 61274 47237 61274 47237 61275 47323 61275 47324 61275 47237 61276 47324 61276 47235 61276 47235 61277 47324 61277 47325 61277 47235 61278 47325 61278 47322 61278 47322 61279 47325 61279 47108 61279 47322 61280 47108 61280 47326 61280 47112 61281 47111 61281 47327 61281 47327 61282 47111 61282 47328 61282 47327 61283 47328 61283 47192 61283 47192 61284 47328 61284 47329 61284 47192 61285 47329 61285 47193 61285 47193 61286 47329 61286 47238 61286 47193 61287 47238 61287 47330 61287 47330 61288 47238 61288 47331 61288 47330 61289 47331 61289 47181 61289 47181 61290 47331 61290 47082 61290 47058 61291 47337 61291 47332 61291 47332 61292 47337 61292 47333 61292 47332 61293 47333 61293 47334 61293 47334 61294 47333 61294 47338 61294 47334 61295 47338 61295 47335 61295 47335 61296 47338 61296 47339 61296 47335 61297 47339 61297 47327 61297 47327 61298 47339 61298 47341 61298 47327 61299 47341 61299 47161 61299 47336 61300 47346 61300 47340 61300 47173 61301 47342 61301 47337 61301 47337 61302 47342 61302 47343 61302 47337 61303 47343 61303 47333 61303 47333 61304 47343 61304 47344 61304 47333 61305 47344 61305 47338 61305 47338 61306 47344 61306 47336 61306 47338 61307 47336 61307 47339 61307 47339 61308 47336 61308 47340 61308 47339 61309 47340 61309 47341 61309 47060 61310 47348 61310 47342 61310 47342 61311 47348 61311 47351 61311 47342 61312 47351 61312 47343 61312 47343 61313 47351 61313 47352 61313 47343 61314 47352 61314 47344 61314 47344 61315 47352 61315 47345 61315 47344 61316 47345 61316 47336 61316 47336 61317 47345 61317 47160 61317 47336 61318 47160 61318 47346 61318 47347 61319 47354 61319 47348 61319 47348 61320 47354 61320 47349 61320 47348 61321 47349 61321 47351 61321 47351 61322 47349 61322 47350 61322 47351 61323 47350 61323 47352 61323 47352 61324 47350 61324 47357 61324 47352 61325 47357 61325 47345 61325 47345 61326 47357 61326 47115 61326 47345 61327 47115 61327 47118 61327 47356 61328 47119 61328 47353 61328 47055 61329 47172 61329 47354 61329 47354 61330 47172 61330 47359 61330 47354 61331 47359 61331 47349 61331 47349 61332 47359 61332 47355 61332 47349 61333 47355 61333 47350 61333 47350 61334 47355 61334 47356 61334 47350 61335 47356 61335 47357 61335 47357 61336 47356 61336 47353 61336 47357 61337 47353 61337 47115 61337 47358 61338 47370 61338 47172 61338 47172 61339 47370 61339 47212 61339 47172 61340 47212 61340 47359 61340 47359 61341 47212 61341 47360 61341 47359 61342 47360 61342 47355 61342 47355 61343 47360 61343 47239 61343 47355 61344 47239 61344 47356 61344 47356 61345 47239 61345 47361 61345 47356 61346 47361 61346 47119 61346 47362 61347 47121 61347 47242 61347 47242 61348 47121 61348 47363 61348 47242 61349 47363 61349 47364 61349 47364 61350 47363 61350 47365 61350 47364 61351 47365 61351 47239 61351 47239 61352 47365 61352 47366 61352 47239 61353 47366 61353 47361 61353 47125 61354 47240 61354 47367 61354 47367 61355 47240 61355 47241 61355 47367 61356 47241 61356 47213 61356 47213 61357 47241 61357 47368 61357 47213 61358 47368 61358 47369 61358 47369 61359 47368 61359 47244 61359 47369 61360 47244 61360 47165 61360 47165 61361 47244 61361 47370 61361 47165 61362 47370 61362 47371 61362 47371 61363 47370 61363 47358 61363 47372 61364 47373 61364 47375 61364 47075 61365 47378 61365 47374 61365 47374 61366 47378 61366 47379 61366 47374 61367 47379 61367 47215 61367 47215 61368 47379 61368 47380 61368 47215 61369 47380 61369 47214 61369 47214 61370 47380 61370 47372 61370 47214 61371 47372 61371 47367 61371 47367 61372 47372 61372 47375 61372 47367 61373 47375 61373 47125 61373 47386 61374 47126 61374 47381 61374 47376 61375 47377 61375 47378 61375 47378 61376 47377 61376 47382 61376 47378 61377 47382 61377 47379 61377 47379 61378 47382 61378 47384 61378 47379 61379 47384 61379 47380 61379 47380 61380 47384 61380 47386 61380 47380 61381 47386 61381 47372 61381 47372 61382 47386 61382 47381 61382 47372 61383 47381 61383 47373 61383 47074 61384 47387 61384 47377 61384 47377 61385 47387 61385 47383 61385 47377 61386 47383 61386 47382 61386 47382 61387 47383 61387 47385 61387 47382 61388 47385 61388 47384 61388 47384 61389 47385 61389 47388 61389 47384 61390 47388 61390 47386 61390 47386 61391 47388 61391 47128 61391 47386 61392 47128 61392 47126 61392 47073 61393 47171 61393 47387 61393 47387 61394 47171 61394 47390 61394 47387 61395 47390 61395 47383 61395 47383 61396 47390 61396 47392 61396 47383 61397 47392 61397 47385 61397 47385 61398 47392 61398 47393 61398 47385 61399 47393 61399 47388 61399 47388 61400 47393 61400 47130 61400 47388 61401 47130 61401 47132 61401 47389 61402 47134 61402 47133 61402 47169 61403 47170 61403 47171 61403 47171 61404 47170 61404 47395 61404 47171 61405 47395 61405 47390 61405 47390 61406 47395 61406 47391 61406 47390 61407 47391 61407 47392 61407 47392 61408 47391 61408 47389 61408 47392 61409 47389 61409 47393 61409 47393 61410 47389 61410 47133 61410 47393 61411 47133 61411 47130 61411 47083 61412 47394 61412 47170 61412 47170 61413 47394 61413 47252 61413 47170 61414 47252 61414 47395 61414 47395 61415 47252 61415 47217 61415 47395 61416 47217 61416 47391 61416 47391 61417 47217 61417 47245 61417 47391 61418 47245 61418 47389 61418 47389 61419 47245 61419 47396 61419 47389 61420 47396 61420 47134 61420 47247 61421 47397 61421 47249 61421 47249 61422 47397 61422 47135 61422 47249 61423 47135 61423 47246 61423 47246 61424 47135 61424 47398 61424 47246 61425 47398 61425 47245 61425 47245 61426 47398 61426 47136 61426 47245 61427 47136 61427 47396 61427 47410 61428 47399 61428 47408 61428 47408 61429 47399 61429 47248 61429 47408 61430 47248 61430 47200 61430 47200 61431 47248 61431 47250 61431 47200 61432 47250 61432 47201 61432 47201 61433 47250 61433 47400 61433 47201 61434 47400 61434 47184 61434 47184 61435 47400 61435 47394 61435 47184 61436 47394 61436 47401 61436 47401 61437 47394 61437 47083 61437 47409 61438 47402 61438 47403 61438 47221 61439 47404 61439 47219 61439 47219 61440 47404 61440 47405 61440 47219 61441 47405 61441 47406 61441 47406 61442 47405 61442 47416 61442 47406 61443 47416 61443 47407 61443 47407 61444 47416 61444 47409 61444 47407 61445 47409 61445 47408 61445 47408 61446 47409 61446 47403 61446 47408 61447 47403 61447 47410 61447 47415 61448 47142 61448 47411 61448 47412 61449 47413 61449 47404 61449 47404 61450 47413 61450 47414 61450 47404 61451 47414 61451 47405 61451 47405 61452 47414 61452 47418 61452 47405 61453 47418 61453 47416 61453 47416 61454 47418 61454 47415 61454 47416 61455 47415 61455 47409 61455 47409 61456 47415 61456 47411 61456 47409 61457 47411 61457 47402 61457 47080 61458 47419 61458 47413 61458 47413 61459 47419 61459 47417 61459 47413 61460 47417 61460 47414 61460 47414 61461 47417 61461 47422 61461 47414 61462 47422 61462 47418 61462 47418 61463 47422 61463 47159 61463 47418 61464 47159 61464 47415 61464 47415 61465 47159 61465 47145 61465 47415 61466 47145 61466 47142 61466 47079 61467 47424 61467 47419 61467 47419 61468 47424 61468 47420 61468 47419 61469 47420 61469 47417 61469 47417 61470 47420 61470 47421 61470 47417 61471 47421 61471 47422 61471 47422 61472 47421 61472 47428 61472 47422 61473 47428 61473 47159 61473 47159 61474 47428 61474 47423 61474 47159 61475 47423 61475 47144 61475 47427 61476 47146 61476 47429 61476 47077 61477 47430 61477 47424 61477 47424 61478 47430 61478 47425 61478 47424 61479 47425 61479 47420 61479 47420 61480 47425 61480 47426 61480 47420 61481 47426 61481 47421 61481 47421 61482 47426 61482 47427 61482 47421 61483 47427 61483 47428 61483 47428 61484 47427 61484 47429 61484 47428 61485 47429 61485 47423 61485 47076 61486 47442 61486 47430 61486 47430 61487 47442 61487 47431 61487 47430 61488 47431 61488 47425 61488 47425 61489 47431 61489 47432 61489 47425 61490 47432 61490 47426 61490 47426 61491 47432 61491 47435 61491 47426 61492 47435 61492 47427 61492 47427 61493 47435 61493 47148 61493 47427 61494 47148 61494 47146 61494 47254 61495 47151 61495 47433 61495 47433 61496 47151 61496 47434 61496 47433 61497 47434 61497 47253 61497 47253 61498 47434 61498 47149 61498 47253 61499 47149 61499 47435 61499 47435 61500 47149 61500 47436 61500 47435 61501 47436 61501 47148 61501 47437 61502 47153 61502 47222 61502 47222 61503 47153 61503 47438 61503 47222 61504 47438 61504 47205 61504 47205 61505 47438 61505 47439 61505 47205 61506 47439 61506 47441 61506 47441 61507 47439 61507 47440 61507 47441 61508 47440 61508 47164 61508 47164 61509 47440 61509 47442 61509 47164 61510 47442 61510 47443 61510 47443 61511 47442 61511 47076 61511 47444 61512 47157 61512 47156 61512 47072 61513 47449 61513 47224 61513 47224 61514 47449 61514 47450 61514 47224 61515 47450 61515 47445 61515 47445 61516 47450 61516 47446 61516 47445 61517 47446 61517 47223 61517 47223 61518 47446 61518 47444 61518 47223 61519 47444 61519 47222 61519 47222 61520 47444 61520 47156 61520 47222 61521 47156 61521 47437 61521 47168 61522 47447 61522 47449 61522 47449 61523 47447 61523 47448 61523 47449 61524 47448 61524 47450 61524 47450 61525 47448 61525 47451 61525 47450 61526 47451 61526 47446 61526 47446 61527 47451 61527 47257 61527 47446 61528 47257 61528 47444 61528 47444 61529 47257 61529 47158 61529 47444 61530 47158 61530 47157 61530 47452 61531 47488 61531 47453 61531 47453 61532 47488 61532 47481 61532 47453 61533 47481 61533 47454 61533 47454 61534 47481 61534 47455 61534 47455 61535 47481 61535 47478 61535 47455 61536 47478 61536 47456 61536 47456 61537 47478 61537 47457 61537 47457 61538 47478 61538 47475 61538 47457 61539 47475 61539 47458 61539 47465 590 47459 590 47460 590 47460 61540 47459 61540 47461 61540 47461 61541 47462 61541 47460 61541 47460 61542 47462 61542 47463 61542 47460 61543 47463 61543 47464 61543 47460 61544 47489 61544 47465 61544 47465 61545 47489 61545 47486 61545 47465 61546 47486 61546 47466 61546 47475 61547 47469 61547 47474 61547 47478 590 47600 590 47601 590 47480 590 47467 590 47475 590 47475 61548 47467 61548 47468 61548 47475 61549 47468 61549 47469 61549 47639 590 47620 590 47488 590 47611 590 47470 590 47489 590 47489 590 47470 590 47471 590 47489 590 47471 590 47583 590 47583 590 47584 590 47489 590 47489 61550 47584 61550 47585 61550 47489 61551 47585 61551 47486 61551 47585 61552 47587 61552 47486 61552 47486 590 47587 590 47588 590 47486 590 47588 590 47645 590 47601 61553 47472 61553 47478 61553 47478 590 47472 590 47726 590 47478 61554 47726 61554 47629 61554 47485 61555 47473 61555 47481 61555 47481 590 47473 590 47617 590 47595 590 47769 590 47481 590 47592 590 47591 590 47488 590 47474 590 47696 590 47475 590 47475 61556 47696 61556 47476 61556 47475 590 47476 590 47489 590 47489 61557 47476 61557 47582 61557 47489 61558 47582 61558 47581 61558 47629 61559 47477 61559 47478 61559 47478 61560 47477 61560 47603 61560 47478 61561 47603 61561 47475 61561 47475 61562 47603 61562 47479 61562 47475 590 47479 590 47480 590 47617 590 47605 590 47481 590 47481 590 47605 590 47606 590 47481 590 47606 590 47478 590 47478 590 47606 590 47746 590 47478 590 47746 590 47600 590 47620 590 47482 590 47488 590 47488 61563 47482 61563 47483 61563 47488 590 47483 590 47481 590 47481 61564 47483 61564 47484 61564 47481 61565 47484 61565 47595 61565 47769 590 47597 590 47481 590 47481 61566 47597 61566 47599 61566 47481 590 47599 590 47485 590 47645 590 47487 590 47486 590 47486 61567 47487 61567 47623 61567 47486 61568 47623 61568 47609 61568 47591 590 47594 590 47488 590 47488 61569 47594 61569 47640 61569 47488 61570 47640 61570 47639 61570 47581 590 47490 590 47489 590 47489 61571 47490 61571 47491 61571 47489 61572 47491 61572 47611 61572 47609 590 47610 590 47486 590 47486 590 47610 590 47492 590 47486 61573 47492 61573 47488 61573 47488 590 47492 590 47589 590 47488 61574 47589 61574 47592 61574 47493 61575 47495 61575 47575 61575 47699 61576 47494 61576 47700 61576 47700 61577 47494 61577 47495 61577 47700 61578 47495 61578 47496 61578 47496 61579 47495 61579 47493 61579 47699 61580 47695 61580 47494 61580 47494 61581 47695 61581 47710 61581 47494 61582 47710 61582 47497 61582 47708 61583 47500 61583 47498 61583 47498 61584 47500 61584 47497 61584 47498 61585 47497 61585 47499 61585 47499 61586 47497 61586 47710 61586 47708 61587 47706 61587 47500 61587 47500 61588 47706 61588 47649 61588 47500 61589 47649 61589 47501 61589 47502 61590 47504 61590 47503 61590 47503 61591 47504 61591 47501 61591 47503 61592 47501 61592 47715 61592 47715 61593 47501 61593 47649 61593 47502 61594 47505 61594 47504 61594 47504 61595 47505 61595 47506 61595 47504 61596 47506 61596 47507 61596 47506 61597 47508 61597 47507 61597 47507 61598 47508 61598 47509 61598 47507 61599 47509 61599 47510 61599 47729 61600 47512 61600 47724 61600 47724 61601 47512 61601 47510 61601 47724 61602 47510 61602 47725 61602 47725 61603 47510 61603 47509 61603 47729 61604 47511 61604 47512 61604 47512 61605 47511 61605 47577 61605 47512 61606 47577 61606 47514 61606 47513 61607 47516 61607 47740 61607 47740 61608 47516 61608 47514 61608 47740 61609 47514 61609 47742 61609 47742 61610 47514 61610 47577 61610 47513 61611 47515 61611 47516 61611 47516 61612 47515 61612 47517 61612 47516 61613 47517 61613 47518 61613 47750 61614 47519 61614 47520 61614 47520 61615 47519 61615 47518 61615 47520 61616 47518 61616 47521 61616 47521 61617 47518 61617 47517 61617 47750 61618 47522 61618 47519 61618 47519 61619 47522 61619 47749 61619 47519 61620 47749 61620 47523 61620 47749 61621 47524 61621 47523 61621 47523 61622 47524 61622 47525 61622 47523 61623 47525 61623 47526 61623 47527 61624 47528 61624 47757 61624 47757 61625 47528 61625 47526 61625 47757 61626 47526 61626 47576 61626 47576 61627 47526 61627 47525 61627 47527 61628 47758 61628 47528 61628 47528 61629 47758 61629 47529 61629 47528 61630 47529 61630 47531 61630 47776 61631 47533 61631 47530 61631 47530 61632 47533 61632 47531 61632 47530 61633 47531 61633 47532 61633 47532 61634 47531 61634 47529 61634 47776 61635 47779 61635 47533 61635 47533 61636 47779 61636 47537 61636 47533 61637 47537 61637 47536 61637 47782 61638 47535 61638 47534 61638 47534 61639 47535 61639 47536 61639 47534 61640 47536 61640 47784 61640 47784 61641 47536 61641 47537 61641 47782 61642 47781 61642 47535 61642 47535 61643 47781 61643 47538 61643 47535 61644 47538 61644 47539 61644 47538 61645 47669 61645 47539 61645 47539 61646 47669 61646 47542 61646 47539 61647 47542 61647 47540 61647 47543 61648 47545 61648 47541 61648 47541 61649 47545 61649 47540 61649 47541 61650 47540 61650 47793 61650 47793 61651 47540 61651 47542 61651 47543 61652 47802 61652 47545 61652 47545 61653 47802 61653 47544 61653 47545 61654 47544 61654 47546 61654 47810 61655 47550 61655 47547 61655 47547 61656 47550 61656 47546 61656 47547 61657 47546 61657 47548 61657 47548 61658 47546 61658 47544 61658 47810 61659 47813 61659 47550 61659 47550 61660 47813 61660 47549 61660 47550 61661 47549 61661 47551 61661 47816 61662 47554 61662 47552 61662 47552 61663 47554 61663 47551 61663 47552 61664 47551 61664 47817 61664 47817 61665 47551 61665 47549 61665 47816 61666 47553 61666 47554 61666 47554 61667 47553 61667 47814 61667 47554 61668 47814 61668 47555 61668 47814 61669 47818 61669 47555 61669 47555 61670 47818 61670 47827 61670 47555 61671 47827 61671 47556 61671 47827 61672 47557 61672 47556 61672 47556 61673 47557 61673 47832 61673 47556 61674 47832 61674 47558 61674 47558 61675 47832 61675 47559 61675 47558 61676 47559 61676 47560 61676 47560 61677 47559 61678 47828 61679 47560 61680 47828 61680 47837 61680 47840 61681 47561 61681 47562 61681 47562 61682 47561 61682 47560 61682 47562 61683 47560 61683 47563 61683 47563 61684 47560 61684 47837 61684 47840 61685 47850 61685 47561 61685 47561 61686 47850 61686 47853 61686 47561 61687 47853 61687 47565 61687 47564 61688 47568 61688 47852 61688 47852 61689 47568 61689 47565 61689 47852 61690 47565 61690 47566 61690 47566 61691 47565 61691 47853 61691 47564 61692 47567 61692 47568 61692 47568 61693 47567 61693 47680 61693 47568 61694 47680 61694 47570 61694 47680 61695 47569 61695 47570 61695 47570 61696 47569 61696 47571 61696 47570 61697 47571 61697 47573 61697 47571 61698 47572 61698 47573 61698 47573 61699 47572 61699 47574 61699 47573 61700 47574 61700 47575 61700 47575 61701 47574 61701 47863 61701 47575 61702 47863 61702 47493 61702 47563 61703 47837 61703 47836 61703 47548 61704 47544 61704 47805 61704 47532 61705 47529 61705 47772 61705 47576 61706 47525 61706 47630 61706 47742 61707 47577 61707 47741 61707 47725 61708 47509 61708 47723 61708 47496 61709 47493 61709 47578 61709 47579 61710 47612 61710 47624 61710 47821 61711 47608 61711 47621 61711 47607 61712 47618 61712 47787 61712 47754 61713 47604 61713 47616 61713 47580 61714 47614 61714 47613 61714 47581 61715 47582 61715 47686 61715 47490 61716 47581 61716 47860 61716 47584 61717 47583 61717 47846 61717 47585 61718 47584 61718 47841 61718 47587 61719 47585 61719 47586 61719 47588 61720 47587 61720 47833 61720 47645 61721 47588 61721 47823 61721 47589 61722 47492 61722 47811 61722 47592 61723 47589 61723 47590 61723 47591 61724 47592 61724 47593 61724 47594 61725 47591 61725 47796 61725 47640 61726 47594 61726 47795 61726 47595 61727 47484 61727 47777 61727 47769 61728 47595 61728 47596 61728 47597 61729 47769 61729 47763 61729 47599 61730 47597 61730 47598 61730 47485 61731 47599 61731 47759 61731 47600 61732 47746 61732 47743 61732 47601 61733 47600 61733 47737 61733 47472 61734 47601 61734 47730 61734 47726 61735 47472 61735 47731 61735 47629 61736 47726 61736 47602 61736 47696 61737 47474 61737 47701 61737 47476 61738 47696 61738 47690 61738 47582 61739 47476 61739 47691 61739 47603 61740 47614 61740 47479 61740 47479 61741 47614 61741 47580 61741 47479 61742 47580 61742 47480 61742 47617 61743 47604 61743 47605 61743 47605 61744 47604 61744 47754 61744 47605 61745 47754 61745 47606 61745 47620 61746 47618 61746 47482 61746 47482 61747 47618 61747 47607 61747 47482 61748 47607 61748 47483 61748 47623 61749 47608 61749 47609 61749 47609 61750 47608 61750 47821 61750 47609 61751 47821 61751 47610 61751 47611 61752 47612 61752 47470 61752 47470 61753 47612 61753 47579 61753 47470 61754 47579 61754 47471 61754 47717 61755 47613 61755 47626 61755 47626 61756 47613 61756 47614 61756 47626 61757 47614 61757 47627 61757 47627 61758 47614 61758 47603 61758 47627 61759 47603 61759 47477 61759 47753 61760 47616 61760 47615 61760 47615 61761 47616 61761 47604 61761 47615 61762 47604 61762 47632 61762 47632 61763 47604 61763 47617 61763 47632 61764 47617 61764 47473 61764 47637 61765 47787 61765 47638 61765 47638 61766 47787 61766 47618 61766 47638 61767 47618 61767 47619 61767 47619 61768 47618 61768 47620 61768 47619 61769 47620 61769 47639 61769 47820 61770 47621 61770 47622 61770 47622 61771 47621 61771 47608 61771 47622 61772 47608 61772 47643 61772 47643 61773 47608 61773 47623 61773 47643 61774 47623 61774 47487 61774 47856 61775 47624 61775 47625 61775 47625 61776 47624 61776 47612 61776 47625 61777 47612 61777 47648 61777 47648 61778 47612 61778 47611 61778 47648 61779 47611 61779 47491 61779 47651 61780 47704 61780 47653 61780 47723 61781 47717 61781 47722 61781 47722 61782 47717 61782 47626 61782 47722 61783 47626 61783 47721 61783 47721 61784 47626 61784 47627 61784 47721 61785 47627 61785 47628 61785 47628 61786 47627 61786 47477 61786 47628 61787 47477 61787 47629 61787 47662 61788 47661 61788 47666 61788 47630 61789 47753 61789 47631 61789 47631 61790 47753 61790 47615 61790 47631 61791 47615 61791 47756 61791 47756 61792 47615 61792 47632 61792 47756 61793 47632 61793 47633 61793 47633 61794 47632 61794 47473 61794 47633 61795 47473 61795 47485 61795 47668 61796 47634 61796 47635 61796 47785 61797 47637 61797 47636 61797 47636 61798 47637 61798 47638 61798 47636 61799 47638 61799 47791 61799 47791 61800 47638 61800 47619 61800 47791 61801 47619 61801 47790 61801 47790 61802 47619 61802 47639 61802 47790 61803 47639 61803 47640 61803 47674 61804 47673 61804 47641 61804 47819 61805 47820 61805 47642 61805 47642 61806 47820 61806 47622 61806 47642 61807 47622 61807 47824 61807 47824 61808 47622 61808 47643 61808 47824 61809 47643 61809 47644 61809 47644 61810 47643 61810 47487 61810 47644 61811 47487 61811 47645 61811 47682 61812 47678 61812 47684 61812 47854 61813 47856 61813 47646 61813 47646 61814 47856 61814 47625 61814 47646 61815 47625 61815 47647 61815 47647 61816 47625 61816 47648 61816 47647 61817 47648 61817 47857 61817 47857 61818 47648 61818 47491 61818 47857 61819 47491 61819 47490 61819 47705 61820 47704 61820 47709 61820 47709 61821 47704 61821 47651 61821 47709 61822 47651 61822 47707 61822 47715 61823 47649 61823 47650 61823 47650 61824 47649 61824 47707 61824 47650 61825 47707 61825 47713 61825 47713 61826 47707 61826 47651 61826 47713 61827 47651 61827 47652 61827 47652 61828 47651 61828 47653 61828 47652 61829 47653 61829 47702 61829 47469 61830 47468 61830 47711 61830 47711 61831 47468 61831 47658 61831 47711 61832 47658 61832 47712 61832 47712 61833 47658 61833 47654 61833 47712 61834 47654 61834 47714 61834 47714 61835 47654 61835 47656 61835 47714 61836 47656 61836 47655 61836 47655 61837 47656 61837 47659 61837 47468 61838 47467 61838 47658 61838 47658 61839 47467 61839 47657 61839 47658 61840 47657 61840 47654 61840 47654 61841 47657 61841 47719 61841 47654 61842 47719 61842 47656 61842 47656 61843 47719 61843 47718 61843 47656 61844 47718 61844 47659 61844 47659 61845 47718 61845 47716 61845 47659 61846 47716 61846 47506 61846 47506 61847 47716 61848 47508 61849 47660 61850 47661 61850 47752 61850 47752 61851 47661 61851 47662 61851 47752 61852 47662 61852 47751 61852 47524 61853 47749 61853 47663 61853 47663 61854 47749 61854 47751 61854 47663 61855 47751 61855 47664 61855 47664 61856 47751 61856 47662 61856 47664 61857 47662 61857 47665 61857 47665 61858 47662 61858 47666 61858 47665 61859 47666 61859 47755 61859 47783 61860 47634 61860 47667 61860 47667 61861 47634 61861 47668 61861 47667 61862 47668 61862 47780 61862 47669 61863 47538 61863 47786 61863 47786 61864 47538 61864 47780 61864 47786 61865 47780 61865 47670 61865 47670 61866 47780 61866 47668 61866 47670 61867 47668 61867 47788 61867 47788 61868 47668 61868 47635 61868 47788 61869 47635 61869 47789 61869 47671 61870 47673 61870 47672 61870 47672 61871 47673 61871 47674 61871 47672 61872 47674 61872 47815 61872 47818 61873 47814 61873 47675 61873 47675 61874 47814 61874 47815 61874 47675 61875 47815 61875 47676 61875 47676 61876 47815 61876 47674 61876 47676 61877 47674 61877 47677 61877 47677 61878 47674 61878 47641 61878 47677 61879 47641 61879 47822 61879 47849 61880 47678 61880 47679 61880 47679 61881 47678 61881 47682 61881 47679 61882 47682 61882 47851 61882 47569 61883 47680 61883 47855 61883 47855 61884 47680 61884 47851 61884 47855 61885 47851 61885 47681 61885 47681 61886 47851 61886 47682 61886 47681 61887 47682 61887 47683 61887 47683 61888 47682 61888 47684 61888 47683 61889 47684 61889 47847 61889 47582 61890 47691 61890 47686 61890 47686 61891 47691 61891 47685 61891 47686 61892 47685 61892 47861 61892 47861 61893 47685 61893 47688 61893 47861 61894 47688 61894 47687 61894 47687 61895 47688 61895 47578 61895 47687 61896 47578 61896 47689 61896 47689 61897 47578 61897 47493 61897 47689 61898 47493 61898 47863 61898 47476 61899 47690 61899 47691 61899 47691 61900 47690 61900 47692 61900 47691 61901 47692 61901 47685 61901 47685 61902 47692 61902 47693 61902 47685 61903 47693 61903 47688 61903 47688 61904 47693 61904 47694 61904 47688 61905 47694 61905 47578 61905 47578 61906 47694 61906 47700 61906 47578 61907 47700 61907 47496 61907 47698 61908 47695 61908 47699 61908 47696 61909 47701 61909 47690 61909 47690 61910 47701 61910 47703 61910 47690 61911 47703 61911 47692 61911 47692 61912 47703 61912 47697 61912 47692 61913 47697 61913 47693 61913 47693 61914 47697 61914 47698 61914 47693 61915 47698 61915 47694 61915 47694 61916 47698 61916 47699 61916 47694 61917 47699 61917 47700 61917 47474 61918 47702 61918 47701 61918 47701 61919 47702 61919 47653 61919 47701 61920 47653 61920 47703 61920 47703 61921 47653 61921 47704 61921 47703 61922 47704 61922 47697 61922 47697 61923 47704 61923 47705 61923 47697 61924 47705 61924 47698 61924 47698 61925 47705 61925 47710 61925 47698 61926 47710 61926 47695 61926 47649 61927 47706 61927 47707 61927 47707 61928 47706 61928 47708 61928 47707 61929 47708 61929 47709 61929 47709 61930 47708 61930 47498 61930 47709 61931 47498 61931 47705 61931 47705 61932 47498 61932 47499 61932 47705 61933 47499 61933 47710 61933 47474 61934 47469 61934 47702 61934 47702 61935 47469 61935 47711 61935 47702 61936 47711 61936 47652 61936 47652 61937 47711 61937 47712 61937 47652 61938 47712 61938 47713 61938 47713 61939 47712 61939 47714 61939 47713 61940 47714 61940 47650 61940 47650 61941 47714 61941 47655 61941 47650 61942 47655 61942 47715 61942 47506 61943 47505 61943 47659 61943 47659 61944 47505 61944 47502 61944 47659 61945 47502 61945 47655 61945 47655 61946 47502 61946 47503 61946 47655 61947 47503 61947 47715 61947 47509 61948 47508 61948 47723 61948 47723 61949 47508 61949 47716 61949 47723 61950 47716 61950 47717 61950 47717 61951 47716 61951 47718 61951 47717 61952 47718 61952 47613 61952 47613 61953 47718 61953 47719 61953 47613 61954 47719 61954 47580 61954 47580 61955 47719 61955 47657 61955 47580 61956 47657 61956 47480 61956 47480 61957 47657 61957 47467 61957 47629 61958 47602 61958 47628 61958 47628 61959 47602 61959 47720 61959 47628 61960 47720 61960 47721 61960 47721 61961 47720 61961 47727 61961 47721 61962 47727 61962 47722 61962 47722 61963 47727 61963 47728 61963 47722 61964 47728 61964 47723 61964 47723 61965 47728 61965 47724 61965 47723 61966 47724 61966 47725 61966 47736 61967 47511 61968 47729 61969 47726 61970 47731 61970 47602 61970 47602 61971 47731 61971 47733 61971 47602 61972 47733 61972 47720 61972 47720 61973 47733 61973 47734 61973 47720 61974 47734 61974 47727 61974 47727 61975 47734 61975 47736 61975 47727 61976 47736 61976 47728 61976 47728 61977 47736 61977 47729 61977 47728 61978 47729 61978 47724 61978 47472 61979 47730 61979 47731 61979 47731 61980 47730 61980 47732 61980 47731 61981 47732 61981 47733 61981 47733 61982 47732 61982 47735 61982 47733 61983 47735 61983 47734 61983 47734 61984 47735 61984 47741 61984 47734 61985 47741 61985 47736 61985 47736 61986 47741 61986 47577 61986 47736 61987 47577 61987 47511 61987 47601 61988 47737 61988 47730 61988 47730 61989 47737 61989 47738 61989 47730 61990 47738 61990 47732 61990 47732 61991 47738 61991 47744 61991 47732 61992 47744 61992 47735 61992 47735 61993 47744 61993 47739 61993 47735 61994 47739 61994 47741 61994 47741 61995 47739 61995 47740 61995 47741 61996 47740 61996 47742 61996 47745 61997 47515 61997 47513 61997 47600 61998 47743 61998 47737 61998 47737 61999 47743 61999 47747 61999 47737 62000 47747 62000 47738 62000 47738 62001 47747 62001 47748 62001 47738 62002 47748 62002 47744 62002 47744 62003 47748 62003 47745 62003 47744 62004 47745 62004 47739 62004 47739 62005 47745 62005 47513 62005 47739 62006 47513 62006 47740 62006 47746 62007 47755 62007 47743 62007 47743 62008 47755 62008 47666 62008 47743 62009 47666 62009 47747 62009 47747 62010 47666 62010 47661 62010 47747 62011 47661 62011 47748 62011 47748 62012 47661 62012 47660 62012 47748 62013 47660 62013 47745 62013 47745 62014 47660 62014 47517 62014 47745 62015 47517 62015 47515 62015 47749 62016 47522 62016 47751 62016 47751 62017 47522 62017 47750 62017 47751 62018 47750 62018 47752 62018 47752 62019 47750 62019 47520 62019 47752 62020 47520 62020 47660 62020 47660 62021 47520 62021 47521 62021 47660 62022 47521 62022 47517 62022 47525 62023 47524 62023 47630 62023 47630 62024 47524 62024 47663 62024 47630 62025 47663 62025 47753 62025 47753 62026 47663 62026 47664 62026 47753 62027 47664 62027 47616 62027 47616 62028 47664 62028 47665 62028 47616 62029 47665 62029 47754 62029 47754 62030 47665 62030 47755 62030 47754 62031 47755 62031 47606 62031 47606 62032 47755 62032 47746 62032 47485 62033 47759 62033 47633 62033 47633 62034 47759 62034 47760 62034 47633 62035 47760 62035 47756 62035 47756 62036 47760 62036 47761 62036 47756 62037 47761 62037 47631 62037 47631 62038 47761 62038 47762 62038 47631 62039 47762 62039 47630 62039 47630 62040 47762 62040 47757 62040 47630 62041 47757 62041 47576 62041 47768 62042 47758 62042 47527 62042 47599 62043 47598 62043 47759 62043 47759 62044 47598 62044 47765 62044 47759 62045 47765 62045 47760 62045 47760 62046 47765 62046 47767 62046 47760 62047 47767 62047 47761 62047 47761 62048 47767 62048 47768 62048 47761 62049 47768 62049 47762 62049 47762 62050 47768 62050 47527 62050 47762 62051 47527 62051 47757 62051 47597 62052 47763 62052 47598 62052 47598 62053 47763 62053 47764 62053 47598 62054 47764 62054 47765 62054 47765 62055 47764 62055 47766 62055 47765 62056 47766 62056 47767 62056 47767 62057 47766 62057 47772 62057 47767 62058 47772 62058 47768 62058 47768 62059 47772 62059 47529 62059 47768 62060 47529 62060 47758 62060 47769 62061 47596 62061 47763 62061 47763 62062 47596 62062 47770 62062 47763 62063 47770 62063 47764 62063 47764 62064 47770 62064 47773 62064 47764 62065 47773 62065 47766 62065 47766 62066 47773 62066 47771 62066 47766 62067 47771 62067 47772 62067 47772 62068 47771 62068 47530 62068 47772 62069 47530 62069 47532 62069 47775 62070 47779 62070 47776 62070 47595 62071 47777 62071 47596 62071 47596 62072 47777 62072 47778 62072 47596 62073 47778 62073 47770 62073 47770 62074 47778 62074 47774 62074 47770 62075 47774 62075 47773 62075 47773 62076 47774 62076 47775 62076 47773 62077 47775 62077 47771 62077 47771 62078 47775 62078 47776 62078 47771 62079 47776 62079 47530 62079 47484 62080 47789 62080 47777 62080 47777 62081 47789 62081 47635 62081 47777 62082 47635 62082 47778 62082 47778 62083 47635 62083 47634 62083 47778 62084 47634 62084 47774 62084 47774 62085 47634 62085 47783 62085 47774 62086 47783 62086 47775 62086 47775 62087 47783 62087 47537 62087 47775 62088 47537 62088 47779 62088 47538 62089 47781 62089 47780 62089 47780 62090 47781 62090 47782 62090 47780 62091 47782 62091 47667 62091 47667 62092 47782 62092 47534 62092 47667 62093 47534 62093 47783 62093 47783 62094 47534 62094 47784 62094 47783 62095 47784 62095 47537 62095 47542 62096 47669 62096 47785 62096 47785 62097 47669 62097 47786 62097 47785 62098 47786 62098 47637 62098 47637 62099 47786 62099 47670 62099 47637 62100 47670 62100 47787 62100 47787 62101 47670 62101 47788 62101 47787 62102 47788 62102 47607 62102 47607 62103 47788 62103 47789 62103 47607 62104 47789 62104 47483 62104 47483 62105 47789 62105 47484 62105 47800 62106 47541 62106 47793 62106 47640 62107 47795 62107 47790 62107 47790 62108 47795 62108 47797 62108 47790 62109 47797 62109 47791 62109 47791 62110 47797 62110 47792 62110 47791 62111 47792 62111 47636 62111 47636 62112 47792 62112 47800 62112 47636 62113 47800 62113 47785 62113 47785 62114 47800 62114 47793 62114 47785 62115 47793 62115 47542 62115 47794 62116 47802 62116 47543 62116 47594 62117 47796 62117 47795 62117 47795 62118 47796 62118 47798 62118 47795 62119 47798 62119 47797 62119 47797 62120 47798 62120 47799 62120 47797 62121 47799 62121 47792 62121 47792 62122 47799 62122 47794 62122 47792 62123 47794 62123 47800 62123 47800 62124 47794 62124 47543 62124 47800 62125 47543 62125 47541 62125 47591 62126 47593 62126 47796 62126 47796 62127 47593 62127 47804 62127 47796 62128 47804 62128 47798 62128 47798 62129 47804 62129 47801 62129 47798 62130 47801 62130 47799 62130 47799 62131 47801 62131 47805 62131 47799 62132 47805 62132 47794 62132 47794 62133 47805 62133 47544 62133 47794 62134 47544 62134 47802 62134 47592 62135 47590 62135 47593 62135 47593 62136 47590 62136 47807 62136 47593 62137 47807 62137 47804 62137 47804 62138 47807 62138 47803 62138 47804 62139 47803 62139 47801 62139 47801 62140 47803 62140 47806 62140 47801 62141 47806 62141 47805 62141 47805 62142 47806 62142 47547 62142 47805 62143 47547 62143 47548 62143 47812 62144 47813 62144 47810 62144 47589 62145 47811 62145 47590 62145 47590 62146 47811 62146 47808 62146 47590 62147 47808 62147 47807 62147 47807 62148 47808 62148 47809 62148 47807 62149 47809 62149 47803 62149 47803 62150 47809 62150 47812 62150 47803 62151 47812 62151 47806 62151 47806 62152 47812 62152 47810 62152 47806 62153 47810 62153 47547 62153 47492 62154 47822 62154 47811 62154 47811 62155 47822 62155 47641 62155 47811 62156 47641 62156 47808 62156 47808 62157 47641 62157 47673 62157 47808 62158 47673 62158 47809 62158 47809 62159 47673 62159 47671 62159 47809 62160 47671 62160 47812 62160 47812 62161 47671 62161 47549 62161 47812 62162 47549 62162 47813 62162 47814 62163 47553 62163 47815 62163 47815 62164 47553 62164 47816 62164 47815 62165 47816 62165 47672 62165 47672 62166 47816 62166 47552 62166 47672 62167 47552 62167 47671 62167 47671 62168 47552 62168 47817 62168 47671 62169 47817 62169 47549 62169 47827 62170 47818 62170 47819 62170 47819 62171 47818 62171 47675 62171 47819 62172 47675 62172 47820 62172 47820 62173 47675 62173 47676 62173 47820 62174 47676 62174 47621 62174 47621 62175 47676 62175 47677 62175 47621 62176 47677 62176 47821 62176 47821 62177 47677 62177 47822 62177 47821 62178 47822 62178 47610 62178 47610 62179 47822 62179 47492 62179 47831 62180 47832 62180 47557 62180 47645 62181 47823 62181 47644 62181 47644 62182 47823 62182 47825 62182 47644 62183 47825 62183 47824 62183 47824 62184 47825 62184 47826 62184 47824 62185 47826 62185 47642 62185 47642 62186 47826 62186 47831 62186 47642 62187 47831 62187 47819 62187 47819 62188 47831 62188 47557 62188 47819 62189 47557 62189 47827 62189 47830 62190 47828 62190 47559 62190 47588 62191 47833 62191 47823 62191 47823 62192 47833 62192 47829 62192 47823 62193 47829 62193 47825 62193 47825 62194 47829 62194 47835 62194 47825 62195 47835 62195 47826 62195 47826 62196 47835 62196 47830 62196 47826 62197 47830 62197 47831 62197 47831 62198 47830 62198 47559 62198 47831 62199 47559 62199 47832 62199 47587 62200 47586 62200 47833 62200 47833 62201 47586 62201 47834 62201 47833 62202 47834 62202 47829 62202 47829 62203 47834 62203 47838 62203 47829 62204 47838 62204 47835 62204 47835 62205 47838 62205 47836 62205 47835 62206 47836 62206 47830 62206 47830 62207 47836 62207 47837 62207 47830 62208 47837 62208 47828 62208 47585 62209 47841 62209 47586 62209 47586 62210 47841 62210 47843 62210 47586 62211 47843 62211 47834 62211 47834 62212 47843 62212 47844 62212 47834 62213 47844 62213 47838 62213 47838 62214 47844 62214 47845 62214 47838 62215 47845 62215 47836 62215 47836 62216 47845 62216 47562 62216 47836 62217 47562 62217 47563 62217 47839 62218 47850 62218 47840 62218 47584 62219 47846 62219 47841 62219 47841 62220 47846 62220 47842 62220 47841 62221 47842 62221 47843 62221 47843 62222 47842 62222 47848 62222 47843 62223 47848 62223 47844 62223 47844 62224 47848 62224 47839 62224 47844 62225 47839 62225 47845 62225 47845 62226 47839 62226 47840 62226 47845 62227 47840 62227 47562 62227 47583 62228 47847 62228 47846 62228 47846 62229 47847 62229 47684 62229 47846 62230 47684 62230 47842 62230 47842 62231 47684 62231 47678 62231 47842 62232 47678 62232 47848 62232 47848 62233 47678 62233 47849 62233 47848 62234 47849 62234 47839 62234 47839 62235 47849 62235 47853 62235 47839 62236 47853 62236 47850 62236 47680 62237 47567 62237 47851 62237 47851 62238 47567 62238 47564 62238 47851 62239 47564 62239 47679 62239 47679 62240 47564 62240 47852 62240 47679 62241 47852 62241 47849 62241 47849 62242 47852 62242 47566 62242 47849 62243 47566 62243 47853 62243 47571 62244 47569 62244 47854 62244 47854 62245 47569 62245 47855 62245 47854 62246 47855 62246 47856 62246 47856 62247 47855 62247 47681 62247 47856 62248 47681 62248 47624 62248 47624 62249 47681 62249 47683 62249 47624 62250 47683 62250 47579 62250 47579 62251 47683 62251 47847 62251 47579 62252 47847 62252 47471 62252 47471 62253 47847 62253 47583 62253 47859 62254 47574 62254 47572 62254 47490 62255 47860 62255 47857 62255 47857 62256 47860 62256 47858 62256 47857 62257 47858 62257 47647 62257 47647 62258 47858 62258 47862 62258 47647 62259 47862 62259 47646 62259 47646 62260 47862 62260 47859 62260 47646 62261 47859 62261 47854 62261 47854 62262 47859 62262 47572 62262 47854 62263 47572 62263 47571 62263 47581 62264 47686 62264 47860 62264 47860 62265 47686 62265 47861 62265 47860 62266 47861 62266 47858 62266 47858 62267 47861 62267 47687 62267 47858 62268 47687 62268 47862 62268 47862 62269 47687 62269 47689 62269 47862 62270 47689 62270 47859 62270 47859 62271 47689 62271 47863 62271 47859 62272 47863 62272 47574 62272 47868 62273 47891 62273 47864 62273 47864 62274 47891 62274 47865 62274 47864 62275 47865 62275 47866 62275 47870 62276 47896 62276 47867 62276 47867 62277 47896 62277 47891 62277 47867 62278 47891 62278 47868 62278 47873 62279 47879 62279 47869 62279 47869 62280 47879 62280 47896 62280 47869 62279 47896 62279 47870 62279 47876 62281 47871 62281 47872 62281 47872 62282 47871 62282 47879 62282 47872 62283 47879 62283 47873 62283 47874 62284 47875 62284 48281 62284 48281 62285 47875 62285 47871 62285 48281 62286 47871 62286 47876 62286 48020 590 48009 590 47871 590 47871 590 48009 590 48010 590 47879 62287 47995 62287 47996 62287 47897 62288 48259 62288 47875 62288 47875 62289 48259 62289 48024 62289 47875 590 48024 590 48023 590 47877 590 47878 590 47865 590 47996 590 48180 590 47879 590 47879 62290 48180 62290 47880 62290 47879 62291 47880 62291 47885 62291 48010 62292 47991 62292 47871 62292 47871 62293 47991 62293 47993 62293 47871 62294 47993 62294 47879 62294 47879 62295 47993 62295 48192 62295 47879 62296 48192 62296 47995 62296 48023 62297 48012 62297 47875 62297 47875 62298 48012 62298 48257 62298 47875 590 48257 590 48258 590 47881 62299 48042 62299 47871 62299 47871 590 48042 590 47882 590 47871 590 47882 590 48020 590 47878 590 47883 590 47865 590 47865 62300 47883 62300 48049 62300 47865 62301 48049 62301 48000 62301 47893 590 47884 590 47891 590 47885 590 47886 590 47879 590 47879 62302 47886 62302 48006 62302 47879 590 48006 590 47896 590 47896 62303 48006 62303 48168 62303 47896 590 48168 590 47894 590 48258 590 47887 590 47875 590 47875 590 47887 590 47989 590 47875 590 47989 590 47871 590 47871 590 47989 590 48225 590 47871 590 48225 590 47881 590 47884 590 48114 590 47891 590 47891 62304 48114 62304 47998 62304 47891 62305 47998 62305 47888 62305 48147 62306 47997 62306 47896 62306 47896 62307 47997 62307 48031 62307 47896 62308 48031 62308 48004 62308 48004 590 47889 590 47896 590 47896 590 47889 590 47890 590 47896 62309 47890 62309 47891 62309 47891 590 47890 590 47892 590 47891 62310 47892 62310 47893 62310 47894 62311 47895 62311 47896 62311 47896 62312 47895 62312 48152 62312 47896 62313 48152 62313 48147 62313 48000 590 48083 590 47865 590 47865 62314 48083 62314 48002 62314 47865 590 48002 590 47875 590 47875 62315 48002 62315 47987 62315 47875 62316 47987 62316 47897 62316 47888 590 47898 590 47891 590 47891 62317 47898 62317 47899 62317 47891 590 47899 590 47865 590 47865 62318 47899 62318 47900 62318 47865 62319 47900 62319 47877 62319 47976 62320 47902 62320 47975 62320 48082 62321 47901 62321 48080 62321 48080 62322 47901 62322 47902 62322 48080 62323 47902 62323 47903 62323 47903 62324 47902 62324 47976 62324 48082 62325 47904 62325 47901 62325 47901 62326 47904 62326 48090 62326 47901 62327 48090 62327 47905 62327 48093 62328 47907 62328 48094 62328 48094 62329 47907 62329 47905 62329 48094 62330 47905 62330 47906 62330 47906 62331 47905 62331 48090 62331 48093 62332 48092 62332 47907 62332 47907 62333 48092 62333 48091 62333 47907 62334 48091 62334 47908 62334 47909 62335 47912 62335 47910 62335 47910 62336 47912 62336 47908 62336 47910 62337 47908 62337 48100 62337 48100 62338 47908 62338 48091 62338 47909 62339 47911 62339 47912 62339 47912 62340 47911 62340 48057 62340 47912 62341 48057 62341 47914 62341 48057 62342 47913 62342 47914 62342 47914 62343 47913 62343 47982 62343 47914 62344 47982 62344 47916 62344 47917 62345 47915 62345 48113 62345 48113 62346 47915 62346 47916 62346 48113 62347 47916 62347 47981 62347 47981 62348 47916 62348 47982 62348 47917 62349 48118 62349 47915 62349 47915 62350 48118 62350 48117 62350 47915 62351 48117 62351 47918 62351 47921 62352 47919 62352 47920 62352 47920 62353 47919 62353 47918 62353 47920 62354 47918 62354 47980 62354 47980 62355 47918 62355 48117 62355 47921 62356 47922 62356 47919 62356 47919 62357 47922 62357 48133 62357 47919 62358 48133 62358 47923 62358 48135 62359 47925 62359 48136 62359 48136 62360 47925 62360 47923 62360 48136 62361 47923 62361 48138 62361 48138 62362 47923 62362 48133 62362 48135 62363 47924 62363 47925 62363 47925 62364 47924 62364 47926 62364 47925 62365 47926 62365 47928 62365 47926 62366 47927 62366 47928 62366 47928 62367 47927 62367 47931 62367 47928 62368 47931 62368 47929 62368 48151 62369 47933 62369 47930 62369 47930 62370 47933 62370 47929 62370 47930 62371 47929 62371 48145 62371 48145 62372 47929 62372 47931 62372 48151 62373 47932 62373 47933 62373 47933 62374 47932 62374 47937 62374 47933 62375 47937 62375 47936 62375 48162 62376 47934 62376 48160 62376 48160 62377 47934 62377 47936 62377 48160 62378 47936 62378 47935 62378 47935 62379 47936 62379 47937 62379 48162 62380 48161 62380 47934 62380 47934 62381 48161 62381 48169 62381 47934 62382 48169 62382 47938 62382 48171 62383 47939 62383 47940 62383 47940 62384 47939 62384 47938 62384 47940 62385 47938 62385 47941 62385 47941 62386 47938 62386 48169 62386 48171 62387 47942 62387 47939 62387 47939 62388 47942 62388 48062 62388 47939 62389 48062 62389 47943 62389 48062 62390 48060 62390 47943 62390 47943 62391 48060 62391 47947 62391 47943 62392 47947 62392 47946 62392 47944 62393 47949 62393 48186 62393 48186 62394 47949 62394 47946 62394 48186 62395 47946 62395 47945 62395 47945 62396 47946 62396 47947 62396 47944 62397 47948 62397 47949 62397 47949 62398 47948 62398 47953 62398 47949 62399 47953 62399 47952 62399 48201 62400 47951 62400 47950 62400 47950 62401 47951 62401 47952 62401 47950 62402 47952 62402 47977 62402 47977 62403 47952 62403 47953 62403 48201 62404 48197 62404 47951 62404 47951 62405 48197 62405 48212 62405 47951 62406 48212 62406 47954 62406 48209 62407 47955 62407 48211 62407 48211 62408 47955 62408 47954 62408 48211 62409 47954 62409 47956 62409 47956 62410 47954 62410 48212 62410 48209 62411 48207 62411 47955 62411 47955 62412 48207 62412 48206 62412 47955 62413 48206 62413 47958 62413 48206 62414 47957 62414 47958 62414 47958 62415 47957 62415 47959 62415 47958 62416 47959 62416 47961 62416 47959 62417 48218 62417 47961 62417 47961 62418 48218 62418 47960 62418 47961 62419 47960 62419 47962 62419 47962 62420 47960 62420 48220 62420 47962 62421 48220 62421 47966 62421 47966 62422 48220 62422 48231 62422 47966 62423 48231 62423 48230 62423 48241 62424 47963 62424 47964 62424 47964 62425 47963 62425 47966 62425 47964 62426 47966 62426 47965 62426 47965 62427 47966 62427 48230 62427 48241 62428 48245 62428 47963 62428 47963 62429 48245 62429 47967 62429 47963 62430 47967 62430 47969 62430 48247 62431 47970 62431 47968 62431 47968 62432 47970 62432 47969 62432 47968 62433 47969 62433 48249 62433 48249 62434 47969 62434 47967 62434 48247 62435 47971 62435 47970 62435 47970 62436 47971 62436 48071 62436 47970 62437 48071 62437 47972 62437 48071 62438 48251 62438 47972 62438 47972 62439 48251 62439 48264 62439 47972 62440 48264 62440 47974 62440 48264 62441 47973 62441 47974 62441 47974 62442 47973 62442 48270 62442 47974 62443 48270 62443 47975 62443 47975 62444 48270 62444 48075 62444 47975 62445 48075 62445 47976 62445 47965 62446 48230 62446 48235 62446 47977 62447 47953 62447 48191 62447 47935 62448 47937 62448 47978 62448 48145 62449 47931 62449 47979 62449 47980 62450 48117 62450 48123 62450 47981 62451 47982 62451 48102 62451 47903 62452 47976 62452 48079 62452 48256 62453 48011 62453 48254 62453 48008 62454 48007 62454 47983 62454 48177 62455 48017 62455 48176 62455 48005 62456 47984 62456 47985 62456 48105 62457 48014 62457 47986 62457 47897 62458 47987 62458 47988 62458 48259 62459 47897 62459 48261 62459 47887 62460 48258 62460 48237 62460 47989 62461 47887 62461 48238 62461 48225 62462 47989 62462 48232 62462 47881 62463 48225 62463 48226 62463 48042 62464 47881 62464 47990 62464 47993 62465 47991 62465 47992 62465 48192 62466 47993 62466 47994 62466 47995 62467 48192 62467 48193 62467 47996 62468 47995 62468 48187 62468 48180 62469 47996 62469 48181 62469 47894 62470 48168 62470 48163 62470 47895 62471 47894 62471 48158 62471 48152 62472 47895 62472 48153 62472 48147 62473 48152 62473 48154 62473 47997 62474 48147 62474 48148 62474 47893 62475 47892 62475 48125 62475 47884 62476 47893 62476 48119 62476 48114 62477 47884 62477 48115 62477 47998 62478 48114 62478 47999 62478 47888 62479 47998 62479 48106 62479 48083 62480 48000 62480 48001 62480 48002 62481 48083 62481 48076 62481 47987 62482 48002 62482 48003 62482 47899 62483 48014 62483 47900 62483 47900 62484 48014 62484 48105 62484 47900 62485 48105 62485 47877 62485 48004 62486 47984 62486 47889 62486 47889 62487 47984 62487 48005 62487 47889 62488 48005 62488 47890 62488 47885 62489 48017 62489 47886 62489 47886 62490 48017 62490 48177 62490 47886 62491 48177 62491 48006 62491 48020 62492 48007 62492 48009 62492 48009 62493 48007 62493 48008 62493 48009 62494 48008 62494 48010 62494 48023 62495 48011 62495 48012 62495 48012 62496 48011 62496 48256 62496 48012 62497 48256 62497 48257 62497 48013 62498 47986 62498 48026 62498 48026 62499 47986 62499 48014 62499 48026 62500 48014 62500 48015 62500 48015 62501 48014 62501 47899 62501 48015 62502 47899 62502 47898 62502 48140 62503 47985 62503 48030 62503 48030 62504 47985 62504 47984 62504 48030 62505 47984 62505 48016 62505 48016 62506 47984 62506 48004 62506 48016 62507 48004 62507 48031 62507 48035 62508 48176 62508 48037 62508 48037 62509 48176 62509 48017 62509 48037 62510 48017 62510 48039 62510 48039 62511 48017 62511 47885 62511 48039 62512 47885 62512 47880 62512 48213 62513 47983 62513 48018 62513 48018 62514 47983 62514 48007 62514 48018 62515 48007 62515 48019 62515 48019 62516 48007 62516 48020 62516 48019 62517 48020 62517 47882 62517 48253 62518 48254 62518 48021 62518 48021 62519 48254 62519 48011 62519 48021 62520 48011 62520 48022 62520 48022 62521 48011 62521 48023 62521 48022 62522 48023 62522 48024 62522 48044 62523 48088 62523 48086 62523 48102 62524 48013 62524 48025 62524 48025 62525 48013 62525 48026 62525 48025 62526 48026 62526 48027 62526 48027 62527 48026 62527 48015 62527 48027 62528 48015 62528 48107 62528 48107 62529 48015 62529 47898 62529 48107 62530 47898 62530 47888 62530 48028 62531 48130 62531 48129 62531 47979 62532 48140 62532 48029 62532 48029 62533 48140 62533 48030 62533 48029 62534 48030 62534 48143 62534 48143 62535 48030 62535 48016 62535 48143 62536 48016 62536 48032 62536 48032 62537 48016 62537 48031 62537 48032 62538 48031 62538 47997 62538 48064 62539 48033 62539 48034 62539 48174 62540 48035 62540 48036 62540 48036 62541 48035 62541 48037 62541 48036 62542 48037 62542 48038 62542 48038 62543 48037 62543 48039 62543 48038 62544 48039 62544 48182 62544 48182 62545 48039 62545 47880 62545 48182 62546 47880 62546 48180 62546 48067 62547 48203 62547 48068 62547 48040 62548 48213 62548 48217 62548 48217 62549 48213 62549 48018 62549 48217 62550 48018 62550 48216 62550 48216 62551 48018 62551 48019 62551 48216 62552 48019 62552 48041 62552 48041 62553 48019 62553 47882 62553 48041 62554 47882 62554 48042 62554 48070 62555 48069 62555 48073 62555 48250 62556 48253 62556 48043 62556 48043 62557 48253 62557 48021 62557 48043 62558 48021 62558 48262 62558 48262 62559 48021 62559 48022 62559 48262 62560 48022 62560 48260 62560 48260 62561 48022 62561 48024 62561 48260 62562 48024 62562 48259 62562 48096 62563 48088 62563 48095 62563 48095 62564 48088 62564 48044 62564 48095 62565 48044 62565 48045 62565 48100 62566 48091 62566 48098 62566 48098 62567 48091 62567 48045 62567 48098 62568 48045 62568 48046 62568 48046 62569 48045 62569 48044 62569 48046 62570 48044 62570 48047 62570 48047 62571 48044 62571 48086 62571 48047 62572 48086 62572 48048 62572 48049 62573 47883 62573 48097 62573 48097 62574 47883 62574 48050 62574 48097 62575 48050 62575 48051 62575 48051 62576 48050 62576 48052 62576 48051 62577 48052 62577 48053 62577 48053 62578 48052 62578 48055 62578 48053 62579 48055 62579 48099 62579 48099 62580 48055 62580 48056 62580 47883 62581 47878 62581 48050 62581 48050 62582 47878 62582 48054 62582 48050 62583 48054 62583 48052 62583 48052 62584 48054 62584 48104 62584 48052 62585 48104 62585 48055 62585 48055 62586 48104 62586 48103 62586 48055 62587 48103 62587 48056 62587 48056 62588 48103 62588 48101 62588 48056 62589 48101 62589 48057 62589 48057 62590 48101 62590 47913 62590 48132 62591 48130 62591 48137 62591 48137 62592 48130 62592 48028 62592 48137 62593 48028 62593 48134 62593 47927 62594 47926 62594 48139 62594 48139 62595 47926 62595 48134 62595 48139 62596 48134 62596 48058 62596 48058 62597 48134 62597 48028 62597 48058 62598 48028 62598 48059 62598 48059 62599 48028 62599 48129 62599 48059 62600 48129 62600 48141 62600 48173 62601 48033 62601 48172 62601 48172 62602 48033 62602 48064 62602 48172 62603 48064 62603 48063 62603 48060 62604 48062 62604 48061 62604 48061 62605 48062 62605 48063 62605 48061 62606 48063 62606 48175 62606 48175 62607 48063 62607 48064 62607 48175 62608 48064 62608 48065 62608 48065 62609 48064 62609 48034 62609 48065 62610 48034 62610 48178 62610 48204 62611 48203 62611 48210 62611 48210 62612 48203 62612 48067 62612 48210 62613 48067 62613 48208 62613 47957 62614 48206 62614 48214 62614 48214 62615 48206 62615 48208 62615 48214 62616 48208 62616 48066 62616 48066 62617 48208 62617 48067 62617 48066 62618 48067 62618 48215 62618 48215 62619 48067 62619 48068 62619 48215 62620 48068 62620 48202 62620 48244 62621 48069 62621 48248 62621 48248 62622 48069 62622 48070 62622 48248 62623 48070 62623 48246 62623 48251 62624 48071 62625 48252 62626 48252 62627 48071 62627 48246 62627 48252 62628 48246 62628 48072 62628 48072 62629 48246 62629 48070 62629 48072 62630 48070 62630 48255 62630 48255 62631 48070 62631 48073 62631 48255 62632 48073 62632 48242 62632 47987 62633 48003 62633 47988 62633 47988 62634 48003 62634 48074 62634 47988 62635 48074 62635 48265 62635 48265 62636 48074 62636 48078 62636 48265 62637 48078 62637 48267 62637 48267 62638 48078 62638 48079 62638 48267 62639 48079 62639 48268 62639 48268 62640 48079 62640 47976 62640 48268 62641 47976 62641 48075 62641 48002 62642 48076 62642 48003 62642 48003 62643 48076 62643 48084 62643 48003 62644 48084 62644 48074 62644 48074 62645 48084 62645 48077 62645 48074 62646 48077 62646 48078 62646 48078 62647 48077 62647 48085 62647 48078 62648 48085 62648 48079 62648 48079 62649 48085 62649 48080 62649 48079 62650 48080 62650 47903 62650 48081 62651 47904 62651 48082 62651 48083 62652 48001 62652 48076 62652 48076 62653 48001 62653 48087 62653 48076 62654 48087 62654 48084 62654 48084 62655 48087 62655 48089 62655 48084 62656 48089 62656 48077 62656 48077 62657 48089 62657 48081 62657 48077 62658 48081 62658 48085 62658 48085 62659 48081 62659 48082 62659 48085 62660 48082 62660 48080 62660 48000 62661 48048 62661 48001 62661 48001 62662 48048 62662 48086 62662 48001 62663 48086 62663 48087 62663 48087 62664 48086 62664 48088 62664 48087 62665 48088 62665 48089 62665 48089 62666 48088 62666 48096 62666 48089 62667 48096 62667 48081 62667 48081 62668 48096 62668 48090 62668 48081 62669 48090 62669 47904 62669 48091 62670 48092 62670 48045 62670 48045 62671 48092 62671 48093 62671 48045 62672 48093 62672 48095 62672 48095 62673 48093 62673 48094 62673 48095 62674 48094 62674 48096 62674 48096 62675 48094 62675 47906 62675 48096 62676 47906 62676 48090 62676 48000 62677 48049 62677 48048 62677 48048 62678 48049 62678 48097 62678 48048 62679 48097 62679 48047 62679 48047 62680 48097 62680 48051 62680 48047 62681 48051 62681 48046 62681 48046 62682 48051 62682 48053 62682 48046 62683 48053 62683 48098 62683 48098 62684 48053 62684 48099 62684 48098 62685 48099 62685 48100 62685 48057 62686 47911 62686 48056 62686 48056 62687 47911 62687 47909 62687 48056 62688 47909 62688 48099 62688 48099 62689 47909 62689 47910 62689 48099 62690 47910 62690 48100 62690 47982 62691 47913 62691 48102 62691 48102 62692 47913 62692 48101 62692 48102 62693 48101 62693 48013 62693 48013 62694 48101 62694 48103 62694 48013 62695 48103 62695 47986 62695 47986 62696 48103 62696 48104 62696 47986 62697 48104 62697 48105 62697 48105 62698 48104 62698 48054 62698 48105 62699 48054 62699 47877 62699 47877 62700 48054 62700 47878 62700 47888 62701 48106 62701 48107 62701 48107 62702 48106 62702 48110 62702 48107 62703 48110 62703 48027 62703 48027 62704 48110 62704 48108 62704 48027 62705 48108 62705 48025 62705 48025 62706 48108 62706 48112 62706 48025 62707 48112 62707 48102 62707 48102 62708 48112 62708 48113 62708 48102 62709 48113 62709 47981 62709 48116 62710 48118 62710 47917 62710 47998 62711 47999 62711 48106 62711 48106 62712 47999 62712 48109 62712 48106 62713 48109 62713 48110 62713 48110 62714 48109 62714 48111 62714 48110 62715 48111 62715 48108 62715 48108 62716 48111 62716 48116 62716 48108 62717 48116 62717 48112 62717 48112 62718 48116 62718 47917 62718 48112 62719 47917 62719 48113 62719 48114 62720 48115 62720 47999 62720 47999 62721 48115 62721 48120 62721 47999 62722 48120 62722 48109 62722 48109 62723 48120 62723 48122 62723 48109 62724 48122 62724 48111 62724 48111 62725 48122 62725 48123 62725 48111 62726 48123 62726 48116 62726 48116 62727 48123 62727 48117 62727 48116 62728 48117 62728 48118 62728 47884 62729 48119 62729 48115 62729 48115 62730 48119 62730 48127 62730 48115 62731 48127 62731 48120 62731 48120 62732 48127 62732 48121 62732 48120 62733 48121 62733 48122 62733 48122 62734 48121 62734 48124 62734 48122 62735 48124 62735 48123 62735 48123 62736 48124 62736 47920 62736 48123 62737 47920 62737 47980 62737 48128 62738 47922 62738 47921 62738 47893 62739 48125 62739 48119 62739 48119 62740 48125 62740 48126 62740 48119 62741 48126 62741 48127 62741 48127 62742 48126 62742 48131 62742 48127 62743 48131 62743 48121 62743 48121 62744 48131 62744 48128 62744 48121 62745 48128 62745 48124 62745 48124 62746 48128 62746 47921 62746 48124 62747 47921 62747 47920 62747 47892 62748 48141 62748 48125 62748 48125 62749 48141 62749 48129 62749 48125 62750 48129 62750 48126 62750 48126 62751 48129 62751 48130 62751 48126 62752 48130 62752 48131 62752 48131 62753 48130 62753 48132 62753 48131 62754 48132 62754 48128 62754 48128 62755 48132 62755 48133 62755 48128 62756 48133 62756 47922 62756 47926 62757 47924 62757 48134 62757 48134 62758 47924 62758 48135 62758 48134 62759 48135 62759 48137 62759 48137 62760 48135 62760 48136 62760 48137 62761 48136 62761 48132 62761 48132 62762 48136 62762 48138 62762 48132 62763 48138 62763 48133 62763 47931 62764 47927 62764 47979 62764 47979 62765 47927 62765 48139 62765 47979 62766 48139 62766 48140 62766 48140 62767 48139 62767 48058 62767 48140 62768 48058 62768 47985 62768 47985 62769 48058 62769 48059 62769 47985 62770 48059 62770 48005 62770 48005 62771 48059 62771 48141 62771 48005 62772 48141 62772 47890 62772 47890 62773 48141 62773 47892 62773 47997 62774 48148 62774 48032 62774 48032 62775 48148 62775 48142 62775 48032 62776 48142 62776 48143 62776 48143 62777 48142 62777 48144 62777 48143 62778 48144 62778 48029 62778 48029 62779 48144 62779 48150 62779 48029 62780 48150 62780 47979 62780 47979 62781 48150 62781 47930 62781 47979 62782 47930 62782 48145 62782 48146 62783 47932 62784 48151 62785 48147 62786 48154 62786 48148 62786 48148 62787 48154 62787 48156 62787 48148 62788 48156 62788 48142 62788 48142 62789 48156 62789 48149 62789 48142 62790 48149 62790 48144 62790 48144 62791 48149 62791 48146 62791 48144 62792 48146 62792 48150 62792 48150 62793 48146 62793 48151 62793 48150 62794 48151 62794 47930 62794 48152 62795 48153 62795 48154 62795 48154 62796 48153 62796 48155 62796 48154 62797 48155 62797 48156 62797 48156 62798 48155 62798 48157 62798 48156 62799 48157 62799 48149 62799 48149 62800 48157 62800 47978 62800 48149 62801 47978 62801 48146 62801 48146 62802 47978 62802 47937 62802 48146 62803 47937 62803 47932 62803 47895 62804 48158 62804 48153 62804 48153 62805 48158 62805 48159 62805 48153 62806 48159 62806 48155 62806 48155 62807 48159 62807 48166 62807 48155 62808 48166 62808 48157 62808 48157 62809 48166 62809 48167 62809 48157 62810 48167 62810 47978 62810 47978 62811 48167 62811 48160 62811 47978 62812 48160 62812 47935 62812 48170 62813 48161 62813 48162 62813 47894 62814 48163 62814 48158 62814 48158 62815 48163 62815 48164 62815 48158 62816 48164 62816 48159 62816 48159 62817 48164 62817 48165 62817 48159 62818 48165 62818 48166 62818 48166 62819 48165 62819 48170 62819 48166 62820 48170 62820 48167 62820 48167 62821 48170 62821 48162 62821 48167 62822 48162 62822 48160 62822 48168 62823 48178 62823 48163 62823 48163 62824 48178 62824 48034 62824 48163 62825 48034 62825 48164 62825 48164 62826 48034 62826 48033 62826 48164 62827 48033 62827 48165 62827 48165 62828 48033 62828 48173 62828 48165 62829 48173 62829 48170 62829 48170 62830 48173 62830 48169 62830 48170 62831 48169 62831 48161 62831 48062 62832 47942 62832 48063 62832 48063 62833 47942 62833 48171 62833 48063 62834 48171 62834 48172 62834 48172 62835 48171 62835 47940 62835 48172 62836 47940 62836 48173 62836 48173 62837 47940 62837 47941 62837 48173 62838 47941 62838 48169 62838 47947 62839 48060 62839 48174 62839 48174 62840 48060 62840 48061 62840 48174 62841 48061 62841 48035 62841 48035 62842 48061 62842 48175 62842 48035 62843 48175 62843 48176 62843 48176 62844 48175 62844 48065 62844 48176 62845 48065 62845 48177 62845 48177 62846 48065 62846 48178 62846 48177 62847 48178 62847 48006 62847 48006 62848 48178 62848 48168 62848 48179 62849 48186 62849 47945 62849 48180 62850 48181 62850 48182 62850 48182 62851 48181 62851 48183 62851 48182 62852 48183 62852 48038 62852 48038 62853 48183 62853 48185 62853 48038 62854 48185 62854 48036 62854 48036 62855 48185 62855 48179 62855 48036 62856 48179 62856 48174 62856 48174 62857 48179 62857 47945 62857 48174 62858 47945 62858 47947 62858 48184 62859 47948 62859 47944 62859 47996 62860 48187 62860 48181 62860 48181 62861 48187 62861 48189 62861 48181 62862 48189 62862 48183 62862 48183 62863 48189 62863 48190 62863 48183 62864 48190 62864 48185 62864 48185 62865 48190 62865 48184 62865 48185 62866 48184 62866 48179 62866 48179 62867 48184 62867 47944 62867 48179 62868 47944 62868 48186 62868 47995 62869 48193 62869 48187 62869 48187 62870 48193 62870 48188 62870 48187 62871 48188 62871 48189 62871 48189 62872 48188 62872 48196 62872 48189 62873 48196 62873 48190 62873 48190 62874 48196 62874 48191 62874 48190 62875 48191 62875 48184 62875 48184 62876 48191 62876 47953 62876 48184 62877 47953 62877 47948 62877 48192 62878 47994 62878 48193 62878 48193 62879 47994 62879 48194 62879 48193 62880 48194 62880 48188 62880 48188 62881 48194 62881 48200 62881 48188 62882 48200 62882 48196 62882 48196 62883 48200 62883 48195 62883 48196 62884 48195 62884 48191 62884 48191 62885 48195 62885 47950 62885 48191 62886 47950 62886 47977 62886 48205 62887 48197 62887 48201 62887 47993 62888 47992 62888 47994 62888 47994 62889 47992 62889 48198 62889 47994 62890 48198 62890 48194 62890 48194 62891 48198 62891 48199 62891 48194 62892 48199 62892 48200 62892 48200 62893 48199 62893 48205 62893 48200 62894 48205 62894 48195 62894 48195 62895 48205 62895 48201 62895 48195 62896 48201 62896 47950 62896 47991 62897 48202 62897 47992 62897 47992 62898 48202 62898 48068 62898 47992 62899 48068 62899 48198 62899 48198 62900 48068 62900 48203 62900 48198 62901 48203 62901 48199 62901 48199 62902 48203 62902 48204 62902 48199 62903 48204 62903 48205 62903 48205 62904 48204 62904 48212 62904 48205 62905 48212 62905 48197 62905 48206 62906 48207 62906 48208 62906 48208 62907 48207 62907 48209 62907 48208 62908 48209 62908 48210 62908 48210 62909 48209 62909 48211 62909 48210 62910 48211 62910 48204 62910 48204 62911 48211 62911 47956 62911 48204 62912 47956 62912 48212 62912 47959 62913 47957 62913 48040 62913 48040 62914 47957 62914 48214 62914 48040 62915 48214 62915 48213 62915 48213 62916 48214 62916 48066 62916 48213 62917 48066 62917 47983 62917 47983 62918 48066 62918 48215 62918 47983 62919 48215 62919 48008 62919 48008 62920 48215 62920 48202 62920 48008 62921 48202 62921 48010 62921 48010 62922 48202 62922 47991 62922 48224 62923 47960 62923 48218 62923 48042 62924 47990 62924 48041 62924 48041 62925 47990 62925 48222 62925 48041 62926 48222 62926 48216 62926 48216 62927 48222 62927 48223 62927 48216 62928 48223 62928 48217 62928 48217 62929 48223 62929 48224 62929 48217 62930 48224 62930 48040 62930 48040 62931 48224 62931 48218 62931 48040 62932 48218 62932 47959 62932 48219 62933 48231 62933 48220 62933 47881 62934 48226 62934 47990 62934 47990 62935 48226 62935 48221 62935 47990 62936 48221 62936 48222 62936 48222 62937 48221 62937 48229 62937 48222 62938 48229 62938 48223 62938 48223 62939 48229 62939 48219 62939 48223 62940 48219 62940 48224 62940 48224 62941 48219 62941 48220 62941 48224 62942 48220 62942 47960 62942 48225 62943 48232 62943 48226 62943 48226 62944 48232 62944 48227 62944 48226 62945 48227 62945 48221 62945 48221 62946 48227 62946 48228 62946 48221 62947 48228 62947 48229 62947 48229 62948 48228 62948 48235 62948 48229 62949 48235 62949 48219 62949 48219 62950 48235 62950 48230 62950 48219 62951 48230 62951 48231 62951 47989 62952 48238 62952 48232 62952 48232 62953 48238 62953 48240 62953 48232 62954 48240 62954 48227 62954 48227 62955 48240 62955 48233 62955 48227 62956 48233 62956 48228 62956 48228 62957 48233 62957 48234 62957 48228 62958 48234 62958 48235 62958 48235 62959 48234 62959 47964 62959 48235 62960 47964 62960 47965 62960 48236 62961 48245 62961 48241 62961 47887 62962 48237 62962 48238 62962 48238 62963 48237 62963 48243 62963 48238 62964 48243 62964 48240 62964 48240 62965 48243 62965 48239 62965 48240 62966 48239 62966 48233 62966 48233 62967 48239 62967 48236 62967 48233 62968 48236 62968 48234 62968 48234 62969 48236 62969 48241 62969 48234 62970 48241 62970 47964 62970 48258 62971 48242 62971 48237 62971 48237 62972 48242 62972 48073 62972 48237 62973 48073 62973 48243 62973 48243 62974 48073 62974 48069 62974 48243 62975 48069 62975 48239 62975 48239 62976 48069 62976 48244 62976 48239 62977 48244 62977 48236 62977 48236 62978 48244 62978 47967 62978 48236 62979 47967 62979 48245 62979 48071 62980 47971 62980 48246 62980 48246 62981 47971 62981 48247 62981 48246 62982 48247 62982 48248 62982 48248 62983 48247 62983 47968 62983 48248 62984 47968 62984 48244 62984 48244 62985 47968 62985 48249 62985 48244 62986 48249 62986 47967 62986 48264 62987 48251 62987 48250 62987 48250 62988 48251 62988 48252 62988 48250 62989 48252 62989 48253 62989 48253 62990 48252 62990 48072 62990 48253 62991 48072 62991 48254 62991 48254 62992 48072 62992 48255 62992 48254 62993 48255 62993 48256 62993 48256 62994 48255 62994 48242 62994 48256 62995 48242 62995 48257 62995 48257 62996 48242 62996 48258 62996 48269 62997 48270 62997 47973 62997 48259 62998 48261 62998 48260 62998 48260 62999 48261 62999 48266 62999 48260 63000 48266 63000 48262 63000 48262 63001 48266 63001 48263 63001 48262 63002 48263 63002 48043 63002 48043 63003 48263 63003 48269 63003 48043 63004 48269 63004 48250 63004 48250 63005 48269 63005 47973 63005 48250 63006 47973 63006 48264 63006 47897 63007 47988 63007 48261 63007 48261 63008 47988 63008 48265 63008 48261 63009 48265 63009 48266 63009 48266 63010 48265 63010 48267 63010 48266 63011 48267 63011 48263 63011 48263 63012 48267 63012 48268 63012 48263 63013 48268 63013 48269 63013 48269 63014 48268 63014 48075 63014 48269 63015 48075 63015 48270 63015 48307 63016 48271 63016 48277 63016 48273 63017 48271 63017 48307 63017 48272 63018 48273 63018 48307 63018 48307 63019 48276 63019 48274 63019 48275 63020 48276 63020 48307 63020 48277 63021 48275 63021 48307 63021 48307 63022 48278 63022 48279 63022 48280 63023 48278 63023 48307 63023 48281 63024 48280 63024 48307 63024 48307 63025 48282 63025 48309 63025 48283 63026 48282 63026 48307 63026 48279 63027 48283 63027 48307 63027 47872 63028 48287 63028 48307 63028 48307 63029 48286 63029 48284 63029 48285 63030 48286 63030 48307 63030 48287 63031 48285 63031 48307 63031 48307 63032 48288 63032 47869 63032 48289 63033 48288 63033 48307 63033 48284 63034 48289 63034 48307 63034 48307 63035 48291 63035 48290 63035 48292 63036 48291 63036 48307 63036 47869 63037 48292 63037 48307 63037 48307 63038 48294 63038 48308 63038 48293 63039 48294 63039 48307 63039 48290 63040 48293 63040 48307 63040 48307 63041 48295 63041 48296 63041 48297 63042 48295 63042 48307 63042 47867 63043 48297 63043 48307 63043 48307 63044 48299 63044 48298 63044 48300 63045 48299 63045 48307 63045 48296 63046 48300 63046 48307 63046 48307 63047 48301 63047 48304 63047 48302 63048 48301 63048 48307 63048 47864 63049 48302 63049 48307 63049 48307 63050 48303 63050 48306 63050 48305 63051 48303 63051 48307 63051 48304 63052 48305 63052 48307 63052 48306 63053 48272 63053 48307 63053 48298 63054 47864 63054 48307 63054 48308 63055 47867 63055 48307 63055 48309 63056 47872 63056 48307 63056 48274 63057 48281 63057 48307 63057 48310 63058 48311 63058 48312 63058 48312 63059 48311 63059 48334 63059 48312 63060 48334 63060 48313 63060 48314 63061 48335 63061 48315 63061 48315 63062 48335 63062 48328 63062 48315 63063 48328 63063 48316 63063 48486 590 48443 590 48318 590 48319 590 48317 590 48670 590 48670 590 48317 590 48318 590 48670 63064 48318 63064 48444 63064 48444 590 48318 590 48443 590 48319 63065 48320 63065 48317 63065 48317 63066 48320 63066 48480 63066 48317 590 48480 590 48479 590 48329 590 48321 590 48328 590 48328 63067 48321 63067 48322 63067 48328 63068 48322 63068 48323 63068 48323 590 48427 590 48328 590 48328 590 48427 590 48689 590 48328 63069 48689 63069 48495 63069 48479 63070 48324 63070 48317 63070 48317 590 48324 590 48325 590 48317 63071 48325 63071 48336 63071 48456 590 48441 590 48311 590 48311 63072 48441 63072 48337 63072 48428 590 48326 590 48318 590 48318 63073 48326 63073 48327 63073 48318 590 48327 590 48486 590 48436 590 48437 590 48335 590 48335 590 48437 590 48533 590 48335 63074 48533 63074 48328 63074 48328 590 48533 590 48426 590 48328 590 48426 590 48329 590 48330 63075 48433 63075 48334 63075 48334 63076 48433 63076 48465 63076 48334 63077 48465 63077 48438 63077 48435 63078 48434 63078 48335 63078 48335 63079 48434 63079 48547 63079 48335 590 48547 590 48436 590 48341 590 48593 590 48334 590 48334 63080 48593 63080 48594 63080 48334 63081 48594 63081 48330 63081 48495 590 48331 590 48328 590 48328 63082 48331 63082 48332 63082 48328 63083 48332 63083 48318 63083 48318 590 48332 590 48333 590 48318 63084 48333 63084 48428 63084 48438 590 48440 590 48334 590 48334 590 48440 590 48573 590 48334 590 48573 590 48335 590 48335 63085 48573 63085 48566 63085 48335 63086 48566 63086 48435 63086 48336 63087 48631 63087 48317 63087 48317 63088 48631 63088 48429 63088 48317 63089 48429 63089 48311 63089 48311 590 48429 590 48474 590 48311 590 48474 590 48456 590 48337 590 48620 590 48311 590 48311 63090 48620 63090 48621 63090 48311 63091 48621 63091 48431 63091 48431 590 48338 590 48311 590 48311 63092 48338 63092 48339 63092 48311 590 48339 590 48334 590 48334 63093 48339 63093 48340 63093 48334 63094 48340 63094 48341 63094 48532 63095 48342 63095 48414 63095 48538 63096 48343 63096 48540 63096 48540 63097 48343 63097 48342 63097 48540 63098 48342 63098 48537 63098 48537 63099 48342 63099 48532 63099 48538 63100 48546 63100 48343 63100 48343 63101 48546 63101 48418 63101 48343 63102 48418 63102 48345 63102 48418 63103 48344 63103 48345 63103 48345 63104 48344 63104 48554 63104 48345 63105 48554 63105 48346 63105 48554 63106 48556 63106 48346 63106 48346 63107 48556 63107 48555 63107 48346 63108 48555 63108 48347 63108 48347 63109 48555 63109 48348 63109 48347 63110 48348 63110 48349 63110 48349 63111 48348 63111 48561 63111 48349 63112 48561 63112 48350 63112 48351 63113 48353 63113 48352 63113 48352 63114 48353 63114 48349 63114 48352 63115 48349 63115 48569 63115 48569 63116 48349 63116 48350 63116 48351 63117 48354 63117 48353 63117 48353 63118 48354 63118 48356 63118 48353 63119 48356 63119 48355 63119 48356 63120 48498 63120 48355 63120 48355 63121 48498 63121 48360 63121 48355 63122 48360 63122 48359 63122 48579 63123 48357 63123 48583 63123 48583 63124 48357 63124 48359 63124 48583 63125 48359 63125 48358 63125 48358 63126 48359 63126 48360 63126 48579 63127 48361 63127 48357 63127 48357 63128 48361 63128 48591 63128 48357 63129 48591 63129 48364 63129 48590 63130 48362 63130 48363 63130 48363 63131 48362 63131 48364 63131 48363 63132 48364 63132 48365 63132 48365 63133 48364 63133 48591 63133 48590 63134 48589 63134 48362 63134 48362 63135 48589 63135 48588 63135 48362 63136 48588 63136 48367 63136 48588 63137 48366 63138 48367 63139 48367 63140 48366 63140 48601 63140 48367 63141 48601 63141 48368 63141 48369 63142 48370 63142 48595 63142 48595 63143 48370 63143 48368 63143 48595 63144 48368 63144 48600 63144 48600 63145 48368 63145 48601 63145 48369 63146 48371 63147 48370 63148 48370 63149 48371 63149 48608 63149 48370 63150 48608 63150 48372 63150 48609 63151 48374 63151 48611 63151 48611 63152 48374 63152 48372 63152 48611 63153 48372 63153 48612 63153 48612 63154 48372 63154 48608 63154 48609 63155 48373 63155 48374 63155 48374 63156 48373 63156 48509 63156 48374 63157 48509 63157 48375 63157 48509 63158 48615 63158 48375 63158 48375 63159 48615 63159 48614 63159 48375 63160 48614 63160 48376 63160 48378 63161 48377 63161 48630 63161 48630 63162 48377 63162 48376 63162 48630 63163 48376 63163 48622 63163 48622 63164 48376 63164 48614 63164 48378 63165 48635 63165 48377 63165 48377 63166 48635 63166 48633 63166 48377 63167 48633 63167 48380 63167 48637 63168 48379 63168 48639 63168 48639 63169 48379 63169 48380 63169 48639 63170 48380 63170 48641 63170 48641 63171 48380 63171 48633 63171 48637 63172 48636 63172 48379 63172 48379 63173 48636 63173 48515 63173 48379 63174 48515 63174 48381 63174 48515 63175 48643 63175 48381 63175 48381 63176 48643 63176 48642 63176 48381 63177 48642 63177 48383 63177 48384 63178 48385 63178 48649 63178 48649 63179 48385 63179 48383 63179 48649 63180 48383 63180 48382 63180 48382 63181 48383 63181 48642 63181 48384 63182 48650 63182 48385 63182 48385 63183 48650 63183 48389 63183 48385 63184 48389 63184 48387 63184 48663 63185 48386 63185 48664 63185 48664 63186 48386 63186 48387 63186 48664 63187 48387 63187 48388 63187 48388 63188 48387 63188 48389 63188 48663 63189 48390 63189 48386 63189 48386 63190 48390 63190 48391 63190 48386 63191 48391 63191 48392 63191 48391 63192 48518 63192 48392 63192 48392 63193 48518 63193 48665 63193 48392 63194 48665 63194 48396 63194 48678 63195 48393 63195 48394 63195 48394 63196 48393 63196 48396 63196 48394 63197 48396 63197 48395 63197 48395 63198 48396 63198 48665 63198 48678 63199 48683 63199 48393 63199 48393 63200 48683 63200 48397 63200 48393 63201 48397 63201 48398 63201 48685 63202 48401 63202 48399 63202 48399 63203 48401 63203 48398 63203 48399 63204 48398 63204 48400 63204 48400 63205 48398 63205 48397 63205 48685 63206 48684 63206 48401 63206 48401 63207 48684 63207 48402 63207 48401 63208 48402 63208 48403 63208 48402 63209 48404 63209 48403 63209 48403 63210 48404 63210 48408 63210 48403 63211 48408 63211 48405 63211 48406 63212 48409 63212 48691 63212 48691 63213 48409 63213 48405 63213 48691 63214 48405 63214 48407 63214 48407 63215 48405 63215 48408 63215 48406 63216 48692 63216 48409 63216 48409 63217 48692 63217 48410 63217 48409 63218 48410 63218 48411 63218 48410 63219 48412 63219 48411 63219 48411 63220 48412 63220 48710 63220 48411 63221 48710 63221 48413 63221 48710 63222 48709 63222 48413 63222 48413 63223 48709 63223 48415 63223 48413 63224 48415 63224 48414 63224 48414 63225 48415 63225 48416 63225 48414 63226 48416 63226 48532 63226 48412 63227 48410 63227 48705 63227 48407 63228 48408 63228 48686 63228 48395 63229 48665 63229 48483 63229 48382 63230 48642 63230 48417 63230 48344 63231 48418 63231 48419 63231 48537 63232 48532 63232 48530 63232 48447 63233 48460 63233 48688 63233 48446 63234 48445 63234 48669 63234 48420 63235 48457 63235 48421 63235 48442 63236 48422 63236 48423 63236 48424 63237 48425 63237 48453 63237 48572 63238 48439 63238 48449 63238 48329 63239 48426 63239 48526 63239 48321 63240 48329 63240 48711 63240 48322 63241 48321 63241 48706 63241 48323 63242 48322 63242 48697 63242 48427 63243 48323 63243 48698 63243 48689 63244 48427 63244 48693 63244 48326 63245 48428 63245 48679 63245 48327 63246 48326 63246 48671 63246 48320 63247 48319 63247 48658 63247 48480 63248 48320 63248 48651 63248 48429 63249 48631 63249 48625 63249 48474 63250 48429 63250 48430 63250 48431 63251 48621 63251 48603 63251 48338 63252 48431 63252 48432 63252 48330 63253 48594 63253 48586 63253 48433 63254 48330 63254 48574 63254 48435 63255 48566 63255 48562 63255 48434 63256 48435 63256 48557 63256 48547 63257 48434 63257 48548 63257 48436 63258 48547 63258 48549 63258 48437 63259 48436 63259 48541 63259 48533 63260 48437 63260 48539 63260 48426 63261 48533 63261 48525 63261 48438 63262 48439 63262 48440 63262 48440 63263 48439 63263 48572 63263 48440 63264 48572 63264 48573 63264 48340 63265 48425 63265 48341 63265 48341 63266 48425 63266 48424 63266 48341 63267 48424 63267 48593 63267 48441 63268 48422 63268 48337 63268 48337 63269 48422 63269 48442 63269 48337 63270 48442 63270 48620 63270 48324 63271 48457 63271 48325 63271 48325 63272 48457 63272 48420 63272 48325 63273 48420 63273 48336 63273 48443 63274 48445 63274 48444 63274 48444 63275 48445 63275 48446 63275 48444 63276 48446 63276 48670 63276 48331 63277 48460 63277 48332 63277 48332 63278 48460 63278 48447 63278 48332 63279 48447 63279 48333 63279 48463 63280 48449 63280 48448 63280 48448 63281 48449 63281 48439 63281 48448 63282 48439 63282 48450 63282 48450 63283 48439 63283 48438 63283 48450 63284 48438 63284 48465 63284 48451 63285 48453 63285 48452 63285 48452 63286 48453 63286 48425 63286 48452 63287 48425 63287 48467 63287 48467 63288 48425 63288 48340 63288 48467 63289 48340 63289 48339 63289 48617 63290 48423 63290 48454 63290 48454 63291 48423 63291 48422 63291 48454 63292 48422 63292 48455 63292 48455 63293 48422 63293 48441 63293 48455 63294 48441 63294 48456 63294 48475 63295 48421 63295 48476 63295 48476 63296 48421 63296 48457 63296 48476 63297 48457 63297 48478 63297 48478 63298 48457 63298 48324 63298 48478 63299 48324 63299 48479 63299 48458 63300 48669 63300 48484 63300 48484 63301 48669 63301 48445 63301 48484 63302 48445 63302 48459 63302 48459 63303 48445 63303 48443 63303 48459 63304 48443 63304 48486 63304 48489 63305 48688 63305 48490 63305 48490 63306 48688 63306 48460 63306 48490 63307 48460 63307 48492 63307 48492 63308 48460 63308 48331 63308 48492 63309 48331 63309 48495 63309 48497 63310 48461 63310 48462 63310 48570 63311 48463 63312 48577 63313 48577 63314 48463 63314 48448 63314 48577 63315 48448 63315 48576 63315 48576 63316 48448 63316 48450 63316 48576 63317 48450 63317 48464 63317 48464 63318 48450 63318 48465 63318 48464 63319 48465 63319 48433 63319 48507 63320 48503 63320 48585 63320 48599 63321 48451 63321 48466 63321 48466 63322 48451 63322 48452 63322 48466 63323 48452 63323 48468 63323 48468 63324 48452 63324 48467 63324 48468 63325 48467 63325 48469 63325 48469 63326 48467 63326 48339 63326 48469 63327 48339 63327 48338 63327 48470 63328 48606 63328 48604 63328 48624 63329 48617 63329 48471 63329 48471 63330 48617 63330 48454 63330 48471 63331 48454 63331 48472 63331 48472 63332 48454 63332 48455 63332 48472 63333 48455 63333 48473 63333 48473 63334 48455 63334 48456 63334 48473 63335 48456 63335 48474 63335 48513 63336 48512 63336 48517 63336 48417 63337 48475 63337 48648 63337 48648 63338 48475 63338 48476 63338 48648 63339 48476 63339 48477 63339 48477 63340 48476 63340 48478 63340 48477 63341 48478 63341 48646 63341 48646 63342 48478 63342 48479 63342 48646 63343 48479 63343 48480 63343 48481 63344 48482 63344 48659 63344 48483 63345 48458 63345 48675 63345 48675 63346 48458 63346 48484 63346 48675 63347 48484 63347 48673 63347 48673 63348 48484 63348 48459 63348 48673 63349 48459 63349 48485 63349 48485 63350 48459 63350 48486 63350 48485 63351 48486 63351 48327 63351 48487 63352 48488 63352 48524 63352 48686 63353 48489 63353 48491 63353 48491 63354 48489 63354 48490 63354 48491 63355 48490 63355 48493 63355 48493 63356 48490 63356 48492 63356 48493 63357 48492 63357 48494 63357 48494 63358 48492 63358 48495 63358 48494 63359 48495 63359 48689 63359 48568 63360 48461 63360 48496 63360 48496 63361 48461 63361 48497 63361 48496 63362 48497 63362 48500 63362 48498 63363 48356 63363 48499 63363 48499 63364 48356 63364 48500 63364 48499 63365 48500 63365 48571 63365 48571 63366 48500 63366 48497 63366 48571 63367 48497 63367 48501 63367 48501 63368 48497 63368 48462 63368 48501 63369 48462 63369 48567 63369 48502 63370 48503 63370 48504 63370 48504 63371 48503 63371 48507 63371 48504 63372 48507 63372 48506 63372 48366 63373 48588 63373 48505 63374 48505 63375 48588 63375 48506 63375 48505 63376 48506 63376 48592 63376 48592 63377 48506 63377 48507 63377 48592 63378 48507 63378 48508 63378 48508 63379 48507 63379 48585 63379 48508 63380 48585 63380 48584 63380 48613 63381 48606 63381 48610 63381 48610 63382 48606 63382 48470 63382 48610 63383 48470 63383 48510 63383 48615 63384 48509 63384 48616 63384 48616 63385 48509 63385 48510 63385 48616 63386 48510 63386 48618 63386 48618 63387 48510 63387 48470 63387 48618 63388 48470 63388 48511 63388 48511 63389 48470 63389 48604 63389 48511 63390 48604 63390 48619 63390 48640 63391 48512 63391 48514 63391 48514 63392 48512 63392 48513 63392 48514 63393 48513 63393 48638 63393 48643 63394 48515 63394 48644 63394 48644 63395 48515 63395 48638 63395 48644 63396 48638 63396 48645 63396 48645 63397 48638 63397 48513 63397 48645 63398 48513 63398 48516 63398 48516 63399 48513 63399 48517 63399 48516 63400 48517 63400 48632 63400 48660 63401 48482 63401 48662 63401 48662 63402 48482 63402 48481 63402 48662 63403 48481 63403 48661 63403 48518 63404 48391 63405 48666 63406 48666 63407 48391 63407 48661 63407 48666 63408 48661 63408 48667 63408 48667 63409 48661 63409 48481 63409 48667 63410 48481 63410 48668 63410 48668 63411 48481 63411 48659 63411 48668 63412 48659 63412 48657 63412 48519 63413 48488 63413 48520 63413 48520 63414 48488 63414 48487 63414 48520 63415 48487 63415 48522 63415 48404 63416 48402 63416 48687 63416 48687 63417 48402 63417 48522 63417 48687 63418 48522 63418 48521 63418 48521 63419 48522 63419 48487 63419 48521 63420 48487 63420 48523 63420 48523 63421 48487 63421 48524 63421 48523 63422 48524 63422 48680 63422 48426 63423 48525 63423 48526 63423 48526 63424 48525 63424 48527 63424 48526 63425 48527 63425 48528 63425 48528 63426 48527 63426 48529 63426 48528 63427 48529 63427 48713 63427 48713 63428 48529 63428 48530 63428 48713 63429 48530 63429 48531 63429 48531 63430 48530 63430 48532 63430 48531 63431 48532 63431 48416 63431 48533 63432 48539 63432 48525 63432 48525 63433 48539 63433 48534 63433 48525 63434 48534 63434 48527 63434 48527 63435 48534 63435 48535 63435 48527 63436 48535 63436 48529 63436 48529 63437 48535 63437 48536 63437 48529 63438 48536 63438 48530 63438 48530 63439 48536 63439 48540 63439 48530 63440 48540 63440 48537 63440 48545 63441 48546 63441 48538 63441 48437 63442 48541 63442 48539 63442 48539 63443 48541 63443 48542 63443 48539 63444 48542 63444 48534 63444 48534 63445 48542 63445 48544 63445 48534 63446 48544 63446 48535 63446 48535 63447 48544 63447 48545 63447 48535 63448 48545 63448 48536 63448 48536 63449 48545 63449 48538 63449 48536 63450 48538 63450 48540 63450 48436 63451 48549 63451 48541 63451 48541 63452 48549 63452 48543 63452 48541 63453 48543 63453 48542 63453 48542 63454 48543 63454 48551 63454 48542 63455 48551 63455 48544 63455 48544 63456 48551 63456 48419 63456 48544 63457 48419 63457 48545 63457 48545 63458 48419 63458 48418 63458 48545 63459 48418 63459 48546 63459 48547 63460 48548 63460 48549 63460 48549 63461 48548 63461 48550 63461 48549 63462 48550 63462 48543 63462 48543 63463 48550 63463 48552 63463 48543 63464 48552 63464 48551 63464 48551 63465 48552 63465 48553 63465 48551 63466 48553 63466 48419 63466 48419 63467 48553 63467 48554 63467 48419 63468 48554 63468 48344 63468 48565 63469 48555 63469 48556 63469 48434 63470 48557 63470 48548 63470 48548 63471 48557 63471 48558 63471 48548 63472 48558 63472 48550 63472 48550 63473 48558 63473 48559 63473 48550 63474 48559 63474 48552 63474 48552 63475 48559 63475 48565 63475 48552 63476 48565 63476 48553 63476 48553 63477 48565 63477 48556 63477 48553 63478 48556 63478 48554 63478 48560 63479 48561 63479 48348 63479 48435 63480 48562 63480 48557 63480 48557 63481 48562 63481 48563 63481 48557 63482 48563 63482 48558 63482 48558 63483 48563 63483 48564 63483 48558 63484 48564 63484 48559 63484 48559 63485 48564 63485 48560 63485 48559 63486 48560 63486 48565 63486 48565 63487 48560 63487 48348 63487 48565 63488 48348 63488 48555 63488 48566 63489 48567 63489 48562 63489 48562 63490 48567 63490 48462 63490 48562 63491 48462 63491 48563 63491 48563 63492 48462 63492 48461 63492 48563 63493 48461 63493 48564 63493 48564 63494 48461 63494 48568 63494 48564 63495 48568 63495 48560 63495 48560 63496 48568 63496 48350 63496 48560 63497 48350 63498 48561 63499 48356 63500 48354 63500 48500 63500 48500 63501 48354 63501 48351 63501 48500 63502 48351 63503 48496 63502 48496 63504 48351 63504 48352 63504 48496 63505 48352 63506 48568 63507 48568 63508 48352 63508 48569 63508 48568 63509 48569 63509 48350 63509 48360 63510 48498 63510 48570 63510 48570 63511 48498 63511 48499 63511 48570 63512 48499 63512 48463 63512 48463 63513 48499 63513 48571 63513 48463 63514 48571 63514 48449 63514 48449 63515 48571 63515 48501 63515 48449 63516 48501 63516 48572 63516 48572 63517 48501 63517 48567 63517 48572 63518 48567 63518 48573 63518 48573 63519 48567 63519 48566 63519 48582 63520 48583 63521 48358 63522 48433 63523 48574 63523 48464 63523 48464 63524 48574 63524 48575 63524 48464 63525 48575 63525 48576 63525 48576 63526 48575 63526 48578 63526 48576 63527 48578 63527 48577 63527 48577 63528 48578 63528 48582 63528 48577 63529 48582 63529 48570 63529 48570 63530 48582 63531 48358 63532 48570 63533 48358 63533 48360 63533 48587 63534 48361 63535 48579 63536 48330 63537 48586 63537 48574 63537 48574 63538 48586 63538 48580 63538 48574 63539 48580 63539 48575 63539 48575 63540 48580 63540 48581 63540 48575 63541 48581 63541 48578 63541 48578 63542 48581 63542 48587 63542 48578 63543 48587 63543 48582 63543 48582 63544 48587 63544 48579 63544 48582 63545 48579 63545 48583 63545 48594 63546 48584 63546 48586 63546 48586 63547 48584 63547 48585 63547 48586 63548 48585 63548 48580 63548 48580 63549 48585 63549 48503 63549 48580 63550 48503 63550 48581 63550 48581 63551 48503 63551 48502 63551 48581 63552 48502 63552 48587 63552 48587 63553 48502 63553 48591 63553 48587 63554 48591 63554 48361 63554 48588 63555 48589 63555 48506 63555 48506 63556 48589 63556 48590 63556 48506 63557 48590 63557 48504 63557 48504 63558 48590 63558 48363 63558 48504 63559 48363 63560 48502 63561 48502 63562 48363 63562 48365 63562 48502 63563 48365 63563 48591 63563 48601 63564 48366 63565 48599 63566 48599 63567 48366 63568 48505 63569 48599 63570 48505 63570 48451 63570 48451 63571 48505 63571 48592 63571 48451 63572 48592 63572 48453 63572 48453 63573 48592 63573 48508 63573 48453 63574 48508 63574 48424 63574 48424 63575 48508 63575 48584 63575 48424 63576 48584 63576 48593 63576 48593 63577 48584 63577 48594 63577 48598 63578 48595 63578 48600 63578 48338 63579 48432 63579 48469 63579 48469 63580 48432 63580 48596 63580 48469 63581 48596 63581 48468 63581 48468 63582 48596 63582 48597 63582 48468 63583 48597 63583 48466 63583 48466 63584 48597 63584 48598 63584 48466 63585 48598 63585 48599 63585 48599 63586 48598 63587 48600 63588 48599 63589 48600 63589 48601 63589 48602 63590 48371 63591 48369 63591 48431 63592 48603 63592 48432 63592 48432 63593 48603 63593 48605 63593 48432 63594 48605 63594 48596 63594 48596 63595 48605 63595 48607 63595 48596 63596 48607 63596 48597 63596 48597 63597 48607 63597 48602 63597 48597 63598 48602 63598 48598 63598 48598 63599 48602 63599 48369 63599 48598 63600 48369 63600 48595 63600 48621 63601 48619 63601 48603 63601 48603 63602 48619 63602 48604 63602 48603 63603 48604 63603 48605 63603 48605 63604 48604 63604 48606 63604 48605 63605 48606 63605 48607 63605 48607 63606 48606 63606 48613 63606 48607 63607 48613 63607 48602 63607 48602 63608 48613 63608 48608 63608 48602 63609 48608 63609 48371 63609 48509 63610 48373 63611 48510 63612 48510 63613 48373 63613 48609 63613 48510 63614 48609 63614 48610 63614 48610 63615 48609 63615 48611 63615 48610 63616 48611 63616 48613 63616 48613 63617 48611 63618 48612 63619 48613 63620 48612 63620 48608 63620 48614 63621 48615 63621 48624 63621 48624 63622 48615 63622 48616 63622 48624 63623 48616 63623 48617 63623 48617 63624 48616 63624 48618 63624 48617 63625 48618 63625 48423 63625 48423 63626 48618 63626 48511 63626 48423 63627 48511 63627 48442 63627 48442 63628 48511 63628 48619 63628 48442 63629 48619 63629 48620 63629 48620 63630 48619 63630 48621 63630 48629 63631 48630 63631 48622 63631 48474 63632 48430 63632 48473 63632 48473 63633 48430 63633 48623 63633 48473 63634 48623 63634 48472 63634 48472 63635 48623 63635 48628 63635 48472 63636 48628 63636 48471 63636 48471 63637 48628 63637 48629 63637 48471 63638 48629 63638 48624 63638 48624 63639 48629 63639 48622 63639 48624 63640 48622 63640 48614 63640 48634 63641 48635 63641 48378 63641 48429 63642 48625 63642 48430 63642 48430 63643 48625 63643 48626 63643 48430 63644 48626 63644 48623 63644 48623 63645 48626 63645 48627 63645 48623 63646 48627 63646 48628 63646 48628 63647 48627 63647 48634 63647 48628 63648 48634 63648 48629 63648 48629 63649 48634 63649 48378 63649 48629 63650 48378 63650 48630 63650 48631 63651 48632 63651 48625 63651 48625 63652 48632 63652 48517 63652 48625 63653 48517 63653 48626 63653 48626 63654 48517 63654 48512 63654 48626 63655 48512 63655 48627 63655 48627 63656 48512 63656 48640 63656 48627 63657 48640 63657 48634 63657 48634 63658 48640 63658 48633 63658 48634 63659 48633 63659 48635 63659 48515 63660 48636 63660 48638 63660 48638 63661 48636 63661 48637 63661 48638 63662 48637 63662 48514 63662 48514 63663 48637 63663 48639 63663 48514 63664 48639 63664 48640 63664 48640 63665 48639 63665 48641 63665 48640 63666 48641 63666 48633 63666 48642 63667 48643 63667 48417 63667 48417 63668 48643 63668 48644 63668 48417 63669 48644 63669 48475 63669 48475 63670 48644 63670 48645 63670 48475 63671 48645 63671 48421 63671 48421 63672 48645 63672 48516 63672 48421 63673 48516 63673 48420 63673 48420 63674 48516 63674 48632 63674 48420 63675 48632 63675 48336 63675 48336 63676 48632 63676 48631 63676 48480 63677 48651 63677 48646 63677 48646 63678 48651 63678 48647 63678 48646 63679 48647 63679 48477 63679 48477 63680 48647 63680 48653 63680 48477 63681 48653 63681 48648 63681 48648 63682 48653 63682 48655 63682 48648 63683 48655 63683 48417 63683 48417 63684 48655 63684 48649 63684 48417 63685 48649 63685 48382 63685 48656 63686 48650 63686 48384 63686 48320 63687 48658 63687 48651 63687 48651 63688 48658 63688 48652 63688 48651 63689 48652 63689 48647 63689 48647 63690 48652 63690 48654 63690 48647 63691 48654 63691 48653 63691 48653 63692 48654 63692 48656 63692 48653 63693 48656 63693 48655 63693 48655 63694 48656 63694 48384 63694 48655 63695 48384 63695 48649 63695 48319 63696 48657 63696 48658 63696 48658 63697 48657 63697 48659 63697 48658 63698 48659 63698 48652 63698 48652 63699 48659 63699 48482 63699 48652 63700 48482 63700 48654 63700 48654 63701 48482 63701 48660 63701 48654 63702 48660 63702 48656 63702 48656 63703 48660 63703 48389 63703 48656 63704 48389 63704 48650 63704 48391 63705 48390 63705 48661 63705 48661 63706 48390 63706 48663 63706 48661 63707 48663 63707 48662 63707 48662 63708 48663 63708 48664 63708 48662 63709 48664 63709 48660 63709 48660 63710 48664 63710 48388 63710 48660 63711 48388 63711 48389 63711 48665 63712 48518 63713 48483 63714 48483 63715 48518 63715 48666 63715 48483 63716 48666 63716 48458 63716 48458 63717 48666 63717 48667 63717 48458 63718 48667 63718 48669 63718 48669 63719 48667 63719 48668 63719 48669 63720 48668 63720 48446 63720 48446 63721 48668 63721 48657 63721 48446 63722 48657 63722 48670 63722 48670 63723 48657 63723 48319 63723 48327 63724 48671 63724 48485 63724 48485 63725 48671 63725 48672 63725 48485 63726 48672 63726 48673 63726 48673 63727 48672 63727 48674 63727 48673 63728 48674 63728 48675 63728 48675 63729 48674 63730 48676 63731 48675 63732 48676 63732 48483 63732 48483 63733 48676 63733 48394 63733 48483 63734 48394 63734 48395 63734 48682 63735 48683 63736 48678 63737 48326 63738 48679 63738 48671 63738 48671 63739 48679 63739 48681 63739 48671 63740 48681 63740 48672 63740 48672 63741 48681 63741 48677 63741 48672 63742 48677 63742 48674 63742 48674 63743 48677 63743 48682 63743 48674 63744 48682 63745 48676 63746 48676 63747 48682 63747 48678 63747 48676 63748 48678 63748 48394 63748 48428 63749 48680 63749 48679 63749 48679 63750 48680 63750 48524 63750 48679 63751 48524 63751 48681 63751 48681 63752 48524 63752 48488 63752 48681 63753 48488 63753 48677 63753 48677 63754 48488 63754 48519 63754 48677 63755 48519 63756 48682 63757 48682 63758 48519 63758 48397 63758 48682 63759 48397 63759 48683 63759 48402 63760 48684 63760 48522 63760 48522 63761 48684 63761 48685 63761 48522 63762 48685 63762 48520 63762 48520 63763 48685 63764 48399 63765 48520 63766 48399 63766 48519 63766 48519 63767 48399 63768 48400 63769 48519 63770 48400 63771 48397 63772 48408 63773 48404 63773 48686 63773 48686 63774 48404 63774 48687 63774 48686 63775 48687 63775 48489 63775 48489 63776 48687 63776 48521 63776 48489 63777 48521 63777 48688 63777 48688 63778 48521 63778 48523 63778 48688 63779 48523 63779 48447 63779 48447 63780 48523 63780 48680 63780 48447 63781 48680 63781 48333 63781 48333 63782 48680 63782 48428 63782 48689 63783 48693 63783 48494 63783 48494 63784 48693 63784 48695 63784 48494 63785 48695 63785 48493 63785 48493 63786 48695 63786 48690 63786 48493 63787 48690 63788 48491 63789 48491 63790 48690 63790 48696 63790 48491 63791 48696 63791 48686 63791 48686 63792 48696 63792 48691 63792 48686 63793 48691 63794 48407 63795 48700 63796 48692 63796 48406 63796 48427 63797 48698 63797 48693 63797 48693 63798 48698 63798 48699 63798 48693 63799 48699 63799 48695 63799 48695 63800 48699 63800 48694 63800 48695 63801 48694 63801 48690 63801 48690 63802 48694 63802 48700 63802 48690 63803 48700 63803 48696 63803 48696 63804 48700 63804 48406 63804 48696 63805 48406 63805 48691 63805 48323 63806 48697 63806 48698 63806 48698 63807 48697 63807 48702 63807 48698 63808 48702 63808 48699 63808 48699 63809 48702 63809 48703 63809 48699 63810 48703 63810 48694 63810 48694 63811 48703 63811 48705 63811 48694 63812 48705 63812 48700 63812 48700 63813 48705 63813 48410 63813 48700 63814 48410 63814 48692 63814 48322 63815 48706 63815 48697 63815 48697 63816 48706 63816 48701 63816 48697 63817 48701 63817 48702 63817 48702 63818 48701 63818 48708 63818 48702 63819 48708 63819 48703 63819 48703 63820 48708 63820 48704 63820 48703 63821 48704 63821 48705 63821 48705 63822 48704 63822 48710 63822 48705 63823 48710 63823 48412 63823 48714 63824 48415 63824 48709 63824 48321 63825 48711 63825 48706 63825 48706 63826 48711 63826 48712 63826 48706 63827 48712 63827 48701 63827 48701 63828 48712 63828 48707 63828 48701 63829 48707 63829 48708 63829 48708 63830 48707 63830 48714 63830 48708 63831 48714 63831 48704 63831 48704 63832 48714 63832 48709 63832 48704 63833 48709 63833 48710 63833 48329 63834 48526 63834 48711 63834 48711 63835 48526 63835 48528 63835 48711 63836 48528 63836 48712 63836 48712 63837 48528 63837 48713 63837 48712 63838 48713 63838 48707 63838 48707 63839 48713 63839 48531 63839 48707 63840 48531 63840 48714 63840 48714 63841 48531 63841 48416 63841 48714 63842 48416 63842 48415 63842 48756 63843 48716 63843 48715 63843 48715 63844 48716 63844 48717 63844 48715 63845 48717 63845 48718 63845 48718 63846 48717 63846 48720 63846 48718 63847 48720 63847 48719 63847 48719 63848 48720 63848 48721 63848 48719 63849 48721 63849 48722 63849 48722 63850 48721 63850 48723 63850 48722 63851 48723 63851 48724 63851 48724 63852 48723 63852 48725 63852 48724 63852 48725 63852 48726 63852 48726 63853 48725 63853 48727 63853 48726 63854 48727 63854 48729 63854 48729 63855 48727 63855 48728 63855 48729 63856 48728 63856 48730 63856 48730 63857 48728 63857 48732 63857 48730 63858 48732 63858 48731 63858 48731 63859 48732 63859 48733 63859 48731 63860 48733 63860 48734 63860 48734 63861 48733 63861 48735 63861 48734 63862 48735 63862 48736 63862 48736 63863 48735 63863 48737 63863 48736 63864 48737 63864 48739 63864 48739 63865 48737 63865 48738 63865 48739 63866 48738 63866 48740 63866 48740 63867 48738 63867 48741 63867 48740 63868 48741 63868 48743 63868 48743 63869 48741 63869 48742 63869 48743 63870 48742 63870 48744 63870 48744 63871 48742 63871 48746 63871 48744 63872 48746 63872 48745 63872 48745 63873 48746 63873 48748 63873 48745 63874 48748 63874 48747 63874 48747 63875 48748 63875 48749 63875 48747 63876 48749 63876 48750 63876 48750 63877 48749 63877 48752 63877 48750 63877 48752 63877 48751 63877 48751 63878 48752 63878 48753 63878 48751 63878 48753 63878 48754 63878 48754 63879 48753 63879 48755 63879 48754 63880 48755 63880 48757 63880 48757 63881 48755 63881 48756 63881 48757 63882 48756 63882 48715 63882 48921 590 48894 590 48767 590 48921 590 48767 590 48758 590 48768 63883 48890 63883 48988 63883 48759 590 48760 590 48775 590 48775 63884 48760 63884 48888 63884 48896 63885 48761 63885 48767 63885 48783 63886 48762 63886 48785 63886 48785 63887 48762 63887 48763 63887 48988 63888 48764 63888 48768 63888 48768 63889 48764 63889 48980 63889 48768 590 48980 590 48765 590 48779 63890 48773 63890 49142 63890 48894 63891 48766 63891 48767 63891 48767 63892 48766 63892 49011 63892 48767 590 49011 590 48768 590 48768 590 49011 590 49012 590 48768 63893 49012 63893 48890 63893 48761 590 48889 590 48767 590 48767 63894 48889 63894 48769 63894 48767 63895 48769 63895 48758 63895 48898 63896 48770 63896 48788 63896 48788 590 48770 590 48899 590 48771 590 48908 590 48775 590 48775 63897 48908 63897 48897 63897 48775 63898 48897 63898 48759 63898 48765 590 48892 590 48768 590 48768 63899 48892 63899 48772 63899 48768 63900 48772 63900 48779 63900 48779 63901 48772 63901 48881 63901 48779 63902 48881 63902 48773 63902 48899 590 48774 590 48788 590 48788 590 48774 590 48887 590 48788 63903 48887 63903 48775 63903 48775 590 48887 590 48886 590 48775 590 48886 590 48771 590 48763 63904 49105 63904 48785 63904 48785 63905 49105 63905 48776 63905 48785 63906 48776 63906 48913 63906 48777 590 48885 590 48788 590 48788 63907 48885 63907 48930 63907 48788 63908 48930 63908 48898 63908 48888 590 48924 590 48775 590 48775 63909 48924 63909 48778 63909 48775 590 48778 590 48767 590 48767 63910 48778 63910 48895 63910 48767 63911 48895 63911 48896 63911 49142 590 48883 590 48779 590 48779 63912 48883 63912 48884 63912 48779 63913 48884 63913 48780 63913 48780 63914 48781 63914 48779 63914 48779 63915 48781 63915 48918 63915 48779 590 48918 590 48785 590 48785 63916 48918 63916 48782 63916 48785 63917 48782 63917 48783 63917 48913 63918 48784 63918 48785 63918 48785 63919 48784 63919 48786 63919 48785 63920 48786 63920 48788 63920 48788 63921 48786 63921 48787 63921 48788 63922 48787 63922 48777 63922 48971 63923 48793 63923 48789 63923 48790 63924 48791 63924 48977 63924 48977 63925 48791 63925 48793 63925 48977 63926 48793 63926 48792 63926 48792 63927 48793 63927 48971 63927 48790 63928 48985 63928 48791 63928 48791 63929 48985 63929 48872 63929 48791 63930 48872 63930 48794 63930 48872 63931 48795 63931 48794 63931 48794 63932 48795 63932 48987 63932 48794 63933 48987 63933 48796 63933 48987 63934 48994 63934 48796 63934 48796 63935 48994 63935 48798 63935 48796 63936 48798 63936 48797 63936 48797 63937 48798 63937 48995 63937 48797 63938 48995 63938 48799 63938 48799 63939 48995 63939 48800 63939 48799 63940 48800 63940 49005 63940 48804 63941 48801 63941 48802 63941 48802 63942 48801 63942 48799 63942 48802 63943 48799 63943 48803 63943 48803 63944 48799 63944 49005 63944 48804 63945 48805 63945 48801 63945 48801 63946 48805 63946 48806 63946 48801 63947 48806 63947 48807 63947 48806 63948 48940 63948 48807 63948 48807 63949 48940 63949 49006 63949 48807 63950 49006 63950 48808 63950 48809 63951 48811 63951 49024 63951 49024 63952 48811 63952 48808 63952 49024 63953 48808 63953 49019 63953 49019 63954 48808 63954 49006 63954 48809 63955 48810 63955 48811 63955 48811 63956 48810 63956 49028 63956 48811 63957 49028 63957 48814 63957 49029 63958 48812 63958 49031 63958 49031 63959 48812 63959 48814 63959 49031 63960 48814 63960 48813 63960 48813 63961 48814 63961 49028 63961 49029 63962 48815 63962 48812 63962 48812 63963 48815 63963 48946 63963 48812 63964 48946 63964 48816 63964 48946 63965 48817 63965 48816 63965 48816 63966 48817 63966 48818 63966 48816 63967 48818 63967 48820 63967 49046 63968 48821 63968 49038 63968 49038 63969 48821 63969 48820 63969 49038 63970 48820 63970 48819 63970 48819 63971 48820 63971 48818 63971 49046 63972 49051 63972 48821 63972 48821 63973 49051 63973 49057 63973 48821 63974 49057 63974 48822 63974 49052 63975 48824 63975 49055 63975 49055 63976 48824 63976 48822 63976 49055 63977 48822 63977 49056 63977 49056 63978 48822 63978 49057 63978 49052 63979 48823 63979 48824 63979 48824 63980 48823 63980 48825 63980 48824 63981 48825 63981 48827 63981 48825 63982 48826 63982 48827 63982 48827 63983 48826 63983 48871 63983 48827 63984 48871 63984 48829 63984 48831 63985 48828 63985 49068 63985 49068 63986 48828 63986 48829 63986 49068 63987 48829 63987 48830 63987 48830 63988 48829 63988 48871 63988 48831 63989 48832 63989 48828 63989 48828 63990 48832 63990 49080 63990 48828 63991 49080 63991 48833 63991 48834 63992 48836 63992 49078 63992 49078 63993 48836 63993 48833 63993 49078 63994 48833 63994 49079 63994 49079 63995 48833 63995 49080 63995 48834 63996 48835 63996 48836 63996 48836 63997 48835 63997 48838 63997 48836 63998 48838 63998 48837 63998 48838 63999 48953 63999 48837 63999 48837 64000 48953 64000 48870 64000 48837 64001 48870 64001 48841 64001 48839 64002 48844 64002 48840 64002 48840 64003 48844 64003 48841 64003 48840 64004 48841 64004 48842 64004 48842 64005 48841 64005 48870 64005 48839 64006 48843 64006 48844 64006 48844 64007 48843 64007 48848 64007 48844 64008 48848 64008 48847 64008 48845 64009 48849 64009 49102 64009 49102 64010 48849 64010 48847 64010 49102 64011 48847 64011 48846 64011 48846 64012 48847 64012 48848 64012 48845 64013 49100 64013 48849 64013 48849 64014 49100 64014 48959 64014 48849 64015 48959 64015 48850 64015 48959 64016 48958 64016 48850 64016 48850 64017 48958 64017 49103 64017 48850 64018 49103 64018 48852 64018 48851 64019 48853 64019 49111 64019 49111 64020 48853 64020 48852 64020 49111 64021 48852 64021 49112 64021 49112 64022 48852 64022 49103 64022 48851 64023 49113 64024 48853 64025 48853 64026 49113 64026 48854 64026 48853 64027 48854 64027 48856 64027 48855 64028 48857 64028 49124 64028 49124 64029 48857 64029 48856 64029 49124 64030 48856 64030 49125 64030 49125 64031 48856 64031 48854 64031 48855 64032 49122 64032 48857 64032 48857 64033 49122 64033 48858 64033 48857 64034 48858 64034 48859 64034 48858 64035 49128 64036 48859 64037 48859 64038 49128 64038 49127 64038 48859 64039 49127 64039 48861 64039 48862 64040 48863 64040 48860 64040 48860 64041 48863 64041 48861 64041 48860 64042 48861 64042 49133 64042 49133 64043 48861 64043 49127 64043 48862 64044 49141 64044 48863 64044 48863 64045 49141 64045 49139 64045 48863 64046 49139 64046 48866 64046 49139 64047 48864 64047 48866 64047 48866 64048 48864 64048 48865 64048 48866 64049 48865 64049 48867 64049 48865 64050 49148 64050 48867 64050 48867 64051 49148 64051 48868 64051 48867 64052 48868 64052 48789 64052 48789 64053 48868 64053 48869 64053 48789 64054 48869 64054 48971 64054 48864 64055 49139 64055 49146 64055 49133 64056 49127 64056 49132 64056 49112 64057 49103 64057 49110 64057 48842 64058 48870 64058 49081 64058 48830 64059 48871 64059 49058 64059 48795 64060 48872 64060 48983 64060 48792 64061 48971 64061 48976 64061 48873 64062 48874 64062 48875 64062 48876 64063 48900 64063 48911 64063 49086 64064 48877 64064 49084 64064 49062 64065 48878 64065 49060 64065 49036 64066 48906 64066 48879 64066 49010 64067 48902 64067 48880 64067 48881 64068 48772 64068 49151 64068 48773 64069 48881 64069 49152 64069 49142 64070 48773 64070 48882 64070 48883 64071 49142 64071 49143 64071 48884 64072 48883 64072 49135 64072 48780 64073 48884 64073 49134 64073 48763 64074 48762 64074 49114 64074 49105 64075 48763 64075 49106 64075 48777 64076 48787 64076 49096 64076 48885 64077 48777 64077 49088 64077 48887 64078 48774 64078 49069 64078 48886 64079 48887 64079 49064 64079 48888 64080 48760 64080 49047 64080 48924 64081 48888 64081 49039 64081 48769 64082 48889 64082 49025 64082 48758 64083 48769 64083 49013 64083 48890 64084 49012 64084 48999 64084 48988 64085 48890 64085 48996 64085 48764 64086 48988 64086 48989 64086 48980 64087 48764 64087 48891 64087 48765 64088 48980 64088 48978 64088 48892 64089 48765 64089 48893 64089 48772 64090 48892 64090 48968 64090 48894 64091 48902 64091 48766 64091 48766 64092 48902 64092 49010 64092 48766 64093 49010 64093 49011 64093 48895 64094 48906 64094 48896 64094 48896 64095 48906 64095 49036 64095 48896 64096 49036 64096 48761 64096 48908 64097 48878 64097 48897 64097 48897 64098 48878 64098 49062 64098 48897 64099 49062 64099 48759 64099 48898 64100 48877 64100 48770 64100 48770 64101 48877 64101 49086 64101 48770 64102 49086 64102 48899 64102 48913 64103 48900 64103 48784 64103 48784 64104 48900 64104 48876 64104 48784 64105 48876 64105 48786 64105 48918 64106 48874 64106 48782 64106 48782 64107 48874 64107 48873 64107 48782 64108 48873 64108 48783 64108 48901 64109 48880 64109 48903 64109 48903 64110 48880 64110 48902 64110 48903 64111 48902 64111 48920 64111 48920 64112 48902 64112 48894 64112 48920 64113 48894 64113 48921 64113 48904 64114 48879 64114 48905 64114 48905 64115 48879 64115 48906 64115 48905 64116 48906 64116 48907 64116 48907 64117 48906 64117 48895 64117 48907 64118 48895 64118 48778 64118 49059 64119 49060 64119 48926 64119 48926 64120 49060 64120 48878 64120 48926 64121 48878 64121 48929 64121 48929 64122 48878 64122 48908 64122 48929 64123 48908 64123 48771 64123 49083 64124 49084 64124 48909 64124 48909 64125 49084 64125 48877 64125 48909 64126 48877 64126 48910 64126 48910 64127 48877 64127 48898 64127 48910 64128 48898 64128 48930 64128 48933 64129 48911 64129 48912 64129 48912 64130 48911 64130 48900 64130 48912 64131 48900 64131 48914 64131 48914 64132 48900 64132 48913 64132 48914 64133 48913 64133 48776 64133 48915 64134 48875 64134 48916 64134 48916 64135 48875 64135 48874 64135 48916 64136 48874 64136 48917 64136 48917 64137 48874 64137 48918 64137 48917 64138 48918 64138 48781 64138 48942 64139 49001 64139 48919 64139 49018 64140 48901 64140 49017 64140 49017 64141 48901 64141 48903 64141 49017 64142 48903 64142 49015 64142 49015 64143 48903 64143 48920 64143 49015 64144 48920 64144 49014 64144 49014 64145 48920 64145 48921 64145 49014 64146 48921 64146 48758 64146 48948 64147 48945 64147 49027 64147 49032 64148 48904 64148 49041 64148 49041 64149 48904 64149 48905 64149 49041 64150 48905 64150 48922 64150 48922 64151 48905 64151 48907 64151 48922 64152 48907 64152 48923 64152 48923 64153 48907 64153 48778 64153 48923 64154 48778 64154 48924 64154 48949 64155 49048 64155 48925 64155 49058 64156 49059 64156 48927 64156 48927 64157 49059 64157 48926 64157 48927 64158 48926 64158 48928 64158 48928 64159 48926 64160 48929 64161 48928 64162 48929 64162 49065 64162 49065 64163 48929 64163 48771 64163 49065 64164 48771 64164 48886 64164 48952 64165 49074 64165 49072 64165 49081 64166 49083 64166 49090 64166 49090 64167 49083 64167 48909 64167 49090 64168 48909 64168 49089 64168 49089 64169 48909 64169 48910 64169 49089 64170 48910 64170 48931 64170 48931 64171 48910 64171 48930 64171 48931 64172 48930 64172 48885 64172 48957 64173 48932 64173 48962 64173 49110 64174 48933 64174 49109 64174 49109 64175 48933 64175 48912 64175 49109 64176 48912 64176 49108 64176 49108 64177 48912 64177 48914 64177 49108 64178 48914 64178 48934 64178 48934 64179 48914 64179 48776 64179 48934 64180 48776 64180 49105 64180 48965 64181 48935 64181 49118 64181 49132 64182 48915 64182 48936 64182 48936 64183 48915 64183 48916 64183 48936 64184 48916 64185 48937 64186 48937 64187 48916 64187 48917 64187 48937 64188 48917 64188 48938 64188 48938 64189 48917 64189 48781 64189 48938 64190 48781 64190 48780 64190 48939 64191 49001 64191 49004 64191 49004 64192 49001 64192 48942 64192 49004 64193 48942 64193 48941 64193 48940 64194 48806 64194 49007 64194 49007 64195 48806 64195 48941 64195 49007 64196 48941 64196 49008 64196 49008 64197 48941 64197 48942 64197 49008 64198 48942 64198 49009 64198 49009 64199 48942 64199 48919 64199 49009 64200 48919 64200 48943 64200 48944 64201 48945 64202 49030 64203 49030 64204 48945 64205 48948 64206 49030 64207 48948 64208 48947 64209 48817 64210 48946 64210 49033 64210 49033 64211 48946 64211 48947 64211 49033 64212 48947 64212 49034 64212 49034 64213 48947 64213 48948 64213 49034 64214 48948 64214 49035 64214 49035 64215 48948 64215 49027 64215 49035 64216 49027 64216 49037 64216 49050 64217 49048 64217 49054 64217 49054 64218 49048 64218 48949 64218 49054 64219 48949 64219 49053 64219 48826 64220 48825 64220 48950 64220 48950 64221 48825 64221 49053 64221 48950 64222 49053 64222 48951 64222 48951 64223 49053 64224 48949 64225 48951 64226 48949 64226 49061 64226 49061 64227 48949 64227 48925 64227 49061 64228 48925 64228 49063 64228 49075 64229 49074 64229 49077 64229 49077 64230 49074 64230 48952 64230 49077 64231 48952 64231 48954 64231 48953 64232 48838 64233 49082 64232 49082 64234 48838 64234 48954 64234 49082 64235 48954 64235 48955 64235 48955 64236 48954 64236 48952 64236 48955 64237 48952 64237 49085 64237 49085 64238 48952 64238 49072 64238 49085 64239 49072 64239 49087 64239 49098 64240 48932 64240 48956 64240 48956 64241 48932 64241 48957 64241 48956 64242 48957 64242 49101 64242 48958 64243 48959 64243 48960 64243 48960 64244 48959 64245 49101 64245 48960 64246 49101 64246 49104 64246 49104 64247 49101 64247 48957 64247 49104 64248 48957 64248 48961 64248 48961 64249 48957 64249 48962 64249 48961 64250 48962 64250 49095 64250 49126 64251 48935 64251 49123 64251 49123 64252 48935 64252 48965 64252 49123 64253 48965 64253 49121 64253 49128 64254 48858 64255 48963 64256 48963 64257 48858 64257 49121 64257 48963 64258 49121 64258 48964 64258 48964 64259 49121 64259 48965 64259 48964 64260 48965 64260 48966 64260 48966 64261 48965 64261 49118 64261 48966 64262 49118 64262 48967 64262 48772 64263 48968 64263 49151 64263 49151 64264 48968 64264 48973 64264 49151 64265 48973 64265 49153 64265 49153 64266 48973 64266 48969 64266 49153 64267 48969 64267 49155 64267 49155 64268 48969 64268 48976 64268 49155 64269 48976 64269 48970 64269 48970 64270 48976 64270 48971 64270 48970 64271 48971 64271 48869 64271 48892 64272 48893 64272 48968 64272 48968 64273 48893 64273 48972 64273 48968 64274 48972 64274 48973 64274 48973 64275 48972 64275 48974 64275 48973 64276 48974 64276 48969 64276 48969 64277 48974 64277 48975 64277 48969 64278 48975 64278 48976 64278 48976 64279 48975 64279 48977 64279 48976 64280 48977 64280 48792 64280 48984 64281 48985 64281 48790 64281 48765 64282 48978 64282 48893 64282 48893 64283 48978 64283 48982 64283 48893 64284 48982 64284 48972 64284 48972 64285 48982 64285 48979 64285 48972 64286 48979 64286 48974 64286 48974 64287 48979 64287 48984 64287 48974 64288 48984 64288 48975 64288 48975 64289 48984 64289 48790 64289 48975 64290 48790 64290 48977 64290 48980 64291 48891 64291 48978 64291 48978 64292 48891 64292 48981 64292 48978 64293 48981 64293 48982 64293 48982 64294 48981 64294 48986 64294 48982 64295 48986 64295 48979 64295 48979 64296 48986 64296 48983 64296 48979 64297 48983 64297 48984 64297 48984 64298 48983 64298 48872 64298 48984 64299 48872 64299 48985 64299 48764 64300 48989 64300 48891 64300 48891 64301 48989 64301 48990 64301 48891 64302 48990 64302 48981 64302 48981 64303 48990 64303 48992 64303 48981 64304 48992 64304 48986 64304 48986 64305 48992 64305 48993 64305 48986 64306 48993 64306 48983 64306 48983 64307 48993 64307 48987 64307 48983 64308 48987 64308 48795 64308 48991 64309 48798 64309 48994 64309 48988 64310 48996 64310 48989 64310 48989 64311 48996 64311 48997 64311 48989 64312 48997 64312 48990 64312 48990 64313 48997 64313 48998 64313 48990 64314 48998 64314 48992 64314 48992 64315 48998 64315 48991 64315 48992 64316 48991 64316 48993 64316 48993 64317 48991 64317 48994 64317 48993 64318 48994 64318 48987 64318 49003 64319 48800 64320 48995 64321 48890 64322 48999 64322 48996 64322 48996 64323 48999 64323 49000 64323 48996 64324 49000 64324 48997 64324 48997 64325 49000 64325 49002 64325 48997 64326 49002 64326 48998 64326 48998 64327 49002 64327 49003 64327 48998 64328 49003 64328 48991 64328 48991 64329 49003 64329 48995 64329 48991 64330 48995 64330 48798 64330 49012 64331 48943 64331 48999 64331 48999 64332 48943 64332 48919 64332 48999 64333 48919 64333 49000 64333 49000 64334 48919 64334 49001 64334 49000 64335 49001 64335 49002 64335 49002 64336 49001 64336 48939 64336 49002 64337 48939 64337 49003 64337 49003 64338 48939 64338 49005 64338 49003 64339 49005 64339 48800 64339 48806 64340 48805 64340 48941 64340 48941 64341 48805 64341 48804 64341 48941 64342 48804 64342 49004 64342 49004 64343 48804 64343 48802 64343 49004 64344 48802 64344 48939 64344 48939 64345 48802 64345 48803 64345 48939 64346 48803 64346 49005 64346 49006 64347 48940 64347 49018 64347 49018 64348 48940 64348 49007 64348 49018 64349 49007 64349 48901 64349 48901 64350 49007 64350 49008 64350 48901 64351 49008 64351 48880 64351 48880 64352 49008 64352 49009 64352 48880 64353 49009 64353 49010 64353 49010 64354 49009 64354 48943 64354 49010 64355 48943 64355 49011 64355 49011 64356 48943 64356 49012 64356 49016 64357 49024 64357 49019 64357 48758 64358 49013 64358 49014 64358 49014 64359 49013 64359 49020 64359 49014 64360 49020 64360 49015 64360 49015 64361 49020 64361 49022 64361 49015 64362 49022 64362 49017 64362 49017 64363 49022 64363 49016 64363 49017 64364 49016 64364 49018 64364 49018 64365 49016 64365 49019 64365 49018 64366 49019 64366 49006 64366 49023 64367 48810 64367 48809 64367 48769 64368 49025 64368 49013 64368 49013 64369 49025 64369 49026 64369 49013 64370 49026 64370 49020 64370 49020 64371 49026 64371 49021 64371 49020 64372 49021 64372 49022 64372 49022 64373 49021 64373 49023 64373 49022 64374 49023 64374 49016 64374 49016 64375 49023 64375 48809 64375 49016 64376 48809 64377 49024 64378 48889 64379 49037 64379 49025 64379 49025 64380 49037 64380 49027 64380 49025 64381 49027 64381 49026 64381 49026 64382 49027 64382 48945 64382 49026 64383 48945 64383 49021 64383 49021 64384 48945 64385 48944 64386 49021 64387 48944 64387 49023 64387 49023 64388 48944 64388 49028 64388 49023 64389 49028 64389 48810 64389 48946 64390 48815 64390 48947 64390 48947 64391 48815 64391 49029 64391 48947 64392 49029 64392 49030 64392 49030 64393 49029 64393 49031 64393 49030 64394 49031 64394 48944 64394 48944 64395 49031 64395 48813 64395 48944 64396 48813 64397 49028 64398 48818 64399 48817 64399 49032 64399 49032 64400 48817 64400 49033 64400 49032 64401 49033 64401 48904 64401 48904 64402 49033 64402 49034 64402 48904 64403 49034 64403 48879 64403 48879 64404 49034 64404 49035 64404 48879 64405 49035 64405 49036 64405 49036 64406 49035 64406 49037 64406 49036 64407 49037 64407 48761 64407 48761 64408 49037 64408 48889 64408 49044 64409 49038 64409 48819 64409 48924 64410 49039 64410 48923 64410 48923 64411 49039 64411 49040 64411 48923 64412 49040 64412 48922 64412 48922 64413 49040 64413 49043 64413 48922 64414 49043 64414 49041 64414 49041 64415 49043 64415 49044 64415 49041 64416 49044 64416 49032 64416 49032 64417 49044 64417 48819 64417 49032 64418 48819 64418 48818 64418 49045 64419 49051 64420 49046 64421 48888 64422 49047 64422 49039 64422 49039 64423 49047 64423 49042 64423 49039 64424 49042 64424 49040 64424 49040 64425 49042 64425 49049 64425 49040 64426 49049 64427 49043 64428 49043 64429 49049 64429 49045 64429 49043 64430 49045 64430 49044 64430 49044 64431 49045 64431 49046 64431 49044 64432 49046 64432 49038 64432 48760 64433 49063 64433 49047 64433 49047 64434 49063 64434 48925 64434 49047 64435 48925 64435 49042 64435 49042 64436 48925 64436 49048 64436 49042 64437 49048 64437 49049 64437 49049 64438 49048 64438 49050 64438 49049 64439 49050 64439 49045 64439 49045 64440 49050 64440 49057 64440 49045 64441 49057 64441 49051 64441 48825 64442 48823 64442 49053 64442 49053 64443 48823 64443 49052 64443 49053 64444 49052 64444 49054 64444 49054 64445 49052 64445 49055 64445 49054 64446 49055 64446 49050 64446 49050 64447 49055 64447 49056 64447 49050 64448 49056 64448 49057 64448 48871 64449 48826 64449 49058 64449 49058 64450 48826 64450 48950 64450 49058 64451 48950 64451 49059 64451 49059 64452 48950 64452 48951 64452 49059 64453 48951 64453 49060 64453 49060 64454 48951 64454 49061 64454 49060 64455 49061 64455 49062 64455 49062 64456 49061 64456 49063 64456 49062 64457 49063 64457 48759 64457 48759 64458 49063 64458 48760 64458 48886 64459 49064 64459 49065 64459 49065 64460 49064 64460 49066 64460 49065 64461 49066 64461 48928 64461 48928 64462 49066 64462 49071 64462 48928 64463 49071 64463 48927 64463 48927 64464 49071 64464 49067 64464 48927 64465 49067 64465 49058 64465 49058 64466 49067 64466 49068 64466 49058 64467 49068 64467 48830 64467 49076 64468 48832 64468 48831 64468 48887 64469 49069 64469 49064 64469 49064 64470 49069 64470 49073 64470 49064 64471 49073 64471 49066 64471 49066 64472 49073 64472 49070 64472 49066 64473 49070 64473 49071 64473 49071 64474 49070 64474 49076 64474 49071 64475 49076 64475 49067 64475 49067 64476 49076 64476 48831 64476 49067 64477 48831 64477 49068 64477 48774 64478 49087 64478 49069 64478 49069 64479 49087 64479 49072 64479 49069 64480 49072 64480 49073 64480 49073 64481 49072 64481 49074 64481 49073 64482 49074 64482 49070 64482 49070 64483 49074 64483 49075 64483 49070 64484 49075 64484 49076 64484 49076 64485 49075 64485 49080 64485 49076 64486 49080 64486 48832 64486 48838 64487 48835 64487 48954 64487 48954 64488 48835 64488 48834 64488 48954 64489 48834 64489 49077 64489 49077 64490 48834 64490 49078 64490 49077 64491 49078 64491 49075 64491 49075 64492 49078 64492 49079 64492 49075 64493 49079 64493 49080 64493 48870 64494 48953 64494 49081 64494 49081 64495 48953 64495 49082 64495 49081 64496 49082 64496 49083 64496 49083 64497 49082 64497 48955 64497 49083 64498 48955 64498 49084 64498 49084 64499 48955 64499 49085 64499 49084 64500 49085 64500 49086 64500 49086 64501 49085 64501 49087 64501 49086 64502 49087 64502 48899 64502 48899 64503 49087 64503 48774 64503 48885 64504 49088 64504 48931 64504 48931 64505 49088 64505 49093 64505 48931 64506 49093 64506 49089 64506 49089 64507 49093 64507 49094 64507 49089 64508 49094 64508 49090 64508 49090 64509 49094 64509 49091 64509 49090 64510 49091 64510 49081 64510 49081 64511 49091 64511 48840 64511 49081 64512 48840 64512 48842 64512 49099 64513 48843 64513 48839 64513 48777 64514 49096 64514 49088 64514 49088 64515 49096 64515 49097 64515 49088 64516 49097 64516 49093 64516 49093 64517 49097 64517 49092 64517 49093 64518 49092 64518 49094 64518 49094 64519 49092 64519 49099 64519 49094 64520 49099 64520 49091 64520 49091 64521 49099 64521 48839 64521 49091 64522 48839 64522 48840 64522 48787 64523 49095 64523 49096 64523 49096 64524 49095 64524 48962 64524 49096 64525 48962 64525 49097 64525 49097 64526 48962 64526 48932 64526 49097 64527 48932 64527 49092 64527 49092 64528 48932 64529 49098 64530 49092 64531 49098 64531 49099 64531 49099 64532 49098 64532 48848 64532 49099 64533 48848 64533 48843 64534 48959 64535 49100 64535 49101 64535 49101 64536 49100 64537 48845 64538 49101 64539 48845 64539 48956 64539 48956 64540 48845 64540 49102 64540 48956 64541 49102 64541 49098 64541 49098 64542 49102 64542 48846 64542 49098 64543 48846 64543 48848 64543 49103 64544 48958 64544 49110 64544 49110 64545 48958 64546 48960 64547 49110 64548 48960 64548 48933 64548 48933 64549 48960 64549 49104 64549 48933 64550 49104 64550 48911 64550 48911 64551 49104 64551 48961 64551 48911 64552 48961 64552 48876 64552 48876 64553 48961 64553 49095 64553 48876 64554 49095 64554 48786 64554 48786 64555 49095 64555 48787 64555 49105 64556 49106 64556 48934 64556 48934 64557 49106 64557 49107 64557 48934 64558 49107 64558 49108 64558 49108 64559 49107 64559 49116 64559 49108 64560 49116 64560 49109 64560 49109 64561 49116 64561 49117 64561 49109 64562 49117 64562 49110 64562 49110 64563 49117 64563 49111 64563 49110 64564 49111 64564 49112 64564 49120 64565 49113 64566 48851 64567 48763 64568 49114 64568 49106 64568 49106 64569 49114 64569 49115 64569 49106 64570 49115 64570 49107 64570 49107 64571 49115 64571 49119 64571 49107 64572 49119 64572 49116 64572 49116 64573 49119 64573 49120 64573 49116 64574 49120 64574 49117 64574 49117 64575 49120 64575 48851 64575 49117 64576 48851 64576 49111 64576 48762 64577 48967 64577 49114 64577 49114 64578 48967 64578 49118 64578 49114 64579 49118 64579 49115 64579 49115 64580 49118 64580 48935 64580 49115 64581 48935 64581 49119 64581 49119 64582 48935 64582 49126 64582 49119 64583 49126 64583 49120 64583 49120 64584 49126 64584 48854 64584 49120 64585 48854 64585 49113 64585 48858 64586 49122 64586 49121 64586 49121 64587 49122 64587 48855 64587 49121 64588 48855 64589 49123 64588 49123 64590 48855 64590 49124 64590 49123 64591 49124 64591 49126 64591 49126 64592 49124 64592 49125 64592 49126 64593 49125 64593 48854 64593 49127 64594 49128 64594 49132 64594 49132 64595 49128 64595 48963 64595 49132 64596 48963 64596 48915 64596 48915 64597 48963 64597 48964 64597 48915 64598 48964 64598 48875 64598 48875 64599 48964 64599 48966 64599 48875 64600 48966 64600 48873 64600 48873 64601 48966 64601 48967 64601 48873 64602 48967 64602 48783 64602 48783 64603 48967 64603 48762 64603 48780 64604 49134 64604 48938 64604 48938 64605 49134 64605 49129 64605 48938 64606 49129 64606 48937 64606 48937 64607 49129 64607 49130 64607 48937 64608 49130 64608 48936 64608 48936 64609 49130 64609 49131 64609 48936 64610 49131 64611 49132 64612 49132 64613 49131 64614 48860 64615 49132 64616 48860 64617 49133 64618 49140 64619 49141 64619 48862 64619 48884 64620 49135 64620 49134 64620 49134 64621 49135 64621 49137 64621 49134 64622 49137 64622 49129 64622 49129 64623 49137 64623 49138 64623 49129 64624 49138 64624 49130 64624 49130 64625 49138 64625 49140 64625 49130 64626 49140 64626 49131 64626 49131 64627 49140 64627 48862 64627 49131 64628 48862 64628 48860 64628 48883 64629 49143 64629 49135 64629 49135 64630 49143 64630 49136 64630 49135 64631 49136 64631 49137 64631 49137 64632 49136 64632 49145 64632 49137 64633 49145 64633 49138 64633 49138 64634 49145 64634 49146 64634 49138 64635 49146 64635 49140 64635 49140 64636 49146 64636 49139 64636 49140 64637 49139 64637 49141 64637 49142 64638 48882 64638 49143 64638 49143 64639 48882 64639 49149 64639 49143 64640 49149 64640 49136 64640 49136 64641 49149 64641 49144 64641 49136 64642 49144 64642 49145 64642 49145 64643 49144 64643 49147 64643 49145 64644 49147 64644 49146 64644 49146 64645 49147 64646 48865 64647 49146 64648 48865 64648 48864 64648 49156 64649 48868 64649 49148 64649 48773 64650 49152 64650 48882 64650 48882 64651 49152 64651 49154 64651 48882 64652 49154 64652 49149 64652 49149 64653 49154 64653 49150 64653 49149 64654 49150 64654 49144 64654 49144 64655 49150 64655 49156 64655 49144 64656 49156 64656 49147 64656 49147 64657 49156 64657 49148 64657 49147 64658 49148 64658 48865 64658 48881 64659 49151 64659 49152 64659 49152 64660 49151 64660 49153 64660 49152 64661 49153 64661 49154 64661 49154 64662 49153 64662 49155 64662 49154 64663 49155 64663 49150 64663 49150 64664 49155 64664 48970 64664 49150 64665 48970 64665 49156 64665 49156 64666 48970 64666 48869 64666 49156 64667 48869 64667 48868 64667 49199 64668 49157 64668 49158 64668 49158 64669 49157 64669 49159 64669 49158 64670 49159 64670 49160 64670 49160 64671 49159 64671 49161 64671 49160 64672 49161 64672 49162 64672 49162 64673 49161 64673 49163 64673 49162 64674 49163 64674 49164 64674 49164 64675 49163 64675 49165 64675 49164 64676 49165 64676 49166 64676 49166 64677 49165 64677 49167 64677 49166 64677 49167 64677 49168 64677 49168 64678 49167 64678 49169 64678 49168 64679 49169 64679 49170 64679 49170 64680 49169 64680 49171 64680 49170 64681 49171 64681 49173 64681 49173 64682 49171 64682 49172 64682 49173 64683 49172 64683 49174 64683 49174 64684 49172 64684 49175 64684 49174 64684 49175 64684 49176 64684 49176 64685 49175 64685 49178 64685 49176 64686 49178 64686 49177 64686 49177 64687 49178 64687 49179 64687 49177 64688 49179 64688 49181 64688 49181 64689 49179 64689 49180 64689 49181 64690 49180 64690 49182 64690 49182 64691 49180 64691 49183 64691 49182 64692 49183 64692 49184 64692 49184 64693 49183 64693 49185 64693 49184 64694 49185 64694 49186 64694 49186 64695 49185 64695 49187 64695 49186 64696 49187 64696 49188 64696 49188 64697 49187 64697 49189 64697 49188 64698 49189 64698 49190 64698 49190 64699 49189 64699 49191 64699 49190 64700 49191 64700 49192 64700 49192 64701 49191 64701 49193 64701 49192 64702 49193 64702 49194 64702 49194 64703 49193 64703 49196 64703 49194 64704 49196 64704 49195 64704 49195 64705 49196 64705 49197 64705 49195 64705 49197 64705 49198 64705 49198 64706 49197 64706 49199 64706 49198 64707 49199 64707 49158 64707 49278 64708 49201 64708 49276 64708 49200 64709 49203 64709 49398 64709 49398 64710 49203 64710 49201 64710 49398 64711 49201 64711 49399 64711 49399 64712 49201 64712 49278 64712 49200 64713 49202 64713 49203 64713 49203 64714 49202 64714 49409 64714 49203 64715 49409 64715 49204 64715 49409 64716 49205 64716 49204 64716 49204 64717 49205 64717 49418 64717 49204 64718 49418 64718 49207 64718 49418 64719 49206 64719 49207 64719 49207 64720 49206 64720 49208 64720 49207 64721 49208 64721 49209 64721 49209 64722 49208 64722 49210 64722 49209 64723 49210 64723 49214 64723 49214 64724 49210 64725 49211 64726 49214 64727 49211 64727 49212 64727 49429 64728 49213 64728 49215 64728 49215 64729 49213 64729 49214 64729 49215 64730 49214 64730 49216 64730 49216 64731 49214 64731 49212 64731 49429 64732 49217 64732 49213 64732 49213 64733 49217 64733 49366 64733 49213 64734 49366 64734 49218 64734 49366 64735 49430 64735 49218 64735 49218 64736 49430 64736 49219 64736 49218 64737 49219 64737 49221 64737 49443 64738 49223 64738 49220 64738 49220 64739 49223 64739 49221 64739 49220 64740 49221 64740 49441 64740 49441 64741 49221 64741 49219 64741 49443 64742 49442 64742 49223 64742 49223 64743 49442 64743 49222 64743 49223 64744 49222 64744 49224 64744 49456 64745 49226 64745 49457 64745 49457 64746 49226 64746 49224 64746 49457 64747 49224 64747 49458 64747 49458 64748 49224 64748 49222 64748 49456 64749 49225 64749 49226 64749 49226 64750 49225 64750 49227 64750 49226 64751 49227 64751 49228 64751 49227 64752 49459 64752 49228 64752 49228 64753 49459 64753 49234 64753 49228 64754 49234 64754 49233 64754 49229 64755 49230 64755 49231 64755 49231 64756 49230 64756 49233 64756 49231 64757 49233 64757 49232 64757 49232 64758 49233 64758 49234 64758 49229 64759 49235 64759 49230 64759 49230 64760 49235 64760 49236 64760 49230 64761 49236 64761 49238 64761 49479 64762 49237 64762 49480 64762 49480 64763 49237 64763 49238 64763 49480 64764 49238 64764 49481 64764 49481 64765 49238 64765 49236 64765 49479 64766 49478 64766 49237 64766 49237 64767 49478 64767 49239 64767 49237 64768 49239 64768 49240 64768 49239 64769 49483 64769 49240 64769 49240 64770 49483 64770 49241 64770 49240 64771 49241 64771 49244 64771 49495 64772 49242 64772 49243 64772 49243 64773 49242 64773 49244 64773 49243 64774 49244 64774 49491 64774 49491 64775 49244 64775 49241 64775 49495 64776 49245 64777 49242 64778 49242 64779 49245 64779 49504 64779 49242 64780 49504 64780 49246 64780 49507 64781 49247 64781 49509 64781 49509 64782 49247 64782 49246 64782 49509 64783 49246 64783 49510 64783 49510 64784 49246 64784 49504 64784 49507 64785 49505 64785 49247 64785 49247 64786 49505 64786 49248 64786 49247 64787 49248 64787 49249 64787 49248 64788 49511 64788 49249 64788 49249 64789 49511 64789 49253 64789 49249 64790 49253 64790 49250 64790 49519 64791 49254 64791 49251 64791 49251 64792 49254 64792 49250 64792 49251 64793 49250 64793 49252 64793 49252 64794 49250 64794 49253 64794 49519 64795 49518 64795 49254 64795 49254 64796 49518 64796 49255 64796 49254 64797 49255 64797 49256 64797 49257 64798 49258 64798 49534 64798 49534 64799 49258 64799 49256 64799 49534 64800 49256 64800 49535 64800 49535 64801 49256 64801 49255 64801 49257 64802 49259 64802 49258 64802 49258 64803 49259 64803 49531 64803 49258 64804 49531 64804 49260 64804 49531 64805 49537 64805 49260 64805 49260 64806 49537 64806 49263 64806 49260 64807 49263 64807 49261 64807 49551 64808 49262 64808 49543 64808 49543 64809 49262 64809 49261 64809 49543 64810 49261 64810 49281 64810 49281 64811 49261 64811 49263 64811 49551 64812 49264 64812 49262 64812 49262 64813 49264 64813 49553 64813 49262 64814 49553 64814 49265 64814 49556 64815 49267 64815 49557 64815 49557 64816 49267 64816 49265 64816 49557 64817 49265 64817 49266 64817 49266 64818 49265 64818 49553 64818 49556 64819 49554 64819 49267 64819 49267 64820 49554 64820 49387 64820 49267 64821 49387 64821 49268 64821 49387 64822 49385 64823 49268 64824 49268 64825 49385 64825 49269 64825 49268 64826 49269 64826 49270 64826 49567 64827 49271 64827 49272 64827 49272 64828 49271 64828 49270 64828 49272 64829 49270 64829 49280 64829 49280 64830 49270 64830 49269 64830 49567 64831 49576 64831 49271 64831 49271 64832 49576 64832 49273 64832 49271 64833 49273 64833 49274 64833 49273 64834 49279 64834 49274 64834 49274 64835 49279 64835 49582 64835 49274 64836 49582 64836 49275 64836 49582 64837 49588 64837 49275 64837 49275 64838 49588 64838 49584 64838 49275 64839 49584 64839 49276 64839 49276 64840 49584 64840 49277 64840 49276 64841 49277 64841 49278 64841 49279 64842 49273 64842 49581 64842 49280 64843 49269 64843 49566 64843 49281 64844 49263 64844 49536 64844 49252 64845 49253 64845 49517 64845 49491 64846 49241 64846 49490 64846 49205 64847 49409 64847 49408 64847 49399 64848 49278 64848 49395 64848 49321 64849 49319 64849 49282 64849 49283 64850 49284 64850 49538 64850 49316 64851 49314 64851 49332 64851 49486 64852 49311 64852 49285 64852 49465 64853 49308 64853 49463 64853 49307 64854 49305 64854 49323 64854 49286 64855 49303 64855 49391 64855 49288 64856 49286 64856 49589 64856 49287 64857 49288 64857 49585 64857 49289 64858 49287 64858 49574 64858 49568 64859 49289 64859 49573 64859 49290 64860 49568 64860 49569 64860 49291 64861 49561 64861 49544 64861 49358 64862 49291 64862 49546 64862 49520 64863 49292 64863 49526 64863 49293 64864 49520 64864 49521 64864 49294 64865 49496 64865 49498 64865 49487 64866 49294 64866 49492 64866 49470 64867 49295 64867 49296 64867 49467 64868 49470 64868 49297 64868 49298 64869 49447 64869 49449 64869 49340 64870 49298 64870 49437 64870 49299 64871 49435 64871 49424 64871 49300 64872 49299 64872 49414 64872 49301 64873 49300 64873 49413 64873 49302 64874 49301 64874 49410 64874 49400 64875 49302 64875 49406 64875 49396 64876 49400 64876 49401 64876 49303 64877 49396 64877 49390 64877 49304 64878 49305 64878 49306 64878 49306 64879 49305 64879 49307 64879 49306 64880 49307 64880 49434 64880 49328 64881 49308 64881 49309 64881 49309 64882 49308 64882 49465 64882 49309 64883 49465 64883 49466 64883 49330 64884 49311 64884 49310 64884 49310 64885 49311 64885 49486 64885 49310 64886 49486 64886 49312 64886 49313 64887 49314 64887 49315 64887 49315 64888 49314 64888 49316 64888 49315 64889 49316 64889 49514 64889 49336 64890 49284 64890 49317 64890 49317 64891 49284 64891 49283 64891 49317 64892 49283 64892 49318 64892 49337 64893 49319 64893 49320 64893 49320 64894 49319 64894 49321 64894 49320 64895 49321 64895 49560 64895 49322 64896 49323 64896 49324 64896 49324 64897 49323 64897 49305 64897 49324 64898 49305 64898 49325 64898 49325 64899 49305 64899 49304 64899 49325 64900 49304 64900 49326 64900 49341 64901 49463 64901 49343 64901 49343 64902 49463 64902 49308 64902 49343 64903 49308 64903 49327 64903 49327 64904 49308 64904 49328 64904 49327 64905 49328 64905 49329 64905 49346 64906 49285 64906 49348 64906 49348 64907 49285 64907 49311 64907 49348 64908 49311 64908 49349 64908 49349 64909 49311 64909 49330 64909 49349 64910 49330 64910 49331 64910 49513 64911 49332 64911 49333 64911 49333 64912 49332 64912 49314 64912 49333 64913 49314 64913 49334 64913 49334 64914 49314 64914 49313 64914 49334 64915 49313 64915 49335 64915 49353 64916 49538 64916 49354 64916 49354 64917 49538 64917 49284 64917 49354 64918 49284 64918 49356 64918 49356 64919 49284 64919 49336 64919 49356 64920 49336 64920 49357 64920 49558 64921 49282 64921 49361 64921 49361 64922 49282 64922 49319 64922 49361 64923 49319 64923 49338 64923 49338 64924 49319 64924 49337 64924 49338 64925 49337 64925 49363 64925 49368 64926 49426 64926 49425 64926 49431 64927 49322 64927 49339 64927 49339 64928 49322 64928 49324 64928 49339 64929 49324 64929 49438 64929 49438 64930 49324 64930 49325 64930 49438 64931 49325 64931 49436 64931 49436 64932 49325 64932 49326 64932 49436 64933 49326 64933 49340 64933 49370 64934 49451 64934 49450 64934 49460 64935 49341 64935 49342 64935 49342 64936 49341 64936 49343 64936 49342 64937 49343 64937 49344 64937 49344 64938 49343 64938 49327 64938 49344 64939 49327 64939 49345 64939 49345 64940 49327 64940 49329 64940 49345 64941 49329 64941 49467 64941 49373 64942 49475 64942 49474 64942 49490 64943 49346 64943 49347 64943 49347 64944 49346 64944 49348 64944 49347 64945 49348 64945 49488 64945 49488 64946 49348 64946 49349 64946 49488 64947 49349 64947 49350 64947 49350 64948 49349 64948 49331 64948 49350 64949 49331 64949 49487 64949 49376 64950 49501 64950 49499 64950 49517 64951 49513 64951 49351 64951 49351 64952 49513 64952 49333 64952 49351 64953 49333 64953 49352 64953 49352 64954 49333 64954 49334 64954 49352 64955 49334 64955 49515 64955 49515 64956 49334 64956 49335 64956 49515 64957 49335 64957 49293 64957 49379 64958 49528 64958 49527 64958 49536 64959 49353 64959 49541 64959 49541 64960 49353 64960 49354 64960 49541 64961 49354 64961 49540 64961 49540 64962 49354 64962 49356 64962 49540 64963 49356 64963 49355 64963 49355 64964 49356 64964 49357 64964 49355 64965 49357 64965 49358 64965 49359 64966 49383 64966 49360 64966 49566 64967 49558 64967 49564 64967 49564 64968 49558 64968 49361 64968 49564 64969 49361 64969 49362 64969 49362 64970 49361 64970 49338 64970 49362 64971 49338 64971 49563 64971 49563 64972 49338 64972 49363 64972 49563 64973 49363 64973 49290 64973 49427 64974 49426 64974 49364 64974 49364 64975 49426 64975 49368 64975 49364 64976 49368 64976 49365 64976 49430 64977 49366 64977 49432 64977 49432 64978 49366 64978 49365 64978 49432 64979 49365 64979 49367 64979 49367 64980 49365 64980 49368 64980 49367 64981 49368 64981 49369 64981 49369 64982 49368 64982 49425 64982 49369 64983 49425 64983 49433 64983 49452 64984 49451 64984 49455 64984 49455 64985 49451 64985 49370 64985 49455 64986 49370 64986 49454 64986 49459 64987 49227 64987 49461 64987 49461 64988 49227 64988 49454 64988 49461 64989 49454 64989 49462 64989 49462 64990 49454 64990 49370 64990 49462 64991 49370 64991 49464 64991 49464 64992 49370 64992 49450 64992 49464 64993 49450 64993 49448 64993 49482 64994 49475 64994 49371 64994 49371 64995 49475 64995 49373 64995 49371 64996 49373 64996 49372 64996 49483 64997 49239 64998 49484 64999 49484 65000 49239 65000 49372 65000 49484 65001 49372 65001 49485 65001 49485 65002 49372 65002 49373 65002 49485 65003 49373 65003 49374 65003 49374 65004 49373 65004 49474 65004 49374 65005 49474 65005 49473 65005 49508 65006 49501 65006 49375 65006 49375 65007 49501 65007 49376 65007 49375 65008 49376 65008 49506 65008 49511 65009 49248 65010 49512 65011 49512 65012 49248 65012 49506 65012 49512 65013 49506 65013 49377 65013 49377 65014 49506 65014 49376 65014 49377 65015 49376 65015 49378 65015 49378 65016 49376 65016 49499 65016 49378 65017 49499 65017 49497 65017 49530 65018 49528 65018 49533 65018 49533 65019 49528 65019 49379 65019 49533 65020 49379 65020 49532 65020 49537 65021 49531 65021 49380 65021 49380 65022 49531 65022 49532 65022 49380 65023 49532 65023 49381 65023 49381 65024 49532 65024 49379 65024 49381 65025 49379 65025 49539 65025 49539 65026 49379 65026 49527 65026 49539 65027 49527 65027 49382 65027 49552 65028 49383 65028 49384 65028 49384 65029 49383 65029 49359 65029 49384 65030 49359 65030 49555 65030 49385 65031 49387 65032 49386 65033 49386 65034 49387 65034 49555 65034 49386 65035 49555 65035 49559 65035 49559 65036 49555 65036 49359 65036 49559 65037 49359 65037 49388 65037 49388 65038 49359 65038 49360 65038 49388 65039 49360 65039 49389 65039 49303 65040 49390 65040 49391 65040 49391 65041 49390 65041 49392 65041 49391 65042 49392 65042 49590 65042 49590 65043 49392 65043 49393 65043 49590 65044 49393 65044 49591 65044 49591 65045 49393 65045 49395 65045 49591 65046 49395 65046 49394 65046 49394 65047 49395 65047 49278 65047 49394 65048 49278 65048 49277 65048 49396 65049 49401 65049 49390 65049 49390 65050 49401 65050 49397 65050 49390 65051 49397 65051 49392 65051 49392 65052 49397 65052 49403 65052 49392 65053 49403 65053 49393 65053 49393 65054 49403 65054 49405 65054 49393 65055 49405 65055 49395 65055 49395 65056 49405 65056 49398 65056 49395 65057 49398 65057 49399 65057 49404 65058 49202 65058 49200 65058 49400 65059 49406 65059 49401 65059 49401 65060 49406 65060 49407 65060 49401 65061 49407 65061 49397 65061 49397 65062 49407 65062 49402 65062 49397 65063 49402 65063 49403 65063 49403 65064 49402 65064 49404 65064 49403 65065 49404 65065 49405 65065 49405 65066 49404 65066 49200 65066 49405 65067 49200 65067 49398 65067 49302 65068 49410 65068 49406 65068 49406 65069 49410 65069 49411 65069 49406 65070 49411 65070 49407 65070 49407 65071 49411 65071 49412 65071 49407 65072 49412 65072 49402 65072 49402 65073 49412 65073 49408 65073 49402 65074 49408 65074 49404 65074 49404 65075 49408 65075 49409 65075 49404 65076 49409 65076 49202 65076 49301 65077 49413 65077 49410 65077 49410 65078 49413 65078 49415 65078 49410 65079 49415 65079 49411 65079 49411 65080 49415 65080 49416 65080 49411 65081 49416 65081 49412 65081 49412 65082 49416 65082 49417 65082 49412 65083 49417 65083 49408 65083 49408 65084 49417 65084 49418 65084 49408 65085 49418 65085 49205 65085 49423 65086 49208 65086 49206 65086 49300 65087 49414 65087 49413 65087 49413 65088 49414 65088 49420 65088 49413 65089 49420 65089 49415 65089 49415 65090 49420 65090 49421 65090 49415 65091 49421 65091 49416 65091 49416 65092 49421 65092 49423 65092 49416 65093 49423 65093 49417 65093 49417 65094 49423 65094 49206 65094 49417 65095 49206 65095 49418 65095 49428 65096 49211 65097 49210 65098 49299 65099 49424 65099 49414 65099 49414 65100 49424 65100 49419 65100 49414 65101 49419 65101 49420 65101 49420 65102 49419 65102 49422 65102 49420 65103 49422 65103 49421 65103 49421 65104 49422 65104 49428 65104 49421 65105 49428 65105 49423 65105 49423 65106 49428 65106 49210 65106 49423 65107 49210 65107 49208 65107 49435 65108 49433 65108 49424 65108 49424 65109 49433 65109 49425 65109 49424 65110 49425 65110 49419 65110 49419 65111 49425 65111 49426 65111 49419 65112 49426 65112 49422 65112 49422 65113 49426 65113 49427 65113 49422 65114 49427 65114 49428 65114 49428 65115 49427 65115 49212 65115 49428 65116 49212 65116 49211 65116 49366 65117 49217 65117 49365 65117 49365 65118 49217 65118 49429 65118 49365 65119 49429 65120 49364 65121 49364 65122 49429 65122 49215 65122 49364 65123 49215 65123 49427 65123 49427 65124 49215 65124 49216 65124 49427 65125 49216 65125 49212 65125 49219 65126 49430 65126 49431 65126 49431 65127 49430 65127 49432 65127 49431 65128 49432 65128 49322 65128 49322 65129 49432 65129 49367 65129 49322 65130 49367 65130 49323 65130 49323 65131 49367 65131 49369 65131 49323 65132 49369 65132 49307 65132 49307 65133 49369 65133 49433 65133 49307 65134 49433 65134 49434 65134 49434 65135 49433 65135 49435 65135 49440 65136 49220 65137 49441 65138 49340 65139 49437 65139 49436 65139 49436 65140 49437 65140 49444 65140 49436 65141 49444 65141 49438 65141 49438 65142 49444 65142 49439 65142 49438 65143 49439 65143 49339 65143 49339 65144 49439 65144 49440 65144 49339 65145 49440 65145 49431 65145 49431 65146 49440 65146 49441 65146 49431 65147 49441 65147 49219 65147 49453 65148 49442 65148 49443 65148 49298 65149 49449 65149 49437 65149 49437 65150 49449 65150 49445 65150 49437 65151 49445 65151 49444 65151 49444 65152 49445 65152 49446 65152 49444 65153 49446 65153 49439 65153 49439 65154 49446 65154 49453 65154 49439 65155 49453 65155 49440 65155 49440 65156 49453 65156 49443 65156 49440 65157 49443 65157 49220 65157 49447 65158 49448 65158 49449 65158 49449 65159 49448 65159 49450 65159 49449 65160 49450 65160 49445 65160 49445 65161 49450 65161 49451 65161 49445 65162 49451 65162 49446 65162 49446 65163 49451 65163 49452 65163 49446 65164 49452 65164 49453 65164 49453 65165 49452 65165 49222 65165 49453 65166 49222 65166 49442 65166 49227 65167 49225 65167 49454 65167 49454 65168 49225 65168 49456 65168 49454 65169 49456 65170 49455 65171 49455 65172 49456 65172 49457 65172 49455 65173 49457 65173 49452 65173 49452 65174 49457 65174 49458 65174 49452 65175 49458 65176 49222 65177 49234 65178 49459 65178 49460 65178 49460 65179 49459 65179 49461 65179 49460 65180 49461 65180 49341 65180 49341 65181 49461 65181 49462 65181 49341 65182 49462 65182 49463 65182 49463 65183 49462 65183 49464 65183 49463 65184 49464 65184 49465 65184 49465 65185 49464 65185 49448 65185 49465 65186 49448 65186 49466 65186 49466 65187 49448 65187 49447 65187 49469 65188 49231 65188 49232 65188 49467 65189 49297 65189 49345 65189 49345 65190 49297 65190 49468 65190 49345 65191 49468 65191 49344 65191 49344 65192 49468 65192 49472 65192 49344 65193 49472 65193 49342 65193 49342 65194 49472 65195 49469 65196 49342 65197 49469 65197 49460 65197 49460 65198 49469 65198 49232 65198 49460 65199 49232 65199 49234 65199 49477 65200 49235 65200 49229 65200 49470 65201 49296 65201 49297 65201 49297 65202 49296 65202 49471 65202 49297 65203 49471 65203 49468 65203 49468 65204 49471 65204 49476 65204 49468 65205 49476 65205 49472 65205 49472 65206 49476 65206 49477 65206 49472 65207 49477 65207 49469 65207 49469 65208 49477 65208 49229 65208 49469 65209 49229 65209 49231 65209 49295 65210 49473 65210 49296 65210 49296 65211 49473 65211 49474 65211 49296 65212 49474 65212 49471 65212 49471 65213 49474 65213 49475 65213 49471 65214 49475 65214 49476 65214 49476 65215 49475 65215 49482 65215 49476 65216 49482 65216 49477 65216 49477 65217 49482 65217 49236 65217 49477 65218 49236 65218 49235 65218 49239 65219 49478 65219 49372 65219 49372 65220 49478 65220 49479 65220 49372 65221 49479 65221 49371 65221 49371 65222 49479 65222 49480 65222 49371 65223 49480 65223 49482 65223 49482 65224 49480 65224 49481 65224 49482 65225 49481 65226 49236 65227 49241 65228 49483 65228 49490 65228 49490 65229 49483 65229 49484 65229 49490 65230 49484 65230 49346 65230 49346 65231 49484 65231 49485 65231 49346 65232 49485 65232 49285 65232 49285 65233 49485 65233 49374 65233 49285 65234 49374 65234 49486 65234 49486 65235 49374 65235 49473 65235 49486 65236 49473 65236 49312 65236 49312 65237 49473 65237 49295 65237 49487 65238 49492 65238 49350 65238 49350 65239 49492 65239 49493 65239 49350 65240 49493 65240 49488 65240 49488 65241 49493 65241 49489 65241 49488 65242 49489 65242 49347 65242 49347 65243 49489 65243 49494 65243 49347 65244 49494 65244 49490 65244 49490 65245 49494 65245 49243 65245 49490 65246 49243 65246 49491 65246 49503 65247 49245 65247 49495 65247 49294 65248 49498 65248 49492 65248 49492 65249 49498 65249 49500 65249 49492 65250 49500 65250 49493 65250 49493 65251 49500 65251 49502 65251 49493 65252 49502 65252 49489 65252 49489 65253 49502 65253 49503 65253 49489 65254 49503 65255 49494 65256 49494 65257 49503 65257 49495 65257 49494 65258 49495 65258 49243 65258 49496 65259 49497 65259 49498 65259 49498 65260 49497 65260 49499 65260 49498 65261 49499 65261 49500 65261 49500 65262 49499 65262 49501 65262 49500 65263 49501 65263 49502 65263 49502 65264 49501 65264 49508 65264 49502 65265 49508 65265 49503 65265 49503 65266 49508 65266 49504 65266 49503 65267 49504 65267 49245 65267 49248 65268 49505 65268 49506 65268 49506 65269 49505 65269 49507 65269 49506 65270 49507 65270 49375 65270 49375 65271 49507 65271 49509 65271 49375 65272 49509 65272 49508 65272 49508 65273 49509 65273 49510 65273 49508 65274 49510 65274 49504 65274 49253 65275 49511 65275 49517 65275 49517 65276 49511 65276 49512 65276 49517 65277 49512 65277 49513 65277 49513 65278 49512 65278 49377 65278 49513 65279 49377 65279 49332 65279 49332 65280 49377 65280 49378 65280 49332 65281 49378 65281 49316 65281 49316 65282 49378 65282 49497 65282 49316 65283 49497 65283 49514 65283 49514 65284 49497 65284 49496 65284 49293 65285 49521 65285 49515 65285 49515 65286 49521 65286 49523 65286 49515 65287 49523 65287 49352 65287 49352 65288 49523 65288 49516 65288 49352 65289 49516 65289 49351 65289 49351 65290 49516 65290 49524 65290 49351 65291 49524 65291 49517 65291 49517 65292 49524 65292 49251 65292 49517 65293 49251 65293 49252 65293 49525 65294 49518 65294 49519 65294 49520 65295 49526 65295 49521 65295 49521 65296 49526 65296 49522 65296 49521 65297 49522 65297 49523 65297 49523 65298 49522 65298 49529 65298 49523 65299 49529 65299 49516 65299 49516 65300 49529 65300 49525 65300 49516 65301 49525 65301 49524 65301 49524 65302 49525 65302 49519 65302 49524 65303 49519 65303 49251 65303 49292 65304 49382 65304 49526 65304 49526 65305 49382 65305 49527 65305 49526 65306 49527 65306 49522 65306 49522 65307 49527 65307 49528 65307 49522 65308 49528 65308 49529 65308 49529 65309 49528 65309 49530 65309 49529 65310 49530 65310 49525 65310 49525 65311 49530 65311 49255 65311 49525 65312 49255 65312 49518 65312 49531 65313 49259 65313 49532 65313 49532 65314 49259 65314 49257 65314 49532 65315 49257 65315 49533 65315 49533 65316 49257 65316 49534 65316 49533 65317 49534 65317 49530 65317 49530 65318 49534 65318 49535 65318 49530 65319 49535 65319 49255 65319 49263 65320 49537 65320 49536 65320 49536 65321 49537 65321 49380 65321 49536 65322 49380 65322 49353 65322 49353 65323 49380 65323 49381 65323 49353 65324 49381 65324 49538 65324 49538 65325 49381 65325 49539 65325 49538 65326 49539 65326 49283 65326 49283 65327 49539 65327 49382 65327 49283 65328 49382 65328 49318 65328 49318 65329 49382 65329 49292 65329 49358 65330 49546 65330 49355 65330 49355 65331 49546 65331 49548 65331 49355 65332 49548 65332 49540 65332 49540 65333 49548 65333 49549 65333 49540 65334 49549 65334 49541 65334 49541 65335 49549 65335 49542 65335 49541 65336 49542 65336 49536 65336 49536 65337 49542 65337 49543 65337 49536 65338 49543 65339 49281 65340 49550 65341 49264 65341 49551 65341 49291 65342 49544 65342 49546 65342 49546 65343 49544 65343 49545 65343 49546 65344 49545 65344 49548 65344 49548 65345 49545 65345 49547 65345 49548 65346 49547 65346 49549 65346 49549 65347 49547 65347 49550 65347 49549 65348 49550 65348 49542 65348 49542 65349 49550 65349 49551 65349 49542 65350 49551 65350 49543 65350 49561 65351 49389 65351 49544 65351 49544 65352 49389 65352 49360 65352 49544 65353 49360 65353 49545 65353 49545 65354 49360 65354 49383 65354 49545 65355 49383 65355 49547 65355 49547 65356 49383 65356 49552 65356 49547 65357 49552 65357 49550 65357 49550 65358 49552 65358 49553 65358 49550 65359 49553 65359 49264 65359 49387 65360 49554 65360 49555 65360 49555 65361 49554 65361 49556 65361 49555 65362 49556 65362 49384 65362 49384 65363 49556 65363 49557 65363 49384 65364 49557 65364 49552 65364 49552 65365 49557 65366 49266 65366 49552 65367 49266 65367 49553 65367 49269 65368 49385 65368 49566 65368 49566 65369 49385 65369 49386 65369 49566 65370 49386 65371 49558 65372 49558 65373 49386 65374 49559 65375 49558 65376 49559 65376 49282 65376 49282 65377 49559 65377 49388 65377 49282 65378 49388 65378 49321 65378 49321 65379 49388 65379 49389 65379 49321 65380 49389 65380 49560 65380 49560 65381 49389 65381 49561 65381 49290 65382 49569 65382 49563 65382 49563 65383 49569 65383 49562 65383 49563 65384 49562 65384 49362 65384 49362 65385 49562 65385 49572 65385 49362 65386 49572 65386 49564 65386 49564 65387 49572 65387 49565 65387 49564 65388 49565 65388 49566 65388 49566 65389 49565 65389 49272 65389 49566 65390 49272 65391 49280 65391 49575 65392 49576 65392 49567 65392 49568 65393 49573 65393 49569 65393 49569 65394 49573 65394 49570 65394 49569 65395 49570 65395 49562 65395 49562 65396 49570 65396 49571 65396 49562 65397 49571 65397 49572 65397 49572 65398 49571 65398 49575 65398 49572 65399 49575 65399 49565 65399 49565 65400 49575 65400 49567 65400 49565 65401 49567 65401 49272 65401 49289 65402 49574 65402 49573 65402 49573 65403 49574 65403 49578 65403 49573 65404 49578 65404 49570 65404 49570 65405 49578 65405 49579 65405 49570 65406 49579 65406 49571 65406 49571 65407 49579 65407 49581 65407 49571 65408 49581 65408 49575 65408 49575 65409 49581 65409 49273 65409 49575 65410 49273 65410 49576 65410 49287 65411 49585 65411 49574 65411 49574 65412 49585 65412 49577 65412 49574 65413 49577 65413 49578 65413 49578 65414 49577 65414 49587 65414 49578 65415 49587 65415 49579 65415 49579 65416 49587 65416 49580 65416 49579 65417 49580 65417 49581 65418 49581 65419 49580 65419 49582 65419 49581 65420 49582 65420 49279 65420 49583 65421 49584 65421 49588 65421 49288 65422 49589 65422 49585 65422 49585 65423 49589 65423 49586 65423 49585 65424 49586 65424 49577 65424 49577 65425 49586 65425 49592 65425 49577 65426 49592 65426 49587 65426 49587 65427 49592 65427 49583 65427 49587 65428 49583 65429 49580 65430 49580 65431 49583 65431 49588 65431 49580 65432 49588 65432 49582 65432 49286 65433 49391 65433 49589 65433 49589 65434 49391 65434 49590 65434 49589 65435 49590 65435 49586 65435 49586 65436 49590 65436 49591 65436 49586 65437 49591 65437 49592 65437 49592 65438 49591 65438 49394 65438 49592 65439 49394 65439 49583 65439 49583 65440 49394 65440 49277 65440 49583 65441 49277 65441 49584 65441 49639 65442 49593 65442 49594 65442 49594 65443 49593 65443 49596 65443 49594 65444 49596 65444 49595 65444 49595 65445 49596 65445 49598 65445 49595 65446 49598 65446 49597 65446 49597 65447 49598 65447 49600 65447 49597 65448 49600 65448 49599 65448 49599 65449 49600 65449 49601 65449 49599 65450 49601 65450 49602 65450 49602 65451 49601 65451 49604 65451 49602 65452 49604 65452 49603 65452 49603 65453 49604 65453 49606 65453 49603 65454 49606 65454 49605 65454 49605 65455 49606 65455 49608 65455 49605 65456 49608 65456 49607 65456 49607 65457 49608 65457 49609 65457 49607 65458 49609 65458 49611 65458 49611 65459 49609 65459 49610 65459 49611 65460 49610 65460 49613 65460 49613 65461 49610 65461 49612 65461 49613 65461 49612 65461 49614 65461 49614 65462 49612 65462 49616 65462 49614 65463 49616 65463 49615 65463 49615 65464 49616 65464 49617 65464 49615 65465 49617 65465 49618 65465 49618 65466 49617 65466 49619 65466 49618 65467 49619 65467 49620 65467 49620 65468 49619 65468 49621 65468 49620 65469 49621 65469 49622 65469 49622 65470 49621 65470 49624 65470 49622 65471 49624 65471 49623 65471 49623 65472 49624 65472 49625 65472 49623 65473 49625 65473 49626 65473 49626 65474 49625 65474 49628 65474 49626 65475 49628 65475 49627 65475 49627 65476 49628 65476 49630 65476 49627 65477 49630 65477 49629 65477 49629 65478 49630 65478 49631 65478 49629 65479 49631 65479 49632 65479 49632 65480 49631 65480 49633 65480 49632 65481 49633 65481 49634 65481 49634 65482 49633 65482 49635 65482 49634 65483 49635 65483 49636 65483 49636 65484 49635 65484 49638 65484 49636 65485 49638 65485 49637 65485 49637 65486 49638 65486 49639 65486 49637 65487 49639 65487 49594 65487 49640 65488 49642 65488 49641 65488 49641 65489 49642 65489 49643 65489 49641 65490 49643 65490 49644 65490 49644 65491 49643 65491 49646 65491 49644 65492 49646 65492 49645 65492 49645 65493 49646 65493 49647 65493 49645 65494 49647 65494 49648 65494 49648 65495 49647 65495 49649 65495 49648 65496 49649 65496 49651 65496 49651 65497 49649 65497 49650 65497 49651 65498 49650 65498 49652 65498 49652 65499 49650 65499 49653 65499 49652 65500 49653 65500 49654 65500 49654 65501 49653 65501 49655 65501 49654 65502 49655 65502 49656 65502 49656 65503 49655 65503 49657 65503 49656 65504 49657 65504 49658 65504 49658 65505 49657 65505 49660 65505 49658 65506 49660 65506 49659 65506 49659 65507 49660 65507 49661 65507 49659 65508 49661 65508 49662 65508 49662 65509 49661 65509 49663 65509 49662 65509 49663 65509 49664 65509 49664 65510 49663 65510 49666 65510 49664 65511 49666 65511 49665 65511 49665 65512 49666 65512 49667 65512 49665 65513 49667 65513 49668 65513 49668 65514 49667 65514 49669 65514 49668 65514 49669 65514 49670 65514 49670 65515 49669 65515 49672 65515 49670 65516 49672 65516 49671 65516 49671 65517 49672 65517 49674 65517 49671 65517 49674 65517 49673 65517 49673 65518 49674 65518 49676 65518 49673 65518 49676 65518 49675 65518 49675 65519 49676 65519 49677 65519 49675 65520 49677 65520 49678 65520 49678 65521 49677 65521 49679 65521 49678 65522 49679 65522 49681 65522 49681 65523 49679 65523 49680 65523 49681 65524 49680 65524 49682 65524 49682 65525 49680 65525 49683 65525 49682 65526 49683 65526 49685 65526 49685 65527 49683 65527 49684 65527 49685 65528 49684 65528 49687 65528 49687 65529 49684 65529 49686 65529 49687 65530 49686 65530 49689 65530 49689 65531 49686 65531 49688 65531 49689 65532 49688 65532 49690 65532 49690 65533 49688 65533 49691 65533 49690 65534 49691 65534 49692 65534 49692 65535 49691 65535 49693 65535 49692 65536 49693 65536 49694 65536 49694 65537 49693 65537 49696 65537 49694 65538 49696 65538 49695 65538 49695 65539 49696 65539 49698 65539 49695 65540 49698 65540 49697 65540 49697 65541 49698 65541 49699 65541 49697 65542 49699 65542 49700 65542 49700 65543 49699 65543 49701 65543 49700 65543 49701 65543 49702 65543 49702 65544 49701 65544 49703 65544 49702 65544 49703 65544 49704 65544 49704 65545 49703 65545 49705 65545 49704 65546 49705 65546 49707 65546 49707 65547 49705 65547 49706 65547 49707 65547 49706 65547 49708 65547 49708 65548 49706 65548 49709 65548 49708 65549 49709 65549 49710 65549 49710 65550 49709 65550 49712 65550 49710 65550 49712 65550 49711 65550 49711 65551 49712 65551 49713 65551 49711 65552 49713 65552 49714 65552 49714 65553 49713 65553 49715 65553 49714 65553 49715 65553 49640 65553 49640 65488 49715 65488 49642 65488 49716 65554 49718 65554 49717 65554 49717 65555 49718 65555 49720 65555 49717 65556 49720 65556 49719 65556 49719 65557 49720 65557 49722 65557 49719 65558 49722 65558 49721 65558 49721 65559 49722 65559 49723 65559 49721 65560 49723 65560 49725 65560 49725 65561 49723 65561 49724 65561 49725 65562 49724 65562 49727 65562 49727 65563 49724 65563 49726 65563 49727 65564 49726 65564 49729 65564 49729 65565 49726 65565 49728 65565 49729 65566 49728 65566 49730 65566 49730 65567 49728 65567 49731 65567 49730 65568 49731 65568 49733 65568 49733 65569 49731 65569 49732 65569 49733 65570 49732 65570 49734 65570 49734 65571 49732 65571 49736 65571 49734 65572 49736 65572 49735 65572 49735 65573 49736 65573 49737 65573 49735 65574 49737 65574 49738 65574 49738 65575 49737 65575 49739 65575 49738 65576 49739 65576 49740 65576 49740 65577 49739 65577 49741 65577 49740 65578 49741 65578 49742 65578 49742 65579 49741 65579 49743 65579 49742 65580 49743 65580 49744 65580 49744 65581 49743 65581 49746 65581 49744 65582 49746 65582 49745 65582 49745 65583 49746 65583 49747 65583 49745 65584 49747 65584 49748 65584 49748 65585 49747 65585 49749 65585 49748 65586 49749 65586 49750 65586 49750 65587 49749 65587 49752 65587 49750 65588 49752 65588 49751 65588 49751 65589 49752 65589 49753 65589 49751 65590 49753 65590 49754 65590 49754 65591 49753 65591 49755 65591 49754 65592 49755 65592 49757 65592 49757 65593 49755 65593 49756 65593 49757 65594 49756 65594 49759 65594 49759 65595 49756 65595 49758 65595 49759 65596 49758 65596 49760 65596 49760 65597 49758 65597 49761 65597 49760 65598 49761 65598 49762 65598 49762 65599 49761 65599 49716 65599 49762 65600 49716 65600 49717 65600 49769 65601 49773 65601 49767 65601 49767 590 49773 590 49772 590 49778 590 49763 590 49765 590 49770 590 49781 590 49764 590 49765 590 49763 590 49766 590 49801 65602 49776 65602 49790 65602 49766 590 49763 590 49767 590 49767 65603 49763 65603 49768 65603 49767 65604 49768 65604 49769 65604 49770 590 49764 590 49775 590 49790 65605 49776 65605 49771 65605 49772 65606 49773 65606 49764 65606 49764 65607 49773 65607 49774 65607 49764 65608 49774 65608 49775 65608 49771 65609 49776 65609 49765 65609 49765 65610 49776 65610 49777 65610 49765 65611 49777 65611 49778 65611 49779 65612 49780 65612 49781 65612 49781 65613 49780 65613 49782 65613 49781 65614 49782 65614 49764 65614 49779 65615 49781 65615 49785 65615 49785 65616 49781 65616 49783 65616 49785 65617 49783 65617 49784 65617 49784 65618 49786 65618 49785 65618 49785 65619 49786 65619 49787 65619 49785 65620 49787 65620 49788 65620 49792 65621 49790 65621 49789 65621 49789 590 49790 590 49791 590 49792 65622 49793 65622 49790 65622 49790 65623 49793 65623 49794 65623 49790 65624 49794 65624 49798 65624 49788 65625 49795 65625 49785 65625 49785 65626 49795 65626 49796 65626 49785 65627 49796 65627 49797 65627 49798 590 49799 590 49790 590 49790 65628 49799 65628 49800 65628 49790 65629 49800 65629 49801 65629 49802 65630 49803 65630 49837 65630 49837 65631 49803 65631 49804 65631 49837 65632 49804 65632 49850 65632 49850 65633 49804 65633 49805 65633 49850 65634 49805 65634 49807 65634 49807 65635 49805 65635 49806 65635 49807 65636 49806 65636 49808 65636 49808 65637 49806 65637 49809 65637 49808 65638 49809 65638 49846 65638 49846 65639 49809 65639 49811 65639 49846 65640 49811 65640 49810 65640 49810 65641 49811 65641 49812 65641 49810 65642 49812 65642 49843 65642 49843 65643 49812 65643 49813 65643 49843 65644 49813 65644 49841 65644 49841 65645 49813 65645 49814 65645 49841 65646 49814 65646 49815 65646 49815 65647 49814 65647 49816 65647 49815 65648 49816 65648 49838 65648 49838 65649 49816 65649 49817 65649 49838 65650 49817 65650 49870 65650 49870 65651 49817 65651 49818 65651 49870 65652 49818 65652 49819 65652 49819 65653 49818 65653 49821 65653 49819 65654 49821 65654 49820 65654 49820 65655 49821 65655 49822 65655 49820 65656 49822 65656 49824 65656 49824 65657 49822 65657 49823 65657 49824 65658 49823 65658 49864 65658 49864 65659 49823 65659 49825 65659 49864 65660 49825 65660 49863 65660 49863 65661 49825 65661 49826 65661 49863 65662 49826 65662 49827 65662 49827 65663 49826 65663 49828 65663 49827 65664 49828 65664 49859 65664 49859 65665 49828 65665 49829 65665 49859 65666 49829 65666 49857 65666 49857 65667 49829 65667 49830 65667 49857 65668 49830 65668 49832 65668 49832 65669 49830 65669 49831 65669 49832 65670 49831 65670 49855 65670 49855 65671 49831 65671 49833 65671 49855 65672 49833 65672 49834 65672 49834 65673 49833 65673 49835 65673 49834 65674 49835 65674 49836 65674 49836 65675 49835 65675 49802 65675 49836 65676 49802 65676 49837 65676 49870 65677 49871 65677 49838 65677 49838 65678 49871 65678 49839 65678 49838 65679 49839 65679 49815 65679 49815 65680 49839 65680 49840 65680 49815 65681 49840 65681 49841 65681 49841 65682 49840 65682 49842 65682 49841 65683 49842 65683 49843 65683 49843 65684 49842 65684 49844 65684 49843 65685 49844 65685 49810 65685 49810 65686 49844 65686 49845 65686 49810 65687 49845 65687 49846 65687 49846 65688 49845 65688 49847 65688 49846 65689 49847 65689 49808 65689 49808 65690 49847 65690 49848 65690 49808 65691 49848 65691 49807 65691 49807 65692 49848 65692 49849 65692 49807 65693 49849 65693 49850 65693 49850 65694 49849 65694 49851 65694 49850 65695 49851 65695 49837 65695 49837 65696 49851 65696 49852 65696 49837 65697 49852 65697 49836 65697 49836 65698 49852 65698 49853 65698 49836 65699 49853 65699 49834 65699 49834 65700 49853 65700 49854 65700 49834 65701 49854 65701 49855 65701 49855 65702 49854 65702 49856 65702 49855 65703 49856 65703 49832 65703 49832 65704 49856 65704 49858 65704 49832 65705 49858 65705 49857 65705 49857 65706 49858 65706 49860 65706 49857 65707 49860 65707 49859 65707 49859 65708 49860 65708 49861 65708 49859 65709 49861 65709 49827 65709 49827 65710 49861 65710 49862 65710 49827 65711 49862 65711 49863 65711 49863 65712 49862 65712 49865 65712 49863 65713 49865 65713 49864 65713 49864 65714 49865 65714 49866 65714 49864 65715 49866 65715 49824 65715 49824 65716 49866 65716 49867 65716 49824 65717 49867 65717 49820 65717 49820 65718 49867 65718 49868 65718 49820 65719 49868 65719 49819 65719 49819 65720 49868 65720 49869 65720 49819 65721 49869 65721 49870 65721 49870 65722 49869 65722 49871 65722 49905 65723 49872 65723 49917 65723 49917 65724 49872 65724 49873 65724 49917 65725 49873 65725 49916 65725 49916 65726 49873 65726 49874 65726 49916 65727 49874 65727 49914 65727 49914 65728 49874 65728 49876 65728 49914 65728 49876 65728 49875 65728 49875 65729 49876 65729 49877 65729 49875 65730 49877 65730 49878 65730 49878 65731 49877 65731 49879 65731 49878 65732 49879 65732 49911 65732 49911 65733 49879 65733 49880 65733 49911 65734 49880 65734 49910 65734 49910 65735 49880 65735 49881 65735 49910 65736 49881 65736 49908 65736 49908 65737 49881 65737 49882 65737 49908 65738 49882 65738 49907 65738 49907 65739 49882 65739 49884 65739 49907 65740 49884 65740 49883 65740 49883 65741 49884 65741 49885 65741 49883 65742 49885 65742 49931 65742 49931 65743 49885 65743 49886 65743 49931 65744 49886 65744 49887 65744 49887 65745 49886 65745 49888 65745 49887 65746 49888 65746 49890 65746 49890 65747 49888 65747 49889 65747 49890 65748 49889 65748 49928 65748 49928 65749 49889 65749 49891 65749 49928 65750 49891 65750 49926 65750 49926 65751 49891 65751 49892 65751 49926 65752 49892 65752 49893 65752 49893 65753 49892 65753 49894 65753 49893 65754 49894 65754 49924 65754 49924 65755 49894 65755 49895 65755 49924 65755 49895 65755 49896 65755 49896 65756 49895 65756 49897 65756 49896 65757 49897 65757 49898 65757 49898 65758 49897 65758 49900 65758 49898 65759 49900 65759 49899 65759 49899 65760 49900 65760 49901 65760 49899 65761 49901 65761 49921 65761 49921 65762 49901 65762 49902 65762 49921 65763 49902 65763 49903 65763 49903 65764 49902 65764 49904 65764 49903 65765 49904 65765 49919 65765 49919 65766 49904 65766 49905 65766 49919 65767 49905 65767 49917 65767 49931 65768 49939 65768 49883 65768 49883 65769 49939 65769 49941 65769 49883 65770 49941 65770 49907 65770 49907 65771 49941 65771 49906 65771 49907 65772 49906 65772 49908 65772 49908 65773 49906 65773 49909 65773 49908 65774 49909 65774 49910 65774 49910 65775 49909 65775 49938 65775 49910 65776 49938 65776 49911 65776 49911 65777 49938 65777 49912 65777 49911 65778 49912 65778 49878 65778 49878 65779 49912 65779 49913 65779 49878 65780 49913 65780 49875 65780 49875 65781 49913 65781 49940 65781 49875 65782 49940 65782 49914 65782 49914 65783 49940 65783 49915 65783 49914 65784 49915 65784 49916 65784 49916 65785 49915 65785 49933 65785 49916 65786 49933 65786 49917 65786 49917 65787 49933 65787 49918 65787 49917 65788 49918 65788 49919 65788 49919 65789 49918 65789 49920 65789 49919 65790 49920 65790 49903 65790 49903 65791 49920 65791 49934 65791 49903 65792 49934 65792 49921 65792 49921 65793 49934 65793 49922 65793 49921 65794 49922 65794 49899 65794 49899 65795 49922 65795 49937 65795 49899 65796 49937 65796 49898 65796 49898 65797 49937 65797 49923 65797 49898 65798 49923 65798 49896 65798 49896 65799 49923 65799 49935 65799 49896 65800 49935 65800 49924 65800 49924 65801 49935 65801 49925 65801 49924 65802 49925 65802 49893 65802 49893 65803 49925 65803 49936 65803 49893 65804 49936 65804 49926 65804 49926 65805 49936 65805 49927 65805 49926 65806 49927 65806 49928 65806 49928 65807 49927 65807 49929 65807 49928 65808 49929 65808 49890 65808 49890 65809 49929 65809 49930 65809 49890 65810 49930 65810 49887 65810 49887 65811 49930 65811 49932 65811 49887 65812 49932 65812 49931 65812 49931 65813 49932 65813 49939 65813 49918 590 49933 590 49939 590 49932 65814 49930 65814 49934 65814 49936 65815 49925 65815 49935 65815 49930 590 49929 590 49934 590 49934 65816 49929 65816 49927 65816 49934 590 49927 590 49922 590 49922 590 49927 590 49937 590 49932 590 49934 590 49939 590 49939 65817 49934 65817 49920 65817 49939 65818 49920 65818 49918 65818 49936 65819 49935 65819 49927 65819 49927 65820 49935 65820 49923 65820 49927 590 49923 590 49937 590 49940 65821 49909 65821 49906 65821 49913 590 49912 590 49940 590 49940 590 49912 590 49938 590 49940 65822 49938 65822 49909 65822 49933 590 49915 590 49939 590 49939 65823 49915 65823 49940 65823 49939 590 49940 590 49941 590 49941 590 49940 590 49906 590 49976 65824 49942 65824 49991 65824 49991 65825 49942 65825 49943 65825 49991 65826 49943 65826 49990 65826 49990 65827 49943 65827 49944 65827 49990 65828 49944 65828 49989 65828 49989 65829 49944 65829 49945 65829 49989 65830 49945 65830 49946 65830 49946 65831 49945 65831 49947 65831 49946 65832 49947 65832 49986 65832 49986 65833 49947 65833 49948 65833 49986 65834 49948 65834 49984 65834 49984 65835 49948 65835 49949 65835 49984 65836 49949 65836 49951 65836 49951 65837 49949 65837 49950 65837 49951 65838 49950 65838 49953 65838 49953 65839 49950 65839 49952 65839 49953 65840 49952 65840 49981 65840 49981 65841 49952 65841 49954 65841 49981 65842 49954 65842 49978 65842 49978 65843 49954 65843 49955 65843 49978 65844 49955 65844 49977 65844 49977 65845 49955 65845 49956 65845 49977 65846 49956 65846 49957 65846 49957 65847 49956 65847 49958 65847 49957 65847 49958 65847 49959 65847 49959 65848 49958 65848 49960 65848 49959 65848 49960 65848 49962 65848 49962 65849 49960 65849 49961 65849 49962 65850 49961 65850 50001 65850 50001 65851 49961 65851 49963 65851 50001 65852 49963 65852 50000 65852 50000 65853 49963 65853 49964 65853 50000 65854 49964 65854 49965 65854 49965 65855 49964 65855 49966 65855 49965 65856 49966 65856 49967 65856 49967 65857 49966 65857 49969 65857 49967 65858 49969 65858 49968 65858 49968 65859 49969 65859 49970 65859 49968 65860 49970 65860 49995 65860 49995 65861 49970 65861 49971 65861 49995 65862 49971 65862 49973 65862 49973 65863 49971 65863 49972 65863 49973 65864 49972 65864 49974 65864 49974 65865 49972 65865 49975 65865 49974 65865 49975 65865 49994 65865 49994 65866 49975 65866 49976 65866 49994 65867 49976 65867 49991 65867 49977 65868 49979 65868 49978 65868 49978 65869 49979 65869 49980 65869 49978 65870 49980 65870 49981 65870 49981 65871 49980 65871 49982 65871 49981 65872 49982 65872 49953 65872 49953 65873 49982 65873 49983 65873 49953 65874 49983 65874 49951 65874 49951 65875 49983 65875 50011 65875 49951 65876 50011 65876 49984 65876 49984 65877 50011 65877 49985 65877 49984 65878 49985 65878 49986 65878 49986 65879 49985 65879 49987 65879 49986 65880 49987 65880 49946 65880 49946 65881 49987 65881 49988 65881 49946 65882 49988 65882 49989 65882 49989 65883 49988 65883 50008 65883 49989 65884 50008 65884 49990 65884 49990 65885 50008 65885 50007 65885 49990 65886 50007 65886 49991 65886 49991 65887 50007 65887 49992 65887 49991 65888 49992 65888 49994 65888 49994 65889 49992 65889 49993 65889 49994 65890 49993 65890 49974 65890 49974 65891 49993 65891 50006 65891 49974 65892 50006 65892 49973 65892 49973 65893 50006 65893 50010 65893 49973 65894 50010 65894 49995 65894 49995 65895 50010 65895 49996 65895 49995 65896 49996 65896 49968 65896 49968 65897 49996 65897 49997 65897 49968 65898 49997 65898 49967 65898 49967 65899 49997 65899 49998 65899 49967 65900 49998 65900 49965 65900 49965 65901 49998 65901 49999 65901 49965 65902 49999 65902 50000 65902 50000 65903 49999 65903 50009 65903 50000 65904 50009 65904 50001 65904 50001 65905 50009 65905 50002 65905 50001 65906 50002 65906 49962 65906 49962 65907 50002 65907 50003 65907 49962 65908 50003 65908 49959 65908 49959 65909 50003 65909 50004 65909 49959 65910 50004 65910 49957 65910 49957 65911 50004 65911 50005 65911 49957 65912 50005 65912 49977 65912 49977 65913 50005 65913 49979 65913 50008 65914 49980 65914 49979 65914 50010 65915 50006 65915 50009 65915 50009 65916 50006 65916 49993 65916 50003 65917 50007 65917 50004 65917 50004 65918 50007 65918 50008 65918 50004 65919 50008 65919 50005 65919 50005 590 50008 590 49979 590 50003 65920 50002 65920 50007 65920 50007 590 50002 590 50009 590 50007 65921 50009 65921 49992 65921 49992 590 50009 590 49993 590 49988 590 49987 590 50008 590 50008 65922 49987 65922 49985 65922 50008 590 49985 590 50011 590 50009 65923 49999 65923 50010 65923 50010 590 49999 590 49998 590 50010 65924 49998 65924 49996 65924 49996 590 49998 590 49997 590 50011 590 49983 590 50008 590 50008 65925 49983 65925 49982 65925 50008 65926 49982 65926 49980 65926 50012 65927 50013 65927 50046 65927 50046 65928 50013 65928 50014 65928 50046 65929 50014 65929 50015 65929 50015 65930 50014 65930 50016 65930 50015 65931 50016 65931 50055 65931 50055 65932 50016 65932 50017 65932 50055 65933 50017 65933 50019 65933 50019 65934 50017 65934 50018 65934 50019 65935 50018 65935 50020 65935 50020 65936 50018 65936 50021 65936 50020 65937 50021 65937 50052 65937 50052 65938 50021 65938 50023 65938 50052 65938 50023 65938 50022 65938 50022 65939 50023 65939 50025 65939 50022 65940 50025 65940 50024 65940 50024 65941 50025 65941 50026 65941 50024 65942 50026 65942 50027 65942 50027 65943 50026 65943 50029 65943 50027 65944 50029 65944 50028 65944 50028 65945 50029 65945 50031 65945 50028 65946 50031 65946 50030 65946 50030 65947 50031 65947 50032 65947 50030 65948 50032 65948 50079 65948 50079 65949 50032 65949 50034 65949 50079 65949 50034 65949 50033 65949 50033 65950 50034 65950 50035 65950 50033 65951 50035 65951 50037 65951 50037 65952 50035 65952 50036 65952 50037 65953 50036 65953 50076 65953 50076 65954 50036 65954 50038 65954 50076 65955 50038 65955 50074 65955 50074 65956 50038 65956 50039 65956 50074 65956 50039 65956 50073 65956 50073 65957 50039 65957 50040 65957 50073 65958 50040 65958 50070 65958 50070 65959 50040 65959 50041 65959 50070 65960 50041 65960 50068 65960 50068 65961 50041 65961 50042 65961 50068 65962 50042 65962 50065 65962 50065 65963 50042 65963 50043 65963 50065 65964 50043 65964 50064 65964 50064 65965 50043 65965 50044 65965 50064 65965 50044 65965 50062 65965 50062 65966 50044 65966 50045 65966 50062 65967 50045 65967 50060 65967 50060 65968 50045 65968 50012 65968 50060 65969 50012 65969 50046 65969 50030 65970 50047 65970 50028 65970 50028 65971 50047 65971 50048 65971 50028 65972 50048 65972 50027 65972 50027 65973 50048 65973 50049 65973 50027 65974 50049 65974 50024 65974 50024 65975 50049 65975 50050 65975 50024 65976 50050 65976 50022 65976 50022 65977 50050 65977 50051 65977 50022 65978 50051 65978 50052 65978 50052 65979 50051 65979 50053 65979 50052 65980 50053 65980 50020 65980 50020 65981 50053 65981 50054 65981 50020 65982 50054 65982 50019 65982 50019 65983 50054 65983 50056 65983 50019 65984 50056 65984 50055 65984 50055 65985 50056 65985 50057 65985 50055 65986 50057 65986 50015 65986 50015 65987 50057 65987 50058 65987 50015 65988 50058 65988 50046 65988 50046 65989 50058 65989 50059 65989 50046 65990 50059 65990 50060 65990 50060 65991 50059 65991 50061 65991 50060 65992 50061 65992 50062 65992 50062 65993 50061 65993 50063 65993 50062 65994 50063 65994 50064 65994 50064 65995 50063 65995 50066 65995 50064 65996 50066 65996 50065 65996 50065 65997 50066 65997 50067 65997 50065 65998 50067 65998 50068 65998 50068 65999 50067 65999 50069 65999 50068 66000 50069 66000 50070 66000 50070 66001 50069 66001 50071 66001 50070 66002 50071 66002 50073 66002 50073 66003 50071 66003 50072 66003 50073 66004 50072 66004 50074 66004 50074 66005 50072 66005 50075 66005 50074 66006 50075 66006 50076 66006 50076 66007 50075 66007 50077 66007 50076 66008 50077 66008 50037 66008 50037 66009 50077 66009 50078 66009 50037 66010 50078 66010 50033 66010 50033 66011 50078 66011 50080 66011 50033 66012 50080 66012 50079 66012 50079 66013 50080 66013 50081 66013 50079 66014 50081 66014 50030 66014 50030 66015 50081 66015 50047 66015 50082 66016 50083 66016 50084 66016 50084 66017 50083 66017 50121 66017 50084 66018 50121 66018 50086 66018 50086 66019 50121 66019 50085 66019 50086 66020 50085 66020 50087 66020 50087 66021 50085 66021 50088 66021 50087 66022 50088 66022 50089 66022 50089 66023 50088 66023 50135 66023 50089 66024 50135 66024 50090 66024 50090 66025 50135 66025 50134 66025 50090 66026 50134 66026 50091 66026 50091 6 50134 6 50133 6 50091 6 50133 6 50092 6 50092 66027 50133 66027 50094 66027 50092 66028 50094 66028 50093 66028 50093 66029 50094 66029 50095 66029 50093 66030 50095 66030 50096 66030 50096 66031 50095 66031 50097 66031 50096 66032 50097 66032 50099 66032 50099 66033 50097 66033 50098 66033 50099 66034 50098 66034 50100 66034 50100 66035 50098 66035 50127 66035 50100 66036 50127 66036 50101 66036 50101 66037 50127 66037 50125 66037 50101 66038 50125 66038 50102 66038 50102 66039 50125 66039 50124 66039 50102 66040 50124 66040 50103 66040 50103 66041 50124 66041 50123 66041 50103 66042 50123 66042 50104 66042 50104 66043 50123 66043 50105 66043 50104 66044 50105 66044 50106 66044 50106 66045 50105 66045 50131 66045 50106 66046 50131 66046 50107 66046 50107 21 50131 21 50129 21 50107 21 50129 21 50108 21 50108 66047 50129 66047 50128 66047 50108 66048 50128 66048 50109 66048 50109 66049 50128 66049 50110 66049 50109 66050 50110 66050 50111 66050 50111 66051 50110 66051 50112 66051 50111 66052 50112 66052 50113 66052 50113 66053 50112 66053 50122 66053 50113 66054 50122 66054 50082 66054 50082 66055 50122 66055 50083 66055 50117 66056 50114 66056 50126 66056 50126 66057 50114 66057 50130 66057 50115 66058 50117 66058 50116 66058 50116 66059 50117 66059 50126 66059 50136 66060 50119 66060 50137 66060 50137 66061 50119 66061 50118 66061 50119 66062 50120 66062 50118 66062 50118 66063 50120 66063 50132 66063 50120 21 50115 21 50132 21 50132 21 50115 21 50116 21 50097 590 50095 590 50116 590 50135 590 50088 590 50132 590 50132 66064 50088 66064 50085 66064 50097 66065 50116 66065 50098 66065 50098 590 50116 590 50126 590 50098 66066 50126 66066 50127 66066 50085 66065 50121 66065 50132 66065 50132 66067 50121 66067 50083 66067 50132 590 50083 590 50118 590 50118 66068 50083 66068 50122 66068 50118 590 50122 590 50137 590 50137 66069 50122 66069 50112 66069 50137 66070 50112 66070 50110 66070 50105 590 50123 590 50130 590 50130 66070 50123 66070 50124 66070 50130 66071 50124 66071 50126 66071 50126 66072 50124 66072 50125 66072 50126 66073 50125 66073 50127 66073 50110 590 50128 590 50137 590 50137 590 50128 590 50129 590 50137 590 50129 590 50130 590 50130 66074 50129 66074 50131 66074 50130 590 50131 590 50105 590 50095 590 50094 590 50116 590 50116 590 50094 590 50133 590 50116 590 50133 590 50132 590 50132 66075 50133 66075 50134 66075 50132 590 50134 590 50135 590 50114 6 50136 6 50130 6 50130 6 50136 6 50137 6 50169 66076 50191 66076 50138 66076 50138 66077 50191 66077 50139 66077 50138 66078 50139 66078 50140 66078 50140 66079 50139 66079 50190 66079 50140 66080 50190 66080 50141 66080 50141 66081 50190 66081 50143 66081 50141 66082 50143 66082 50142 66082 50142 66083 50143 66083 50182 66083 50142 66084 50182 66084 50144 66084 50144 66085 50182 66085 50181 66085 50144 66086 50181 66086 50145 66086 50145 66087 50181 66087 50179 66087 50145 66088 50179 66088 50146 66088 50146 66089 50179 66089 50178 66089 50146 66090 50178 66090 50147 66090 50147 66091 50178 66091 50149 66091 50147 66092 50149 66092 50148 66092 50148 66093 50149 66093 50150 66093 50148 66094 50150 66094 50151 66094 50151 66095 50150 66095 50177 66095 50151 66096 50177 66096 50152 66096 50152 66097 50177 66097 50186 66097 50152 66098 50186 66098 50153 66098 50153 66099 50186 66099 50154 66099 50153 66100 50154 66100 50155 66100 50155 66101 50154 66101 50156 66101 50155 66102 50156 66102 50158 66102 50158 66103 50156 66103 50157 66103 50158 66104 50157 66104 50159 66104 50159 66105 50157 66105 50161 66105 50159 66106 50161 66106 50160 66106 50160 66107 50161 66107 50185 66107 50160 66108 50185 66108 50162 66108 50162 66109 50185 66109 50163 66109 50162 66109 50163 66109 50164 66109 50164 66110 50163 66110 50183 66110 50164 66111 50183 66111 50165 66111 50165 66112 50183 66112 50189 66112 50165 66113 50189 66113 50167 66113 50167 66114 50189 66114 50166 66114 50167 66115 50166 66115 50168 66115 50168 66116 50166 66116 50188 66116 50168 66117 50188 66117 50169 66117 50169 66118 50188 66118 50191 66118 50171 66119 50192 66119 50172 66119 50172 66120 50192 66120 50170 66120 50175 66121 50171 66121 50176 66121 50176 66122 50171 66122 50172 66122 50193 66123 50173 66123 50184 66123 50184 66124 50173 66124 50187 66124 50173 66125 50174 66125 50187 66125 50187 66125 50174 66125 50180 66125 50174 66126 50175 66126 50180 66126 50180 66127 50175 66127 50176 66127 50186 66128 50177 66128 50172 66128 50191 66129 50188 66129 50187 66129 50172 590 50177 590 50176 590 50176 590 50177 590 50150 590 50176 66130 50150 66130 50149 66130 50149 66131 50178 66131 50176 66131 50176 66132 50178 66132 50179 66132 50176 590 50179 590 50180 590 50180 66133 50179 66133 50181 66133 50180 66134 50181 66134 50182 66134 50189 66135 50183 66135 50184 66135 50184 66136 50183 66136 50163 66136 50184 590 50163 590 50170 590 50170 66137 50163 66137 50185 66137 50170 66138 50185 66138 50161 66138 50161 590 50157 590 50170 590 50170 590 50157 590 50156 590 50170 590 50156 590 50172 590 50172 66139 50156 66139 50154 66139 50172 66140 50154 66140 50186 66140 50187 590 50188 590 50184 590 50184 590 50188 590 50166 590 50184 66141 50166 66141 50189 66141 50182 590 50143 590 50180 590 50180 590 50143 590 50190 590 50180 590 50190 590 50187 590 50187 66142 50190 66142 50139 66142 50187 66143 50139 66143 50191 66143 50192 66144 50193 66144 50170 66144 50170 66145 50193 66145 50184 66145 50269 66146 50194 66146 50195 66146 50195 66147 50194 66147 50196 66147 50195 66148 50196 66148 50197 66148 50197 66149 50196 66149 50199 66149 50197 66150 50199 66150 50198 66150 50198 66151 50199 66151 50200 66151 50198 66152 50200 66152 50201 66152 50201 66153 50200 66153 50203 66153 50201 66154 50203 66154 50202 66154 50202 66155 50203 66155 50204 66155 50202 66156 50204 66156 50206 66156 50206 66157 50204 66157 50205 66157 50206 66157 50205 66157 50207 66157 50207 66158 50205 66158 50208 66158 50207 66159 50208 66159 50209 66159 50209 66160 50208 66160 50211 66160 50209 66161 50211 66161 50210 66161 50210 66162 50211 66162 50213 66162 50210 66163 50213 66163 50212 66163 50212 4818 50213 4818 50214 4818 50212 66164 50214 66164 50215 66164 50215 66165 50214 66165 50216 66165 50215 66166 50216 66166 50217 66166 50217 66167 50216 66167 50218 66167 50217 66168 50218 66168 50219 66168 50219 66169 50218 66169 50221 66169 50219 66170 50221 66170 50220 66170 50220 66171 50221 66171 50222 66171 50220 66171 50222 66171 50223 66171 50223 66172 50222 66172 50224 66172 50223 66173 50224 66173 50225 66173 50225 66174 50224 66174 50226 66174 50225 66175 50226 66175 50227 66175 50227 66176 50226 66176 50228 66176 50227 66177 50228 66177 50229 66177 50229 66178 50228 66178 50230 66178 50229 66179 50230 66179 50232 66179 50232 66180 50230 66180 50231 66180 50232 66181 50231 66181 50233 66181 50233 66182 50231 66182 50234 66182 50233 66183 50234 66183 50235 66183 50235 66184 50234 66184 50236 66184 50235 66185 50236 66185 50238 66185 50238 66186 50236 66186 50237 66186 50238 66187 50237 66187 50239 66187 50239 66188 50237 66188 50240 66188 50239 66189 50240 66189 50242 66189 50242 66190 50240 66190 50241 66190 50242 66191 50241 66191 50243 66191 50243 66192 50241 66192 50244 66192 50243 66193 50244 66193 50246 66193 50246 66194 50244 66194 50245 66194 50246 66195 50245 66195 50247 66195 50247 66196 50245 66196 50248 66196 50247 66197 50248 66197 50249 66197 50249 66198 50248 66198 50250 66198 50249 66199 50250 66199 50251 66199 50251 66200 50250 66200 50253 66200 50251 66201 50253 66201 50252 66201 50252 66202 50253 66202 50254 66202 50252 66203 50254 66203 50255 66203 50255 66204 50254 66204 50256 66204 50255 66205 50256 66205 50257 66205 50257 66206 50256 66206 50258 66206 50257 66207 50258 66207 50260 66207 50260 66208 50258 66208 50259 66208 50260 66208 50259 66208 50262 66208 50262 66209 50259 66209 50261 66209 50262 66210 50261 66210 50263 66210 50263 66211 50261 66211 50265 66211 50263 66211 50265 66211 50264 66211 50264 66212 50265 66212 50266 66212 50264 66213 50266 66213 50268 66213 50268 66214 50266 66214 50267 66214 50268 66215 50267 66215 50269 66215 50269 66216 50267 66216 50194 66216 50270 66217 50313 66217 50272 66217 50272 66218 50313 66218 50271 66218 50272 66219 50271 66219 50273 66219 50273 66220 50271 66220 50318 66220 50273 66221 50318 66221 50274 66221 50274 66222 50318 66222 50317 66222 50274 66222 50317 66222 50275 66222 50275 66223 50317 66223 50310 66223 50275 66224 50310 66224 50276 66224 50276 66225 50310 66225 50277 66225 50276 66226 50277 66226 50278 66226 50278 66227 50277 66227 50309 66227 50278 66228 50309 66228 50279 66228 50279 66229 50309 66229 50280 66229 50279 66230 50280 66230 50281 66230 50281 66231 50280 66231 50312 66231 50281 66231 50312 66231 50282 66231 50282 66232 50312 66232 50283 66232 50282 66233 50283 66233 50285 66233 50285 66234 50283 66234 50284 66234 50285 66235 50284 66235 50286 66235 50286 66236 50284 66236 50288 66236 50286 66237 50288 66237 50287 66237 50287 66238 50288 66238 50321 66238 50287 66239 50321 66239 50289 66239 50289 66240 50321 66240 50320 66240 50289 66241 50320 66241 50290 66241 50290 66242 50320 66242 50291 66242 50290 66243 50291 66243 50292 66243 50292 66244 50291 66244 50316 66244 50292 66245 50316 66245 50293 66245 50293 66246 50316 66246 50315 66246 50293 66247 50315 66247 50294 66247 50294 66248 50315 66248 50295 66248 50294 66249 50295 66249 50296 66249 50296 66250 50295 66250 50314 66250 50296 66251 50314 66251 50297 66251 50297 66252 50314 66252 50311 66252 50297 66253 50311 66253 50298 66253 50298 66254 50311 66254 50299 66254 50298 66255 50299 66255 50300 66255 50300 66256 50299 66256 50301 66256 50300 66257 50301 66257 50270 66257 50270 66258 50301 66258 50313 66258 50302 66259 50322 66259 50303 66259 50303 66260 50322 66260 50323 66260 50304 66261 50302 66261 50305 66261 50305 66262 50302 66262 50303 66262 50324 66263 50306 66263 50325 66263 50325 66264 50306 66264 50319 66264 50306 66265 50307 66265 50319 66265 50319 66266 50307 66266 50308 66266 50307 66267 50304 66267 50308 66267 50308 66268 50304 66268 50305 66268 50305 590 50309 590 50308 590 50308 66269 50309 66269 50277 66269 50308 66270 50277 66270 50310 66270 50325 66271 50299 66271 50311 66271 50283 590 50312 590 50305 590 50305 66272 50312 66272 50280 66272 50305 66273 50280 66273 50309 66273 50299 66274 50325 66274 50301 66274 50301 590 50325 590 50319 590 50301 66275 50319 66275 50313 66275 50311 590 50314 590 50325 590 50325 66276 50314 66276 50295 66276 50325 590 50295 590 50323 590 50323 66277 50295 66277 50315 66277 50323 66278 50315 66278 50316 66278 50283 66279 50305 66279 50284 66279 50284 66280 50305 66280 50303 66280 50284 66281 50303 66281 50288 66281 50310 590 50317 590 50308 590 50308 66282 50317 66282 50318 66282 50308 590 50318 590 50319 590 50319 66283 50318 66283 50271 66283 50319 66284 50271 66284 50313 66284 50316 590 50291 590 50323 590 50323 66285 50291 66285 50320 66285 50323 66286 50320 66286 50303 66286 50303 66287 50320 66287 50321 66287 50303 66288 50321 66288 50288 66288 50322 66289 50324 66289 50323 66289 50323 66290 50324 66290 50325 66290 50358 66291 50377 66291 50326 66291 50326 66292 50377 66292 50376 66292 50326 66293 50376 66293 50327 66293 50327 66294 50376 66294 50328 66294 50327 66295 50328 66295 50329 66295 50329 66296 50328 66296 50375 66296 50329 66297 50375 66297 50330 66297 50330 66298 50375 66298 50374 66298 50330 66299 50374 66299 50331 66299 50331 66300 50374 66300 50333 66300 50331 66301 50333 66301 50332 66301 50332 66302 50333 66302 50373 66302 50332 66303 50373 66303 50334 66303 50334 66304 50373 66304 50372 66304 50334 66305 50372 66305 50335 66305 50335 66306 50372 66306 50371 66306 50335 66307 50371 66307 50336 66307 50336 66308 50371 66308 50369 66308 50336 66309 50369 66309 50337 66309 50337 66310 50369 66310 50368 66310 50337 66311 50368 66311 50338 66311 50338 66312 50368 66312 50380 66312 50338 66313 50380 66313 50339 66313 50339 66314 50380 66314 50340 66314 50339 66315 50340 66315 50341 66315 50341 66316 50340 66316 50342 66316 50341 66317 50342 66317 50344 66317 50344 66318 50342 66318 50343 66318 50344 66319 50343 66319 50346 66319 50346 66320 50343 66320 50345 66320 50346 66321 50345 66321 50347 66321 50347 66322 50345 66322 50348 66322 50347 66323 50348 66323 50349 66323 50349 66324 50348 66324 50379 66324 50349 66325 50379 66325 50350 66325 50350 66326 50379 66326 50352 66326 50350 66327 50352 66327 50351 66327 50351 66328 50352 66328 50353 66328 50351 66329 50353 66329 50354 66329 50354 66330 50353 66330 50356 66330 50354 66331 50356 66331 50355 66331 50355 66332 50356 66332 50357 66332 50355 66333 50357 66333 50358 66333 50358 66334 50357 66334 50377 66334 50362 66335 50359 66335 50360 66335 50360 66336 50359 66336 50361 66336 50367 66337 50362 66337 50370 66337 50370 66338 50362 66338 50360 66338 50381 66339 50363 66339 50378 66339 50378 66340 50363 66340 50364 66340 50363 66341 50365 66341 50364 66341 50364 66342 50365 66342 50366 66342 50365 66343 50367 66343 50366 66343 50366 66344 50367 66344 50370 66344 50380 590 50368 590 50360 590 50360 66345 50368 66345 50370 66345 50370 66346 50368 66346 50369 66346 50370 66347 50369 66347 50371 66347 50371 590 50372 590 50370 590 50370 66348 50372 66348 50373 66348 50370 590 50373 590 50366 590 50366 66349 50373 66349 50333 66349 50366 66350 50333 66350 50374 66350 50376 590 50364 590 50328 590 50328 66351 50364 66351 50366 66351 50328 66352 50366 66352 50375 66352 50375 590 50366 590 50374 590 50376 590 50377 590 50364 590 50364 590 50377 590 50357 590 50364 590 50357 590 50378 590 50378 66353 50357 66353 50356 66353 50378 66354 50356 66354 50353 66354 50353 590 50352 590 50378 590 50378 66355 50352 66355 50379 66355 50378 590 50379 590 50361 590 50361 66356 50379 66356 50348 66356 50361 66357 50348 66357 50345 66357 50345 590 50343 590 50361 590 50361 66358 50343 66358 50342 66358 50361 590 50342 590 50360 590 50360 66359 50342 66359 50340 66359 50360 590 50340 590 50380 590 50359 66360 50381 66360 50361 66360 50361 66361 50381 66361 50378 66361 50382 66362 15576 66362 50383 66362 50383 590 15576 590 15568 590 46047 66363 50384 66363 50386 66363 50386 66364 50384 66364 50385 66364 50386 66365 50385 66365 50387 66365 50387 66366 50385 66366 50388 66366 50387 66367 50388 66367 50390 66367 50390 66368 50388 66368 50389 66368 50390 66369 50389 66369 50391 66369 50391 66369 50389 66369 50392 66369 50391 66370 50392 66370 50393 66370 50393 66371 50392 66371 50394 66371 50393 66372 50394 66372 50395 66372 50395 66373 50394 66373 50396 66373 50395 66374 50396 66374 50398 66374 50398 66374 50396 66374 50397 66374 50398 66375 50397 66375 50399 66375 50399 66376 50397 66376 50401 66376 50399 66377 50401 66377 50400 66377 50400 66378 50401 66378 50402 66378 50400 66379 50402 66379 50403 66379 50403 66380 50402 66380 46048 66380 50403 66381 46048 66381 50404 66381 50405 66382 50407 66382 50753 66382 50405 66383 50406 66383 50407 66383 50409 66384 50408 66384 50421 66384 50409 66385 50421 66385 50410 66385 50410 66386 50421 66386 50411 66386 50412 66387 50429 66387 50421 66387 50412 66388 50421 66388 50413 66388 50413 66389 50421 66389 50408 66389 50415 66390 50414 66390 50763 66390 50415 66391 50763 66391 50421 66391 50421 66392 50763 66392 50416 66392 50421 66393 50416 66393 50411 66393 50421 66394 50419 66394 50417 66394 50421 66395 50417 66395 50418 66395 50420 66396 50419 66396 50421 66396 50420 66397 50421 66397 50422 66397 50422 66398 50421 66398 50423 66398 50424 66399 50423 66399 50421 66399 50424 66400 50421 66400 50425 66400 50425 66401 50421 66401 50426 66401 50427 66402 50426 66402 50421 66402 50427 66403 50421 66403 50428 66403 50428 66404 50421 66404 50429 66404 50431 66405 50430 66405 50439 66405 50439 66406 50430 66406 50437 66406 50432 66407 50431 66407 50439 66407 50432 66408 50439 66408 50433 66408 50433 66409 50439 66409 50688 66409 50435 66410 50434 66410 50439 66410 50435 66411 50439 66411 50436 66411 50436 66412 50439 66412 50437 66412 50438 66413 50695 66413 50439 66413 50438 66414 50439 66414 50440 66414 50440 66415 50439 66415 50434 66415 50441 66416 50439 66416 50442 66416 50703 66417 50442 66417 50439 66417 50703 66418 50439 66418 50443 66418 50443 66419 50439 66419 50444 66419 50445 66420 50444 66420 50439 66420 50445 66421 50439 66421 50446 66421 50446 66422 50439 66422 50447 66422 50448 66423 50447 66423 50439 66423 50448 66424 50439 66424 50449 66424 50449 66425 50439 66425 50695 66425 50451 66426 50450 66426 50470 66426 50521 66427 50452 66427 50453 66427 50473 66428 50471 66428 50458 66428 50456 66429 50461 66429 50462 66429 50479 66430 50537 66430 50454 66430 50479 66431 50454 66431 50455 66431 50455 66432 50454 66432 50487 66432 50456 66433 50462 66433 50457 66433 50456 66434 50457 66434 50494 66434 50494 66435 50457 66435 50491 66435 50473 66436 50458 66436 50459 66436 50473 66437 50459 66437 50460 66437 50460 66438 50459 66438 50467 66438 50461 66439 50458 66439 50471 66439 50461 66440 50471 66440 50462 66440 50462 66441 50471 66441 50525 66441 50463 66442 50543 66442 50457 66442 50463 66443 50457 66443 50542 66443 50542 66444 50457 66444 50462 66444 50542 66445 50462 66445 50526 66445 50526 66446 50462 66446 50525 66446 50528 66447 50464 66447 50473 66447 50520 66448 50521 66448 50453 66448 50520 66449 50453 66449 50476 66449 50476 66450 50453 66450 50466 66450 50528 66451 50473 66451 50460 66451 50528 66452 50460 66452 50517 66452 50517 66453 50460 66453 50465 66453 50452 66454 50465 66454 50460 66454 50452 66455 50460 66455 50453 66455 50453 66456 50460 66456 50467 66456 50453 66457 50467 66457 50466 66457 50466 66458 50467 66458 50468 66458 50466 66459 50468 66459 50495 66459 50495 66460 50468 66460 50469 66460 50495 66461 50469 66461 50470 66461 50470 66462 50469 66462 50451 66462 50524 66463 50525 66463 50471 66463 50524 66464 50471 66464 50532 66464 50532 66465 50471 66465 50531 66465 50529 66466 50531 66466 50471 66466 50529 66467 50471 66467 50472 66467 50472 66468 50471 66468 50473 66468 50472 66469 50473 66469 50474 66469 50474 66470 50473 66470 50464 66470 50495 66471 50475 66471 50535 66471 50495 66472 50535 66472 50466 66472 50466 66473 50535 66473 50518 66473 50466 66474 50518 66474 50476 66474 50478 66475 50486 66476 50477 66477 50478 66478 50477 66478 50481 66478 50539 66479 50537 66479 50479 66479 50539 66480 50479 66480 50541 66480 50541 66481 50479 66481 50455 66481 50541 66482 50455 66482 50480 66482 50480 66483 50455 66483 50506 66483 50482 66484 50481 66484 50477 66484 50482 66485 50477 66485 50483 66485 50483 66486 50477 66486 50485 66486 50483 66487 50485 66487 50484 66487 50484 66488 50485 66488 50488 66488 50484 66489 50488 66489 50504 66489 50504 66490 50488 66490 50503 66490 50510 66491 50503 66491 50488 66491 50510 66492 50488 66492 50509 66492 50509 66493 50488 66493 50498 66493 50509 66494 50498 66494 50508 66494 50486 66495 50506 66495 50455 66495 50486 66496 50455 66496 50477 66496 50477 66497 50455 66497 50487 66497 50477 66498 50487 66498 50485 66498 50485 66499 50487 66499 50489 66499 50485 66500 50489 66500 50488 66500 50488 66501 50489 66501 50490 66501 50488 66502 50490 66502 50498 66502 50498 66503 50490 66503 50492 66503 50498 66504 50492 66504 50491 66504 50491 66505 50492 66505 50493 66505 50491 66506 50493 66506 50494 66506 50533 66507 50475 66507 50495 66507 50533 66508 50495 66508 50496 66508 50496 66509 50495 66509 50470 66509 50496 66510 50470 66510 50536 66510 50536 66511 50470 66511 50450 66511 50491 66512 50515 66512 50497 66512 50491 66513 50497 66513 50498 66513 50498 66514 50497 66514 50507 66514 50498 66515 50507 66515 50508 66515 50514 66516 50515 66516 50491 66516 50514 66517 50491 66517 50511 66517 50511 66518 50491 66518 50512 66518 50513 66519 50512 66519 50491 66519 50513 66520 50491 66520 50499 66520 50499 66521 50491 66521 50457 66521 50499 66522 50457 66522 50544 66522 50544 66523 50457 66523 50543 66523 50510 66524 50602 66524 50500 66524 50510 66525 50500 66525 50503 66525 50503 66526 50500 66526 50501 66526 50482 66527 50505 66527 50502 66527 50482 66528 50502 66528 50481 66528 50481 66529 50502 66529 50600 66529 50504 66530 50503 66530 50501 66530 50504 66531 50501 66532 50484 66533 50484 66534 50501 66534 50505 66534 50484 66535 50505 66535 50483 66535 50483 66536 50505 66536 50482 66536 50478 66537 50481 66537 50600 66537 50478 66538 50600 66538 50486 66538 50486 66539 50600 66539 50637 66539 50486 66540 50637 66540 50506 66540 50506 66541 50637 66541 50540 66541 50507 66542 50608 66542 50603 66542 50507 66543 50603 66543 50508 66543 50508 66544 50603 66544 50602 66544 50508 66545 50602 66545 50509 66545 50509 66546 50602 66546 50510 66546 50640 66547 50511 66547 50512 66547 50640 66548 50512 66548 50643 66548 50643 66549 50512 66549 50513 66549 50514 66550 50511 66550 50640 66550 50514 66551 50640 66551 50515 66551 50515 66552 50640 66552 50608 66552 50515 66553 50608 66553 50497 66553 50497 66554 50608 66554 50507 66554 50534 66555 50519 66555 50518 66555 50465 66556 50516 66556 50609 66556 50465 66557 50609 66557 50517 66557 50517 66558 50609 66558 50527 66558 50476 66559 50518 66559 50519 66559 50476 66560 50519 66560 50520 66560 50520 66561 50519 66561 50611 66561 50520 66562 50611 66562 50521 66562 50521 66563 50611 66563 50516 66563 50521 66564 50516 66564 50452 66564 50452 66565 50516 66565 50465 66565 50522 66566 50542 66566 50526 66566 50522 66567 50526 66567 50523 66567 50532 66568 50530 66568 50615 66568 50532 66569 50615 66569 50524 66569 50524 66570 50615 66570 50523 66570 50524 66571 50523 66571 50525 66571 50525 66572 50523 66572 50526 66572 50528 66573 50517 66573 50527 66573 50528 66574 50527 66574 50464 66574 50464 66575 50527 66575 50620 66575 50464 66576 50620 66576 50474 66576 50474 66577 50620 66577 50621 66577 50474 66578 50621 66578 50472 66578 50472 66579 50621 66579 50622 66579 50472 66580 50622 66580 50529 66580 50529 66581 50622 66581 50530 66581 50529 66582 50530 66582 50531 66582 50531 66583 50530 66584 50532 66585 50628 66586 50624 66586 50496 66586 50533 66587 50496 66587 50624 66587 50533 66588 50624 66588 50475 66588 50475 66589 50624 66589 50534 66589 50475 66590 50534 66590 50535 66590 50535 66591 50534 66591 50518 66591 50451 66592 50631 66592 50634 66592 50451 66593 50634 66593 50450 66593 50450 66594 50634 66594 50628 66594 50450 66595 50628 66595 50536 66595 50536 66596 50628 66596 50496 66596 50538 66597 50537 66597 50539 66597 50538 66598 50539 66598 50635 66598 50635 66599 50539 66599 50541 66599 50635 66600 50541 66600 50540 66600 50540 66601 50541 66601 50480 66601 50540 66602 50480 66602 50506 66602 50463 66603 50542 66603 50522 66603 50463 66604 50522 66605 50543 66606 50543 66607 50522 66607 50644 66607 50543 66608 50644 66608 50544 66608 50544 66609 50644 66609 50643 66609 50544 66610 50643 66610 50499 66610 50499 66611 50643 66611 50513 66611 50606 66612 50607 66612 50570 66612 50596 66613 50601 66613 50571 66613 50617 66614 50593 66614 50580 66614 50612 66615 50613 66615 50553 66615 50588 66616 50574 66616 50589 66616 50565 66617 50545 66617 50546 66617 50565 66618 50546 66618 50547 66618 50547 66619 50546 66619 50678 66619 50678 66620 50567 66620 50547 66620 50548 66621 50552 66621 50550 66621 50548 66622 50550 66622 50585 66622 50549 66623 50594 66623 50595 66623 50549 66624 50595 66624 50580 66624 50580 66625 50595 66625 50616 66625 50580 66626 50616 66626 50617 66626 50646 66627 50594 66627 50549 66627 50646 66628 50549 66628 50645 66628 50645 66629 50549 66629 50550 66629 50645 66630 50550 66630 50551 66630 50551 66631 50550 66631 50552 66631 50612 66632 50553 66632 50577 66632 50612 66633 50577 66633 50610 66633 50610 66634 50577 66634 50554 66634 50555 66635 50554 66635 50577 66635 50555 66636 50577 66636 50556 66636 50556 66637 50577 66637 50557 66637 50556 66638 50557 66638 50618 66638 50618 66639 50557 66639 50580 66639 50618 66640 50580 66640 50619 66640 50619 66641 50580 66641 50593 66641 50561 66642 50558 66642 50623 66642 50561 66643 50623 66643 50573 66643 50573 66644 50623 66644 50625 66644 50559 66645 50558 66645 50561 66645 50559 66646 50561 66646 50560 66646 50560 66647 50561 66647 50553 66647 50560 66648 50553 66648 50614 66648 50614 66649 50553 66649 50613 66649 50569 66650 50563 66650 50564 66650 50569 66651 50564 66651 50562 66651 50562 66652 50564 66652 50599 66652 50571 66653 50570 66653 50587 66653 50571 66654 50587 66654 50563 66654 50563 66655 50587 66655 50545 66655 50563 66656 50545 66656 50564 66656 50564 66657 50545 66657 50565 66657 50564 66658 50565 66658 50599 66658 50599 66659 50565 66659 50639 66659 50638 66660 50639 66660 50565 66660 50638 66661 50565 66661 50566 66661 50566 66662 50565 66662 50547 66662 50566 66663 50547 66663 50636 66663 50636 66664 50547 66664 50567 66664 50568 66665 50596 66665 50571 66665 50568 66666 50571 66666 50598 66666 50598 66667 50571 66667 50563 66667 50598 66668 50563 66668 50597 66668 50597 66669 50563 66669 50569 66669 50605 66670 50606 66670 50570 66670 50605 66671 50570 66671 50604 66671 50604 66672 50570 66672 50571 66672 50604 66673 50571 66673 50572 66673 50572 66674 50571 66674 50601 66674 50573 66675 50589 66675 50574 66675 50573 66676 50574 66676 50561 66676 50561 66677 50574 66677 50575 66677 50561 66678 50575 66678 50553 66678 50553 66679 50575 66679 50576 66679 50553 66680 50576 66680 50577 66680 50577 66681 50576 66681 50578 66681 50577 66682 50578 66682 50557 66682 50557 66683 50578 66683 50579 66683 50557 66684 50579 66684 50580 66684 50580 66685 50579 66685 50581 66685 50580 66686 50581 66686 50549 66686 50549 66687 50581 66687 50582 66687 50549 66688 50582 66688 50550 66688 50550 66689 50582 66689 50583 66689 50550 66690 50583 66690 50585 66690 50585 66691 50583 66691 50584 66691 50585 66692 50584 66692 50570 66692 50570 66693 50584 66693 50586 66693 50570 66694 50586 66694 50587 66694 50632 66695 50679 66695 50589 66695 50632 66696 50589 66696 50633 66696 50679 66697 50588 66697 50589 66697 50630 66698 50633 66698 50589 66698 50630 66699 50589 66699 50629 66699 50629 66700 50589 66700 50590 66700 50591 66701 50590 66701 50589 66701 50591 66702 50589 66702 50627 66702 50627 66703 50589 66703 50573 66703 50627 66704 50573 66704 50626 66704 50626 66705 50573 66705 50625 66705 50642 66706 50548 66706 50585 66706 50642 66707 50585 66707 50641 66707 50641 66708 50585 66708 50570 66708 50641 66709 50570 66709 50592 66709 50592 66710 50570 66710 50607 66710 50593 66711 50617 66711 50530 66711 50595 66712 50594 66712 50523 66712 50602 66713 50596 66713 50500 66713 50597 66714 50505 66714 50501 66714 50597 66715 50501 66715 50598 66715 50598 66716 50501 66716 50500 66716 50598 66717 50500 66717 50568 66717 50568 66718 50500 66718 50596 66718 50639 66719 50637 66719 50600 66719 50639 66720 50600 66720 50599 66720 50599 66721 50600 66721 50502 66721 50599 66722 50502 66722 50562 66722 50562 66723 50502 66723 50505 66723 50562 66724 50505 66725 50569 66726 50569 66727 50505 66727 50597 66727 50601 66728 50596 66728 50602 66728 50601 66729 50602 66729 50572 66729 50572 66730 50602 66730 50603 66730 50572 66731 50603 66731 50604 66731 50604 66732 50603 66732 50608 66732 50604 66733 50608 66733 50605 66733 50605 66734 50608 66734 50606 66734 50607 66735 50606 66735 50608 66735 50607 66736 50608 66736 50592 66736 50592 66737 50608 66737 50640 66737 50560 66738 50519 66738 50534 66738 50560 66739 50534 66739 50559 66739 50559 66740 50534 66740 50558 66740 50556 66741 50527 66741 50555 66741 50555 66742 50527 66742 50609 66742 50555 66743 50609 66744 50554 66745 50554 66746 50609 66746 50516 66746 50610 66747 50554 66747 50516 66747 50610 66748 50516 66748 50612 66748 50612 66749 50516 66749 50611 66749 50612 66750 50611 66750 50613 66750 50613 66751 50611 66751 50519 66751 50613 66752 50519 66752 50614 66752 50614 66753 50519 66753 50560 66753 50595 66754 50523 66754 50615 66754 50595 66755 50615 66755 50530 66755 50595 66756 50530 66756 50616 66756 50616 66757 50530 66757 50617 66757 50527 66758 50556 66758 50618 66758 50527 66759 50618 66759 50620 66759 50620 66760 50618 66761 50619 66762 50620 66763 50619 66763 50621 66763 50621 66764 50619 66764 50593 66764 50621 66765 50593 66765 50622 66765 50622 66766 50593 66766 50530 66766 50623 66767 50558 66767 50534 66767 50623 66768 50534 66768 50625 66768 50625 66769 50534 66769 50624 66769 50625 66770 50624 66770 50628 66770 50625 66771 50628 66771 50626 66771 50626 66772 50628 66772 50627 66772 50591 66773 50627 66773 50628 66773 50591 66774 50628 66774 50590 66774 50590 66775 50628 66775 50634 66775 50590 66776 50634 66776 50629 66776 50629 66777 50634 66777 50630 66777 50631 66778 50679 66778 50632 66778 50631 66779 50632 66779 50634 66779 50634 66780 50632 66780 50633 66780 50634 66781 50633 66781 50630 66781 50538 66782 50635 66782 50678 66782 50567 66783 50678 66783 50635 66783 50567 66784 50635 66784 50636 66784 50636 66785 50635 66785 50540 66785 50636 66786 50540 66786 50566 66786 50566 66787 50540 66787 50637 66787 50566 66788 50637 66788 50638 66788 50638 66789 50637 66789 50639 66789 50641 66790 50592 66790 50640 66790 50641 66791 50640 66791 50642 66791 50642 66792 50640 66792 50643 66792 50642 66793 50643 66793 50548 66793 50548 66794 50643 66794 50644 66794 50552 66795 50548 66795 50644 66795 50552 66796 50644 66796 50551 66796 50551 66797 50644 66797 50522 66797 50551 66798 50522 66798 50645 66798 50645 66799 50522 66799 50523 66799 50645 66800 50523 66800 50646 66800 50646 66801 50523 66801 50594 66801 50729 66802 50706 66802 50709 66802 50729 66803 50709 66803 50654 66803 50714 66804 50647 66804 50648 66804 50714 66805 50648 66805 50712 66805 50712 66806 50648 66806 50650 66806 50712 66807 50650 66807 50649 66807 50649 66808 50650 66808 50652 66808 50649 66809 50652 66809 50651 66809 50651 66810 50652 66810 50653 66810 50651 66811 50653 66811 50655 66811 50655 66812 50653 66812 50654 66812 50655 66813 50654 66813 50656 66813 50656 66814 50654 66814 50709 66814 50658 960 50657 960 50706 960 50659 960 50658 960 50706 960 50659 960 50706 960 50660 960 50660 960 50706 960 50729 960 50660 66815 50729 66815 50661 66815 50661 960 50729 960 50662 960 50663 960 50662 960 50729 960 50663 960 50729 960 50664 960 50664 66816 50729 66816 50672 66816 50664 960 50672 960 50665 960 50665 960 50672 960 50671 960 50665 960 50671 960 50666 960 50666 960 50671 960 50667 960 50668 960 50667 960 50671 960 50668 960 50671 960 50669 960 50669 66817 50671 66817 50706 66817 50669 960 50706 960 50670 960 50670 960 50706 960 50657 960 50671 66818 50672 66818 50677 66818 50671 66819 50677 66819 50704 66819 50672 66820 50727 66820 50674 66820 50672 66821 50674 66821 50677 66821 50673 66822 50674 66822 50768 66822 50674 66823 50673 66823 50675 66823 50675 66824 50676 66824 50674 66824 50538 66825 50677 66825 50537 66825 50681 66826 50631 66826 50451 66826 50681 66827 50451 66827 50676 66827 50676 66828 50451 66828 50537 66828 50676 66829 50537 66829 50674 66829 50674 66830 50537 66830 50677 66830 50631 66826 50681 66826 50679 66826 50677 66825 50538 66825 50678 66825 50677 66831 50678 66831 50704 66831 50704 66832 50678 66832 50679 66832 50704 66833 50679 66833 50680 66833 50680 66834 50679 66834 50681 66834 50682 66835 50704 66835 50680 66835 50704 66836 50682 66836 50683 66836 50683 66837 50705 66837 50704 66837 50686 66838 50684 66838 50687 66838 50687 66839 50684 66839 50685 66839 50715 66840 50707 66840 50687 66840 50715 66841 50687 66841 50685 66841 50688 66842 50686 66842 50687 66842 50688 66843 50687 66843 50433 66843 50433 66844 50687 66844 50707 66844 50707 66845 50713 66845 50433 66845 50689 66846 50694 66846 50690 66846 50703 66847 50691 66847 50693 66847 50693 66848 50691 66848 50692 66848 50693 66849 50692 66849 50689 66849 50693 66850 50689 66850 50708 66850 50708 66851 50689 66851 50690 66851 50690 66852 50694 66852 50695 66852 50690 66853 50695 66853 50710 66853 50710 66854 50695 66854 50696 66854 50710 66855 50696 66855 50711 66855 50711 66856 50696 66856 50697 66856 50711 66857 50697 66857 50700 66857 50700 66858 50697 66858 50702 66858 50698 66859 50433 66859 50713 66859 50698 66860 50713 66860 50699 66860 50699 66861 50713 66861 50700 66861 50699 66862 50700 66862 50701 66862 50701 66863 50700 66863 50702 66863 50703 66864 50693 66864 50704 66864 50703 66865 50704 66865 50442 66865 50442 66866 50704 66866 50705 66866 50706 66867 50671 66867 50704 66867 50706 66868 50704 66868 50693 66868 50693 66869 50708 66869 50706 66869 50714 66870 50712 66870 50707 66870 50709 66871 50706 66871 50708 66871 50709 66872 50708 66872 50656 66872 50656 66873 50708 66873 50690 66873 50656 66874 50690 66874 50655 66874 50655 66875 50690 66875 50710 66875 50655 66876 50710 66876 50651 66876 50651 66877 50710 66877 50711 66877 50651 66878 50711 66878 50649 66878 50649 66879 50711 66879 50700 66879 50649 66880 50700 66880 50712 66880 50712 66881 50700 66881 50713 66881 50712 66882 50713 66882 50707 66882 50715 66883 50714 66883 50707 66883 50716 66884 50647 66884 50714 66884 50716 66885 50714 66885 50715 66885 50647 66886 50716 66886 50717 66886 50647 66887 50717 66887 50726 66887 50719 66888 50722 66888 50718 66888 50719 66889 50718 66889 50720 66889 50719 66890 50720 66890 50721 66890 50721 66891 50720 66891 50751 66891 50721 66892 50751 66892 50729 66892 50729 66802 50751 66802 50743 66802 50723 66893 50718 66893 50722 66893 50723 66894 50722 66894 50748 66894 50748 66895 50722 66895 50724 66895 50748 66896 50724 66896 50746 66896 50746 66897 50724 66897 50725 66897 50746 66898 50725 66898 50726 66898 50726 66899 50725 66899 50647 66899 50742 960 50727 960 50728 960 50733 960 50732 960 50729 960 50728 66900 50727 66900 50672 66900 50728 960 50672 960 50730 960 50730 66901 50672 66901 50729 66901 50730 66902 50729 66902 50731 66902 50731 66903 50729 66903 50732 66903 50734 960 50733 960 50729 960 50734 960 50729 960 50735 960 50735 960 50729 960 50743 960 50736 66904 50735 66904 50743 66904 50736 960 50743 960 50737 960 50737 960 50743 960 50738 960 50739 960 50738 960 50743 960 50739 66905 50743 66905 50740 66905 50740 960 50743 960 50727 960 50740 960 50727 960 50741 960 50741 960 50727 960 50742 960 50727 66906 50743 66906 50744 66906 50727 66907 50744 66907 50674 66907 50752 66908 50745 66908 50726 66908 50746 66909 50726 66909 50745 66909 50746 66910 50745 66910 50748 66910 50748 66911 50745 66911 50747 66911 50748 66912 50747 66912 50723 66912 50723 66913 50747 66913 50761 66913 50723 66914 50761 66914 50718 66914 50718 66915 50761 66915 50749 66915 50718 66916 50749 66916 50720 66916 50720 66917 50749 66917 50750 66917 50720 66918 50750 66918 50751 66918 50751 66919 50750 66919 50764 66919 50751 66920 50764 66920 50743 66920 50743 66921 50764 66921 50744 66921 50717 66922 50752 66922 50726 66922 50753 66923 50407 66923 50717 66923 50406 66924 50418 66924 50417 66924 50406 66925 50417 66925 50407 66925 50407 66926 50417 66926 50752 66926 50407 66927 50752 66927 50717 66927 50754 66928 50758 66928 50752 66928 50754 66929 50752 66929 50755 66929 50755 66930 50752 66930 50417 66930 50756 66931 50761 66931 50747 66931 50756 66932 50747 66932 50757 66932 50745 66933 50752 66933 50758 66933 50745 66934 50758 66934 50747 66934 50747 66935 50758 66935 50759 66935 50747 66936 50759 66936 50757 66936 50760 66937 50749 66937 50761 66937 50760 66938 50761 66938 50762 66938 50762 66939 50761 66939 50756 66939 50763 66940 50744 66940 50764 66940 50763 66941 50764 66941 50765 66941 50765 66942 50764 66942 50750 66942 50765 66943 50750 66943 50766 66943 50766 66944 50750 66944 50749 66944 50766 66945 50749 66945 50767 66945 50767 66946 50749 66946 50760 66946 50744 66947 50763 66947 50414 66947 50744 66948 50414 66948 50674 66948 50674 66949 50414 66949 50768 66949

+
+
+
+
+ + + + + 1 0 0 0 0 7.54979e-8 -1 0 0 1 7.54979e-8 0 0 0 0 1 + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/datasets/EuRoC_MAV/ros2_ws/src/euroc_slam/meshes/propeller_ccw_purple.dae b/datasets/EuRoC_MAV/ros2_ws/src/euroc_slam/meshes/propeller_ccw_purple.dae new file mode 100644 index 0000000..20ba033 --- /dev/null +++ b/datasets/EuRoC_MAV/ros2_ws/src/euroc_slam/meshes/propeller_ccw_purple.dae @@ -0,0 +1,90 @@ + + + + + Blender User + Blender 4.4.3 commit date:2025-04-29, commit time:14:09, hash:802179c51ccc + + 2025-06-29T16:23:03 + 2025-06-29T16:23:03 + + Z_UP + + + + + + + + 0 0 0 1 + + + 0.2015545 0.1470271 1 1 + + + 1.4 + + + + + + + + + + + + + + + + + -0.08357137 -0.140031 -0.07364559 -0.04984259 -0.421246 -0.05464208 -0.113511 -0.274039 -0.135752 -0.114702 -0.415125 -0.12953 -0.0746712 -0.825968 -0.01752549 -0.006384253 -0.650908 -0.007860422 -0.08786529 -0.651074 -0.06115299 0.02411299 -0.533313 -0.009510278 -0.004485666 -0.501709 -0.01888436 0.02989476 -0.965824 0.003342509 0.056674 -0.330572 -0.009868323 -0.04309499 -0.154126 -0.04547905 -0.001135528 -0.221271 -0.02289515 -0.0281136 -0.982709 0.005786299 0.01792007 -0.804511 0.004148125 0.0537911 -0.643416 -0.009041249 0.01270467 -0.08871167 -0.01068186 -0.05569106 0.06617146 -0.009633123 -0.001740574 0.08183485 -0.008683502 0.05587345 0.0659486 -0.009712874 0.113541 0.274172 -0.135785 0.05002099 0.443601 -0.05284029 0.114702 0.415126 -0.12953 0.08786499 0.651077 -0.06115216 0.07467055 0.825975 -0.01752436 0.07500165 0.975039 -0.009344518 -0.02411299 0.533313 -0.009510278 0.004387199 0.503608 -0.01880586 -0.02989256 0.965824 0.003343641 -0.0537911 0.643416 -0.009041249 -0.01791989 0.804512 0.004148125 -0.05746185 0.180075 -0.01048707 0.03759586 0.2035869 -0.04804205 -4.65212e-4 0.233604 -0.02185988 0.006384253 0.650907 -0.007860422 0.02811557 0.982719 0.005785882 0.005636513 0.123583 -0.140777 -0.01352626 0.104834 -0.06578278 -0.008937716 -0.12151 -0.03823006 0.01669639 -0.104368 -0.03856408 -0.01139456 -0.103689 -0.07061046 -0.02350908 -0.001719653 -0.126579 -0.02270388 0.852975 0.003909945 0.08989727 0.239197 -0.104766 0.06469625 0.513252 -0.06428438 0.01306509 0.698342 -0.004997551 -0.05181485 0.839194 -0.007662951 -0.01441615 0.525621 -0.01091027 -0.00491935 0.2193599 -0.01960456 0.02581328 0.234838 -0.03882688 0.03097367 0.441406 -0.03693485 0.02315187 -0.1180109 -0.01180338 -0.02513229 -0.102274 -0.01690846 0.02124375 -0.116969 -0.14857 0.005702793 -0.134397 -0.140058 -0.007970929 -0.08548545 -0.05241137 0.01413875 -0.0882616 -0.01229757 0.004915118 0.08468848 -0.03843736 0.01923799 0.127822 -0.02761846 -0.008259117 0.02590775 -0.04809045 0.02114057 0.01493579 -0.14038 0.01596206 -0.02784717 -0.009969472 0.01530045 0.07616269 -0.009242415 -0.004152774 -0.02592706 -0.04324597 -0.002245604 -0.01577097 -0.04894036 0.002544999 0.01094615 -0.03091675 -0.02556526 0.119737 -0.143772 -0.01976299 -0.118895 -0.152086 -0.0537343 -0.160254 -0.05635988 -0.07500165 -0.975039 -0.009344518 -0.04071539 -0.989476 0.001363396 0.02274048 -0.85053 0.003789126 0.05181485 -0.839194 -0.007662951 -0.02601414 -0.279747 -0.03863978 -0.02280759 -0.525923 -0.02692067 0.0238769 -0.383433 -0.01485514 -0.006653904 -0.855493 0.005400896 -0.02521896 -9.5966e-4 -0.009703278 0.02526098 0.104341 -0.1522189 -0.004465639 0.0936833 -0.146062 -0.004475712 -0.09316939 -0.142415 0.01738977 -0.08933287 -0.135902 -0.05395716 -0.701021 -0.02630597 -0.104818 -0.545401 -0.0968858 -0.08082765 -0.780351 -0.02766716 -0.07623398 -0.898608 -0.01278054 0.05355197 -0.950918 -0.007589936 0.01210075 -0.591485 -0.007279276 0.05800127 -0.596443 -0.009949684 -0.09369957 -0.203884 -0.08886867 -0.09207588 -0.704367 -0.03806626 -0.07087057 -0.465201 -0.07459056 -0.124309 -0.39154 -0.1281329 0.05621486 -0.618315 3.61391e-4 0.05580097 -0.1858699 -3.02646e-4 0.03031265 -0.955269 0.01302218 0.05731767 -0.951992 -4.06283e-5 0.05838209 -0.07186806 -2.54228e-4 -0.05585819 -0.06658595 -0.009723842 -0.118004 -0.364506 -0.138633 -0.108654 -0.285812 -0.127115 -0.105771 -0.219694 -0.119224 0.0559017 -0.05887275 -0.009658515 0.009496212 -0.07469969 4.02485e-4 -0.05847799 -0.06418055 -4.29309e-6 0.0762335 0.898779 -0.01276886 0.118975 0.372814 -0.139636 0.04087787 0.989495 0.001317739 -0.05334836 0.950983 -0.00752902 0.08204609 0.76524 -0.03049999 0.083117 0.138354 -0.0731762 0.08804827 0.743603 -0.02757126 -0.05731767 0.951992 -4.06283e-5 -0.02968448 0.956045 0.01264089 0.07118469 0.139598 -0.05544304 0.05826526 0.07324856 -0.00292778 0.104825 0.545342 -0.09690028 -0.05840498 0.254076 -0.009581387 -0.05636346 0.558111 -0.009766757 0.01019978 0.09296905 -8.44993e-4 -9.75602e-4 -0.140125 -0.02252715 -0.004225373 -0.205437 -0.02482235 -0.006746888 0.07961887 -0.06490367 -0.008473753 0.07539319 -0.008508503 0.01403909 0.02056425 -0.01045829 -0.01035904 0.1718389 -0.005759954 -0.05781835 0.06625831 -1.51025e-4 -0.04920077 0.410316 -7.90412e-4 0.03791308 1.00303 0.01297837 0.08138436 0.885023 -0.00491482 0.118766 0.442389 -0.1158789 0.06292277 0.518668 -0.04692286 0.126334 0.293997 -0.136557 0.05210298 0.2456899 -0.04788094 0.01034718 0.4132 -0.01469397 -0.05018508 0.589529 9.47399e-4 0.02894824 0.672397 -0.004935443 -0.02322369 0.568443 0.002280354 -0.006842434 0.801128 0.01595836 -0.02066528 0.127101 -0.009004652 -0.005914211 -0.486521 -0.008993983 -0.03800916 -1.00287 0.01289409 -0.1222079 -0.283356 -0.130685 -0.03316658 -0.121489 -0.02041786 -0.05146765 -0.26177 -0.04790687 -0.06078189 -0.534174 -0.04289525 0.005785644 -0.220441 -0.0104773 0.04920077 -0.410316 -7.90412e-4 -0.003093421 -0.647823 0.003427028 -0.08106648 -0.84862 -0.007434844 0.003467977 -0.808683 0.01592606 0.01608777 0.104192 -0.04741775 -0.008073508 0.122668 -0.03704249 + + + + + + + + + + -0.5063766 -0.02654135 0.861904 -0.2561631 0.0544551 0.9650985 -0.02502733 0.07398051 0.9969456 0.04262155 -0.00182563 0.9990897 -0.787692 -0.001235306 0.6160681 -0.6074824 -0.2182466 0.7637628 -0.4951817 -0.01728755 0.8686174 -0.5394257 0.06887161 0.839212 -0.7540056 0.03529155 0.6559192 -0.7474553 0.1050762 0.6559494 -0.5400907 0.1651149 0.8252509 -0.2771843 0.05326265 0.9593394 -0.1903482 0.01631236 0.9815811 0.1555908 0.04614269 0.9867434 -0.2664306 0.04449021 0.9628268 0.3482323 0.02116984 0.9371693 0.3320552 0.003288745 0.9432543 -0.005797445 0.00269711 0.9999796 -0.02310597 -8.37758e-4 0.9997327 -0.3160503 -0.05427068 0.947189 -0.5984382 0.01860415 0.8009529 -0.546244 0.06671637 0.834965 -0.1631705 0.05120933 0.9852681 -0.2840583 0.05796569 0.9570533 -0.3480801 0.03593325 0.936776 0.001978516 -0.03713738 0.9993082 -0.6139588 -0.3735313 0.6953625 -0.1130124 -0.3897746 0.9139497 7.15614e-4 4.35905e-4 0.9999997 -5.37792e-4 -6.82675e-4 0.9999997 0.1816256 0.6086464 0.772374 5.88414e-4 -0.062536 0.9980427 0.5683009 0.08108615 0.8188157 0.257855 -0.05447107 0.9646469 0.02246606 -0.07438749 0.9969764 -0.04259389 0.001821219 0.9990908 0.6646189 0.184848 0.7239565 0.5357984 -0.06979107 0.8414567 0.7664235 -0.02684646 0.6417744 0.7574722 -0.03516882 0.6519196 0.7397353 -0.1083229 0.6641218 0.5400924 -0.1651114 0.8252506 0.2771921 -0.05325907 0.9593373 -0.1555902 -0.04614251 0.9867435 -0.3482325 -0.02117222 0.9371691 -0.3320537 -0.003288745 0.9432548 0.004106462 -0.003152906 0.9999866 0.2822207 -0.02929586 0.9589022 0.2090194 -0.01481622 0.9777993 -0.01968544 0.007189273 0.9997804 0.5994701 0.06422746 0.797816 0.1176777 0.08491063 0.9894151 0.5600346 -0.01243162 0.828376 0.5810082 -0.01964491 0.8136606 0.5462601 -0.0661872 0.8349965 0.1631781 -0.05120795 0.9852668 0.2840475 -0.05796378 0.9570566 0.3472915 -0.03620535 0.9370582 -0.8846099 0.4524528 -0.1129236 0.6290682 0.7721284 0.08995157 -0.4929583 0.7458968 0.4479176 -0.1266317 0.9831503 0.1318331 0.6706963 0.7395397 -0.056988 0.5530956 -0.8248124 0.1173446 -0.8001524 -0.5490462 -0.241463 -0.8902644 0.3382073 0.3050332 -0.7668218 0.4173959 0.4876117 -0.9130268 -0.1026079 0.3947832 -0.9022585 -0.3207336 0.2882009 0.7146323 0.6840231 0.146332 0.9002432 0.4018454 0.167579 -0.9646869 -0.004684388 0.263358 0.5079121 0.0588026 0.8593996 0.7158573 0.02908402 0.6976406 -0.02455437 0.003803908 0.9996913 0.9722998 0.2287868 -0.04785323 0.6830106 -0.04302632 0.7291401 0.4292867 -0.100491 0.8975602 0.7178507 -0.03668403 0.69523 0.6592679 -0.02335315 0.7515456 0.7970223 -0.01588964 0.6037409 0.4667906 -0.1490125 0.8717235 0.2831407 -0.0384581 0.9583071 0.1091668 -0.0319783 0.9935089 0.532979 -0.007492244 0.8460953 0.1698924 -0.02270019 0.9852012 -0.3618379 -0.01837271 0.93206 -0.416996 -0.006809175 0.9088828 -0.007953047 -0.04542601 0.9989361 0.02757871 4.24384e-4 0.9996196 -0.2921757 0.158231 0.9431842 0.3648033 -0.0897684 0.9267472 0.4693852 -0.01981145 0.8827713 0.0596975 -0.04363751 0.9972622 0.2651395 -0.04621821 0.9631018 -0.6792315 0.7337695 0.01506668 -0.9566912 -0.2902227 -0.02264714 -0.9895223 -0.1438199 0.01270955 0.4942455 0.8664742 0.07031291 0.7976647 -0.5939413 0.1047127 -0.1336385 -0.9910171 0.005074381 -0.7487994 0.6627175 -0.01025032 -0.03680652 -0.03737127 0.9986234 -0.4100429 -0.5058207 0.7589535 -0.9349218 0.3377496 -0.1088417 -0.9019961 0.2040873 0.380462 0.855598 -0.5173972 0.01588189 -0.2751775 -0.9610257 0.02659261 0.7689499 0.6392697 0.007092773 0.1636962 0.6147019 0.7715862 0.5594852 0.2132793 0.8009296 0.4995365 0.2562861 0.8275148 -0.007449328 4.34049e-4 0.9999722 -0.02757048 0.008996903 0.9995794 0.006054341 -0.02200043 0.9997397 0.1493045 -0.07001596 0.9863093 7.9346e-4 -6.84351e-4 0.9999995 -0.02168536 -0.01088762 0.9997057 -0.997797 -0.04016751 -0.05279928 0.04273188 -0.9976819 0.05296188 0.8478156 0.526244 0.06539237 -0.5060456 0.8605446 0.05814558 -0.987651 0.04385817 0.1504065 0.9801895 0.1975204 0.014647 0.5265773 0.003673434 -0.8501194 -0.4626699 -0.01931154 0.8863204 -0.3972007 -0.01163607 0.917658 -0.7268374 -0.06725209 0.683509 -0.5988584 -0.2271306 0.7679716 -0.7474559 -0.04649734 0.6626823 -0.694957 0.09606373 0.7126054 0.06241977 -0.04591226 0.9969935 -0.3523842 0.1033991 0.9301258 -0.2830752 0.03851866 0.958324 0.3600898 0.01873135 0.9327296 0.4158139 0.007059574 0.9094223 0.06288373 0.04518246 0.9969976 0.06158322 0.03283894 0.9975616 -0.06160539 -0.002083837 0.9980985 -0.5368998 5.57159e-4 0.8436459 -0.643665 -0.1873664 0.7420171 -0.7315927 0.04508447 0.6802496 -0.6874805 0.02559417 0.7257517 -0.407267 0.05624562 0.9115757 -0.3616915 0.03963023 0.9314553 0.04719078 0.0445761 0.9978908 -0.6235638 0.1136462 0.7734681 -0.3837379 0.07149833 0.92067 -0.4400901 0.1106169 0.8911143 -0.2906218 0.06649094 0.9545251 -0.2765139 0.04136323 0.9601194 0.9401355 -0.21038 0.2681148 0.7174015 0.6937342 0.06378006 -0.6634045 -0.7405015 0.1074798 0.3426035 -0.9390431 0.0286526 -0.3049767 0.9397791 0.1542875 0.7761545 0.6172512 0.1287837 -0.7771327 -0.6293368 -2.96322e-4 -0.1392037 0.9684817 0.2065563 0.1201542 -0.9924949 0.02273702 -0.09725207 0.5054605 0.8573516 0.03071355 -0.9831268 0.1803289 -0.8583922 0.5129383 -0.007564902 0.8438764 -0.5308245 0.07808959 0.146116 -0.9851849 0.08978271 -0.187367 -0.4307873 0.8827888 0.9003378 0.01288366 0.435001 0.9654536 -0.001393318 0.2605711 -0.7999206 0.007214426 0.6000625 -0.6095406 -0.2588474 0.7493053 -0.5681321 0.1786528 0.8033114 0.5359399 0.03845101 -0.84338 0.8829144 0.03528416 0.4682066 0.04130703 0.6566475 0.7530658 -0.195273 0.07210451 0.9780949 0.9919516 0.06198096 -0.1104111 -0.04446381 -0.01160722 0.9989436 -0.1491248 -0.001118004 0.9888178 0.3666809 -5.80738e-4 0.9303466 -0.9682472 -0.003917098 0.2499641 0.2089282 0.003887653 0.9779233 0.9226971 0.3497724 0.1621403 0.06109297 0.358763 -0.9314272 0.9420785 -0.1939796 -0.2736057 0.4543955 0.3475617 -0.8201987 0.9448888 0.1775228 0.2750836 0.7106929 0.1976109 0.6751782 -0.271429 -0.1077343 0.9564098 0.9425649 -0.07173103 -0.3262305 0.9387666 -0.0683946 -0.3376972 0.8627394 -0.004827439 0.5056259 0.6639589 -0.1429104 -0.7339859 0.5725545 -0.1282539 -0.8097732 -0.6568169 0.06928485 0.7508603 0.9486161 0.1738634 0.2643843 -0.01057529 0.01786923 -0.9997845 -0.3992544 0.628214 -0.6677898 -0.3950151 0.8613055 0.319556 0.1212425 -0.001408159 -0.992622 -0.8939527 0.01420265 0.4479362 -0.4354152 -3.54429e-4 -0.9002298 -0.04807049 -0.00715202 -0.9988183 0.08278346 -0.001451015 -0.9965666 -0.01347464 7.29751e-4 -0.999909 -0.9996662 0.001202702 -0.02580982 -0.3053323 1.38162e-4 -0.9522459 -0.2154756 -0.02011984 -0.976302 0.9682728 0.06788712 0.2404978 -0.3042889 0.4057152 0.8618606 -0.2706817 -0.1024369 0.9572034 -0.3880661 0.555013 0.7357754 -0.05083411 -0.01843762 -0.9985369 -0.0130043 -0.007384717 -0.9998882 0.004829585 -0.007460057 -0.9999606 -0.00977987 -0.001075387 -0.9999517 -0.8096391 -0.2591603 -0.5266124 -0.9427679 0.3324826 -0.02538049 -0.9430956 -6.81558e-5 0.3325218 -0.9655426 0.004016935 0.2602144 0.3947334 0.2503853 0.8840209 -0.9098519 -0.2034486 0.3616325 0.6904554 -0.1426193 0.7091764 -0.5577566 -0.08020192 -0.8261207 -0.8637861 -0.03651815 0.5025336 -0.04353445 -0.6575406 0.7521603 0.1903445 -0.07005679 0.9792146 -0.9969646 -0.06373298 -0.04471999 0.1857047 0.002411365 0.9826027 -0.3690202 -9.84833e-4 0.929421 -0.2057546 -0.003994882 0.9785954 -0.2659916 -0.5658881 -0.7803969 -0.7405124 -0.08567708 -0.6665591 -0.8295627 0.002949476 -0.5584058 -0.6893563 0.138181 -0.7111216 0.6539692 -0.05059278 0.7548276 -0.9402019 -0.1805564 0.2888247 0.01802355 -0.01874989 -0.9996618 0.3989396 -0.6273522 -0.6687873 0.3937089 -0.8600286 0.324568 -0.08073532 1.69871e-4 -0.9967356 0.01292103 -0.05883669 -0.9981841 0.6587721 0.01091283 -0.7522636 0.9973257 -5.54665e-4 -0.07308387 0.9405357 -0.006108283 0.3396401 0.4163987 0.005715668 -0.9091643 -0.9008094 -0.09545385 0.4235931 0.4339372 -0.2899629 0.8530065 -0.9697024 -0.08154338 0.2302781 0.5787028 0.08571511 0.8110217 -0.7816755 -0.1344046 0.6090313 0.3813737 -0.5540005 0.7400255 0.8829845 -0.009449601 0.4693071 0.9863836 -0.005172789 -0.1643795 -0.8761643 -0.01795625 0.4816782 -0.8489176 0.1052056 0.5179485 -0.9154825 0.1434491 0.3759179 0.4220476 0.03206223 0.9060066 0.9147675 -0.1180962 0.3863338 0.8330415 -0.0385344 0.5518668 0.9993937 -0.01900428 0.02917826 -0.8556324 0.005878984 0.5175507 -0.9407808 0.01393651 0.3387291 -0.6397441 -0.06045007 -0.7662072 -0.4116777 -0.1631858 -0.8966002 -0.04422503 -0.03316438 -0.998471 -0.2275469 0.003889739 -0.9737594 0.253559 0.01667469 -0.9671762 -0.2946041 0.07274538 -0.9528467 -0.2711204 0.04590845 -0.9614501 -0.4752983 0.1172989 -0.8719705 -0.4860843 0.1286612 -0.864389 -0.7456187 0.05451923 -0.6641389 -0.7751407 0.03293794 -0.6309296 -0.5743263 0.01897794 -0.8184065 -0.5585002 0.02504682 -0.8291262 -0.229604 0.05658829 -0.9716377 -0.2411991 0.05379074 -0.9689838 0.05717355 0.009994566 -0.9983143 -0.6250199 0.07411044 -0.7770829 0.08994442 0.05213272 -0.9945814 -0.2839818 0.07617765 -0.9557989 0.3848482 0.05896264 -0.9210946 0.1523658 0.06971669 -0.9858623 0.2018729 -0.003807902 -0.9794044 -0.01273161 -0.07797789 -0.9968739 0.2930343 -0.06218045 -0.9540779 0.2863032 -0.04620987 -0.9570242 0.5432559 -0.02856528 -0.8390811 0.7768086 -0.02992451 -0.6290253 0.7645408 -0.03797966 -0.6434555 0.7476145 0.07879704 -0.6594419 0.489524 0.1057476 -0.865554 0.7237525 0.04056692 -0.6888663 0.5641825 -0.03446763 -0.8249305 0.1644048 -0.01272737 -0.9863108 0.2412869 -0.07031375 -0.9679032 0.5583775 -0.05398207 -0.8278288 0.4542647 -0.128714 -0.8815193 -0.09945839 -0.987048 0.1258745 -0.3519531 -0.7639593 0.5408284 + + + + + + + + + + + + + + +

16 0 11 0 12 0 7 1 8 1 14 1 14 2 8 2 5 2 9 3 14 3 13 3 1 4 11 4 2 4 11 5 0 5 2 5 11 6 1 6 12 6 1 7 5 7 8 7 2 8 3 8 1 8 1 9 3 9 6 9 5 10 6 10 4 10 70 11 4 11 69 11 12 12 8 12 10 12 14 13 15 13 7 13 8 14 7 14 10 14 9 15 72 15 14 15 72 16 15 16 14 16 7 17 15 17 10 17 102 18 16 18 10 18 12 19 10 19 16 19 12 20 1 20 8 20 1 21 6 21 5 21 5 22 13 22 14 22 5 23 4 23 13 23 13 24 4 24 70 24 102 25 98 25 16 25 11 26 98 26 0 26 11 27 16 27 98 27 19 28 17 28 102 28 17 29 98 29 102 29 110 30 18 30 19 30 17 31 19 31 18 31 18 32 110 32 32 32 26 33 27 33 30 33 30 34 27 34 34 34 28 35 30 35 35 35 32 36 110 36 20 36 21 37 34 37 27 37 32 38 20 38 21 38 20 39 22 39 21 39 21 40 22 40 23 40 34 41 23 41 24 41 107 42 24 42 25 42 30 43 29 43 26 43 28 44 46 44 30 44 46 45 29 45 30 45 26 46 29 46 31 46 26 47 31 47 27 47 31 48 33 48 27 48 31 49 17 49 18 49 18 50 32 50 33 50 33 51 31 51 18 51 33 52 32 52 21 52 33 53 21 53 27 53 21 54 23 54 34 54 34 55 35 55 30 55 34 56 24 56 35 56 35 57 24 57 107 57 37 58 152 58 36 58 36 59 152 59 151 59 38 60 39 60 40 60 80 61 40 61 39 61 80 62 39 62 53 62 53 63 39 63 38 63 53 64 38 64 40 64 41 65 63 65 64 65 64 66 63 66 61 66 64 67 61 67 65 67 59 68 41 68 65 68 65 69 60 69 59 69 60 70 65 70 61 70 64 71 65 71 41 71 58 72 49 72 48 72 58 73 43 73 49 73 139 74 17 74 123 74 123 75 66 75 139 75 50 76 44 76 45 76 105 77 45 77 109 77 49 78 43 78 44 78 49 79 44 79 50 79 44 80 43 80 106 80 44 81 109 81 45 81 25 82 107 82 105 82 45 83 107 83 42 83 49 84 47 84 48 84 48 85 47 85 117 85 42 86 28 86 46 86 28 87 108 87 46 87 42 88 118 88 47 88 47 89 118 89 117 89 48 90 17 90 139 90 47 91 50 91 45 91 49 92 50 92 47 92 47 93 45 93 42 93 107 94 45 94 105 94 53 95 120 95 51 95 51 96 56 96 81 96 81 97 53 97 51 97 67 98 120 98 54 98 67 99 55 99 52 99 81 100 56 100 55 100 120 101 53 101 54 101 56 102 102 102 61 102 0 103 52 103 98 103 78 104 57 104 58 104 57 105 62 105 58 105 59 106 77 106 41 106 59 107 60 107 124 107 77 108 63 108 41 108 62 109 19 109 110 109 110 110 43 110 62 110 58 111 62 111 43 111 102 112 19 112 61 112 61 113 19 113 124 113 19 114 62 114 124 114 52 115 77 115 98 115 98 116 77 116 17 116 17 117 77 117 123 117 60 118 61 118 124 118 139 119 66 119 58 119 66 120 123 120 122 120 122 121 57 121 78 121 121 122 120 122 67 122 121 123 67 123 52 123 121 124 73 124 120 124 120 125 73 125 75 125 120 126 75 126 51 126 73 127 68 127 100 127 68 128 52 128 0 128 68 129 101 129 100 129 91 130 83 130 82 130 76 131 70 131 71 131 82 132 84 132 85 132 85 133 69 133 70 133 9 134 72 134 71 134 72 135 9 135 86 135 71 136 88 136 87 136 87 137 88 137 75 137 56 138 51 138 102 138 68 139 73 139 121 139 52 140 68 140 121 140 73 141 100 141 91 141 73 142 91 142 74 142 75 143 74 143 87 143 73 144 74 144 75 144 87 145 76 145 71 145 74 146 91 146 82 146 74 147 82 147 87 147 82 148 85 148 87 148 87 149 85 149 76 149 70 150 76 150 85 150 123 151 77 151 59 151 151 152 78 152 36 152 36 153 78 153 58 153 151 154 79 154 78 154 78 155 79 155 122 155 122 156 79 156 66 156 66 157 79 157 37 157 66 158 37 158 36 158 66 159 36 159 58 159 54 160 53 160 67 160 53 161 40 161 67 161 40 162 80 162 67 162 67 163 80 163 55 163 55 164 80 164 81 164 81 165 80 165 53 165 104 166 17 166 117 166 104 167 98 167 17 167 91 168 100 168 99 168 101 169 68 169 0 169 82 170 83 170 84 170 69 171 149 171 141 171 85 172 149 172 69 172 69 173 141 173 70 173 70 174 95 174 71 174 71 175 95 175 9 175 51 176 75 176 102 176 75 177 88 177 102 177 88 178 71 178 72 178 97 179 102 179 88 179 88 180 72 180 86 180 104 181 143 181 98 181 104 182 103 182 143 182 142 183 101 183 89 183 89 184 98 184 143 184 83 185 90 185 84 185 90 186 149 186 84 186 142 187 99 187 100 187 98 188 89 188 0 188 0 189 89 189 101 189 99 190 142 190 92 190 92 191 145 191 90 191 90 192 145 192 149 192 91 193 92 193 83 193 83 194 92 194 90 194 150 195 95 195 141 195 95 196 96 196 9 196 86 197 9 197 96 197 93 198 147 198 94 198 88 199 86 199 96 199 95 200 93 200 96 200 93 201 148 201 147 201 94 202 97 202 93 202 94 203 103 203 97 203 97 204 88 204 96 204 93 205 97 205 96 205 95 206 150 206 93 206 85 207 84 207 149 207 92 208 91 208 99 208 100 209 101 209 142 209 141 210 95 210 70 210 115 211 97 211 119 211 119 212 97 212 103 212 119 213 103 213 104 213 119 214 104 214 126 214 115 215 114 215 110 215 115 216 110 216 19 216 19 217 102 217 115 217 102 218 97 218 115 218 110 219 132 219 43 219 111 220 109 220 116 220 109 221 44 221 116 221 25 222 129 222 128 222 105 223 129 223 25 223 25 224 128 224 107 224 107 225 113 225 42 225 42 226 113 226 28 226 17 227 48 227 117 227 46 228 118 228 42 228 118 229 46 229 108 229 119 230 114 230 115 230 132 231 114 231 133 231 110 232 114 232 132 232 111 233 130 233 131 233 44 234 130 234 116 234 116 235 130 235 111 235 138 236 113 236 128 236 113 237 112 237 28 237 108 238 28 238 112 238 112 239 127 239 126 239 126 240 125 240 119 240 112 241 135 241 127 241 126 242 117 242 112 242 117 243 118 243 112 243 113 244 135 244 112 244 105 245 109 245 129 245 130 246 44 246 106 246 130 247 106 247 132 247 106 248 43 248 132 248 109 249 111 249 129 249 128 250 113 250 107 250 112 251 118 251 108 251 117 252 126 252 104 252 55 253 56 253 63 253 124 254 57 254 59 254 59 255 57 255 122 255 139 256 58 256 48 256 55 257 63 257 52 257 63 258 77 258 52 258 122 259 123 259 59 259 63 260 56 260 61 260 57 261 124 261 62 261 114 262 119 262 133 262 133 263 119 263 125 263 125 264 126 264 134 264 134 265 126 265 127 265 138 266 135 266 113 266 136 267 138 267 129 267 128 268 129 268 138 268 129 269 111 269 136 269 111 270 131 270 136 270 131 271 130 271 132 271 131 272 132 272 133 272 125 273 134 273 133 273 133 274 134 274 131 274 134 275 127 275 137 275 134 276 137 276 136 276 127 277 135 277 137 277 131 278 134 278 136 278 137 279 135 279 138 279 136 280 137 280 138 280 146 281 143 281 103 281 103 282 94 282 146 282 146 283 94 283 147 283 148 284 93 284 150 284 148 285 150 285 149 285 141 286 149 286 150 286 140 287 145 287 146 287 145 288 92 288 142 288 145 289 142 289 144 289 144 290 142 290 89 290 143 291 146 291 144 291 89 292 143 292 144 292 144 293 146 293 145 293 146 294 147 294 140 294 140 295 147 295 148 295 145 296 140 296 148 296 145 297 148 297 149 297 79 298 151 298 37 298 37 299 151 299 152 299

+
+
+
+
+ + + + + 1 0 0 0 0 7.54979e-8 -1 0 0 1 7.54979e-8 0 0 0 0 1 + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/datasets/EuRoC_MAV/ros2_ws/src/euroc_slam/meshes/propeller_cw_purple.dae b/datasets/EuRoC_MAV/ros2_ws/src/euroc_slam/meshes/propeller_cw_purple.dae new file mode 100644 index 0000000..02004e9 --- /dev/null +++ b/datasets/EuRoC_MAV/ros2_ws/src/euroc_slam/meshes/propeller_cw_purple.dae @@ -0,0 +1,90 @@ + + + + + Blender User + Blender 4.4.3 commit date:2025-04-29, commit time:14:09, hash:802179c51ccc + + 2025-06-29T16:23:12 + 2025-06-29T16:23:12 + + Z_UP + + + + + + + + 0 0 0 1 + + + 0.2015545 0.1470271 1 1 + + + 1.4 + + + + + + + + + + + + + + + + + -0.08357137 0.140031 -0.07364559 -0.04007649 0.163115 -0.0483281 -0.117913 0.305442 -0.144312 -0.07036066 0.798102 -0.01999926 -0.05604916 0.545571 -0.05124837 -7.8476e-4 0.975427 0.007674992 0.01606506 0.594631 -0.007204651 0.02989476 0.965824 0.003342509 0.007519602 0.685387 3.59752e-4 0.05407118 0.429634 -0.0101518 0.0151478 0.102216 -0.01316577 -0.05569106 -0.06617146 -0.009633123 -0.001740574 -0.08183485 -0.008683502 0.05592417 -0.06496608 -0.009572863 0.07036018 -0.798109 -0.01999789 0.05604976 -0.54557 -0.05124878 0.07500165 -0.975039 -0.009344518 7.82845e-4 -0.975427 0.007674753 -0.01484996 -0.614361 -0.004038691 -0.02989256 -0.965824 0.003343641 -0.05483555 -0.290864 -0.01157456 0.01151537 -0.203636 -0.02641326 0.118578 -0.302999 -0.139409 -0.01212239 -0.120255 -0.07202428 0.02263188 -0.110745 -0.133017 -0.006745219 0.0938006 -0.100237 -0.02318745 -0.121853 -0.01400709 -0.02270388 -0.852975 0.003909945 0.07237458 -0.204958 -0.0813719 0.04065054 -0.549299 -0.03691428 -0.05490517 -0.803689 -0.007775008 -0.0303961 -0.366957 -0.01295906 0.001296401 -0.676714 -0.002967178 0.02298527 0.118236 -0.01211118 -0.01225966 0.1346679 -0.04632985 -0.004974484 0.08488607 -0.01014596 -0.02655094 0.101783 -0.0245763 0.01429349 0.08863997 -0.01224756 0.008306026 -0.02683579 -0.01177436 0.004496157 -0.08362877 -0.01933526 0.02275598 -0.115931 -0.02960836 -0.002748787 0.02695208 -0.0451194 0.01937729 0.01481556 -0.01050579 -0.01770609 -0.005909144 -0.01108169 -0.008674383 -0.07730418 -0.009214937 -0.01486366 -0.09366428 -0.0989573 -0.003920912 0.206809 -0.02398175 -0.07500165 0.975039 -0.009344518 0.02274048 0.85053 0.003789126 0.0574457 0.791463 -0.009513914 3.01326e-4 0.377456 -0.019279 -0.02556794 0.993204 0.006032288 0.01659119 0.104876 -0.05486416 0.01738977 0.08933287 -0.135902 -0.07848 0.839861 -0.01710146 -0.04100614 0.563133 -0.03620529 -0.104112 0.546217 -0.09498959 0.05355197 0.950918 -0.007589936 0.007873177 0.603278 -0.007240653 -0.11474 0.256342 -0.121651 -0.118667 0.439386 -0.118333 0.05621486 0.618315 3.61391e-4 0.02977818 0.463137 -0.002520799 0.03037655 0.95587 0.0126425 0.05731767 0.951992 -4.06283e-5 0.05827754 0.06997066 -5.11708e-4 -0.05585819 0.06658595 -0.009723842 -0.118004 0.364506 -0.138633 -0.09372586 0.247795 -0.109201 -0.0129714 -0.08752119 -2.67106e-4 -0.01420366 0.0889641 -0.001182854 -0.05847799 0.06418055 -4.29309e-6 0.07877576 -0.813625 -0.01916116 0.118975 -0.372814 -0.139636 0.03680235 -0.992893 0.002690553 -0.05334836 -0.950983 -0.00752902 0.083117 -0.138354 -0.0731762 0.0818296 -0.808715 -0.01160478 -0.05731767 -0.951992 -4.06283e-5 -0.02989745 -0.956894 0.01262229 0.05826526 -0.07324856 -0.00292778 0.112117 -0.483966 -0.11112 -0.05834615 -0.1880429 -0.009261846 -0.05784088 -0.07564437 -2.01417e-4 0.01034718 -0.4132 -0.01469397 0.04087215 -1.00118 0.01250755 0.118766 -0.442389 -0.1158789 0.06098169 -0.51919 -0.04451286 0.123134 -0.278077 -0.131944 0.03703707 -0.1346099 -0.03027558 -0.05117255 -0.503887 -2.42579e-4 -0.005612194 -0.652544 0.00854963 0.001387774 -0.137464 -0.02041268 0.005648493 0.249971 -0.01180469 0.003936409 0.767754 0.01455736 -0.04087215 1.00118 0.01250755 -0.06039386 0.509636 -0.04469954 -0.05146765 0.26177 -0.04790687 -0.08054727 0.828811 -0.01039576 0.01611375 -0.103875 -0.03757125 + + + + + + + + + + -0.1332979 0.02117425 -0.9908498 0.5747192 -0.2176964 -0.7888639 0.4586848 0.1166127 -0.8809143 0.796762 0.02866655 -0.603613 0.6374441 0.1301004 -0.7594333 0.4286819 0.1348391 -0.8933367 0.2745487 0.06497281 -0.9593756 0.08579277 0.02757537 -0.9959313 -0.02477777 0.01214742 -0.9996192 0.4304864 0.1151502 -0.8952218 -0.25635 0.03072887 -0.9660955 -0.2013731 0.00360471 -0.9795081 0.08431196 -8.50421e-4 -0.9964391 0.5499697 0.01659274 -0.8350197 0.516535 0.00940299 -0.8562145 0.3224487 0.05207806 -0.9451533 -0.03354609 -0.02965146 -0.9989973 0.6074284 -0.378597 -0.6983518 0.1507421 -0.3882347 -0.9091483 5.47431e-4 -6.82663e-4 -0.9999997 -0.1882065 0.6024785 -0.7756276 0.001150071 -0.05656933 -0.9983981 -0.580676 0.05504006 -0.8122721 0.1316339 -0.02644854 -0.9909455 -0.639939 0.1641546 -0.7506873 -0.6009643 -0.131612 -0.7883657 -0.4553171 -0.1347081 -0.8800796 -0.2721251 -0.06494665 -0.9600677 -0.1553795 -0.03875029 -0.9870947 -0.1636397 -0.04318547 -0.9855745 0.2345483 -0.03044748 -0.9716276 0.1273332 -0.007365763 -0.9918327 0.02012801 0.008714914 -0.9997595 -0.3395801 0.09919244 -0.9353321 -0.7461774 -0.04896026 -0.6639444 -0.547152 -0.01047146 -0.8369678 -0.3039961 -0.0583859 -0.9508824 -0.4118977 0.9064336 -0.09337204 -0.3837486 -0.9225624 0.04019767 0.5688239 0.6823785 -0.4591285 0.4206404 -0.7380014 -0.527651 -0.001751363 0.03090846 -0.9995207 -0.5364992 0.1803271 -0.8244095 0.7014995 -0.7117329 -0.03653562 0.03173953 0.09667271 -0.9948101 -0.9510691 0.3088388 0.009290814 -0.6695774 -0.03410577 -0.7419588 -0.7898501 -0.006409704 -0.6132664 -0.3997249 -0.1187007 -0.9089171 -0.2779762 -0.05183506 -0.9591885 -0.0846765 -0.02733224 -0.9960336 -0.493359 -0.07842147 -0.8662835 0.3198545 -0.0156216 -0.9473379 0.4220877 0.002946972 -0.9065504 0.2427214 -0.07079893 -0.9675091 0.1276044 -0.01893192 -0.9916445 -0.1514522 -0.003233671 -0.9884593 -0.1919465 -0.005290269 -0.9813911 0.3156791 0.1102437 0.9424399 -0.2963038 0.01001852 -0.9550413 -0.2871746 -0.04936665 -0.9566053 0.9592092 -0.2818055 0.02243942 0.1911545 -0.9815597 -7.13677e-4 -0.556972 -0.8205978 -0.1280682 -0.03055059 -0.02567887 -0.9992034 0.2866526 -0.5651289 -0.7736018 0.1735188 -0.5020146 -0.8472737 0.8734638 0.4863294 0.02334147 0.05813062 0.3322538 -0.9413971 -0.3558347 0.5332844 -0.7674565 -0.5282742 0.187115 -0.8281996 0.05812305 0.01495307 -0.9981974 0.1424851 0.1212221 -0.9823458 -0.01263743 0.01207607 -0.9998473 -0.036951 -7.29395e-4 -0.9993168 0.002786755 -0.02578556 -0.9996637 0.3017065 0.9340552 -0.1910867 0.2644739 0.9467483 -0.1836336 -0.9304461 0.2022138 -0.3055809 0.4413065 0.01380783 -0.8972502 0.5505519 -0.2143223 -0.8068201 0.2806304 0.04778814 -0.9586256 -0.3325405 0.01698231 -0.9429361 -0.4191191 7.20954e-4 -0.907931 -0.2681396 0.05901861 -0.9615706 -0.2730813 0.06033819 -0.9600969 0.038966 -0.00683844 -0.9992172 0.7208864 0.1276939 -0.681188 0.6890428 0.002923369 -0.7247148 0.6487409 -0.135546 -0.7488409 0.6361368 0.07148694 -0.7682576 0.4912518 0.02993363 -0.8705031 0.07220184 0.04011571 -0.996583 0.261315 0.0552144 -0.9636732 -0.9396685 -0.2863839 -0.1871025 0.3205546 -0.946581 0.03506356 -0.5658665 -0.7718494 -0.2899032 0.6349674 0.7052456 -0.3153492 -0.9356009 0.2286301 -0.2690338 -0.04737722 -0.9945824 0.09252858 -0.09749835 0.9772415 -0.1883963 -0.5961412 0.7874 -0.1568985 -0.8719198 0.01750493 -0.489336 -0.9654536 -0.001393318 -0.2605711 0.5110267 0.2291217 -0.8284656 0.6545611 0.1399281 -0.7429469 0.4312245 0.1201269 -0.894212 0.7900882 0.009789347 -0.6129151 0.6697728 0.07027631 -0.7392331 -0.5471363 0.01473301 0.8369139 -0.9710187 0.03852111 -0.2358789 0.005758404 0.636913 -0.7709142 0.1635414 0.07084476 -0.9839894 -0.9911192 0.06195741 0.1176618 -0.1477294 -0.04025292 -0.9882084 0.1700915 -2.34383e-4 -0.9854283 0.9738025 -0.001714348 -0.227389 -0.4849794 0.8704153 0.08469039 -0.377603 0.3807094 0.8440831 -0.815029 0.2274841 -0.5328966 0.4682523 -0.1232404 -0.8749581 -0.9596827 -0.1625154 0.2293429 0.4166108 -0.2491956 -0.8742637 -0.9985131 -0.02232342 0.04973244 -0.7202354 -0.118933 0.6834588 0.004204034 0.009587883 0.9999452 0.4018647 0.6354578 0.6593165 0.3950151 0.8613055 -0.319556 0.8929674 0.0272265 -0.4492973 0.4258959 -3.1751e-4 0.9047721 -0.09706401 -0.001949846 0.9952763 -0.008073985 0.004524648 0.9999573 0.9999871 0.001090884 -0.004974722 0.3680294 -9.60804e-5 0.9298142 0.2096652 -0.01951783 0.9775785 -0.9867988 0.116089 -0.1129231 0.5228313 0.8228644 0.22258 0.5228312 0.8228643 0.22258 0.04069131 -0.01685702 0.9990296 -0.007914423 0.005133509 0.9999556 0.02361637 0.005352377 0.9997068 0.001092135 -0.001404762 0.9999985 0.5719971 -0.4907969 0.6572198 0.9498717 0.3086139 0.05001497 0.9452635 0.005422949 -0.3262631 -0.5436242 0.1883268 -0.8179277 -0.6407834 -0.1534485 -0.7522303 0.9470883 -0.1714751 -0.2713303 -0.6466263 -0.1435836 -0.7491717 0.5451384 -0.01098716 0.8382741 0.9357159 -0.04317045 -0.3501033 0.1301303 -0.7304032 -0.6705052 -0.1835187 -0.06950414 -0.9805561 0.9960443 -0.06376045 0.06188982 -0.1320383 -1.43288e-4 -0.9912446 0.671824 -0.1153327 0.7316768 0.6972933 0.1303239 0.7048388 0.9283077 -0.1853488 -0.3223211 0.009517967 0.01262021 0.9998751 -0.4096136 -0.6573992 0.6324896 -0.3937089 -0.8600286 -0.324568 0.01866835 1.94589e-4 0.9998258 -0.9980192 -5.84297e-4 0.06290757 -0.9154884 -0.006088435 -0.4022986 -0.4183478 0.006146311 0.9082661 0.8071342 -0.1929413 -0.55795 0.9947113 -0.0358535 -0.09625035 -0.6347255 0.09017699 -0.767458 -0.4758565 -0.7591502 -0.4441304 -0.8829414 -0.0101161 -0.4693742 -0.9935211 -0.004686951 0.1135519 0.121163 -0.4387544 0.8904011 -0.1898414 0.5020544 -0.8437427 0.07551825 0.1266102 -0.9890738 -0.636103 -0.100472 -0.7650349 -0.9486541 0.1359664 -0.2856021 0.8489187 0.04603695 -0.5265147 -0.01044851 -0.0449987 0.9989324 0.2239375 0.003393292 0.9745977 -0.1176204 0.02267038 0.9927999 0.3122162 0.05239713 0.9485651 0.4414628 0.1326547 0.8874195 0.7526129 0.04422622 0.6569763 0.7803051 0.02544975 0.624881 0.5136889 -0.001226365 0.8579757 0.506903 -3.51055e-4 0.8620032 0.1008224 0.08950465 0.9908702 0.5702965 0.04164338 0.8203827 -0.9890575 0.1159318 -0.0912429 0.1452141 -0.04309862 0.9884611 -0.3176928 -0.05267095 0.9467297 -0.7706339 -0.02807366 0.6366595 -0.7571516 -0.03570669 0.6522628 -0.5127533 0.1193116 0.8502053 -0.7593222 0.0121715 0.650601 -0.5385159 -0.03028923 0.8420708 0.06297814 -0.05053889 0.9967344 -0.5770009 -0.04343223 0.8155881 -0.361323 -0.1221663 0.9244032 0.7944276 -0.3898352 -0.4657394 + + + + + + + + + + + + + + +

7 0 8 0 5 0 1 1 0 1 2 1 4 2 8 2 6 2 1 3 2 3 4 3 4 4 2 4 3 4 8 5 4 5 3 5 51 6 3 6 47 6 51 7 5 7 8 7 10 8 6 8 9 8 6 9 8 9 9 9 7 10 49 10 8 10 49 11 9 11 8 11 13 12 10 12 9 12 10 13 1 13 4 13 10 14 4 14 6 14 8 15 3 15 51 15 13 16 66 16 10 16 1 17 66 17 0 17 1 18 10 18 66 18 11 19 66 19 13 19 76 20 12 20 13 20 11 21 13 21 12 21 12 22 76 22 21 22 19 23 18 23 17 23 21 24 76 24 22 24 15 25 22 25 14 25 18 26 15 26 14 26 74 27 14 27 16 27 74 28 17 28 18 28 21 29 18 29 20 29 19 30 30 30 18 30 30 31 20 31 18 31 20 32 11 32 12 32 21 33 20 33 12 33 21 34 22 34 15 34 21 35 15 35 18 35 18 36 14 36 74 36 24 37 23 37 99 37 24 38 99 38 45 38 34 39 52 39 25 39 43 40 41 40 42 40 38 41 43 41 42 41 40 42 28 42 92 42 92 43 24 43 40 43 26 44 11 44 44 44 44 45 45 45 26 45 29 46 92 46 28 46 29 47 28 47 73 47 29 48 72 48 32 48 16 49 74 49 72 49 32 50 74 50 27 50 29 51 32 51 31 51 27 52 19 52 30 52 19 53 75 53 30 53 27 54 30 54 32 54 32 55 30 55 31 55 31 56 30 56 82 56 31 57 11 57 92 57 92 58 11 58 26 58 92 59 29 59 31 59 74 60 32 60 72 60 33 61 37 61 53 61 53 62 37 62 35 62 53 63 35 63 36 63 37 64 13 64 42 64 0 65 36 65 66 65 66 66 36 66 35 66 24 67 39 67 40 67 13 68 40 68 39 68 40 69 13 69 76 69 76 70 28 70 40 70 42 71 13 71 38 71 13 72 39 72 38 72 35 73 43 73 66 73 66 74 43 74 11 74 11 75 43 75 44 75 45 76 44 76 39 76 45 77 39 77 24 77 46 78 34 78 36 78 46 79 50 79 33 79 68 80 36 80 0 80 54 81 47 81 51 81 7 82 49 82 48 82 49 83 7 83 57 83 48 84 49 84 58 84 58 85 49 85 50 85 37 86 33 86 13 86 33 87 34 87 46 87 68 88 50 88 46 88 36 89 68 89 46 89 50 90 68 90 55 90 50 91 55 91 58 91 58 92 51 92 48 92 58 93 54 93 51 93 45 94 23 94 26 94 26 95 23 95 24 95 26 96 24 96 92 96 33 97 52 97 34 97 34 98 25 98 36 98 36 99 25 99 53 99 53 100 25 100 52 100 53 101 52 101 33 101 71 102 11 102 82 102 71 103 66 103 11 103 60 104 55 104 67 104 54 105 55 105 56 105 54 106 58 106 55 106 55 107 68 107 67 107 55 108 60 108 56 108 47 109 98 109 95 109 54 110 98 110 47 110 47 111 95 111 51 111 51 112 63 112 48 112 48 113 63 113 7 113 33 114 50 114 13 114 50 115 49 115 13 115 65 116 13 116 49 116 71 117 70 117 66 117 59 118 66 118 70 118 60 119 98 119 56 119 59 120 67 120 68 120 66 121 59 121 0 121 0 122 59 122 68 122 67 123 59 123 60 123 60 124 96 124 98 124 94 125 63 125 95 125 63 126 64 126 7 126 57 127 7 127 64 127 49 128 57 128 64 128 63 129 61 129 64 129 62 130 65 130 61 130 62 131 70 131 65 131 65 132 49 132 64 132 61 133 65 133 64 133 63 134 94 134 61 134 56 135 98 135 54 135 95 136 63 136 51 137 80 138 65 138 69 138 69 139 65 139 70 139 69 140 70 140 71 140 69 141 71 141 83 141 80 142 89 142 76 142 80 143 76 143 13 143 13 144 65 144 80 144 76 145 88 145 28 145 81 146 29 146 73 146 77 147 72 147 81 147 72 148 29 148 81 148 16 149 77 149 85 149 72 150 77 150 16 150 16 151 85 151 74 151 74 152 79 152 27 152 27 153 79 153 19 153 11 154 31 154 82 154 76 155 89 155 88 155 77 156 86 156 87 156 81 157 86 157 77 157 91 158 79 158 85 158 79 159 78 159 19 159 75 160 19 160 78 160 78 161 90 161 83 161 83 162 82 162 78 162 82 163 30 163 78 163 79 164 90 164 78 164 86 165 81 165 73 165 86 166 73 166 88 166 73 167 28 167 88 167 85 168 79 168 74 168 78 169 30 169 75 169 82 170 83 170 71 170 89 171 80 171 69 171 35 172 37 172 41 172 38 173 39 173 43 173 43 174 39 174 44 174 41 175 43 175 35 175 41 176 37 176 42 176 69 177 83 177 84 177 84 178 83 178 90 178 91 179 90 179 79 179 85 180 77 180 91 180 77 181 87 181 91 181 87 182 86 182 88 182 87 183 88 183 89 183 69 184 84 184 89 184 89 185 84 185 87 185 84 186 90 186 91 186 87 187 84 187 91 187 70 188 62 188 93 188 62 189 61 189 94 189 95 190 98 190 94 190 96 191 60 191 59 191 96 192 59 192 97 192 70 193 93 193 97 193 59 194 70 194 97 194 97 195 93 195 96 195 93 196 62 196 94 196 96 197 93 197 94 197 96 198 94 198 98 198 45 199 99 199 23 199

+
+
+
+
+ + + + + 1 0 0 0 0 7.54979e-8 -1 0 0 1 7.54979e-8 0 0 0 0 1 + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/datasets/EuRoC_MAV/ros2_ws/src/euroc_slam/package.xml b/datasets/EuRoC_MAV/ros2_ws/src/euroc_slam/package.xml new file mode 100644 index 0000000..7c5781a --- /dev/null +++ b/datasets/EuRoC_MAV/ros2_ws/src/euroc_slam/package.xml @@ -0,0 +1,18 @@ + + + + euroc_slam + 0.0.0 + Convert the EuRoC MAV dataset to MCAP + Carson Kohlbrenner + Apache-2.0 + + ament_copyright + ament_flake8 + ament_pep257 + python3-pytest + + + ament_python + + diff --git a/datasets/EuRoC_MAV/ros2_ws/src/euroc_slam/resource/euroc_slam b/datasets/EuRoC_MAV/ros2_ws/src/euroc_slam/resource/euroc_slam new file mode 100644 index 0000000..e69de29 diff --git a/datasets/EuRoC_MAV/ros2_ws/src/euroc_slam/setup.cfg b/datasets/EuRoC_MAV/ros2_ws/src/euroc_slam/setup.cfg new file mode 100644 index 0000000..981db22 --- /dev/null +++ b/datasets/EuRoC_MAV/ros2_ws/src/euroc_slam/setup.cfg @@ -0,0 +1,4 @@ +[develop] +script_dir=$base/lib/euroc_slam +[install] +install_scripts=$base/lib/euroc_slam diff --git a/datasets/EuRoC_MAV/ros2_ws/src/euroc_slam/setup.py b/datasets/EuRoC_MAV/ros2_ws/src/euroc_slam/setup.py new file mode 100644 index 0000000..e0987b5 --- /dev/null +++ b/datasets/EuRoC_MAV/ros2_ws/src/euroc_slam/setup.py @@ -0,0 +1,28 @@ +import os +from glob import glob +from setuptools import find_packages, setup + +package_name = 'euroc_slam' + +setup( + name=package_name, + version='0.0.0', + packages=find_packages(exclude=['test']), + data_files=[ + ('share/ament_index/resource_index/packages', + ['resource/' + package_name]), + ('share/' + package_name, ['package.xml']), + (os.path.join('share', package_name, 'launch'), glob(os.path.join('launch', '*launch.[pxy][yma]*'))), + (os.path.join('share', package_name, 'urdf'), glob('urdf/*')), + (os.path.join('share', package_name, 'meshes'), glob('meshes/*')), + ], + install_requires=['setuptools'], + zip_safe=True, + maintainer='Foxglove', + license='Apache-2.0', + entry_points={ + 'console_scripts': [ + 'firefly_state_publisher = euroc_slam.firefly_state_publisher:main', + ], + }, +) diff --git a/datasets/EuRoC_MAV/ros2_ws/src/euroc_slam/test/test_copyright.py b/datasets/EuRoC_MAV/ros2_ws/src/euroc_slam/test/test_copyright.py new file mode 100644 index 0000000..97a3919 --- /dev/null +++ b/datasets/EuRoC_MAV/ros2_ws/src/euroc_slam/test/test_copyright.py @@ -0,0 +1,25 @@ +# Copyright 2015 Open Source Robotics Foundation, 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. + +from ament_copyright.main import main +import pytest + + +# Remove the `skip` decorator once the source file(s) have a copyright header +@pytest.mark.skip(reason='No copyright header has been placed in the generated source file.') +@pytest.mark.copyright +@pytest.mark.linter +def test_copyright(): + rc = main(argv=['.', 'test']) + assert rc == 0, 'Found errors' diff --git a/datasets/EuRoC_MAV/ros2_ws/src/euroc_slam/test/test_flake8.py b/datasets/EuRoC_MAV/ros2_ws/src/euroc_slam/test/test_flake8.py new file mode 100644 index 0000000..27ee107 --- /dev/null +++ b/datasets/EuRoC_MAV/ros2_ws/src/euroc_slam/test/test_flake8.py @@ -0,0 +1,25 @@ +# Copyright 2017 Open Source Robotics Foundation, 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. + +from ament_flake8.main import main_with_errors +import pytest + + +@pytest.mark.flake8 +@pytest.mark.linter +def test_flake8(): + rc, errors = main_with_errors(argv=[]) + assert rc == 0, \ + 'Found %d code style errors / warnings:\n' % len(errors) + \ + '\n'.join(errors) diff --git a/datasets/EuRoC_MAV/ros2_ws/src/euroc_slam/test/test_pep257.py b/datasets/EuRoC_MAV/ros2_ws/src/euroc_slam/test/test_pep257.py new file mode 100644 index 0000000..b234a38 --- /dev/null +++ b/datasets/EuRoC_MAV/ros2_ws/src/euroc_slam/test/test_pep257.py @@ -0,0 +1,23 @@ +# Copyright 2015 Open Source Robotics Foundation, 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. + +from ament_pep257.main import main +import pytest + + +@pytest.mark.linter +@pytest.mark.pep257 +def test_pep257(): + rc = main(argv=['.', 'test']) + assert rc == 0, 'Found code style errors / warnings' diff --git a/datasets/EuRoC_MAV/ros2_ws/src/euroc_slam/urdf/firefly.urdf b/datasets/EuRoC_MAV/ros2_ws/src/euroc_slam/urdf/firefly.urdf new file mode 100644 index 0000000..6a0f8a6 --- /dev/null +++ b/datasets/EuRoC_MAV/ros2_ws/src/euroc_slam/urdf/firefly.urdf @@ -0,0 +1,367 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + firefly + firefly_base_link + 10 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + firefly + firefly_rotor_0_joint + firefly_rotor_0 + ccw + 0.0125 + 0.025 + 838 + 8.54858e-06 + 0.016 + gazebo/command/motor_speed + 0 + 8.06428e-05 + 1e-06 + motor_speed/0 + 10 + + + + Gazebo/Red + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + firefly + firefly_rotor_1_joint + firefly_rotor_1 + cw + 0.0125 + 0.025 + 838 + 8.54858e-06 + 0.016 + gazebo/command/motor_speed + 1 + 8.06428e-05 + 1e-06 + motor_speed/1 + 10 + + + + Gazebo/Blue + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + firefly + firefly_rotor_2_joint + firefly_rotor_2 + ccw + 0.0125 + 0.025 + 838 + 8.54858e-06 + 0.016 + gazebo/command/motor_speed + 2 + 8.06428e-05 + 1e-06 + motor_speed/2 + 10 + + + + Gazebo/Blue + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + firefly + firefly_rotor_3_joint + firefly_rotor_3 + cw + 0.0125 + 0.025 + 838 + 8.54858e-06 + 0.016 + gazebo/command/motor_speed + 3 + 8.06428e-05 + 1e-06 + motor_speed/3 + 10 + + + + Gazebo/Blue + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + firefly + firefly_rotor_4_joint + firefly_rotor_4 + ccw + 0.0125 + 0.025 + 838 + 8.54858e-06 + 0.016 + gazebo/command/motor_speed + 4 + 8.06428e-05 + 1e-06 + motor_speed/4 + 10 + + + + Gazebo/Blue + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + firefly + firefly_rotor_5_joint + firefly_rotor_5 + cw + 0.0125 + 0.025 + 838 + 8.54858e-06 + 0.016 + gazebo/command/motor_speed + 5 + 8.06428e-05 + 1e-06 + motor_speed/5 + 10 + + + + Gazebo/Red + + \ No newline at end of file diff --git a/datasets/EuRoC_MAV/ros2_ws/src/euroc_slam/urdf/firefly_url.urdf b/datasets/EuRoC_MAV/ros2_ws/src/euroc_slam/urdf/firefly_url.urdf new file mode 100644 index 0000000..b4d31e5 --- /dev/null +++ b/datasets/EuRoC_MAV/ros2_ws/src/euroc_slam/urdf/firefly_url.urdf @@ -0,0 +1,367 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + firefly + firefly/base_link + 10 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + firefly + firefly/rotor_0_joint + firefly/rotor_0 + ccw + 0.0125 + 0.025 + 838 + 8.54858e-06 + 0.016 + gazebo/command/motor_speed + 0 + 8.06428e-05 + 1e-06 + motor_speed/0 + 10 + + + + Gazebo/Red + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + firefly + firefly/rotor_1_joint + firefly/rotor_1 + cw + 0.0125 + 0.025 + 838 + 8.54858e-06 + 0.016 + gazebo/command/motor_speed + 1 + 8.06428e-05 + 1e-06 + motor_speed/1 + 10 + + + + Gazebo/Blue + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + firefly + firefly/rotor_2_joint + firefly/rotor_2 + ccw + 0.0125 + 0.025 + 838 + 8.54858e-06 + 0.016 + gazebo/command/motor_speed + 2 + 8.06428e-05 + 1e-06 + motor_speed/2 + 10 + + + + Gazebo/Blue + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + firefly + firefly/rotor_3_joint + firefly/rotor_3 + cw + 0.0125 + 0.025 + 838 + 8.54858e-06 + 0.016 + gazebo/command/motor_speed + 3 + 8.06428e-05 + 1e-06 + motor_speed/3 + 10 + + + + Gazebo/Blue + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + firefly + firefly/rotor_4_joint + firefly/rotor_4 + ccw + 0.0125 + 0.025 + 838 + 8.54858e-06 + 0.016 + gazebo/command/motor_speed + 4 + 8.06428e-05 + 1e-06 + motor_speed/4 + 10 + + + + Gazebo/Blue + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + firefly + firefly/rotor_5_joint + firefly/rotor_5 + cw + 0.0125 + 0.025 + 838 + 8.54858e-06 + 0.016 + gazebo/command/motor_speed + 5 + 8.06428e-05 + 1e-06 + motor_speed/5 + 10 + + + + Gazebo/Red + + \ No newline at end of file diff --git a/datasets/EuRoC_MAV/tutorial.md b/datasets/EuRoC_MAV/tutorial.md new file mode 100644 index 0000000..01178d9 --- /dev/null +++ b/datasets/EuRoC_MAV/tutorial.md @@ -0,0 +1,395 @@ +# Visualizing SLAM using Foxglove +Foxglove is a data visualization app that uses the universal [MCAP](https://mcap.dev/) data format to streamline multimodal robotics workflows. Simultaneous localization and mapping (SLAM) is an excellent example of multimodal data fusion that combines videos from calibrated cameras and acceleration data from an inertial measurement unit (IMU) to map out the environment and determine where the robot is located through time. + +In this tutorial, we will demonstrate how to convert the [EuRoC MAV](https://projects.asl.ethz.ch/datasets/doku.php?id=kmavvisualinertialdatasets) dataset into MCAP format and visualize it using Foxglove. + +![Drone Snapshot](media/slam_snapshot.png) + + +## Table of Contents +- [Visualizing SLAM using Foxglove](#visualizing-slam-using-foxglove) + - [Step 1: Install Dependencies](#step-1-install-dependencies) + - [Step 2: Convert to MCAP](#step-2-convert-to-mcap) + - [Option 1: Your SLAM dataset is a directory of files.](#option-1-your-slam-dataset-is-a-directory-of-files) + - [Option 2: Your SLAM dataset is a ROS bag.](#option-2-your-slam-dataset-is-a-ros-bag) + - [Step 3: Visualize the Data](#step-3-visualize-the-data) +- [Deep Dive: Converting Multimodal Data to MCAP using Foxglove SDK](#deep-dive-converting-multimodal-data-to-mcap-using-foxglove-sdk) + - [Defining Message Schemas](#defining-message-schemas) + - [The Image Message](#the-image-message) + - [The IMU Message](#the-imu-message) +- [Where is the Drone? Enhance your Visualization with a URDF](#where-is-the-drone-enhance-your-visualization-with-a-urdf) + - [The Drone URDF](#the-drone-urdf) + - [The Launch File](#the-launch-file) + - [The Joint State Publisher](#the-joint-state-publisher) +- [Visualize the Data](#visualize-the-data) + + +## Step 1: Install Dependencies +A working ROS 2 installation is needed for this tutorial. We tested this pipeline using ROS 2 Humble with an Ubuntu 22.04 system. Run the following commands in a new terminal to get the SLAM and Foxglove dependencies: +```bash +sudo apt install \ + ros-$ROS_DISTRO-foxglove-bridge \ +    ros-$ROS_DISTRO-imu-tools \ + ros-$ROS_DISTRO-rtabmap-ros \ +    ros-$ROS_DISTRO-rosbag2-storage-mcap \ + ros-$ROS_DISTRO-image-proc +``` + +## Step 2: Convert to MCAP +The EuRocC MAV dataset standardized how SLAM data is collected. The EuRoC dataset contains IMU data represented as a .csv and an IMU configuration file, as well as side-by-side camera videos represented as timestamped images and camera configuration files. + +``` +imu0 +├── data.csv +└── sensor.yaml +cam +├── data +│   ├── .png +│   └── ... +├── data.csv +└── sensor.yaml +... +``` +Notice that there is no pointcloud or position estimates included in the original dataset. Luckily, Foxglove can be used to visualize data in real time using the [Foxglove SDK](https://foxglove.dev/blog/announcing-the-foxglove-sdk) for direct streaming or [Foxglove bridge](https://docs.foxglove.dev/docs/connecting-to-data/ros-foxglove-bridge) for visualizing ROS 1 or ROS 2 topics. In this tutorial, we will show how to use **both tools** in a ROS 2 workflow using the popular real-time SLAM package [RTAB-Map](https://introlab.github.io/rtabmap/). + +We will use the Foxglove SDK to convert the EuRoC dataset to an MCAP with the following topics to interact with RTAB-Map, +``` +/cam0/image_raw -> sensor_msgs/msg/Image +/cam1/image_raw -> sensor_msgs/msg/Image +/imu0 -> sensor_msgs/msg/Imu +``` +then record a new MCAP with pointcloud data and a visualization of our robot. MCAP is the default storage format for ROS 2 (Iron) and newer due to its optimized recording and ability to integrate with third-party tools outside ROS environments, making it the ideal format to work with SLAM data. If using a different SLAM dataset that is in ROS 1 .bag format or ROS 2 .db3 format, conversion to MCAP becomes trivial using the [MCAP command line interface (CLI)](https://mcap.dev/guides/cli). +#### Option 1: Your SLAM dataset is a directory of files. +Clone the [code repository](https://github.com/foxglove/tutorials/tree/main/datasets/EuRoC_MAV) for this tutorial. In a new python virtual environment, install the following dependencies: +```bash +pip install foxglove-sdk numpy opencv-python pyyaml +``` +Next, run our custom conversion script designed for the EuRoC dataset using the Foxglove SDK. We will break down how this script works in the [Deep Dive: Converting Multimodal Data to MCAP using Foxglove SDK](#deep-dive-converting-multimodal-data-to-mcap-using-foxglove-sdk) section of this tutorial so you can create your own conversion scripts. +```bash +python3 convert-euroc-2-mcap.py --src --dst .mcap +``` + +#### Option 2: Your SLAM dataset is a ROS bag. +The [MCAP CLI](https://mcap.dev/guides/cli) comes with commands to quickly convert bag files to MCAP! `mcap convert ` can be used as long as the message definitions contain the information that RTAB-Map is expecting. It may be beneficial to convert ROS 1 bags to ROS 2 bag format first before converting to MCAP to improve compatibility. Foxglove's built-in [debugging panels](https://docs.foxglove.dev/docs/visualization/panels/raw-messages) are a quick way to verify topic contents match. + +## Step 3: Visualize the Data +Just like that, we are ready to perform SLAM and visualize the data! Open four new terminals. In the first terminal, start the Foxglove bridge: +```bash +ros2 run foxglove_bridge foxglove_bridge +``` +In the second terminal, start an RTAB-Map instance with settings preset for EuRoC MAV datasets: +```bash +ros2 launch rtabmap_examples euroc_datasets.launch.py gt:=false +# Note: This example script accounts for camera and IMU calibrations and transformations. +# More calibration information is needed for other SLAM datasets. +``` + +In the third terminal, play back the MCAP file we made: +```bash +ros2 bag play --clock +``` +In the last terminal, record the resulting transformations and point clouds in a new MCAP file that can be visualized at a later time. +```bash +ros2 bag record -s mcap --all +``` +Finally, either watch the drone perform SLAM live by connecting to the [Foxglove Websocket](https://app.foxglove.dev) in your browser or import the new MCAP directly to Foxglove! + +![No Drone Image](media/no_drone_slam.png) + +# Deep Dive: Converting Multimodal Data to MCAP using Foxglove SDK +In this section, we will explore how the Foxglove SDK was used to create a custom MCAP conversion script that is compatible with ROS 2 listeners. Please refer to the [full script](https://github.com/foxglove/tutorials/tree/main/datasets/EuRoC_MAV/convert-euroc-2-mcap.py) script while following along. + +### Defining Message Schemas +We start by creating a new MCAP writer that will create an MCAP file for us to write to: +```python +writer = foxglove.open_mcap(out_mcap_path, allow_overwrite=True) # Open the mcap file for writing +``` + +In this tutorial, we will define our schemas to match the ROS 2 `sensor_msgs/msg/Image` and `sensor_msgs/msg/Imu` messages that RTAB-Map is expecting. + +```python +# Direct foxglove to our message definitions +imu_msg_path = Path("msgs/imu_flat.msg") +img_msg_path = Path("msgs/image_flat.msg") + +# Define our custom ROS 2 schemas +img_schema = Schema( +    name="sensor_msgs/msg/Image", +    encoding="ros2msg", +    data=img_msg_path.read_bytes(), +) +imu_schema = Schema( +    name="sensor_msgs/msg/Imu", +    encoding="ros2msg", +    data=imu_msg_path.read_bytes(), +) +``` + +The Foxglove SDK requires that ROS 2 messages be formatted in a delimited, concatenated format. This format is nearly captured using built-in ROS 2 tools such as `ros2 interface show sensor_msgs/msg/Image --no-comments`. More information about schema formatting is available [here](https://mcap.dev/spec/registry). For convenience, the `msgs` folder contains the formatted messages for the `sensor_msgs/msg/Image` and `sensor_msgs/msg/Imu` messages. + +Next, we make separate channels for each of the message schemas for convenient logging: +```python +# ros2msg channels require cdr encoding type +cam0_channel = Channel(topic="/cam0/image_raw", schema=img_schema, message_encoding="cdr") +cam1_channel = Channel(topic="/cam1/image_raw", schema=img_schema, message_encoding="cdr") +imu_channel = Channel(topic="/imu0", schema=imu_schema, message_encoding="cdr") +``` +### The Image Message +We start by looping through each image with `getImageMsg`, which takes in a timestamp and image and outputs an object of type `Image` +```python +def read_images(cam_directory, channel, cam_num): +    # Loop through the data.csv file and read in the image files +    with open(cam_directory + "/data.csv", "r") as csv_file: + reader = csv.reader(csv_file) +        next(reader)  # Skip the first row with headers +        for row in reader: + timestamp = int(row[0]) + image_name = row[1] + image_path = os.path.join(cam_directory, "data", image_name) +            if not os.path.exists(image_path): +                print(f"Image {image_path} does not exist") +                continue + +            # Convert image to ROS2 message and write to channel + image_msg = getImageMsg(image_path, timestamp, cam_num) + channel.log(serialize_message(image_msg), log_time=timestamp) +``` +The EuRoC dataset is composed of stereo images. For RGB images, the parameters of the `getImageMsg` function should be adjusted appropriately. +```python +def getImageMsg(img_path: str, timestamp: int, cam_num: int) -> Image: +    # Load as grayscale image data + img = cv2.imread(img_path, cv2.IMREAD_GRAYSCALE) +    if img is None: +        raise ValueError(f"Could not load image: {img_path}") +    + height, width = img.shape +    + sec = int(timestamp // 1e9) + nsec = int(timestamp % 1e9) + +    # Fill in the image message data + ros_image = Image() + ros_image.header = Header() + ros_image.header.stamp.sec = sec + ros_image.header.stamp.nanosec = nsec + ros_image.header.frame_id = "cam"+str(cam_num) + ros_image.height = height + ros_image.width = width + ros_image.encoding = "mono8" #Stereo images + ros_image.step = width  # For mono8, 1 byte per pixel + ros_image.data = img.tobytes() + +    return ros_image +``` + +### The IMU Message +The IMU data is saved in the data.csv file under the following format: +- Timestamp [ns], +- Angular velocity [rad s^-1] (x,y,z), +- Linear acceleration [rad s^-1] (x,y,z) + +The `sensor_msgs/msgs/Imu` message has the format of: +  - header (header) +  - orientation (quaternion) +  - orientation covariance (float32[9]) +  - angular velocity (vector3) +  - angular velocity covariance (float32[9]) +  - linear acceleration (vector3) +  - linear acceleration covariance (float32[9]) + +Notice that the orientation, orientation covariance, angular velocity covariance, and linear acceleration covariance are not present in the data for each timestamp. This is where the `gyroscope_noise_density` and `accelerometer_noise_density` parameters come into play in the `sensor.yaml` file. We can assume the diagonal of the covariance matrix to be a function of the IMU noise densities and sample rate. + +```python +def read_imu(imu_data_path, imu_channel, imu_yaml_path): +    # Get the IMU config with covariance information +    with open(imu_yaml_path, "r") as imu_yaml_file: + imu_yaml = yaml.load(imu_yaml_file, Loader=yaml.FullLoader) + +    # Get the noise and bias parameters, see https://github.com/ethz-asl/kalibr/wiki/IMU-Noise-Model for more details + sample_sqr_dt = np.sqrt(1.0/float(imu_yaml["rate_hz"])) + sigma_gd = imu_yaml["gyroscope_noise_density"]*sample_sqr_dt + sigma_ad = imu_yaml["accelerometer_noise_density"]*sample_sqr_dt + +    # Calculate the covariance matrices + angular_velocity_cov = np.diag([sigma_gd**2, sigma_gd**2, sigma_gd**2]).astype(np.float64) + linear_acceleration_cov = np.diag([sigma_ad**2, sigma_ad**2, sigma_ad**2]).astype(np.float64) +``` +We can now formulate the IMU ROS 2 message. Orientation is not measured by the IMU for this application, so we will leave its covariance empty. +```python + +    with open(imu_data_path, "r") as imu_file: + reader = csv.reader(imu_file) +        next(reader)  # Skip the first row with headers +        for row in reader: + timestamp = int(row[0]) + angular_velocity = [float(row[1]), float(row[2]), float(row[3])] + linear_acceleration = [float(row[4]), float(row[5]), float(row[6])] + + imu_msg = Imu() + imu_msg.header = Header() + imu_msg.header.stamp.sec = timestamp // int(1e9) + imu_msg.header.stamp.nanosec = timestamp % int(1e9) + imu_msg.header.frame_id = "imu4" # Transformation reference frame +            # Orientation + imu_msg.orientation = Quaternion() + imu_msg.orientation.x = 0.0 + imu_msg.orientation.y = 0.0 + imu_msg.orientation.z = 0.0 + imu_msg.orientation.w = 1.0 + orientation_cov = np.zeros((3,3), dtype=np.float64) + imu_msg.orientation_covariance = list(orientation_cov.flatten(order="C").astype(float)) +            # Angular velocity + imu_msg.angular_velocity = Vector3() + imu_msg.angular_velocity.x = angular_velocity[0] + imu_msg.angular_velocity.y = angular_velocity[1] + imu_msg.angular_velocity.z = angular_velocity[2] + imu_msg.angular_velocity_covariance = list(angular_velocity_cov.flatten(order="C").astype(float)) +            # Linear acceleration + imu_msg.linear_acceleration = Vector3() + imu_msg.linear_acceleration.x = linear_acceleration[0] + imu_msg.linear_acceleration.y = linear_acceleration[1] + imu_msg.linear_acceleration.z = linear_acceleration[2] + imu_msg.linear_acceleration_covariance = list(linear_acceleration_cov.flatten(order="C").astype(float)) + + imu_channel.log(serialize_message(imu_msg), log_time=timestamp) +``` +Now you know how to make custom schemas with the Foxglove SDK that can interface with ROS. The Foxglove SDK is not limited only to `Image` and `Imu` message types; in fact, there is a [wide selection of supported schemas](https://docs.foxglove.dev/docs/visualization/message-schemas) for every type of project. + +# Where is the Drone? Enhance your Visualization with a URDF +Adding a visualization of the drone is optional; however, adding one can lead to insights about correct transformations between the drone, cameras, and IMU. Since SLAM runs in real time, we will make a new [robot_state_publisher](https://docs.ros.org/en/humble/Tutorials/Intermediate/URDF/Using-URDF-with-Robot-State-Publisher-py.html) ROS 2 node that listens to RTAB-Map and dynamically updates the drone's pose. Please refer to [the LAFAN1 tutorial](https://foxglove.dev/blog/converting-the-lafan1-retargeting-dataset-to-mcap) to learn how to apply a URDF to an MCAP dataset in post-processing. + +### The Drone URDF +First, we will make a new ROS2 package to bundle our SLAM, robot_state_publisher, joint_state_publisher, and Foxglove bridge into one executable. +```bash +cd ros2_ws/src +ros2 pkg create --build-type ament_python --license Apache-2.0 euroc_slam +``` + +The EuRoC dataset was recorded on an Asctec Firefly drone, and its URDF model is included in the open-source [RotorS](https://github.com/ethz-asl/rotors_simulator) project for ROS 1. The exact URDF files and meshes for the Firefly can be downloaded [here](https://github.com/foxglove/tutorials/tree/main/datasets/EuRoC_MAV/ros2/src/euroc_slam). + +![drone_img](media/model.png) + +### The Launch File + +Navigate to the package directory and make a new launch file. Don't forget to [configure](https://docs.ros.org/en/humble/Tutorials/Intermediate/Launch/Launch-Main.html) `setup.py` to recognize launch, mesh, and urdf files! + +```bash +cd euroc_slam +mkdir launch +touch launch/firefly.launch.py +``` +Launch files are concise ways to bundle multiple ROS nodes together. `ros2 run foxglove_bridge foxglove_bridge` is equivalently represented in a launch file as: +```python +foxglove_bridge_node = Node( +    package='foxglove_bridge', +    executable='foxglove_bridge', +    name='foxglove_bridge', +    output='screen', +) +``` +In this script, we enable the following nodes: + +1. The Foxglove bridge to visualize ROS 2 topics. +2. The `robot_state_publisher` that publishes the URDF transformations and meshes. +3. A static transformation connecting the drone to the SLAM localization output. +4. A joint state publisher that simulates the rotors in motion. This step is purely for visual effect, as the motor torques are not included in the dataset's scope. +5. RTABMAP to perform SLAM in real time as our dataset is replayed. + +```python +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription, TimerAction +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import Command, LaunchConfiguration, PathJoinSubstitution +from launch_ros.actions import Node +from launch_ros.substitutions import FindPackageShare +from launch_ros.parameter_descriptions import ParameterValue + + +def generate_launch_description(): + use_sim_time = LaunchConfiguration('use_sim_time', default='false') +    +    # Generate URDF from xacro file (or read URDF file) + urdf_file = PathJoinSubstitution([FindPackageShare('rotors_description'), 'urdf', 'firefly.xacro']) + robot_description = ParameterValue(Command(['xacro ', urdf_file, ' namespace:=firefly']), value_type=str) + +    # Create nodes + foxglove_bridge_node = Node( +        package='foxglove_bridge', +        executable='foxglove_bridge', +        name='foxglove_bridge', +        output='screen', + ) + + robot_state_publisher_node = Node( +        package='robot_state_publisher', +        executable='robot_state_publisher', +        name='robot_state_publisher', +        output='screen', +        parameters=[{'use_sim_time': use_sim_time, 'robot_description': robot_description}] + ) + + static_transform_publisher_node = Node( +        package='tf2_ros', +        executable='static_transform_publisher', +        name='static_transform_publisher', +        output='screen', +        arguments=['0', '0', '0', '0', '0', '0', 'base_link', 'firefly/base_link'] + ) + + firefly_state_publisher_node = Node( +       package='rotors_description', +       executable='firefly_state_publisher', +       name='firefly_state_publisher', +       output='screen' + ) + + rtabmap_include = IncludeLaunchDescription( + PythonLaunchDescriptionSource([ + FindPackageShare('rtabmap_examples'), +            '/launch/euroc_datasets.launch.py' + ]), +        launch_arguments={ +            'gt': 'false' + }.items() + ) + +    return LaunchDescription([ + DeclareLaunchArgument( +            'use_sim_time', +            default_value='false', +            description='Use simulation (Gazebo) clock if true'), + foxglove_bridge_node, + TimerAction(period=2.0, actions=[robot_state_publisher_node]),  # 2 second delay + TimerAction(period=4.0, actions=[static_transform_publisher_node]),  # 4 second delay + TimerAction(period=6.0, actions=[rtabmap_include]), +        # TimerAction(period=10.0, actions=[firefly_state_publisher_node]) + ]) +``` +### The Joint State Publisher +The `firefly_state_publisher` is used to spin the rotors at a constant velocity during flight, defined by: +```python +self.increment = (360.0*self.spin_rate)/loop_rate +self.angle = ((self.angle + self.increment) % 360.0) - 180.0 +self.joint_state.position = [self.angle, -self.angle, self.angle, -self.angle, self.angle, -self.angle] +``` +This is purely visual and can be defined based on specific motor torque values, should they be available. + +## Visualize the Data +Open three terminals. In the first terminal, initialize the launch node containing RTAB-Map, the Foxglove bridge, and the URDF with: +```bash +ros2 launch euroc_slam firefly.launch.py +# Note: Don't forget to build and source your ROS environment after making changes! +``` +In the second terminal, play back the MCAP file we made: +```bash +ros2 bag play --clock +``` +In the last terminal, record the resulting transformations, point clouds, and URDF in a new MCAP file that can be visualized at a later time. +```bash +ros2 bag record -s mcap --all +``` +Open Foxglove and watch SLAM happen live, or load the generated MCAP file! + +![Finalviz](media/MH01_Final_gif_cut.gif) + +[Get started with Foxglove](https://app.foxglove.dev/human-interaction-and-robotics-lab/dashboard) and MCAP today! If you have any questions or need support, [join our community](https://discord.com/invite/vUVAdFmMFM)—we’d love to hear from you and help you succeed.